ColAvoid.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 2025
19 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20 * GNU General Public License
21 */
22
23#include "ColAvoid.h"
24
25#include <boost/shared_ptr.hpp>
26
27#include <SimoxUtility/color/Color.h>
28#include <VirtualRobot/MathTools.h>
29#include <VirtualRobot/RobotNodeSet.h>
30
31#include <simox/control/environment/collision.h>
32#include <simox/control/geodesics/util.h>
33#include <simox/control/robot/NodeInterface.h>
34#include <simox/control/utils/primitive.h>
35
37#include <ArmarXCore/core/PackagePath.h> // for GUI
41
45
47#include <armarx/control/common/control_law/aron/CollisionPrimitives.aron.generated.h>
49
51{
52 template <typename NJointControllerType, typename CollisionCtrlCfg>
54 const RobotUnitPtr& robotUnit,
55 const NJointControllerConfigPtr& config,
56 const VirtualRobot::RobotPtr& robot) :
57 NJointControllerType{robotUnit, config, robot}
58 {
59 auto cfg = ConfigPtrT::dynamicCast(config);
61 userCfgWithColl_ = CollisionCtrlCfg::FromAron(cfg->config);
62
63 std::map<std::string, std::vector<size_t>> velCtrlIndices;
64 for (auto& arm : this->limb)
65 {
66 velCtrlIndices.emplace(arm.first, arm.second->rtStatus.jointIDVelocityMode);
67 }
68 coll = std::make_shared<CollAvoidBase>(
69 this->rtGetRobot(), userCfgWithColl_.coll, velCtrlIndices);
70 collReady_.store(true);
71 // const std::string rootNodeName = "root";
72 // rootNode = this->rtGetRobot()->getRobotNode(rootNodeName);
73 }
75 template <typename NJointControllerType, typename CollisionCtrlCfg>
76 void
78 {
79 arm->controller.run(arm->rtConfig, arm->rtStatus);
80
81 if (collReady_.load())
82 {
84 // const std::string rootNodeName = "root";
85 // // coll->collLimb.at(arm->kinematicChainName)->rts.globalPose = rootNode->getGlobalPose();
86 // coll->collLimb.at(arm->kinematicChainName).rts.globalPose =
87 // this->rtGetRobot()->getGlobalPose();
88 coll->rtLimbControllerRun(arm->kinematicChainName,
89 arm->rtConfig.torqueLimit,
90 arm->rtConfig.velocityLimit,
91 arm->rtStatus);
92 // /// experimental implementation of admittance interface
93 // arm->rtStatus.inertia = coll->collLimb.at(arm->kinematicChainName).rts.inertia;
94 }
95
96 // if (collReady.load())
97 // {
98 // this->limbRTSetTarget(
99 // arm,
100 // arm->rtStatus.nDoFTorque,
101 // arm->rtStatus.nDoFVelocity,
102 // coll->collLimb.at(arm->kinematicChainName).rts.desiredJointTorques,
103 // arm->rtStatus.desiredJointVelocity);
104 // }
105 // else
106 // {
107 // this->limbRTSetTarget(arm,
108 // arm->rtStatus.nDoFTorque,
109 // arm->rtStatus.nDoFVelocity,
110 // arm->rtStatus.desiredJointTorque,
111 // arm->rtStatus.desiredJointVelocity);
112 // }
113 this->limbRTSetTarget(arm,
114 arm->rtStatus.nDoFTorque,
115 arm->rtStatus.nDoFVelocity,
116 arm->rtStatus.desiredJointTorque,
117 arm->rtStatus.desiredJointVelocity);
118 }
119
120 template <typename NJointControllerType, typename CollisionCtrlCfg>
121 void
123 const IceUtil::Time& /*sensorValuesTimestamp*/,
124 const IceUtil::Time& timeSinceLastIteration)
125 {
126 double deltaT = timeSinceLastIteration.toSecondsDouble();
127 // globalPose = rtGetRobot()->getRobotNode("root")->getGlobalPose();
128
129 if (collReady_.load())
130 {
132 coll->updateRtConfigFromUser();
133 coll->updateRtCollisionObjects();
134 coll->rtCollisionChecking();
135 }
136 for (auto& pair : this->limb)
137 {
138 this->limbRTUpdateStatus(pair.second, deltaT);
139 }
140
141 this->rtRunCoordinator(deltaT);
142
143 for (auto& pair : this->limb)
144 {
145 limbRT(pair.second);
146 }
147 if (this->hands)
148 {
149 this->hands->updateRTStatus(deltaT);
150 }
151 }
152
153 template <typename NJointControllerType, typename CollisionCtrlCfg>
154 void
156 const ::armarx::aron::data::dto::DictPtr& dto,
157 const Ice::Current& /*iceCurrent*/)
158 {
160 auto cfg = common::control_law::arondto::ObjectCollisionAvoidanceConfigDict::FromAron(dto);
161 coll->setUserCfg(cfg);
162 }
163
164 template <typename NJointControllerType, typename CollisionCtrlCfg>
165 void
167 {
168 size_t numCollisionObjects = 0;
169 for (const auto& pair : collisionObjects)
170 {
171 numCollisionObjects += pair.second.size();
172 }
173
174 std::vector<hpp::fcl::CollisionObject> allCollisionObjects;
175 allCollisionObjects.reserve(numCollisionObjects);
176 for (const auto& pair : collisionObjects)
177 {
178 allCollisionObjects.insert(
179 allCollisionObjects.end(), pair.second.begin(), pair.second.end());
180 }
181
182 coll->updateUserCollisionObjects(allCollisionObjects);
183 }
184
185 template <typename NJointControllerType, typename CollisionCtrlCfg>
186 void
188 const Ice::Current& /*iceCurrent*/)
189 {
190 coll->deleteUserCollisionObjects();
191 }
192
193 template <typename NJointControllerType, typename CollisionCtrlCfg>
194 void
196 const std::string& primitiveSourceName,
197 const ::armarx::aron::data::dto::DictPtr& dtoScene,
198 const Ice::Current& /*iceCurrent*/)
199 {
200 ARMARX_INFO_S << "updateCollisionObjects";
201 auto scene = common::control_law::arondto::CollisionScene::FromAron(dtoScene);
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 =
213 collisionObjects[primitiveSourceName];
214 collisionObjectsOfSource.clear();
215 collisionObjectsOfSource.reserve(boxes.size() + spheres.size() + cylinders.size() +
216 capsules.size() + ellipsoids.size());
217
218 for (const auto& box : boxes)
219 {
220 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
221 simox::control::utils::primitive::Box{
222 .lengthX = box.lengthX, .lengthY = box.lengthY, .lengthZ = box.lengthZ},
223 Eigen::Isometry3d{box.transformation}));
224 }
225
226 for (const auto& sphere : spheres)
227 {
228 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
229 simox::control::utils::primitive::Sphere{.radius = sphere.radius},
230 Eigen::Isometry3d{sphere.transformation}));
231 }
232
233 for (const auto& cylinder : cylinders)
234 {
235 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
236 simox::control::utils::primitive::Cylinder{.radius = cylinder.radius,
237 .lengthY = cylinder.lengthY},
238 Eigen::Isometry3d{cylinder.transformation}));
239 }
240
241 for (const auto& capsule : capsules)
242 {
243 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
244 simox::control::utils::primitive::Capsule{.radius = capsule.radius,
245 .lengthY = capsule.lengthY},
246 Eigen::Isometry3d{capsule.transformation}));
247 }
248
249 for (const auto& ellipsoid : ellipsoids)
250 {
251 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
252 simox::control::utils::primitive::Ellipsoid{.lengthX = ellipsoid.lengthX,
253 .lengthY = ellipsoid.lengthY,
254 .lengthZ = ellipsoid.lengthZ},
255 Eigen::Isometry3d{ellipsoid.transformation}));
256 }
257
259 }
260
261 template <typename NJointControllerType, typename CollisionCtrlCfg>
264 const Ice::Current& /*iceCurrent*/)
265 {
266 if (not collReady_.load())
267 {
268 return nullptr;
269 }
270
272 return coll->userCfg.toAronDTO();
273 }
274
275 template <typename NJointControllerType, typename CollisionCtrlCfg>
276 void
278 const ::armarx::aron::data::dto::DictPtr& dto,
279 const Ice::Current& /*iceCurrent*/)
280 {
281 NJointControllerType::updateConfig(dto);
282 userCfgWithColl_ = CollisionCtrlCfg::FromAron(dto);
284 coll->setUserCfg(userCfgWithColl_.coll);
285 }
286
287 template <typename NJointControllerType, typename CollisionCtrlCfg>
290 const Ice::Current& /*iceCurrent*/)
291 {
292 // for (auto& pair : this->limb)
293 // {
294 // this->userConfig.limbs.at(pair.first) =
295 // pair.second->bufferConfigRtToUser.getUpToDateReadBuffer();
296 // }
297 NJointControllerType::getConfig();
298 userCfgWithColl_.limbs = this->userConfig.limbs;
299 userCfgWithColl_.hands = this->userConfig.hands;
300 return userCfgWithColl_.toAronDTO();
301 }
302
303 template <typename NJointControllerType, typename CollisionCtrlCfg>
304 void
306 const SensorAndControl& sc,
307 const DebugDrawerInterfacePrx& drawer,
308 const DebugObserverInterfacePrx& debugObs)
309 {
310 NJointControllerType::onPublish(sc, drawer, debugObs);
311 if (coll)
312 {
313 for (auto& pair : coll->collLimb)
314 {
315 collLimbPublish(pair.second, debugObs);
316 }
317 }
318 }
319
320 template <typename NJointControllerType, typename CollisionCtrlCfg>
321 void
324 const DebugObserverInterfacePrx& debugObs)
325 {
326 // double limbTimeMeasure = IceUtil::Time::now().toMicroSecondsDouble();
327
328 StringVariantBaseMap datafields;
329 auto rtStatus = arm.bufferRTtoPublish.getUpToDateReadBuffer();
330 auto recoveryState = arm.bufferRecoveryStateSelfColl.getUpToDateReadBuffer();
331
332 datafields["collDistanceThreshold"] = new Variant(recoveryState.collDistanceThreshold);
333 datafields["collDistanceThresholdInit"] =
334 new Variant(recoveryState.collDistanceThresholdInit);
335
336 datafields["trackingError"] = new Variant(rtStatus.trackingError);
337 common::debugEigenVec(datafields, "desiredJointTorques", rtStatus.desiredJointTorques);
338 common::debugEigenVec(datafields, "selfCollisionTorque", rtStatus.selfCollisionJointTorque);
339 common::debugEigenVec(datafields, "jointLimitTorque", rtStatus.jointLimitJointTorque);
340
341 datafields["selfColAdmInterface.active"] =
342 new Variant(static_cast<float>(rtStatus.selfColAdmInterface.active));
344 datafields, "selfColAdmInterface.jointVel", rtStatus.selfColAdmInterface.jointVel);
345 datafields["selfColAdmInterface.nDoFVel"] =
346 new Variant(static_cast<float>(rtStatus.selfColAdmInterface.nDoFVel));
347
348
349 datafields["jointLimAdmInterface.active"] =
350 new Variant(static_cast<float>(rtStatus.jointLimAdmInterface.active));
352 datafields, "jointLimAdmInterface.jointVel", rtStatus.jointLimAdmInterface.jointVel);
353 datafields["jointLimAdmInterface.nDoFVel"] =
354 new Variant(static_cast<float>(rtStatus.jointLimAdmInterface.nDoFVel));
355
357 datafields, "projectedImpedanceTorque", rtStatus.projImpedanceJointTorque);
358 // common::debugEigenVec(datafields, "projectedJointLimitTorque", rtStatus.projJointLimTorque);
359 // common::debugEigenVec(datafields, "projectedForceImpedance", rtStatus.projForceImpedance);
360 // common::debugEigenVec(
361 // datafields, "projectedSelfCollisionTorque", rtStatus.projSelfCollTorque);
362
363 const Eigen::VectorXf selfCollNullspace = rtStatus.selfCollNullSpace.diagonal();
364 const Eigen::VectorXf jointLimNullspace = rtStatus.jointLimNullSpace.diagonal();
365 common::debugEigenVec(datafields, "selfCollNullspaceDiagonal", selfCollNullspace);
366 common::debugEigenVec(datafields, "jointLimNullspaceDiagonal", jointLimNullspace);
367
368 // if (rtData.enableJointLimitAvoidance)
369 // {
370 // for (size_t i = 0; i < rtStatus.jointLimitData.size(); ++i)
371 // {
372 // if (not rtStatus.jointLimitData[i].isLimitless)
373 // {
374 // datafields["n_des(q)_" + std::to_string(i) + "_" +
375 // rtStatus.jointLimitData[i].jointName] =
376 // new Variant(rtStatus.jointLimitData[i].desiredNSjointLim);
377 // datafields["q_damping" + std::to_string(i) + "_" +
378 // rtStatus.jointLimitData[i].jointName] =
379 // new Variant(rtStatus.jointLimitData[i].totalDamping);
380 // datafields["q_repTorque" + std::to_string(i) + "_" +
381 // rtStatus.jointLimitData[i].jointName] =
382 // new Variant(rtStatus.jointLimitData[i].repulsiveTorque);
383 // }
384 // }
385 // }
386
387 datafields["collisionPairsNum"] = new Variant(rtStatus.collisionPairsNum);
388 datafields["activeCollPairsNum"] = new Variant(rtStatus.activeCollPairsNum);
389
390 datafields["collisionPairTime"] = new Variant(rtStatus.collisionPairTime);
391 datafields["collisionTorqueTime"] = new Variant(rtStatus.collisionTorqueTime);
392 datafields["jointLimitTorqueTime"] = new Variant(rtStatus.jointLimitTorqueTime);
393 datafields["selfCollNullspaceTime"] = new Variant(rtStatus.selfCollNullspaceTime);
394 datafields["jointLimitNullspaceTime"] = new Variant(rtStatus.jointLimitNullspaceTime);
395
396 datafields["impForceRatio"] = new Variant(rtStatus.impForceRatio);
397 datafields["impTorqueRatio"] = new Variant(rtStatus.impTorqueRatio);
398
399 for (unsigned int i = 0; i < rtStatus.activeCollPairsNum; ++i)
400 {
401 //size_t index = rtStatus.distanceIndexPairs[i].second;
402 datafields[std::to_string(i) + "_minDistance"] =
403 new Variant(rtStatus.collDataVec[i].minDistance);
404 datafields[std::to_string(i) + "_repForce"] =
405 new Variant(rtStatus.collDataVec[i].repulsiveForce);
406 datafields[std::to_string(i) + "_dampingForce"] = new Variant(
407 -1.0f * rtStatus.collDataVec[i].damping * rtStatus.collDataVec[i].distanceVelocity);
408 datafields[std::to_string(i) + "_n_des(d)"] =
409 new Variant(rtStatus.collDataVec[i].desiredNSColl);
411 datafields, std::to_string(i) + "_point", rtStatus.collDataVec[i].point1);
413 datafields, std::to_string(i) + "_dir", rtStatus.collDataVec[i].direction);
414 }
415
416
417 // /// prepare test case config
418 // const float tolerance = 1e-9f;
419 // if (rtData.testConfig == 1)
420 // {
421 // if (rtStatus.evalData[0].nodeName == "ArmL8_Wri2")
422 // {
423 // // set distance
424 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_dist"] =
425 // new Variant(rtStatus.evalData[0].minDistance);
426 // // set f_rep, damping, desired NS space
427
428
429 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_repF"] =
430 // new Variant(rtStatus.evalData[0].repulsiveForce);
431 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_projMass"] =
432 // new Variant(rtStatus.evalData[0].projectedMass);
433 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_locStiffness"] =
434 // new Variant(rtStatus.evalData[0].localStiffness);
435 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_dampFactor"] =
436 // new Variant(rtStatus.evalData[0].damping);
437 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_distVel"] =
438 // new Variant(rtStatus.evalData[0].distanceVelocity);
439 // if (fabs(rtStatus.evalData[0].damping + 1.0f) < tolerance)
440 // {
441 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_dampForce"] =
442 // new Variant(0.0);
443 // }
444 // else
445 // {
446 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_dampForce"] =
447 // new Variant(-1.0 * rtStatus.evalData[0].damping *
448 // rtStatus.evalData[0].distanceVelocity);
449 // }
450
451 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_n_des(d)"] =
452 // new Variant(rtStatus.evalData[0].desiredNSColl);
453 // }
454 // if (rtStatus.evalData[1].nodeName == "ArmL8_Wri2")
455 // {
456 // // set distance
457 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_dist"] =
458 // new Variant(rtStatus.evalData[1].minDistance);
459 // // set f_rep, damping, desired NS space
460
461 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_repF"] =
462 // new Variant(rtStatus.evalData[1].repulsiveForce);
463 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_projMass"] =
464 // new Variant(rtStatus.evalData[1].projectedMass);
465 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_locStiffness"] =
466 // new Variant(rtStatus.evalData[1].localStiffness);
467 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_dampFactor"] =
468 // new Variant(rtStatus.evalData[1].damping);
469 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_distVel"] =
470 // new Variant(rtStatus.evalData[1].distanceVelocity);
471 // if (fabs(rtStatus.evalData[1].damping + 1.0f) < tolerance)
472 // {
473 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_dampForce"] =
474 // new Variant(0.0);
475 // }
476 // else
477 // {
478 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_dampForce"] =
479 // new Variant(-1.0 * rtStatus.evalData[1].damping *
480 // rtStatus.evalData[1].distanceVelocity);
481 // }
482
483 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_n_des(d)"] =
484 // new Variant(rtStatus.evalData[1].desiredNSColl);
485 // }
486 // if (rtStatus.evalData[2].nodeName == "ArmL7_Wri1")
487 // {
488 // // set distance
489 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_dist"] =
490 // new Variant(rtStatus.evalData[2].minDistance);
491 // // set f_rep, damping, desired NS space
492
493 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_repF"] =
494 // new Variant(rtStatus.evalData[2].repulsiveForce);
495
496 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_projMass"] =
497 // new Variant(rtStatus.evalData[2].projectedMass);
498 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_locStiffness"] =
499 // new Variant(rtStatus.evalData[2].localStiffness);
500 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_dampFactor"] =
501 // new Variant(rtStatus.evalData[2].damping);
502 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_distVel"] =
503 // new Variant(rtStatus.evalData[2].distanceVelocity);
504 // if (fabs(rtStatus.evalData[2].damping + 1.0f) < tolerance)
505 // {
506 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_dampForce"] =
507 // new Variant(0.0);
508 // }
509 // else
510 // {
511 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_dampForce"] =
512 // new Variant(-1.0 * rtStatus.evalData[2].damping *
513 // rtStatus.evalData[2].distanceVelocity);
514 // }
515
516
517 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_n_des(d)"] =
518 // new Variant(rtStatus.evalData[2].desiredNSColl);
519 // }
520 // if (rtStatus.evalData[3].nodeName == "ArmL8_Wri2")
521 // {
522 // // set distance
523 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_dist"] =
524 // new Variant(rtStatus.evalData[3].minDistance);
525 // // set f_rep, damping, desired NS space
526
527 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_repF"] =
528 // new Variant(rtStatus.evalData[3].repulsiveForce);
529
530 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_projMass"] =
531 // new Variant(rtStatus.evalData[3].projectedMass);
532 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_locStiffness"] =
533 // new Variant(rtStatus.evalData[3].localStiffness);
534 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_dampFactor"] =
535 // new Variant(rtStatus.evalData[3].damping);
536 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_distVel"] =
537 // new Variant(rtStatus.evalData[3].distanceVelocity);
538 // if (fabs(rtStatus.evalData[3].damping + 1.0f) < tolerance)
539 // {
540 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_dampForce"] =
541 // new Variant(0.0);
542 // }
543 // else
544 // {
545 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_dampForce"] =
546 // new Variant(-1.0 * rtStatus.evalData[3].damping *
547 // rtStatus.evalData[3].distanceVelocity);
548 // }
549
550
551 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_n_des(d)"] =
552 // new Variant(rtStatus.evalData[3].desiredNSColl);
553 // }
554
555 // if (rtStatus.evalData[4].nodeName == "ArmL8_Wri2")
556 // {
557 // // set distance
558 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_dist"] =
559 // new Variant(rtStatus.evalData[4].minDistance);
560 // // set f_rep, damping, desired NS space
561
562 // // values have been calculated
563 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_repF"] =
564 // new Variant(rtStatus.evalData[4].repulsiveForce);
565
566 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_projMass"] =
567 // new Variant(rtStatus.evalData[4].projectedMass);
568 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_locStiffness"] =
569 // new Variant(rtStatus.evalData[4].localStiffness);
570 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_dampFactor"] =
571 // new Variant(rtStatus.evalData[4].damping);
572 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_distVel"] =
573 // new Variant(rtStatus.evalData[4].distanceVelocity);
574 // if (fabs(rtStatus.evalData[4].damping + 1.0f) < tolerance)
575 // {
576 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_dampForce"] =
577 // new Variant(0.0);
578 // }
579 // else
580 // {
581 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_dampForce"] =
582 // new Variant(-1.0 * rtStatus.evalData[4].damping *
583 // rtStatus.evalData[4].distanceVelocity);
584 // }
585
586
587 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_n_des(d)"] =
588 // new Variant(rtStatus.evalData[4].desiredNSColl);
589 // }
590 // if (rtStatus.evalData[5].nodeName == "ArmL8_Wri2")
591 // {
592 // // set distance
593 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_dist"] =
594 // new Variant(rtStatus.evalData[5].minDistance);
595
596 // // values have been calculated
597 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_repF"] =
598 // new Variant(rtStatus.evalData[5].repulsiveForce);
599
600 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_projMass"] =
601 // new Variant(rtStatus.evalData[5].projectedMass);
602 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_locStiffness"] =
603 // new Variant(rtStatus.evalData[5].localStiffness);
604 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_dampFactor"] =
605 // new Variant(rtStatus.evalData[5].damping);
606 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_distVel"] =
607 // new Variant(rtStatus.evalData[5].distanceVelocity);
608 // if (fabs(rtStatus.evalData[5].damping + 1.0f) < tolerance)
609 // {
610 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_dampForce"] =
611 // new Variant(0.0);
612 // }
613 // else
614 // {
615 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_dampForce"] =
616 // new Variant(-1.0 * rtStatus.evalData[5].damping *
617 // rtStatus.evalData[5].distanceVelocity);
618 // }
619
620
621 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_n_des(d)"] =
622 // new Variant(rtStatus.evalData[5].desiredNSColl);
623 // }
624 // if (rtStatus.evalData[6].nodeName == "ArmL5_Elb1")
625 // {
626 // // set distance
627 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_dist"] =
628 // new Variant(rtStatus.evalData[6].minDistance);
629
630 // // values have been calculated
631 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_repF"] =
632 // new Variant(rtStatus.evalData[6].repulsiveForce);
633
634 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_projMass"] =
635 // new Variant(rtStatus.evalData[6].projectedMass);
636 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_locStiffness"] =
637 // new Variant(rtStatus.evalData[6].localStiffness);
638 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_dampFactor"] =
639 // new Variant(rtStatus.evalData[6].damping);
640 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_distVel"] =
641 // new Variant(rtStatus.evalData[6].distanceVelocity);
642 // if (fabs(rtStatus.evalData[6].damping + 1.0f) < tolerance)
643 // {
644 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_dampForce"] =
645 // new Variant(0.0);
646 // }
647 // else
648 // {
649 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_dampForce"] =
650 // new Variant(-1.0 * rtStatus.evalData[6].damping *
651 // rtStatus.evalData[6].distanceVelocity);
652 // }
653
654
655 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_n_des(d)"] =
656 // new Variant(rtStatus.evalData[6].desiredNSColl);
657 // }
658 // }
659
660
661 //double selfCollDebugTime = IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
662 //datafields["selfCollDebugTime"] = new Variant(selfCollDebugTime);
663
664 // debug value assignment torso, neck joints
665 // datafields["torsoJointValue_float"] = new Variant(rtStatus.torsoJointValuef);
666 // datafields["neck1JointValue_float"] = new Variant(rtStatus.neck1JointValuef);
667 // datafields["neck2JointValue_float"] = new Variant(rtStatus.neck2JointValuef);
668
669 // datafields["torsoJointValue_double"] = new Variant(rtStatus.torsoJointValued);
670 // datafields["neck1JointValue_double"] = new Variant(rtStatus.neck1JointValued);
671 // datafields["neck2JointValue_double"] = new Variant(rtStatus.neck2JointValued);
672
673 // common::debugEigenVec(
674 // datafields, "set_ActuatedJointValues", rtStatus.setActuatedJointValues.cast<float>());
675 // common::debugEigenVec(
676 // datafields, "get_ActuatedJointValues", rtStatus.getActuatedJointValues.cast<float>());
677
678 // double limbTime = IceUtil::Time::now().toMicroSecondsDouble() - limbTimeMeasure;
679 // datafields["limbOnPublishTime"] = new Variant(limbTime);
680
681 debugObs->setDebugChannel("CollAvoid_ImpCtrl_" + arm.nodeSetName, datafields);
682 }
683
684 template <typename NJointControllerType, typename CollisionCtrlCfg>
685 void
687 viz::Layer& layer,
688 const std::vector<hpp::fcl::CollisionObject>& objects)
689 {
690 for (size_t i = 0; i < objects.size(); ++i)
691 {
692 auto object = objects.at(i);
693 const auto position = object.getTranslation().cast<float>() * 1000;
694 const Eigen::Matrix3f rotation = object.getRotation().cast<float>();
695
696 switch (object.getNodeType())
697 {
698 case hpp::fcl::NODE_TYPE::GEOM_BOX:
699 {
700 const hpp::fcl::Box* box =
701 std::static_pointer_cast<hpp::fcl::Box>(object.collisionGeometry()).get();
702 const viz::Box vizObject = viz::Box("box " + std::to_string(i))
703 .size(box->halfSide.cast<float>() * 1000 * 2)
704 .orientation(rotation)
705 .position(position)
706 .color(255, 0, 0, 128);
707 layer.add(vizObject);
708 break;
709 }
710 case hpp::fcl::NODE_TYPE::GEOM_SPHERE:
711 {
712 const hpp::fcl::Sphere* sphere =
713 std::static_pointer_cast<hpp::fcl::Sphere>(object.collisionGeometry())
714 .get();
715 const viz::Sphere vizObject =
716 viz::Sphere("sphere " + std::to_string(i))
717 .radius(static_cast<float>(sphere->radius) * 1000)
718 .orientation(rotation)
719 .position(position)
720 .color(0, 0, 255, 128);
721 layer.add(vizObject);
722 break;
723 }
724 case hpp::fcl::NODE_TYPE::GEOM_CYLINDER:
725 {
726 const hpp::fcl::Cylinder* cylinder =
727 std::static_pointer_cast<hpp::fcl::Cylinder>(object.collisionGeometry())
728 .get();
729 const viz::Cylinder vizObject =
730 viz::Cylinder("cylinder " + std::to_string(i))
731 .height(static_cast<float>(cylinder->halfLength) * 1000 * 2)
732 .radius(static_cast<float>(cylinder->radius) * 1000)
733 .orientation(rotation *
734 Eigen::AngleAxisf(M_PI / 2., Eigen::Vector3f::UnitX()))
735 .position(position)
736 .color(0, 255, 0, 128);
737 layer.add(vizObject);
738 break;
739 }
740 case hpp::fcl::NODE_TYPE::GEOM_CAPSULE:
741 {
742 const hpp::fcl::Capsule* capsule =
743 std::static_pointer_cast<hpp::fcl::Capsule>(object.collisionGeometry())
744 .get();
745 const auto _rotation =
746 rotation * Eigen::AngleAxisf(M_PI / 2., Eigen::Vector3f::UnitX());
747 Eigen::Vector3f offset;
748 offset << 0, static_cast<float>(capsule->halfLength) * 1000, 0;
749 offset = _rotation * offset;
750
751 const viz::Sphere cap1 = viz::Sphere("capsule_cap1 " + std::to_string(i))
752 .radius(static_cast<float>(capsule->radius) * 1000)
753 .position(position + offset)
754 .orientation(_rotation)
755 .color(255, 200, 0, 128);
756 const viz::Sphere cap2 = viz::Sphere("capsule_cap2 " + std::to_string(i))
757 .radius(static_cast<float>(capsule->radius) * 1000)
758 .position(position - offset)
759 .orientation(_rotation)
760 .color(255, 200, 0, 128);
761 const viz::Cylinder vizObject =
762 viz::Cylinder("capsule_mid " + std::to_string(i))
763 .height(static_cast<float>(capsule->halfLength) * 1000 * 2)
764 .radius(static_cast<float>(capsule->radius) * 1000)
765 .color(255, 200, 0, 128)
766 .orientation(_rotation)
767 .position(position);
768 layer.add(vizObject);
769 layer.add(cap1);
770 layer.add(cap2);
771 break;
772 }
773 case hpp::fcl::NODE_TYPE::GEOM_ELLIPSOID:
774 {
775 const hpp::fcl::Ellipsoid* ellipsoid =
776 std::static_pointer_cast<hpp::fcl::Ellipsoid>(object.collisionGeometry())
777 .get();
778 const viz::Ellipsoid vizObject =
779 viz::Ellipsoid("ellipsoid " + std::to_string(i))
780 // axis lengths seem to be radii instead of axis lengths
781 .axisLengths(ellipsoid->radii.cast<float>() * 1000)
782 .orientation(rotation)
783 .position(position)
784 .color(255, 0, 200, 128);
785 layer.add(vizObject);
786 break;
787 }
788 default:;
789 }
790 }
791 }
792
793 template <typename NJointControllerType, typename CollisionCtrlCfg>
794 void
796 viz::StagedCommit& stage) const
797 {
798 NJointControllerType::collectArviz(stage);
799
800 auto transformVector = [](const Eigen::Matrix4f& pose,
801 const Eigen::Vector3f& vec) -> Eigen::Vector3f
802 { return common::getOri(pose) * vec + common::getPos(pose); };
803
804 if (coll)
805 {
806 for (const auto& [_, arm] : coll->collLimb)
807 {
808 const auto& rtStatus = arm.bufferRTtoPublish.getUpToDateReadBuffer();
809
810 viz::Layer layer = this->scopedArviz->layer("ColStatus_" + arm.nodeSetName);
811
812 for (unsigned int i = 0; i < rtStatus.activeCollPairsNum; ++i)
813 {
814 // visualize impedance force
815 // layer.add(viz::Arrow("projImpForce_" + std::to_string(i))
816 // .fromTo(rtStatus.collDataVec[i].point * 1000.0,
817 // rtStatus.collDataVec[i].point * 1000.0 +
818 // rtStatus.collDataVec[i].projectedImpedanceForce *
819 // rtStatus.collDataVec[i].direction * 5.0)
820 // .color(simox::Color::purple()));
821
822 // layer.add(viz::Arrow("impForce_" + std::to_string(i))
823 // .fromTo(rtStatus.collDataVec[i].point * 1000.0,
824 // rtStatus.collDataVec[i].point * 1000.0 +
825 // rtStatus.forceImpedance.head<3>().dot(
826 // rtStatus.collDataVec[i].direction) *
827 // rtStatus.collDataVec[i].direction * 5.0)
828 // .color(simox::Color::yellow())); // project forceImp in dir of collision
829
830 layer.add(
831 viz::Arrow("Force_" + std::to_string(i))
832 .fromTo(transformVector(rtStatus.globalPose,
833 rtStatus.collDataVec[i].point1 * 1000.0F),
834 transformVector(rtStatus.globalPose,
835 rtStatus.collDataVec[i].point1 * 1000.0F +
836 rtStatus.collDataVec[i].direction * 50.0F *
837 rtStatus.collDataVec[i].repulsiveForce))
838 .color(simox::Color::blue())
839 .width(5.0f));
840 }
841
842 layer.add(viz::Pose("RootPose").pose(rtStatus.globalPose).scale(2));
843
844 // visualize impedance force
845 // layer.add(viz::Arrow("impForce")
846 // .fromTo(transformVector(rtStatus.globalPose,
847 // rtStatus.currentPose.block<3, 1>(0, 3)),
848 // transformVector(rtStatus.globalPose,
849 // rtStatus.currentPose.block<3, 1>(0, 3) +
850 // rtStatus.forceImpedance.head<3>() * 1000.0))
851 // .color(simox::Color::yellow()));
852 // layer.add(viz::Arrow("projImpForce")
853 // .fromTo(rtStatus.currentPose.block<3, 1>(0, 3),
854 // rtStatus.currentPose.block<3, 1>(0, 3) +
855 // rtStatus.projForceImpedance.head<3>() * 1000.0)
856 // .color(simox::Color::purple()));
857
858 stage.add(layer);
859 }
860
861 if (not coll->userCollisionObjects.empty())
862 {
863 viz::Layer layer = this->scopedArviz->layer("ColStatus_objectModels");
864 AddArvizObjects(layer, coll->userCollisionObjects);
865 stage.add(layer);
866 }
867 const bool enableRobotPrimitiveVis = true;
868 if (enableRobotPrimitiveVis)
869 {
870 // TODO uses rt collision robot
871 const auto& robotObjects =
872 coll->collisionRobot->getCollisionManager()->getObjects();
873 std::vector<hpp::fcl::CollisionObject> robotObjectsByValue;
874 robotObjectsByValue.reserve(robotObjects.size());
875 for (const auto* ptr : robotObjects)
876 {
877 robotObjectsByValue.push_back(*ptr);
878 }
879 viz::Layer layer = this->scopedArviz->layer("ColStatus_robotModel");
880 AddArvizObjects(layer, robotObjectsByValue);
881 stage.add(layer);
882 }
883 }
884 }
885
886 template <typename NJointControllerType, typename CollisionCtrlCfg>
887 void
889 {
890 // ARMARX_RT_LOGF_INFO("rt Preactivate controller "
891 // "NJointTaskspaceCollisionAvoidanceMixedImpedanceVelocityController");
892 NJointControllerType::rtPreActivateController();
894 if (collReady_.load())
895 {
897 coll->rtPreActivate();
898 }
899 }
900
901 template <typename NJointControllerType, typename CollisionCtrlCfg>
902 void
904 {
905 NJointControllerType::rtPostDeactivateController();
906 if (collReady_.load())
907 {
909 coll->rtPostDeactivate();
910 }
911 // ARMARX_RT_LOGF_INFO("-- post deactivate: "
912 // "NJointTaskspaceCollisionAvoidanceMixedImpedanceVelocityController");
913 }
914
915 template <typename NJointControllerType, typename CollisionCtrlCfg>
918 const StringVariantBaseMap& values)
919 {
920 auto cfgName = values.at("config_box")->getString();
921 const armarx::PackagePath configPath(
922 "armarx_control",
923 "controller_config/" + std::string(NJointControllerType::ControlType::TypeName) +
924 "Col/" + cfgName + ".json");
925 ARMARX_INFO_S << "Loading config from " << configPath.toSystemPath();
926 ARMARX_CHECK(std::filesystem::exists(configPath.toSystemPath()));
927
928 auto cfgDTO = armarx::readFromJson<CollisionCtrlCfg>(configPath.toSystemPath());
929
931 return new ConfigurableNJointControllerConfig{cfgDTO.toAronDTO()};
932 }
933
934 /// ================================== TSMixImpVelCol ==================================
936 law::arondto::TSMixImpVelColConfigDict>;
937
940
942 const RobotUnitPtr& robotUnit,
943 const NJointControllerConfigPtr& config,
944 const VirtualRobot::RobotPtr& robot) :
945 // NJointTSMixImpVelController(robotUnit, config, robot),
946 NJointTSColController<NJointTSMixImpVelController, law::arondto::TSMixImpVelColConfigDict>(
947 robotUnit,
948 config,
949 robot)
950 {
951 }
952
953 std::string
954 NJointTSMixImpVelColController::getClassName(const Ice::Current& /*unused*/) const
955 {
956 return "TSMixImpVelCol";
957 }
958
959 /// ================================== TSImpCol ==================================
960
962
965
967 const NJointControllerConfigPtr& config,
968 const VirtualRobot::RobotPtr& robot) :
969 // NJointTSImpController(robotUnit, config, robot),
971 config,
972 robot)
973 {
974 }
975
976 std::string
977 NJointTSImpColController::getClassName(const Ice::Current& /*unused*/) const
978 {
979 return "TSImpCol";
980 }
981
982 /// ================================== TSVeloCol ==================================
983
985
988
990 const NJointControllerConfigPtr& config,
991 const VirtualRobot::RobotPtr& robot) :
992 // NJointTSVelController(robotUnit, config, robot),
994 config,
995 robot)
996 {
997 }
998
999 std::string
1000 NJointTSVeloColController::getClassName(const Ice::Current& /*unused*/) const
1001 {
1002 return "TSVeloCol";
1003 }
1004
1005
1006} // namespace armarx::control::njoint_controller::task_space
#define M_PI
Definition MathTools.h:17
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 collectArviz(viz::StagedCommit &stage) const override
Definition ColAvoid.cpp:795
NJointTSColController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
Definition ColAvoid.cpp:53
std::map< std::string, std::vector< hpp::fcl::CollisionObject > > collisionObjects
Definition ColAvoid.h:100
static ConfigPtrT GenerateConfigFromVariants(const StringVariantBaseMap &values)
Definition ColAvoid.cpp:917
static void AddArvizObjects(viz::Layer &layer, const std::vector< hpp::fcl::CollisionObject > &objects)
Definition ColAvoid.cpp:686
void collLimbPublish(CollAvoidBase::NodeSetData &arm, const DebugObserverInterfacePrx &debugObs)
Definition ColAvoid.cpp:322
void updateCollisionAvoidanceConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
NJointController interface for collision avoidance.
Definition ColAvoid.cpp:155
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration) override
Definition ColAvoid.cpp:122
typename NJointControllerType::ConfigPtrT ConfigPtrT
Definition ColAvoid.h:49
void onPublish(const SensorAndControl &sc, const DebugDrawerInterfacePrx &drawer, const DebugObserverInterfacePrx &) override
Definition ColAvoid.cpp:305
::armarx::aron::data::dto::DictPtr getConfig(const Ice::Current &iceCurrent) override
Definition ColAvoid.cpp:289
void updateCollisionObjects(const std::string &primitiveSourceName, const ::armarx::aron::data::dto::DictPtr &dtoScene, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
Definition ColAvoid.cpp:195
void rtPreActivateController() override
NJointControllerBase interface.
Definition ColAvoid.cpp:888
void updateConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent) override
Definition ColAvoid.cpp:277
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override
Definition ColAvoid.cpp:977
NJointTSImpColController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
Definition ColAvoid.cpp:966
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override
Definition ColAvoid.cpp:954
NJointTSMixImpVelColController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
Definition ColAvoid.cpp:941
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override
NJointTSVeloColController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
Definition ColAvoid.cpp:989
void limbRTSetTarget(ArmPtr &arm, const size_t nDoFTorque, const size_t nDoFVelocity, const Eigen::VectorXf &targetTorque, const Eigen::VectorXf &targetVelocity)
Definition Base.cpp:380
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
DerivedT & scale(Eigen::Vector3f scale)
Definition ElementOps.h:254
#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_S
Definition Logging.h:202
armarx::aron::data::dto::Dict getCollisionAvoidanceConfig()
std::shared_ptr< class Robot > RobotPtr
Definition Bus.h:19
::IceInternal::Handle< Dict > DictPtr
void debugEigenVec(StringVariantBaseMap &datafields, const std::string &name, Eigen::VectorXf vec)
Definition utils.cpp:190
Eigen::Block< Eigen::Matrix4f, 3, 3 > getOri(Eigen::Matrix4f &matrix)
Definition utils.cpp:265
Eigen::Block< Eigen::Matrix4f, 3, 1 > getPos(Eigen::Matrix4f &matrix)
Definition utils.cpp:301
NJointControllerRegistration< NJointTSVeloColController > registrationControllerNJointTSVeloColController("TSVeloCol")
NJointControllerRegistration< NJointTSMixImpVelColController > registrationControllerNJointTSMixImpVelColController("TSMixImpVelCol")
NJointControllerRegistration< NJointTSImpColController > registrationControllerNJointTSImpColController("TSImpCol")
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface > DebugObserverInterfacePrx
std::map< std::string, VariantBasePtr > StringVariantBaseMap
AronDTO readFromJson(const std::filesystem::path &filename)
IceUtil::Handle< class RobotUnit > RobotUnitPtr
Definition FTSensor.h:34
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugDrawerInterface > DebugDrawerInterfacePrx
detail::ControlThreadOutputBufferEntry SensorAndControl
Arrow & width(float w)
Definition Elements.h:211
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
A staged commit prepares multiple layers to be committed.
Definition Client.h:30
void add(Layer const &layer)
Stage a layer to be committed later via client.apply(*this)
Definition Client.h:36
#define ARMARX_TRACE
Definition trace.h:77