ObjectCollisionAvoidanceImpedanceController.cpp
Go to the documentation of this file.
1/*
2 * This file is part of ArmarX.
3 *
4 * ArmarX is free software; you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License version 2 as
6 * published by the Free Software Foundation.
7 *
8 * ArmarX is distributed in the hope that it will be useful, but
9 * WITHOUT ANY WARRANTY; without even the implied warranty of
10 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 * GNU General Public License for more details.
12 *
13 * You should have received a copy of the GNU General Public License
14 * along with this program. If not, see <http://www.gnu.org/licenses/>.
15 *
16 * @package ...
17 * @author Jianfeng Gao ( jianfeng dot gao at kit dot edu )
18 * @date 2021
19 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20 * GNU General Public License
21 */
22
24
25#include <VirtualRobot/MathTools.h>
26#include <VirtualRobot/RobotNodeSet.h>
27
29#include <ArmarXCore/core/PackagePath.h> // for GUI
33
38
42
43#include <simox/control/geodesics/util.h>
44#include <simox/control/robot/NodeInterface.h>
45#include <simox/control/environment/collision.h>
46#include <simox/control/utils/primitive.h>
47
49
50#include <boost/shared_ptr.hpp>
51
53{
54 NJointControllerRegistration<NJointTaskspaceObjectCollisionAvoidanceImpedanceController>
56 "NJointTaskspaceObjectCollisionAvoidanceImpedanceController");
57
61 const NJointControllerConfigPtr& config,
62 const VirtualRobot::RobotPtr& robot) :
64 {
65 ConfigPtrT cfg = ConfigPtrT::dynamicCast(config);
67 userCfgWithColl = CollisionCtrlCfg::FromAron(cfg->config);
68
69 coll = std::make_shared<core::ObjectCollisionAvoidanceBase>(rtGetRobot(), userCfgWithColl.coll);
70 collReady.store(true);
71 ARMARX_INFO << "-- " << getClassName() << " initialized --";
72 }
73
74 std::string
76 {
77 return "NJointTaskspaceObjectCollisionAvoidanceImpedanceController";
78 }
79
80 void
82 {
83 double time_measure = IceUtil::Time::now().toMicroSecondsDouble();
84 limbRTUpdateStatus(arm, deltaT);
85 double time_update_status = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
86
87 arm->controller.run(arm->rtConfig, arm->rtStatus);
88 double time_run_rt = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
89
90 if (collReady.load())
91 {
93 coll->rtLimbControllerRun(arm->kinematicChainName,
94 arm->rtStatus.jointPosition,
95 arm->rtStatus.qvelFiltered,
96 arm->rtConfig.torqueLimit,
97 arm->rtStatus.desiredJointTorque);
98 }
99 double time_coll_run = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
100
101 if (collReady.load())
102 {
103 limbRTSetTarget(arm,
104 coll->collLimb.at(arm->kinematicChainName).rts.desiredJointTorques);
105 }
106 else
107 {
108 limbRTSetTarget(arm, arm->rtStatus.desiredJointTorque);
109 }
110 double time_set_target = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
111
112 time_measure = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
113
114 if (time_measure > 200)
115 {
116 ARMARX_RT_LOGF_WARN("---- rt too slow: "
117 "time_update_status: %.2f\n"
118 "run_rt_limb: %.2f\n"
119 "run_coll_rt_limb: %.2f\n"
120 "set_target_limb: %.2f\n"
121 "time all: %.2f\n",
122 time_update_status, // 0-1 us
123 time_run_rt - time_update_status, //
124 time_coll_run - time_run_rt, //
125 time_set_target - time_coll_run, //
126 time_measure)
127 .deactivateSpam(1.0f); // 0-1 us
128 }
129 }
130
131 void
133 const IceUtil::Time& sensorValuesTimestamp,
134 const IceUtil::Time& timeSinceLastIteration)
135 {
136 double deltaT = timeSinceLastIteration.toSecondsDouble();
137
138 if (collReady.load())
139 {
141 coll->updateRtConfigFromUser();
142 coll->updateRtCollisionObjects();
143 coll->rtCollisionChecking();
144 }
145 for (auto& pair : limb)
146 {
147 this->limbRT(pair.second, deltaT);
148 }
149 if (hands)
150 {
151 hands->updateRTStatus(deltaT);
152 hands->setTargets();
153 }
154 }
155
156 Eigen::Isometry3d
157 NJointTaskspaceObjectCollisionAvoidanceImpedanceController::matrixToIsometry(Eigen::Matrix<double, 4, 4> transformation)
158 {
159 Eigen::Matrix3d rotation = transformation.block<3,3>(0,0);
160 Eigen::Vector3d translation = transformation.block<3,1>(0,3);
161 Eigen::Isometry3d transform;
162 transform.linear() = rotation;
163 transform.translation() = translation;
164 return transform;
165 }
166
167 void
169 const ::armarx::aron::data::dto::DictPtr& dto,
170 const Ice::Current& iceCurrent)
171 {
173 auto cfg = common::control_law::arondto::ObjectCollisionAvoidanceConfigDict::FromAron(dto);
174 coll->setUserCfg(cfg);
175 }
176
177 void
179 {
180 size_t numCollisionObjects = 0;
181 for (const auto& pair : collisionObjects) {
182 numCollisionObjects += pair.second.size();
183 }
184
185 std::vector<hpp::fcl::CollisionObject> allCollisionObjects;
186 allCollisionObjects.reserve(numCollisionObjects);
187 for (const auto& pair : collisionObjects) {
188 allCollisionObjects.insert(allCollisionObjects.end(), pair.second.begin(), pair.second.end());
189 }
190
191 coll->updateUserCollisionObjects(allCollisionObjects);
192 }
193
194 void
196 const std::string& primitiveSourceName,
197 const ::armarx::aron::data::dto::DictPtr& dto,
198 const Ice::Current& iceCurrent)
199 {
200 ARMARX_INFO_S << "updateCollisionObjects";
201 auto scene = common::control_law::arondto::CollisionScene::FromAron(dto);
202 auto boxes = scene.boxes;
203 auto spheres = scene.spheres;
204 auto cylinders = scene.cylinders;
205 auto capsules = scene.capsules;
206 auto ellipsoids = scene.ellipsoids;
207
208 if (collisionObjects.count(primitiveSourceName) == 0)
209 {
210 collisionObjects.emplace(primitiveSourceName, std::vector<hpp::fcl::CollisionObject>());
211 }
212 std::vector<hpp::fcl::CollisionObject>& collisionObjectsOfSource = collisionObjects[primitiveSourceName];
213 collisionObjectsOfSource.clear();
214 collisionObjectsOfSource.reserve(boxes.size() + spheres.size() + cylinders.size() + capsules.size() + ellipsoids.size());
215
216 for (auto box : boxes)
217 {
218 collisionObjectsOfSource.push_back(
219 simox::control::environment::createCollisionObject(
220 simox::control::utils::primitive::Box{.lengthX = box.lengthX, .lengthY = box.lengthY, .lengthZ = box.lengthZ},
221 matrixToIsometry(box.transformation)
222 )
223 );
224 }
225
226 for (auto sphere : spheres)
227 {
228 collisionObjectsOfSource.push_back(
229 simox::control::environment::createCollisionObject(
230 simox::control::utils::primitive::Sphere{.radius = sphere.radius},
231 matrixToIsometry(sphere.transformation)
232 )
233 );
234 }
235
236 for (auto cylinder : cylinders)
237 {
238 collisionObjectsOfSource.push_back(
239 simox::control::environment::createCollisionObject(
240 simox::control::utils::primitive::Cylinder{.radius = cylinder.radius, .lengthY = cylinder.lengthY},
241 matrixToIsometry(cylinder.transformation)
242 )
243 );
244 }
245
246 for (auto capsule : capsules)
247 {
248 collisionObjectsOfSource.push_back(
249 simox::control::environment::createCollisionObject(
250 simox::control::utils::primitive::Capsule{.radius = capsule.radius, .lengthY = capsule.lengthY},
251 matrixToIsometry(capsule.transformation)
252 )
253 );
254 }
255
256 for (auto ellipsoid : ellipsoids)
257 {
258 collisionObjectsOfSource.push_back(
259 simox::control::environment::createCollisionObject(
260 simox::control::utils::primitive::Ellipsoid{.lengthX = ellipsoid.lengthX, .lengthY = ellipsoid.lengthY, .lengthZ = ellipsoid.lengthZ},
261 matrixToIsometry(ellipsoid.transformation)
262 )
263 );
264 }
265
267 }
268
269
270
273 const Ice::Current& iceCurrent)
274 {
275 if (not collReady.load())
276 return nullptr;
277
279 return coll->userCfg.toAronDTO();
280 }
281
282 void
284 const ::armarx::aron::data::dto::DictPtr& dto,
285 const Ice::Current& iceCurrent)
286 {
288 userCfgWithColl = CollisionCtrlCfg::FromAron(dto);
290 coll->setUserCfg(userCfgWithColl.coll);
291 }
292
295 {
297 userCfgWithColl.limbs = userConfig.limbs;
298 userCfgWithColl.hands = userConfig.hands;
299 return userCfgWithColl.toAronDTO();
300 }
301
302 void
305 const DebugObserverInterfacePrx& debugObs)
306 {
307 // double limbTimeMeasure = IceUtil::Time::now().toMicroSecondsDouble();
308
309 StringVariantBaseMap datafields;
310 auto rtStatus = arm.bufferRTtoPublish.getUpToDateReadBuffer();
311
312 datafields["trackingError"] = new Variant(rtStatus.trackingError);
313 common::debugEigenVec(datafields, "desiredJointTorques", rtStatus.desiredJointTorques);
314 common::debugEigenVec(datafields, "selfCollisionTorque", rtStatus.selfCollisionJointTorque);
315 common::debugEigenVec(datafields, "jointLimitTorque", rtStatus.jointLimitJointTorque);
316
318 datafields, "projectedImpedanceTorque", rtStatus.projImpedanceJointTorque);
319 // common::debugEigenVec(datafields, "projectedJointLimitTorque", rtStatus.projJointLimTorque);
320 // common::debugEigenVec(datafields, "projectedForceImpedance", rtStatus.projForceImpedance);
321 // common::debugEigenVec(
322 // datafields, "projectedSelfCollisionTorque", rtStatus.projSelfCollTorque);
323
324 Eigen::VectorXf selfCollNullspace = rtStatus.selfCollNullSpace.diagonal();
325 Eigen::VectorXf jointLimNullspace = rtStatus.jointLimNullSpace.diagonal();
326 common::debugEigenVec(datafields, "selfCollNullspaceDiagonal", selfCollNullspace);
327 common::debugEigenVec(datafields, "jointLimNullspaceDiagonal", jointLimNullspace);
328
329 // if (rtData.enableJointLimitAvoidance)
330 // {
331 // for (size_t i = 0; i < rtStatus.jointLimitData.size(); ++i)
332 // {
333 // if (not rtStatus.jointLimitData[i].isLimitless)
334 // {
335 // datafields["n_des(q)_" + std::to_string(i) + "_" +
336 // rtStatus.jointLimitData[i].jointName] =
337 // new Variant(rtStatus.jointLimitData[i].desiredNSjointLim);
338 // datafields["q_damping" + std::to_string(i) + "_" +
339 // rtStatus.jointLimitData[i].jointName] =
340 // new Variant(rtStatus.jointLimitData[i].totalDamping);
341 // datafields["q_repTorque" + std::to_string(i) + "_" +
342 // rtStatus.jointLimitData[i].jointName] =
343 // new Variant(rtStatus.jointLimitData[i].repulsiveTorque);
344 // }
345 // }
346 // }
347
348 // datafields["activeCollPairsNum"] = new Variant(rtStatus.activeCollPairsNum);
349 // datafields["collisionPairsNum"] = new Variant(rtStatus.collisionPairsNum);
350 // datafields["jointLimitNullspaceTime"] = new Variant(rtStatus.jointLimitNullspaceTime);
351 // datafields["jointLimitTorqueTime"] = new Variant(rtStatus.jointLimitTorqueTime);
352 // datafields["collisionTorqueTime"] = new Variant(rtStatus.collisionTorqueTime);
353 // datafields["collNullspaceTime"] = new Variant(rtStatus.collNullspaceTime);
354 // datafields["collisionPairTime"] = new Variant(rtStatus.collisionPairTime);
355 // datafields["impForceRatio"] = new Variant(rtStatus.impForceRatio);
356 // datafields["impTorqueRatio"] = new Variant(rtStatus.impTorqueRatio);
357
358 // double timeMeasure = IceUtil::Time::now().toMicroSecondsDouble();
359 viz::Layer layer = arviz.layer(getName() + "_" + arm.nodeSetName);
360 for (int i = 0; i < rtStatus.activeCollPairsNum; ++i) {
361 // visualize impedance force
362
363
364 layer.add(viz::Arrow("force_" + std::to_string(i))
365 .fromTo(rtStatus.collDataVec[i].point1 * 1000.0,
366 rtStatus.collDataVec[i].point1 * 1000.0 +
367 rtStatus.collDataVec[i].direction * 50.0 *
368 rtStatus.collDataVec[i].repulsiveForce)
369 .color(simox::Color::blue()));
370
371
372 //size_t index = rtStatus.distanceIndexPairs[i].second;
373 datafields[std::to_string(i) + "_minDistance"] =
374 new Variant(rtStatus.collDataVec[i].minDistance);
375 datafields[std::to_string(i) + "_repForce"] =
376 new Variant(rtStatus.collDataVec[i].repulsiveForce);
377 datafields[std::to_string(i) + "_dampingForce"] =
378 new Variant(-1.0f * rtStatus.collDataVec[i].damping *
379 rtStatus.collDataVec[i].distanceVelocity);
380 datafields[std::to_string(i) + "_n_des(d)"] =
381 new Variant(rtStatus.collDataVec[i].desiredNSColl);
383 datafields, std::to_string(i) + "_point", rtStatus.collDataVec[i].point1);
385 datafields, std::to_string(i) + "_dir", rtStatus.collDataVec[i].direction);
386 }
387
388
389 // /// prepare test case config
390 // const float tolerance = 1e-9f;
391 // if (rtData.testConfig == 1)
392 // {
393 // if (rtStatus.evalData[0].nodeName == "ArmL8_Wri2")
394 // {
395 // // set distance
396 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_dist"] =
397 // new Variant(rtStatus.evalData[0].minDistance);
398 // // set f_rep, damping, desired NS space
399
400
401 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_repF"] =
402 // new Variant(rtStatus.evalData[0].repulsiveForce);
403 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_projMass"] =
404 // new Variant(rtStatus.evalData[0].projectedMass);
405 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_locStiffness"] =
406 // new Variant(rtStatus.evalData[0].localStiffness);
407 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_dampFactor"] =
408 // new Variant(rtStatus.evalData[0].damping);
409 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_distVel"] =
410 // new Variant(rtStatus.evalData[0].distanceVelocity);
411 // if (fabs(rtStatus.evalData[0].damping + 1.0f) < tolerance)
412 // {
413 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_dampForce"] =
414 // new Variant(0.0);
415 // }
416 // else
417 // {
418 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_dampForce"] =
419 // new Variant(-1.0 * rtStatus.evalData[0].damping *
420 // rtStatus.evalData[0].distanceVelocity);
421 // }
422
423 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_n_des(d)"] =
424 // new Variant(rtStatus.evalData[0].desiredNSColl);
425 // }
426 // if (rtStatus.evalData[1].nodeName == "ArmL8_Wri2")
427 // {
428 // // set distance
429 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_dist"] =
430 // new Variant(rtStatus.evalData[1].minDistance);
431 // // set f_rep, damping, desired NS space
432
433 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_repF"] =
434 // new Variant(rtStatus.evalData[1].repulsiveForce);
435 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_projMass"] =
436 // new Variant(rtStatus.evalData[1].projectedMass);
437 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_locStiffness"] =
438 // new Variant(rtStatus.evalData[1].localStiffness);
439 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_dampFactor"] =
440 // new Variant(rtStatus.evalData[1].damping);
441 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_distVel"] =
442 // new Variant(rtStatus.evalData[1].distanceVelocity);
443 // if (fabs(rtStatus.evalData[1].damping + 1.0f) < tolerance)
444 // {
445 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_dampForce"] =
446 // new Variant(0.0);
447 // }
448 // else
449 // {
450 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_dampForce"] =
451 // new Variant(-1.0 * rtStatus.evalData[1].damping *
452 // rtStatus.evalData[1].distanceVelocity);
453 // }
454
455 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_n_des(d)"] =
456 // new Variant(rtStatus.evalData[1].desiredNSColl);
457 // }
458 // if (rtStatus.evalData[2].nodeName == "ArmL7_Wri1")
459 // {
460 // // set distance
461 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_dist"] =
462 // new Variant(rtStatus.evalData[2].minDistance);
463 // // set f_rep, damping, desired NS space
464
465 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_repF"] =
466 // new Variant(rtStatus.evalData[2].repulsiveForce);
467
468 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_projMass"] =
469 // new Variant(rtStatus.evalData[2].projectedMass);
470 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_locStiffness"] =
471 // new Variant(rtStatus.evalData[2].localStiffness);
472 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_dampFactor"] =
473 // new Variant(rtStatus.evalData[2].damping);
474 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_distVel"] =
475 // new Variant(rtStatus.evalData[2].distanceVelocity);
476 // if (fabs(rtStatus.evalData[2].damping + 1.0f) < tolerance)
477 // {
478 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_dampForce"] =
479 // new Variant(0.0);
480 // }
481 // else
482 // {
483 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_dampForce"] =
484 // new Variant(-1.0 * rtStatus.evalData[2].damping *
485 // rtStatus.evalData[2].distanceVelocity);
486 // }
487
488
489 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_n_des(d)"] =
490 // new Variant(rtStatus.evalData[2].desiredNSColl);
491 // }
492 // if (rtStatus.evalData[3].nodeName == "ArmL8_Wri2")
493 // {
494 // // set distance
495 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_dist"] =
496 // new Variant(rtStatus.evalData[3].minDistance);
497 // // set f_rep, damping, desired NS space
498
499 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_repF"] =
500 // new Variant(rtStatus.evalData[3].repulsiveForce);
501
502 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_projMass"] =
503 // new Variant(rtStatus.evalData[3].projectedMass);
504 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_locStiffness"] =
505 // new Variant(rtStatus.evalData[3].localStiffness);
506 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_dampFactor"] =
507 // new Variant(rtStatus.evalData[3].damping);
508 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_distVel"] =
509 // new Variant(rtStatus.evalData[3].distanceVelocity);
510 // if (fabs(rtStatus.evalData[3].damping + 1.0f) < tolerance)
511 // {
512 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_dampForce"] =
513 // new Variant(0.0);
514 // }
515 // else
516 // {
517 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_dampForce"] =
518 // new Variant(-1.0 * rtStatus.evalData[3].damping *
519 // rtStatus.evalData[3].distanceVelocity);
520 // }
521
522
523 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_n_des(d)"] =
524 // new Variant(rtStatus.evalData[3].desiredNSColl);
525 // }
526
527 // if (rtStatus.evalData[4].nodeName == "ArmL8_Wri2")
528 // {
529 // // set distance
530 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_dist"] =
531 // new Variant(rtStatus.evalData[4].minDistance);
532 // // set f_rep, damping, desired NS space
533
534 // // values have been calculated
535 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_repF"] =
536 // new Variant(rtStatus.evalData[4].repulsiveForce);
537
538 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_projMass"] =
539 // new Variant(rtStatus.evalData[4].projectedMass);
540 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_locStiffness"] =
541 // new Variant(rtStatus.evalData[4].localStiffness);
542 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_dampFactor"] =
543 // new Variant(rtStatus.evalData[4].damping);
544 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_distVel"] =
545 // new Variant(rtStatus.evalData[4].distanceVelocity);
546 // if (fabs(rtStatus.evalData[4].damping + 1.0f) < tolerance)
547 // {
548 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_dampForce"] =
549 // new Variant(0.0);
550 // }
551 // else
552 // {
553 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_dampForce"] =
554 // new Variant(-1.0 * rtStatus.evalData[4].damping *
555 // rtStatus.evalData[4].distanceVelocity);
556 // }
557
558
559 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_n_des(d)"] =
560 // new Variant(rtStatus.evalData[4].desiredNSColl);
561 // }
562 // if (rtStatus.evalData[5].nodeName == "ArmL8_Wri2")
563 // {
564 // // set distance
565 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_dist"] =
566 // new Variant(rtStatus.evalData[5].minDistance);
567
568 // // values have been calculated
569 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_repF"] =
570 // new Variant(rtStatus.evalData[5].repulsiveForce);
571
572 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_projMass"] =
573 // new Variant(rtStatus.evalData[5].projectedMass);
574 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_locStiffness"] =
575 // new Variant(rtStatus.evalData[5].localStiffness);
576 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_dampFactor"] =
577 // new Variant(rtStatus.evalData[5].damping);
578 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_distVel"] =
579 // new Variant(rtStatus.evalData[5].distanceVelocity);
580 // if (fabs(rtStatus.evalData[5].damping + 1.0f) < tolerance)
581 // {
582 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_dampForce"] =
583 // new Variant(0.0);
584 // }
585 // else
586 // {
587 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_dampForce"] =
588 // new Variant(-1.0 * rtStatus.evalData[5].damping *
589 // rtStatus.evalData[5].distanceVelocity);
590 // }
591
592
593 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_n_des(d)"] =
594 // new Variant(rtStatus.evalData[5].desiredNSColl);
595 // }
596 // if (rtStatus.evalData[6].nodeName == "ArmL5_Elb1")
597 // {
598 // // set distance
599 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_dist"] =
600 // new Variant(rtStatus.evalData[6].minDistance);
601
602 // // values have been calculated
603 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_repF"] =
604 // new Variant(rtStatus.evalData[6].repulsiveForce);
605
606 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_projMass"] =
607 // new Variant(rtStatus.evalData[6].projectedMass);
608 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_locStiffness"] =
609 // new Variant(rtStatus.evalData[6].localStiffness);
610 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_dampFactor"] =
611 // new Variant(rtStatus.evalData[6].damping);
612 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_distVel"] =
613 // new Variant(rtStatus.evalData[6].distanceVelocity);
614 // if (fabs(rtStatus.evalData[6].damping + 1.0f) < tolerance)
615 // {
616 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_dampForce"] =
617 // new Variant(0.0);
618 // }
619 // else
620 // {
621 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_dampForce"] =
622 // new Variant(-1.0 * rtStatus.evalData[6].damping *
623 // rtStatus.evalData[6].distanceVelocity);
624 // }
625
626
627 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_n_des(d)"] =
628 // new Variant(rtStatus.evalData[6].desiredNSColl);
629 // }
630 // }
631
632 // visualize impedance force
633
634 layer.add(viz::Arrow("projImpForce")
635 .fromTo(rtStatus.globalPose.block<3, 1>(0, 3),
636 rtStatus.globalPose.block<3, 1>(0, 3) +
637 rtStatus.projForceImpedance.head(3) * 1000.0)
638 .color(simox::Color::red()));
639
640 arviz.commit(layer);
641
642
643 //double selfCollDebugTime = IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
644 //datafields["selfCollDebugTime"] = new Variant(selfCollDebugTime);
645
646 // debug value assignment torso, neck joints
647 // datafields["torsoJointValue_float"] = new Variant(rtStatus.torsoJointValuef);
648 // datafields["neck1JointValue_float"] = new Variant(rtStatus.neck1JointValuef);
649 // datafields["neck2JointValue_float"] = new Variant(rtStatus.neck2JointValuef);
650
651 // datafields["torsoJointValue_double"] = new Variant(rtStatus.torsoJointValued);
652 // datafields["neck1JointValue_double"] = new Variant(rtStatus.neck1JointValued);
653 // datafields["neck2JointValue_double"] = new Variant(rtStatus.neck2JointValued);
654
655 // common::debugEigenVec(
656 // datafields, "set_ActuatedJointValues", rtStatus.setActuatedJointValues.cast<float>());
657 // common::debugEigenVec(
658 // datafields, "get_ActuatedJointValues", rtStatus.getActuatedJointValues.cast<float>());
659
660 // double limbTime = IceUtil::Time::now().toMicroSecondsDouble() - limbTimeMeasure;
661 // datafields["limbOnPublishTime"] = new Variant(limbTime);
662
663 debugObs->setDebugChannel("CollAvoid_ImpCtrl_" + arm.nodeSetName, datafields);
664 }
665
666 void
668 const std::vector<hpp::fcl::CollisionObject>& objects,
669 const DebugObserverInterfacePrx& debugObs,
670 const std::string& layerSuffix)
671 {
672
673 viz::Layer objectLayer = arviz.layer(getName() + layerSuffix);
674 for (size_t i = 0; i < objects.size(); ++i)
675 {
676 auto object = objects.at(i);
677 auto position = object.getTranslation().cast<float>() * 1000;
678 auto rotation = object.getRotation().cast<float>();
679
680 switch (object.getNodeType())
681 {
682 case hpp::fcl::NODE_TYPE::GEOM_BOX:
683 {
684 const hpp::fcl::Box* box = std::static_pointer_cast<hpp::fcl::Box>(object.collisionGeometry()).get();
685 const viz::Box vizObject = viz::Box("box " + std::to_string(i))
686 .size(box->halfSide.cast<float>() * 1000 * 2)
687 .orientation(rotation)
688 .position(position)
689 .color(255, 0, 0, 128);
690 objectLayer.add(vizObject);
691 break;
692 }
693 case hpp::fcl::NODE_TYPE::GEOM_SPHERE:
694 {
695 const hpp::fcl::Sphere* sphere = std::static_pointer_cast<hpp::fcl::Sphere>(object.collisionGeometry()).get();
696 const viz::Sphere vizObject = viz::Sphere("sphere " + std::to_string(i))
697 .radius(static_cast<float>(sphere->radius) * 1000)
698 .orientation(rotation)
699 .position(position)
700 .color(0, 0, 255, 128);
701 objectLayer.add(vizObject);
702 break;
703 }
704 case hpp::fcl::NODE_TYPE::GEOM_CYLINDER:
705 {
706 // hpp fcl has height as z for cylinders, arviz y axis
707 const auto _rotation = rotation * Eigen::AngleAxisf(-M_PI / 2., Eigen::Vector3f::UnitX());
708 const hpp::fcl::Cylinder* cylinder = std::static_pointer_cast<hpp::fcl::Cylinder>(object.collisionGeometry()).get();
709 const viz::Cylinder vizObject = viz::Cylinder("cylinder " + std::to_string(i))
710 .height(static_cast<float>(cylinder->halfLength) * 1000 * 2)
711 .radius(static_cast<float>(cylinder->radius) * 1000)
712 .orientation(_rotation)
713 .position(position)
714 .color(0, 255, 0, 128);
715 objectLayer.add(vizObject);
716 break;
717 }
718 case hpp::fcl::NODE_TYPE::GEOM_CAPSULE: {
719 const hpp::fcl::Capsule* capsule = std::static_pointer_cast<hpp::fcl::Capsule>(object.collisionGeometry()).get();
720 Eigen::Vector3f offset;
721 offset << 0, 0, static_cast<float>(capsule->halfLength) * 1000;
722 offset = rotation * offset;
723 const viz::Sphere cap1 = viz::Sphere("capsule_cap1 " + std::to_string(i))
724 .radius(static_cast<float>(capsule->radius) * 1000)
725 .position(position + offset)
726 .orientation(rotation)
727 .color(255, 200, 0, 128);
728 const viz::Sphere cap2 = viz::Sphere("capsule_cap2 " + std::to_string(i))
729 .radius(static_cast<float>(capsule->radius) * 1000)
730 .position(position - offset)
731 .orientation(rotation)
732 .color(255, 200, 0, 128);
733 const auto _rotation = rotation * Eigen::AngleAxisf(-M_PI / 2., Eigen::Vector3f::UnitX());
734 const viz::Cylinder vizObject = viz::Cylinder("capsule_mid " + std::to_string(i))
735 .height(static_cast<float>(capsule->halfLength) * 1000 * 2)
736 .radius(static_cast<float>(capsule->radius) * 1000)
737 .color(255, 200, 0, 128)
738 .orientation(_rotation)
739 .position(position);
740 objectLayer.add(vizObject);
741 objectLayer.add(cap1);
742 objectLayer.add(cap2);
743 break;
744 }
745 case hpp::fcl::NODE_TYPE::GEOM_ELLIPSOID:
746 {
747 const hpp::fcl::Ellipsoid* ellipsoid = std::static_pointer_cast<hpp::fcl::Ellipsoid>(object.collisionGeometry()).get();
748 const viz::Ellipsoid vizObject = viz::Ellipsoid("ellipsoid " + std::to_string(i))
749 // axis lengths seem to be radii instead of axis lengths
750 .axisLengths(ellipsoid->radii.cast<float>() * 1000)
751 .orientation(rotation)
752 .position(position)
753 .color(255, 0, 200, 128);
754 objectLayer.add(vizObject);
755 break;
756 }
757 default: ;
758 }
759 }
760 arviz.commit(objectLayer);
761 }
762
763 void
765 const SensorAndControl& sc,
766 const DebugDrawerInterfacePrx& drawer,
767 const DebugObserverInterfacePrx& debugObs)
768 {
770 if (coll)
771 {
772 for (auto& pair : coll->collLimb)
773 {
774 collLimbPublish(pair.second, debugObs);
775 }
776 collObjectPublish(coll->userCollisionObjects, debugObs, "_collisionObjects");
777
778 const auto& robotObjects = coll->collisionRobot->getCollisionManager()->getObjects();
779 std::vector<hpp::fcl::CollisionObject> robotObjectsByValue;
780 for (const auto* ptr : robotObjects) {
781 robotObjectsByValue.push_back(*ptr);
782 }
783 collObjectPublish(robotObjectsByValue, debugObs, "_collisionRobot");
784 }
785 }
786
787 void
789 {
791 "rt Preactivate controller NJointTaskspaceObjectCollisionAvoidanceImpedanceController");
794 if (collReady.load())
795 {
797 coll->rtPreActivate();
798 }
799 }
800
801 void
803 {
805 if (collReady.load())
806 {
808 coll->rtPostDeactivate();
809 }
811 "post deactivate: NJointTaskspaceObjectCollisionAvoidanceImpedanceController");
812 }
813
816 const VirtualRobot::RobotPtr& robot,
817 const std::map<std::string, ConstControlDevicePtr>& controlDevices,
818 const std::map<std::string, ConstSensorDevicePtr>&)
819 {
820 using namespace armarx::WidgetDescription;
821 HBoxLayoutPtr layout = new HBoxLayout;
822
823
824 ::armarx::WidgetDescription::WidgetSeq widgets;
825
826 /// select default config
827 LabelPtr label = new Label;
828 label->text = "select a controller config";
829
830 StringComboBoxPtr cfgBox = new StringComboBox;
831 cfgBox->name = "config_box";
832 cfgBox->defaultIndex = 0;
833 cfgBox->multiSelect = false;
834
835 cfgBox->options = std::vector<std::string>{
836 "default", "default_a7_right", "default_a7_right_zero_torque"};
838
839 layout->children.emplace_back(label);
840 layout->children.emplace_back(cfgBox);
842
843 layout->children.insert(layout->children.end(), widgets.begin(), widgets.end());
844 ARMARX_INFO_S << "Layout done";
845 return layout;
846 }
847
850 const StringVariantBaseMap& values)
851 {
852 auto cfgName = values.at("config_box")->getString();
853 const armarx::PackagePath configPath(
854 "armarx_control",
855 "controller_config/NJointTaskspaceObjectCollisionAvoidanceImpedanceController/" + cfgName +
856 ".json");
857 ARMARX_INFO_S << "Loading config from " << configPath.toSystemPath();
858 ARMARX_CHECK(std::filesystem::exists(configPath.toSystemPath()));
859
860 auto cfgDTO = armarx::readFromJson<CollisionCtrlCfg>(configPath.toSystemPath());
861
863 return new ConfigurableNJointControllerConfig{cfgDTO.toAronDTO()};
864 }
865
866} // namespace armarx::control::njoint_controller::task_space
#define ARMARX_RT_LOGF_WARN(...)
#define ARMARX_RT_LOGF_INFO(...)
#define M_PI
Definition MathTools.h:17
std::string getName() const
Retrieve name of object.
const VirtualRobot::RobotPtr & rtGetRobot()
TODO make protected and use attorneys.
static std::filesystem::path toSystemPath(const data::PackagePath &pp)
const T & getUpToDateReadBuffer() const
The Variant class is described here: Variants.
Definition Variant.h:224
void onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &) override
::armarx::aron::data::dto::DictPtr getConfig(const Ice::Current &iceCurrent=Ice::emptyCurrent) override
NJointTaskspaceImpedanceController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
void rtPostDeactivateController() override
This function is called after the controller is deactivated.
void updateConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
NJointController interface.
void rtPreActivateController() override
This function is called before the controller is activated.
void limbRTUpdateStatus(ArmPtr &arm, const double deltaT)
-----------------------------— Real time cotnrol --------------------------------------—
void collObjectPublish(const std::vector< hpp::fcl::CollisionObject > &objects, const DebugObserverInterfacePrx &debugObs, const std::string &layerSuffix)
static WidgetDescription::WidgetPtr GenerateConfigDescription(const VirtualRobot::RobotPtr &, const std::map< std::string, ConstControlDevicePtr > &, const std::map< std::string, ConstSensorDevicePtr > &)
NJointTaskspaceObjectCollisionAvoidanceImpedanceController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
void updateCollisionAvoidanceConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
NJointController interface for collision avoidance.
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration) override
TODO make protected and use attorneys.
void updateCollisionObjects(const std::string &primitiveSourceName, const ::armarx::aron::data::dto::DictPtr &scene, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
void onPublish(const SensorAndControl &sc, const DebugDrawerInterfacePrx &drawer, const DebugObserverInterfacePrx &) override
void collLimbPublish(core::ObjectCollisionAvoidanceBase::NodeSetData &arm, const DebugObserverInterfacePrx &debugObs)
void updateConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent) override
DerivedT & color(Color color)
Definition ElementOps.h:218
DerivedT & position(float x, float y, float z)
Definition ElementOps.h:136
DerivedT & orientation(Eigen::Quaternionf const &ori)
Definition ElementOps.h:152
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
#define ARMARX_INFO
The normal logging level.
Definition Logging.h:181
#define ARMARX_INFO_S
Definition Logging.h:202
armarx::aron::data::dto::Dict getCollisionAvoidanceConfig()
std::shared_ptr< class Robot > RobotPtr
Definition Bus.h:19
::IceInternal::Handle<::armarx::WidgetDescription::Widget > WidgetPtr
::IceInternal::Handle< Dict > DictPtr
void debugEigenVec(StringVariantBaseMap &datafields, const std::string &name, Eigen::VectorXf vec)
Definition utils.cpp:190
NJointControllerRegistration< NJointTaskspaceObjectCollisionAvoidanceImpedanceController > registrationControllerNJointTaskspaceObjectCollisionAvoidanceImpedanceController("NJointTaskspaceObjectCollisionAvoidanceImpedanceController")
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface > DebugObserverInterfacePrx
std::map< std::string, VariantBasePtr > StringVariantBaseMap
AronDTO readFromJson(const std::filesystem::path &filename)
auto transform(const Container< InputT, Alloc > &in, OutputT(*func)(InputT const &)) -> Container< OutputT, typename std::allocator_traits< Alloc >::template rebind_alloc< OutputT > >
Convenience function (with less typing) to transform a container of type InputT into the same contain...
Definition algorithm.h:351
IceUtil::Handle< class RobotUnit > RobotUnitPtr
Definition FTSensor.h:34
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugDrawerInterface > DebugDrawerInterfacePrx
detail::ControlThreadOutputBufferEntry SensorAndControl
Box & size(Eigen::Vector3f const &s)
Definition Elements.h:52
Cylinder & height(float h)
Definition Elements.h:84
Cylinder & radius(float r)
Definition Elements.h:76
Ellipsoid & axisLengths(const Eigen::Vector3f &axisLengths)
Definition Elements.h:156
void add(ElementT const &element)
Definition Layer.h:31
Sphere & radius(float r)
Definition Elements.h:138
#define ARMARX_TRACE
Definition trace.h:77