ColAvoidVel.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 "ColAvoidVel.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>
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 coll = std::make_shared<CollAvoidVelBase>(this->rtGetRobot(), userCfgWithColl.coll);
64 collReady.store(true);
65 // const std::string rootNodeName = "root";
66 // rootNode = this->rtGetRobot()->getRobotNode(rootNodeName);
67 }
68
69 template <typename NJointControllerType, typename CollisionCtrlCfg>
70 void
72 ArmPtr& arm,
73 const double deltaT)
74 {
75 // limbRTUpdateStatus(arm, deltaT);
77 arm->controller.run(arm->rtConfig, arm->rtStatus);
78 // double time_run_rt = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
79
80 if (collReady.load())
81 {
83 // const std::string rootNodeName = "root";
84 // // coll->collLimb.at(arm->kinematicChainName)->rts.globalPose = rootNode->getGlobalPose();
85 // coll->collLimb.at(arm->kinematicChainName).rts.globalPose =
86 // this->rtGetRobot()->getGlobalPose();
87 coll->rtLimbControllerRun(arm->kinematicChainName,
88 arm->rtStatus.jointPosition,
89 arm->rtStatus.qvelFiltered,
90 arm->rtConfig.velocityLimit,
91 arm->rtStatus.desiredJointVelocity,
92 deltaT);
93 /// experimental implementation of admittance interface
94 arm->rtStatus.inertia = coll->collLimb.at(arm->kinematicChainName).rts.inertia;
95 }
96
97 if (collReady.load())
98 {
99 this->limbRTSetTarget(arm,
100 arm->rtStatus.nDoFTorque,
101 arm->rtStatus.nDoFVelocity,
102 arm->rtStatus.desiredJointTorque,
103 coll->collLimb.at(arm->kinematicChainName).rts.desiredJointVel);
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 }
114
115 template <typename NJointControllerType, typename CollisionCtrlCfg>
116 void
118 const IceUtil::Time& sensorValuesTimestamp,
119 const IceUtil::Time& timeSinceLastIteration)
120 {
121 double deltaT = timeSinceLastIteration.toSecondsDouble();
122 // globalPose = rtGetRobot()->getRobotNode("root")->getGlobalPose();
123
124 if (collReady.load())
125 {
127 coll->updateRtConfigFromUser();
128 coll->updateRtCollisionObjects();
129 coll->rtCollisionChecking();
130 }
131 for (auto& pair : this->limb)
132 {
133 this->limbRTUpdateStatus(pair.second, deltaT);
134 }
135
136 this->rtRunCoordinator(deltaT);
137
138 for (auto& pair : this->limb)
139 {
140 limbRT(pair.second, deltaT);
141 }
142 if (this->hands)
143 {
144 this->hands->updateRTStatus(deltaT);
145 }
146 }
147
148 template <typename NJointControllerType, typename CollisionCtrlCfg>
149 void
151 updateCollisionAvoidanceConfig(const ::armarx::aron::data::dto::DictPtr& dto,
152 const Ice::Current& iceCurrent)
153 {
155 auto cfg =
156 common::control_law::arondto::ObjectCollisionAvoidanceVelConfigDict::FromAron(dto);
157 coll->setUserCfg(cfg);
158 }
159
160 template <typename NJointControllerType, typename CollisionCtrlCfg>
161 void
163 {
164 size_t numCollisionObjects = 0;
165 for (const auto& pair : collisionObjects)
166 {
167 numCollisionObjects += pair.second.size();
168 }
169
170 std::vector<hpp::fcl::CollisionObject> allCollisionObjects;
171 allCollisionObjects.reserve(numCollisionObjects);
172 for (const auto& pair : collisionObjects)
173 {
174 allCollisionObjects.insert(
175 allCollisionObjects.end(), pair.second.begin(), pair.second.end());
176 }
177
178 coll->updateUserCollisionObjects(allCollisionObjects);
179 }
180
181 template <typename NJointControllerType, typename CollisionCtrlCfg>
182 void
184 const Ice::Current& iceCurrent)
185 {
186 coll->deleteUserCollisionObjects();
187 }
188
189 template <typename NJointControllerType, typename CollisionCtrlCfg>
190 void
192 const std::string& primitiveSourceName,
193 const ::armarx::aron::data::dto::DictPtr& dto,
194 const Ice::Current& iceCurrent)
195 {
196 ARMARX_INFO_S << "updateCollisionObjects";
197 auto scene = common::control_law::arondto::CollisionScene::FromAron(dto);
198 auto boxes = scene.boxes;
199 auto spheres = scene.spheres;
200 auto cylinders = scene.cylinders;
201 auto capsules = scene.capsules;
202 auto ellipsoids = scene.ellipsoids;
203
204 if (collisionObjects.count(primitiveSourceName) == 0)
205 {
206 collisionObjects.emplace(primitiveSourceName, std::vector<hpp::fcl::CollisionObject>());
207 }
208 std::vector<hpp::fcl::CollisionObject>& collisionObjectsOfSource =
209 collisionObjects[primitiveSourceName];
210 collisionObjectsOfSource.clear();
211 collisionObjectsOfSource.reserve(boxes.size() + spheres.size() + cylinders.size() +
212 capsules.size() + ellipsoids.size());
213
214 for (auto box : boxes)
215 {
216 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
217 simox::control::utils::primitive::Box{
218 .lengthX = box.lengthX, .lengthY = box.lengthY, .lengthZ = box.lengthZ},
219 Eigen::Isometry3d{box.transformation}));
220 }
221
222 for (auto sphere : spheres)
223 {
224 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
225 simox::control::utils::primitive::Sphere{.radius = sphere.radius},
226 Eigen::Isometry3d{sphere.transformation}));
227 }
228
229 for (auto cylinder : cylinders)
230 {
231 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
232 simox::control::utils::primitive::Cylinder{.radius = cylinder.radius,
233 .lengthY = cylinder.lengthY},
234 Eigen::Isometry3d{cylinder.transformation}));
235 }
236
237 for (auto capsule : capsules)
238 {
239 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
240 simox::control::utils::primitive::Capsule{.radius = capsule.radius,
241 .lengthY = capsule.lengthY},
242 Eigen::Isometry3d{capsule.transformation}));
243 }
244
245 for (auto ellipsoid : ellipsoids)
246 {
247 collisionObjectsOfSource.push_back(simox::control::environment::createCollisionObject(
248 simox::control::utils::primitive::Ellipsoid{.lengthX = ellipsoid.lengthX,
249 .lengthY = ellipsoid.lengthY,
250 .lengthZ = ellipsoid.lengthZ},
251 Eigen::Isometry3d{ellipsoid.transformation}));
252 }
253
255 }
256
257 template <typename NJointControllerType, typename CollisionCtrlCfg>
260 getCollisionAvoidanceConfig(const Ice::Current& iceCurrent)
261 {
262 if (not collReady.load())
263 return nullptr;
264
266 return coll->userCfg.toAronDTO();
267 }
268
269 template <typename NJointControllerType, typename CollisionCtrlCfg>
270 void
272 const ::armarx::aron::data::dto::DictPtr& dto,
273 const Ice::Current& iceCurrent)
274 {
275 NJointControllerType::updateConfig(dto);
276 userCfgWithColl = CollisionCtrlCfg::FromAron(dto);
278 coll->setUserCfg(userCfgWithColl.coll);
279 }
280
281 template <typename NJointControllerType, typename CollisionCtrlCfg>
284 const Ice::Current& iceCurrent)
285 {
286 // for (auto& pair : this->limb)
287 // {
288 // this->userConfig.limbs.at(pair.first) =
289 // pair.second->bufferConfigRtToUser.getUpToDateReadBuffer();
290 // }
291 NJointControllerType::getConfig();
292 userCfgWithColl.limbs = this->userConfig.limbs;
293 userCfgWithColl.hands = this->userConfig.hands; // TODO check this
294 return userCfgWithColl.toAronDTO();
295 }
296
297 template <typename NJointControllerType, typename CollisionCtrlCfg>
298 void
301 const DebugObserverInterfacePrx& debugObs)
302 {
303 // double limbTimeMeasure = IceUtil::Time::now().toMicroSecondsDouble();
304
305 StringVariantBaseMap datafields;
306 auto rtStatus = arm.bufferRTtoPublish.getUpToDateReadBuffer();
307 auto recoveryState = arm.bufferRecoveryStateSelfColl.getUpToDateReadBuffer();
308
309 datafields["collDistanceThreshold"] = new Variant(recoveryState.collDistanceThreshold);
310 datafields["collDistanceThresholdInit"] =
311 new Variant(recoveryState.collDistanceThresholdInit);
312
313 datafields["trackingError"] = new Variant(rtStatus.trackingError);
314 common::debugEigenVec(datafields, "desiredJointVel", rtStatus.desiredJointVel);
315 common::debugEigenVec(datafields, "selfCollisionTorque", rtStatus.selfCollisionJointVel);
316 common::debugEigenVec(datafields, "jointLimitTorque", rtStatus.jointLimitJointVel);
317
318 // common::debugEigenVec(
319 // datafields, "projectedImpedanceTorque", rtStatus.projImpedanceJointTorque);
320 // common::debugEigenVec(datafields, "projectedJointLimitTorque", rtStatus.projJointLimTorque);
321 // common::debugEigenVec(datafields, "projectedForceImpedance", rtStatus.projForceImpedance);
322 // common::debugEigenVec(
323 // datafields, "projectedSelfCollisionTorque", rtStatus.projSelfCollTorque);
324
325 const Eigen::VectorXf selfCollNullspace = rtStatus.selfCollNullSpace.diagonal();
326 const Eigen::VectorXf jointLimNullspace = rtStatus.jointLimNullSpace.diagonal();
327 common::debugEigenVec(datafields, "selfCollNullspaceDiagonal", selfCollNullspace);
328 common::debugEigenVec(datafields, "jointLimNullspaceDiagonal", jointLimNullspace);
329
330 // if (rtData.enableJointLimitAvoidance)
331 // {
332 // for (size_t i = 0; i < rtStatus.jointLimitData.size(); ++i)
333 // {
334 // if (not rtStatus.jointLimitData[i].isLimitless)
335 // {
336 // datafields["n_des(q)_" + std::to_string(i) + "_" +
337 // rtStatus.jointLimitData[i].jointName] =
338 // new Variant(rtStatus.jointLimitData[i].desiredNSjointLim);
339 // datafields["q_damping" + std::to_string(i) + "_" +
340 // rtStatus.jointLimitData[i].jointName] =
341 // new Variant(rtStatus.jointLimitData[i].totalDamping);
342 // datafields["q_repTorque" + std::to_string(i) + "_" +
343 // rtStatus.jointLimitData[i].jointName] =
344 // new Variant(rtStatus.jointLimitData[i].repulsiveTorque);
345 // }
346 // }
347 // }
348
349 datafields["collisionPairsNum"] = new Variant(rtStatus.collisionPairsNum);
350 datafields["activeCollPairsNum"] = new Variant(rtStatus.activeCollPairsNum);
351
352 datafields["collisionPairTime"] = new Variant(rtStatus.collisionPairTime);
353 datafields["collisionTorqueTime"] = new Variant(rtStatus.collisionTorqueTime);
354 datafields["jointLimitTorqueTime"] = new Variant(rtStatus.jointLimitTorqueTime);
355 datafields["selfCollNullspaceTime"] = new Variant(rtStatus.selfCollNullspaceTime);
356 datafields["jointLimitNullspaceTime"] = new Variant(rtStatus.jointLimitNullspaceTime);
357
358 datafields["impForceRatio"] = new Variant(rtStatus.impForceRatio);
359 datafields["impTorqueRatio"] = new Variant(rtStatus.impTorqueRatio);
360
361 // auto& globalPose = rtStatus.globalPose;
362 // auto transformVector = [](const Eigen::Matrix4f& pose,
363 // const Eigen::Vector3f& vec) -> Eigen::Vector3f
364 // {
365 // // Eigen::Vector3f homogeneous_vector;
366 // // homogeneous_vector << vec, 1.0;
367 //
368 // return common::getOri(pose) * vec + common::getPos(pose);
369 // // return globalPose.head<3>() / globalPose(3);
370 // };
371
372 // double timeMeasure = IceUtil::Time::now().toMicroSecondsDouble();
373 // viz::Layer layer = arviz.layer(getClassName() + "_" + arm->nodeSetName);
374
375 for (unsigned int i = 0; i < rtStatus.activeCollPairsNum; ++i)
376 {
377 // visualize impedance force
378 // layer.add(viz::Arrow("projImpForce_" + std::to_string(i))
379 // .fromTo(rtStatus.collDataVec[i].point * 1000.0,
380 // rtStatus.collDataVec[i].point * 1000.0 +
381 // rtStatus.collDataVec[i].projectedImpedanceForce *
382 // rtStatus.collDataVec[i].direction * 5.0)
383 // .color(simox::Color::purple()));
384
385 // layer.add(viz::Arrow("impForce_" + std::to_string(i))
386 // .fromTo(rtStatus.collDataVec[i].point * 1000.0,
387 // rtStatus.collDataVec[i].point * 1000.0 +
388 // rtStatus.forceImpedance.head<3>().dot(
389 // rtStatus.collDataVec[i].direction) *
390 // rtStatus.collDataVec[i].direction * 5.0)
391 // .color(simox::Color::yellow())); // project forceImp in dir of collision
392
393 // layer.add(
394 // viz::Arrow("force_" + std::to_string(i))
395 // .fromTo(transformVector(rtStatus.globalPose,
396 // rtStatus.collDataVec[i].point * 1000.0f),
397 // transformVector(rtStatus.globalPose,
398 // rtStatus.collDataVec[i].point * 1000.0f +
399 // rtStatus.collDataVec[i].direction * 50.0f *
400 // rtStatus.collDataVec[i].repulsiveForce))
401 // .color(simox::Color::blue()));
402
403 //size_t index = rtStatus.distanceIndexPairs[i].second;
404 datafields[std::to_string(i) + "_minDistance"] =
405 new Variant(rtStatus.collDataVec[i].minDistance);
406 datafields[std::to_string(i) + "_repVel"] =
407 new Variant(rtStatus.collDataVec[i].repulsiveVel);
408 datafields[std::to_string(i) + "_dampingForce"] = new Variant(
409 -1.0f * rtStatus.collDataVec[i].damping * rtStatus.collDataVec[i].distanceVelocity);
410 datafields[std::to_string(i) + "_n_des(d)"] =
411 new Variant(rtStatus.collDataVec[i].desiredNSColl);
413 datafields, std::to_string(i) + "_point", rtStatus.collDataVec[i].point1);
415 datafields, std::to_string(i) + "_dir", rtStatus.collDataVec[i].direction);
416 }
417 // layer.add(viz::Pose("___root___").pose(rtStatus.globalPose).scale(2));
418
419
420 // /// prepare test case config
421 // const float tolerance = 1e-9f;
422 // if (rtData.testConfig == 1)
423 // {
424 // if (rtStatus.evalData[0].nodeName == "ArmL8_Wri2")
425 // {
426 // // set distance
427 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_dist"] =
428 // new Variant(rtStatus.evalData[0].minDistance);
429 // // set f_rep, damping, desired NS space
430
431
432 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_repF"] =
433 // new Variant(rtStatus.evalData[0].repulsiveForce);
434 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_projMass"] =
435 // new Variant(rtStatus.evalData[0].projectedMass);
436 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_locStiffness"] =
437 // new Variant(rtStatus.evalData[0].localStiffness);
438 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_dampFactor"] =
439 // new Variant(rtStatus.evalData[0].damping);
440 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_distVel"] =
441 // new Variant(rtStatus.evalData[0].distanceVelocity);
442 // if (fabs(rtStatus.evalData[0].damping + 1.0f) < tolerance)
443 // {
444 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_dampForce"] =
445 // new Variant(0.0);
446 // }
447 // else
448 // {
449 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_dampForce"] =
450 // new Variant(-1.0 * rtStatus.evalData[0].damping *
451 // rtStatus.evalData[0].distanceVelocity);
452 // }
453
454 // datafields["ArmL8_Wri2_" + rtStatus.evalData[0].otherName + "_n_des(d)"] =
455 // new Variant(rtStatus.evalData[0].desiredNSColl);
456 // }
457 // if (rtStatus.evalData[1].nodeName == "ArmL8_Wri2")
458 // {
459 // // set distance
460 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_dist"] =
461 // new Variant(rtStatus.evalData[1].minDistance);
462 // // set f_rep, damping, desired NS space
463
464 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_repF"] =
465 // new Variant(rtStatus.evalData[1].repulsiveForce);
466 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_projMass"] =
467 // new Variant(rtStatus.evalData[1].projectedMass);
468 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_locStiffness"] =
469 // new Variant(rtStatus.evalData[1].localStiffness);
470 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_dampFactor"] =
471 // new Variant(rtStatus.evalData[1].damping);
472 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_distVel"] =
473 // new Variant(rtStatus.evalData[1].distanceVelocity);
474 // if (fabs(rtStatus.evalData[1].damping + 1.0f) < tolerance)
475 // {
476 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_dampForce"] =
477 // new Variant(0.0);
478 // }
479 // else
480 // {
481 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_dampForce"] =
482 // new Variant(-1.0 * rtStatus.evalData[1].damping *
483 // rtStatus.evalData[1].distanceVelocity);
484 // }
485
486 // datafields["ArmL8_Wri2_" + rtStatus.evalData[1].otherName + "_n_des(d)"] =
487 // new Variant(rtStatus.evalData[1].desiredNSColl);
488 // }
489 // if (rtStatus.evalData[2].nodeName == "ArmL7_Wri1")
490 // {
491 // // set distance
492 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_dist"] =
493 // new Variant(rtStatus.evalData[2].minDistance);
494 // // set f_rep, damping, desired NS space
495
496 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_repF"] =
497 // new Variant(rtStatus.evalData[2].repulsiveForce);
498
499 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_projMass"] =
500 // new Variant(rtStatus.evalData[2].projectedMass);
501 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_locStiffness"] =
502 // new Variant(rtStatus.evalData[2].localStiffness);
503 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_dampFactor"] =
504 // new Variant(rtStatus.evalData[2].damping);
505 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_distVel"] =
506 // new Variant(rtStatus.evalData[2].distanceVelocity);
507 // if (fabs(rtStatus.evalData[2].damping + 1.0f) < tolerance)
508 // {
509 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_dampForce"] =
510 // new Variant(0.0);
511 // }
512 // else
513 // {
514 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_dampForce"] =
515 // new Variant(-1.0 * rtStatus.evalData[2].damping *
516 // rtStatus.evalData[2].distanceVelocity);
517 // }
518
519
520 // datafields["ArmL7_Wri1_" + rtStatus.evalData[2].otherName + "_n_des(d)"] =
521 // new Variant(rtStatus.evalData[2].desiredNSColl);
522 // }
523 // if (rtStatus.evalData[3].nodeName == "ArmL8_Wri2")
524 // {
525 // // set distance
526 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_dist"] =
527 // new Variant(rtStatus.evalData[3].minDistance);
528 // // set f_rep, damping, desired NS space
529
530 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_repF"] =
531 // new Variant(rtStatus.evalData[3].repulsiveForce);
532
533 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_projMass"] =
534 // new Variant(rtStatus.evalData[3].projectedMass);
535 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_locStiffness"] =
536 // new Variant(rtStatus.evalData[3].localStiffness);
537 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_dampFactor"] =
538 // new Variant(rtStatus.evalData[3].damping);
539 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_distVel"] =
540 // new Variant(rtStatus.evalData[3].distanceVelocity);
541 // if (fabs(rtStatus.evalData[3].damping + 1.0f) < tolerance)
542 // {
543 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_dampForce"] =
544 // new Variant(0.0);
545 // }
546 // else
547 // {
548 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_dampForce"] =
549 // new Variant(-1.0 * rtStatus.evalData[3].damping *
550 // rtStatus.evalData[3].distanceVelocity);
551 // }
552
553
554 // datafields["ArmL8_Wri2_" + rtStatus.evalData[3].otherName + "_n_des(d)"] =
555 // new Variant(rtStatus.evalData[3].desiredNSColl);
556 // }
557
558 // if (rtStatus.evalData[4].nodeName == "ArmL8_Wri2")
559 // {
560 // // set distance
561 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_dist"] =
562 // new Variant(rtStatus.evalData[4].minDistance);
563 // // set f_rep, damping, desired NS space
564
565 // // values have been calculated
566 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_repF"] =
567 // new Variant(rtStatus.evalData[4].repulsiveForce);
568
569 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_projMass"] =
570 // new Variant(rtStatus.evalData[4].projectedMass);
571 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_locStiffness"] =
572 // new Variant(rtStatus.evalData[4].localStiffness);
573 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_dampFactor"] =
574 // new Variant(rtStatus.evalData[4].damping);
575 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_distVel"] =
576 // new Variant(rtStatus.evalData[4].distanceVelocity);
577 // if (fabs(rtStatus.evalData[4].damping + 1.0f) < tolerance)
578 // {
579 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_dampForce"] =
580 // new Variant(0.0);
581 // }
582 // else
583 // {
584 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_dampForce"] =
585 // new Variant(-1.0 * rtStatus.evalData[4].damping *
586 // rtStatus.evalData[4].distanceVelocity);
587 // }
588
589
590 // datafields["ArmL8_Wri2_" + rtStatus.evalData[4].otherName + "_n_des(d)"] =
591 // new Variant(rtStatus.evalData[4].desiredNSColl);
592 // }
593 // if (rtStatus.evalData[5].nodeName == "ArmL8_Wri2")
594 // {
595 // // set distance
596 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_dist"] =
597 // new Variant(rtStatus.evalData[5].minDistance);
598
599 // // values have been calculated
600 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_repF"] =
601 // new Variant(rtStatus.evalData[5].repulsiveForce);
602
603 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_projMass"] =
604 // new Variant(rtStatus.evalData[5].projectedMass);
605 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_locStiffness"] =
606 // new Variant(rtStatus.evalData[5].localStiffness);
607 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_dampFactor"] =
608 // new Variant(rtStatus.evalData[5].damping);
609 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_distVel"] =
610 // new Variant(rtStatus.evalData[5].distanceVelocity);
611 // if (fabs(rtStatus.evalData[5].damping + 1.0f) < tolerance)
612 // {
613 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_dampForce"] =
614 // new Variant(0.0);
615 // }
616 // else
617 // {
618 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_dampForce"] =
619 // new Variant(-1.0 * rtStatus.evalData[5].damping *
620 // rtStatus.evalData[5].distanceVelocity);
621 // }
622
623
624 // datafields["ArmL8_Wri2_" + rtStatus.evalData[5].otherName + "_n_des(d)"] =
625 // new Variant(rtStatus.evalData[5].desiredNSColl);
626 // }
627 // if (rtStatus.evalData[6].nodeName == "ArmL5_Elb1")
628 // {
629 // // set distance
630 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_dist"] =
631 // new Variant(rtStatus.evalData[6].minDistance);
632
633 // // values have been calculated
634 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_repF"] =
635 // new Variant(rtStatus.evalData[6].repulsiveForce);
636
637 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_projMass"] =
638 // new Variant(rtStatus.evalData[6].projectedMass);
639 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_locStiffness"] =
640 // new Variant(rtStatus.evalData[6].localStiffness);
641 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_dampFactor"] =
642 // new Variant(rtStatus.evalData[6].damping);
643 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_distVel"] =
644 // new Variant(rtStatus.evalData[6].distanceVelocity);
645 // if (fabs(rtStatus.evalData[6].damping + 1.0f) < tolerance)
646 // {
647 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_dampForce"] =
648 // new Variant(0.0);
649 // }
650 // else
651 // {
652 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_dampForce"] =
653 // new Variant(-1.0 * rtStatus.evalData[6].damping *
654 // rtStatus.evalData[6].distanceVelocity);
655 // }
656
657
658 // datafields["ArmL5_Elb1_" + rtStatus.evalData[6].otherName + "_n_des(d)"] =
659 // new Variant(rtStatus.evalData[6].desiredNSColl);
660 // }
661 // }
662
663 // visualize impedance force
664
665 // layer.add(viz::Arrow("impForce")
666 // .fromTo(rtStatus.currentPose.block<3, 1>(0, 3),
667 // rtStatus.currentPose.block<3, 1>(0, 3) +
668 // rtStatus.forceImpedance.head<3>() * 1000.0)
669 // .color(simox::Color::yellow()));
670 // layer.add(viz::Arrow("projImpForce")
671 // .fromTo(rtStatus.currentPose.block<3, 1>(0, 3),
672 // rtStatus.currentPose.block<3, 1>(0, 3) +
673 // rtStatus.projForceImpedance.head<3>() * 1000.0)
674 // .color(simox::Color::purple()));
675
676 // layer.add(viz::Robot(filename).pose(Eigen::Matrix4f::Identity()))
677 // arviz.commit(layer);
678
679
680 //double selfCollDebugTime = IceUtil::Time::now().toMicroSecondsDouble() - timeMeasure;
681 //datafields["selfCollDebugTime"] = new Variant(selfCollDebugTime);
682
683 // debug value assignment torso, neck joints
684 // datafields["torsoJointValue_float"] = new Variant(rtStatus.torsoJointValuef);
685 // datafields["neck1JointValue_float"] = new Variant(rtStatus.neck1JointValuef);
686 // datafields["neck2JointValue_float"] = new Variant(rtStatus.neck2JointValuef);
687
688 // datafields["torsoJointValue_double"] = new Variant(rtStatus.torsoJointValued);
689 // datafields["neck1JointValue_double"] = new Variant(rtStatus.neck1JointValued);
690 // datafields["neck2JointValue_double"] = new Variant(rtStatus.neck2JointValued);
691
692 // common::debugEigenVec(
693 // datafields, "set_ActuatedJointValues", rtStatus.setActuatedJointValues.cast<float>());
694 // common::debugEigenVec(
695 // datafields, "get_ActuatedJointValues", rtStatus.getActuatedJointValues.cast<float>());
696
697 // double limbTime = IceUtil::Time::now().toMicroSecondsDouble() - limbTimeMeasure;
698 // datafields["limbOnPublishTime"] = new Variant(limbTime);
699
700 debugObs->setDebugChannel("CollAvoid_ImpCtrl_" + arm.nodeSetName, datafields);
701 }
702
703 template <typename NJointControllerType, typename CollisionCtrlCfg>
704 void
706 const std::vector<hpp::fcl::CollisionObject>& objects,
707 const DebugObserverInterfacePrx& debugObs,
708 const std::string& layerSuffix)
709 {
710
711 viz::Layer objectLayer = arviz.layer(getName() + layerSuffix);
712 for (size_t i = 0; i < objects.size(); ++i)
713 {
714 auto object = objects.at(i);
715 const auto position = object.getTranslation().cast<float>() * 1000;
716 const Eigen::Matrix3f rotation = object.getRotation().cast<float>();
717
718 switch (object.getNodeType())
719 {
720 case hpp::fcl::NODE_TYPE::GEOM_BOX:
721 {
722 const hpp::fcl::Box* box =
723 std::static_pointer_cast<hpp::fcl::Box>(object.collisionGeometry()).get();
724 const viz::Box vizObject = viz::Box("box " + std::to_string(i))
725 .size(box->halfSide.cast<float>() * 1000 * 2)
726 .orientation(rotation)
727 .position(position)
728 .color(255, 0, 0, 128);
729 objectLayer.add(vizObject);
730 break;
731 }
732 case hpp::fcl::NODE_TYPE::GEOM_SPHERE:
733 {
734 const hpp::fcl::Sphere* sphere =
735 std::static_pointer_cast<hpp::fcl::Sphere>(object.collisionGeometry())
736 .get();
737 const viz::Sphere vizObject =
738 viz::Sphere("sphere " + std::to_string(i))
739 .radius(static_cast<float>(sphere->radius) * 1000)
740 .orientation(rotation)
741 .position(position)
742 .color(0, 0, 255, 128);
743 objectLayer.add(vizObject);
744 break;
745 }
746 case hpp::fcl::NODE_TYPE::GEOM_CYLINDER:
747 {
748 const hpp::fcl::Cylinder* cylinder =
749 std::static_pointer_cast<hpp::fcl::Cylinder>(object.collisionGeometry())
750 .get();
751 const viz::Cylinder vizObject =
752 viz::Cylinder("cylinder " + std::to_string(i))
753 .height(static_cast<float>(cylinder->halfLength) * 1000 * 2)
754 .radius(static_cast<float>(cylinder->radius) * 1000)
755 .orientation(rotation *
756 Eigen::AngleAxisf(M_PI / 2., Eigen::Vector3f::UnitX()))
757 .position(position)
758 .color(0, 255, 0, 128);
759 objectLayer.add(vizObject);
760 break;
761 }
762 case hpp::fcl::NODE_TYPE::GEOM_CAPSULE:
763 {
764 const hpp::fcl::Capsule* capsule =
765 std::static_pointer_cast<hpp::fcl::Capsule>(object.collisionGeometry())
766 .get();
767 const auto _rotation =
768 rotation * Eigen::AngleAxisf(M_PI / 2., Eigen::Vector3f::UnitX());
769 Eigen::Vector3f offset;
770 offset << 0, static_cast<float>(capsule->halfLength) * 1000, 0;
771 offset = _rotation * offset;
772
773 const viz::Sphere cap1 = viz::Sphere("capsule_cap1 " + std::to_string(i))
774 .radius(static_cast<float>(capsule->radius) * 1000)
775 .position(position + offset)
776 .orientation(_rotation)
777 .color(255, 200, 0, 128);
778 const viz::Sphere cap2 = viz::Sphere("capsule_cap2 " + std::to_string(i))
779 .radius(static_cast<float>(capsule->radius) * 1000)
780 .position(position - offset)
781 .orientation(_rotation)
782 .color(255, 200, 0, 128);
783 const viz::Cylinder vizObject =
784 viz::Cylinder("capsule_mid " + std::to_string(i))
785 .height(static_cast<float>(capsule->halfLength) * 1000 * 2)
786 .radius(static_cast<float>(capsule->radius) * 1000)
787 .color(255, 200, 0, 128)
788 .orientation(_rotation)
789 .position(position);
790 objectLayer.add(vizObject);
791 objectLayer.add(cap1);
792 objectLayer.add(cap2);
793 break;
794 }
795 case hpp::fcl::NODE_TYPE::GEOM_ELLIPSOID:
796 {
797 const hpp::fcl::Ellipsoid* ellipsoid =
798 std::static_pointer_cast<hpp::fcl::Ellipsoid>(object.collisionGeometry())
799 .get();
800 const viz::Ellipsoid vizObject =
801 viz::Ellipsoid("ellipsoid " + std::to_string(i))
802 // axis lengths seem to be radii instead of axis lengths
803 .axisLengths(ellipsoid->radii.cast<float>() * 1000)
804 .orientation(rotation)
805 .position(position)
806 .color(255, 0, 200, 128);
807 objectLayer.add(vizObject);
808 break;
809 }
810 default:;
811 }
812 }
813 arviz.commit(objectLayer);
814 }
815
816 template <typename NJointControllerType, typename CollisionCtrlCfg>
817 void
819 const SensorAndControl& sc,
820 const DebugDrawerInterfacePrx& drawer,
821 const DebugObserverInterfacePrx& debugObs)
822 {
823 NJointControllerType::onPublish(sc, drawer, debugObs);
824 if (coll)
825 {
826 for (auto& pair : coll->collLimb)
827 {
828 collLimbPublish(pair.second, debugObs);
829 }
830 collObjectPublish(coll->userCollisionObjects, debugObs, "_collisionObjects");
831
832 // TODO uses rt collision robot
833 const auto& robotObjects = coll->collisionRobot->getCollisionManager()->getObjects();
834 std::vector<hpp::fcl::CollisionObject> robotObjectsByValue;
835 for (const auto* ptr : robotObjects)
836 {
837 robotObjectsByValue.push_back(*ptr);
838 }
839 collObjectPublish(robotObjectsByValue, debugObs, "_collisionRobot");
840 }
841 }
842
843 template <typename NJointControllerType, typename CollisionCtrlCfg>
844 void
846 {
847 // ARMARX_RT_LOGF_INFO("rt Preactivate controller "
848 // "NJointTaskspaceCollisionAvoidanceMixedImpedanceVelocityController");
849 NJointControllerType::rtPreActivateController();
851 if (collReady.load())
852 {
854 coll->rtPreActivate();
855 }
856 }
857
858 template <typename NJointControllerType, typename CollisionCtrlCfg>
859 void
860 NJointTSVelBasedColController<NJointControllerType,
862 {
863 NJointControllerType::rtPostDeactivateController();
864 if (collReady.load())
865 {
867 coll->rtPostDeactivate();
868 }
869 // ARMARX_RT_LOGF_INFO("-- post deactivate: "
870 // "NJointTaskspaceCollisionAvoidanceMixedImpedanceVelocityController");
871 }
872
873 template <typename NJointControllerType, typename CollisionCtrlCfg>
877 {
878 auto cfgName = values.at("config_box")->getString();
879 const armarx::PackagePath configPath(
880 "armarx_control",
881 "controller_config/" + std::string(NJointControllerType::ControlType::TypeName) +
882 "Col/" + cfgName + ".json");
883 ARMARX_INFO_S << "Loading config from " << configPath.toSystemPath();
884 ARMARX_CHECK(std::filesystem::exists(configPath.toSystemPath()));
885
886 auto cfgDTO = armarx::readFromJson<CollisionCtrlCfg>(configPath.toSystemPath());
887
889 return new ConfigurableNJointControllerConfig{cfgDTO.toAronDTO()};
890 }
891
892 /// ================================== TSMixImpVelCol ==================================
894 law::arondto::TSVelColConfigDict>;
895
898
900 const NJointControllerConfigPtr& config,
901 const VirtualRobot::RobotPtr& robot) :
902 // NJointTSVelController(robotUnit, config, robot),
904 robotUnit,
905 config,
906 robot)
907 {
908 }
909
910 std::string
911 NJointTSVelColController::getClassName(const Ice::Current&) const
912 {
913 return "TSVelCol";
914 }
915
916} // namespace armarx::control::njoint_controller::task_space
#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 collObjectPublish(const std::vector< hpp::fcl::CollisionObject > &objects, const DebugObserverInterfacePrx &debugObs, const std::string &layerSuffix)
void collLimbPublish(CollAvoidVelBase::NodeSetData &arm, const DebugObserverInterfacePrx &debugObs)
std::map< std::string, std::vector< hpp::fcl::CollisionObject > > collisionObjects
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
void updateCollisionObjects(const std::string &primitiveSourceName, const ::armarx::aron::data::dto::DictPtr &scene, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
static ConfigPtrT GenerateConfigFromVariants(const StringVariantBaseMap &values)
void onPublish(const SensorAndControl &sc, const DebugDrawerInterfacePrx &drawer, const DebugObserverInterfacePrx &) override
::armarx::aron::data::dto::DictPtr getConfig(const Ice::Current &iceCurrent) override
NJointTSVelBasedColController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
void rtPreActivateController() override
NJointControllerBase interface.
void updateConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent) override
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override
NJointTSVelColController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
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
#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
NJointControllerRegistration< NJointTSVelColController > registrationControllerNJointTSVelColController("TSVelCol")
::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
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