Base.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 "Base.h"
24
25#include <SimoxUtility/color/Color.h>
26#include <VirtualRobot/MathTools.h>
27#include <VirtualRobot/RobotNodeSet.h>
28
32
35// #include <RobotAPI/components/units/RobotUnit/NJointControllers/NJointController.h>
38// #include <RobotAPI/libraries/RobotAPIComponentPlugins/ArVizComponentPlugin.h>
39
42
43/// for GUI
44#include <ArmarXCore/core/PackagePath.h> // for GUI
46
48
49/// HandUnit
50//#include <RobotAPI/interface/units/HandUnitInterface.h>
51
53{
54
55 template <typename NJointTaskspaceControllerType>
56 void
58 const std::string& nodeSetName,
59 ArmPtr& arm,
60 Config& cfg,
61 VirtualRobot::RobotPtr& nonRtRobotPtr)
62 {
63 arm->kinematicChainName = nodeSetName;
64 VirtualRobot::RobotNodeSetPtr rtRns =
65 rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
66 VirtualRobot::RobotNodeSetPtr nonRtRns =
67 nonRtRobotPtr->getRobotNodeSet(arm->kinematicChainName);
68 ARMARX_CHECK_EXPRESSION(rtRns) << arm->kinematicChainName;
69 ARMARX_CHECK_EXPRESSION(nonRtRns) << arm->kinematicChainName;
70 ARMARX_IMPORTANT << "--> Creating Taskspace controller with kinematic chain: "
71 << arm->kinematicChainName << " with num of joints: (RT robot) "
72 << rtRns->getSize() << ", and (non-RT robot) " << nonRtRns->getSize();
73
74 std::vector<size_t> jointIDTorqueMode;
75 std::vector<size_t> jointIDVelocityMode;
76 arm->jointNames.clear();
77 for (size_t i = 0; i < rtRns->getSize(); ++i)
78 {
79 std::string jointName = rtRns->getNode(i)->getName();
80 arm->jointNames.push_back(jointName);
81
82 bool foundControlDevice = false;
83 auto it = std::find(
84 cfg.jointNameListTorque.begin(), cfg.jointNameListTorque.end(), jointName);
85 if (it != cfg.jointNameListTorque.end())
86 {
87 ControlTargetBase* ct = useControlTarget(jointName, ControlModes::Torque1DoF);
89 auto* casted_ct = ct->asA<ControlTarget1DoFActuatorTorque>();
90 ARMARX_CHECK_EXPRESSION(casted_ct);
91 arm->targetsTorque.push_back(casted_ct);
92 jointIDTorqueMode.push_back(i);
93 foundControlDevice = true;
94 }
95
96 it = std::find(
97 cfg.jointNameListVelocity.begin(), cfg.jointNameListVelocity.end(), jointName);
98 if (it != cfg.jointNameListVelocity.end())
99 {
100 ControlTargetBase* ct = useControlTarget(jointName, ControlModes::Velocity1DoF);
102 auto* casted_ct = ct->asA<ControlTarget1DoFActuatorVelocity>();
103 ARMARX_CHECK_EXPRESSION(casted_ct);
104 arm->targetsVel.push_back(casted_ct);
105 jointIDVelocityMode.push_back(i);
106 foundControlDevice = true;
107 }
108 if (not foundControlDevice)
109 {
110 auto namesTorque = armarx::control::common::sVecToString(cfg.jointNameListTorque);
111 auto namesVelocity =
112 armarx::control::common::sVecToString(cfg.jointNameListVelocity);
113 ARMARX_ERROR << "Does not found valid control device for joint name: " << jointName
114 << "Please check torque controlled joints: [" << namesTorque
115 << "] and velocity controlled joints: [" << namesVelocity << "].";
117
118 const SensorValueBase* sv = useSensorValue(jointName);
120 arm->sensorDevices.append(sv, jointName);
121 };
122 ARMARX_DEBUG << "Number of torque controlled joints " << jointIDTorqueMode.size();
123 ARMARX_DEBUG << "Number of velocity controlled joints " << jointIDVelocityMode.size();
124 ARMARX_CHECK_EQUAL(rtRns->getNodeNames().size(),
125 jointIDTorqueMode.size() + jointIDVelocityMode.size());
126
127 arm->controller.initialize(nonRtRns, rtRns);
128 arm->controller.ftsensor.initialize(rtRns, robotUnit, cfg.ftConfig);
130 validateConfigData(cfg, arm);
131 arm->rtConfig = cfg;
132 arm->nonRtConfig = cfg;
133 arm->rtStatus.reset(rtRns->getSize(), jointIDTorqueMode, jointIDVelocityMode);
134 ARMARX_INFO << "<-- Limb " << arm->kinematicChainName << " created";
136
137 template <typename NJointTaskspaceControllerType>
140 const NJointControllerConfigPtr& config,
141 const VirtualRobot::RobotPtr&) :
144 ARMARX_INFO << "================ creating controller ============================";
146
147 // // Type: ::armarx::HandUnitInterfacePrx
148 // // auto handUnit = robotUnit->getUnitPrx<::armarx::HandUnitInterface>();
149 // auto handUnit = robotUnit->getUnit<::armarx::HandUnitInterface>();
150 // auto jointValues = handUnit->getCurrentJointValues();
151 // for (auto& pair : jointValues)
152 // {
153 // ARMARX_INFO << " --- joint: " << pair.first << ": " << pair.second;
154 // }
155 // // handUnit->setJointAngles();
156 // // Hand_L_EEF_NJointKITHandV2ShapeController
157 // // Hand_R_EEF_NJointKITHandV2ShapeController
158 // // NJointKITHandV2ShapeController
159
160
161 ConfigPtrT cfg = ConfigPtrT::dynamicCast(config);
163 userConfig.fromAron(cfg->config);
164
166 nonRtRobot = robotUnit->cloneRobot();
167 robotUnit->updateVirtualRobot(nonRtRobot);
168 }
170 template <typename NJointTaskspaceControllerType>
171 void
174 for (auto& pair : userConfig.limbs)
176 limb.emplace(pair.first, std::make_unique<ArmData>());
177 limbInit(pair.first, limb.at(pair.first), pair.second, nonRtRobot);
178 controllableNodeSets.emplace(pair.first, nonRtRobot->getRobotNodeSet(pair.first));
180
181 if (not userConfig.hands.empty())
183 // hands =
184 // std::make_shared<core::HandControlBase>(robotUnit, nonRtRobot, userConfig.hands);
185 // for (auto& pair : userConfig.hands)
186 // {
187 // // for (auto& jointName : hands->hands.at(pair.first)->jointNames)
188 // // {
189 // // hands->appendDevice(pair.first,
190 // // useSensorValue(jointName),
191 // // useControlTarget(jointName, ControlModes::Position1DoF),
192 // // jointName);
193 // // }
194 // ARMARX_INFO << "-- Creating hand: "
195 // << hands->hands.at(pair.first)->kinematicChainName;
196 // controllableNodeSets.emplace(pair.first, nonRtRobot->getRobotNodeSet(pair.first));
197 // }
198 createHands();
200 }
202 template <typename NJointTaskspaceControllerType>
203 void
204 NJointTaskspaceController<NJointTaskspaceControllerType>::createHands()
207 hands = std::make_shared<core::HandControlBase>(robotUnit, nonRtRobot, userConfig.hands);
208 for (auto& [name, hand_cfg] : userConfig.hands)
209 {
210 ARMARX_INFO << "-- Creating hand: " << hands->hands.at(name)->kinematicChainName;
211 controllableNodeSets.emplace(name, nonRtRobot->getRobotNodeSet(name));
212 }
213 }
214
215 template <typename NJointTaskspaceControllerType>
216 void
218 {
219 std::string taskName = getClassName() + "AdditionalTask";
220 runTask(taskName,
221 [&]
222 {
224 4); // please don't set this to 0 as it is the rtRun/control thread
227
228 CycleUtil c(1);
229 getObjectScheduler()->waitForObjectStateMinimum(eManagedIceObjectStarted);
230 ARMARX_IMPORTANT << "Create a new thread for " << getClassName();
231 while (getState() == eManagedIceObjectStarted)
236 }
237 c.waitForCycleDuration();
238 }
239 });
240 }
241
242 template <typename NJointTaskspaceControllerType>
243 void
245 {
246 arm->bufferConfigNonRtToRt.getWriteBuffer() = arm->nonRtConfig;
247 arm->bufferConfigNonRtToRt.commitWrite();
248 }
249
250 template <typename NJointTaskspaceControllerType>
251 void
253 {
254 // bool rtSafe = additionalTaskUpdateStatus();
255 auto [rtTargetSafe, ftSafe] = additionalTaskUpdateStatus();
257 if (not rtTargetSafe)
258 {
260 }
261 }
262
263 template <typename NJointTaskspaceControllerType>
264 std::tuple<bool, bool>
266 {
267 robotUnit->updateVirtualRobot(nonRtRobot);
268 bool rtSafe = true;
269 bool rtTargetSafe = true;
270 bool forceTorqueSafe = true;
271 for (auto& pair : limb)
272 {
273 auto& arm = pair.second;
274 arm->nonRtConfig = arm->bufferConfigUserToNonRt.getUpToDateReadBuffer();
275 arm->rtStatusInNonRT = arm->bufferRtStatusToNonRt.getUpToDateReadBuffer();
276 rtSafe = rtSafe and pair.second->rtStatusInNonRT.rtSafe;
277 rtTargetSafe = rtTargetSafe and pair.second->rtStatusInNonRT.rtTargetSafe;
278 forceTorqueSafe = forceTorqueSafe and pair.second->rtStatusInNonRT.forceTorqueSafe;
279 }
280 if (hands)
281 {
282 hands->nonRTUpdateStatus();
283 }
284 return std::make_tuple(rtTargetSafe, forceTorqueSafe);
285 }
286
287 template <typename NJointTaskspaceControllerType>
288 bool
290 {
291 bool rtDesiredPoseSafe = true;
292 for (auto& [_, arm] : limb)
293 {
294 rtDesiredPoseSafe = rtDesiredPoseSafe and arm->rtStatusInNonRT.rtTargetSafe;
295 }
296 return rtDesiredPoseSafe;
297 }
298
299 template <typename NJointTaskspaceControllerType>
300 bool
302 NJointTaskspaceControllerType>::rtGetDesiredPoseSafeStatusOnActivation()
303 {
304 bool rtDesiredPoseSafe = true;
305 for (auto& [_, arm] : limb)
306 {
307 rtDesiredPoseSafe = rtDesiredPoseSafe and arm->desiredPoseSafeOnActivation.load();
308 }
309 return rtDesiredPoseSafe;
310 }
311
312 template <typename NJointTaskspaceControllerType>
313 void
315 {
316 for (auto& [_, arm] : limb)
317 {
318 limbNonRT(arm);
319 }
320 if (hands)
321 {
322 hands->nonRTSetTarget();
323 }
324 }
325
326 template <typename NJointTaskspaceControllerType>
327 void
329 {
330 for (auto& pair : limb)
331 {
332 if (not pair.second->rtReady)
333 {
334 continue;
335 }
336
337 if (not pair.second->rtStatusInNonRT.rtTargetSafe)
338 {
340 pair.second->rtStatusInNonRT.currentPose,
341 pair.second->rtStatusInNonRT.desiredPoseUnsafe,
342 "current pose",
343 "desired pose");
344 }
345 }
346 }
347
348 /// -------------------------------- Real time cotnrol -----------------------------------------
349 template <typename NJointTaskspaceControllerType>
350 void
352 ArmPtr& arm,
353 const double deltaT)
354 {
355 arm->rtConfig = arm->bufferConfigNonRtToRt.getUpToDateReadBuffer();
356 arm->rtStatus.deltaT = deltaT;
357 arm->rtStatus.accumulateTime += deltaT;
358 arm->rtStatus.globalPose = rtGetRobot()->getGlobalPose();
359
360 arm->controller.ftsensor.updateStatus(arm->rtConfig.ftConfig,
361 arm->rtStatus.currentForceTorque,
362 arm->rtStatus.deltaT,
363 arm->rtFirstRun.load());
364 arm->rtStatus.safeFTGuardOffset.template head<3>() =
365 arm->controller.ftsensor.getSafeGuardForceOffset();
366
367 arm->sensorDevices.updateJointValues(
368 arm->rtStatus.jointPosition, arm->rtStatus.jointVelocity, arm->rtStatus.jointTorque);
369 // rtGetRobot()->getRobotNodeSet(arm->kinematicChainName)
370
371
372 arm->bufferRtStatusToNonRt.getWriteBuffer() = arm->rtStatus;
373 arm->bufferRtStatusToNonRt.commitWrite();
374 arm->bufferRtStatusToUser.getWriteBuffer() = arm->rtStatus;
375 arm->bufferRtStatusToUser.commitWrite();
376 }
377
378 template <typename NJointTaskspaceControllerType>
379 void
381 ArmPtr& arm,
382 const size_t nDoFTorque,
383 const size_t nDoFVelocity,
384 const Eigen::VectorXf& targetTorque,
385 const Eigen::VectorXf& targetVelocity)
386 {
387 for (size_t i = 0; i < nDoFTorque; i++)
388 {
389
390 auto jointIdx = arm->rtStatus.jointIDTorqueMode[i];
391 arm->targetsTorque.at(i)->torque = targetTorque(jointIdx);
392 if (!arm->targetsTorque.at(i)->isValid())
393 {
394 arm->targetsTorque.at(i)->torque = 0;
395 }
396 }
397 for (size_t i = 0; i < nDoFVelocity; i++)
398 {
399 auto jointIdx = arm->rtStatus.jointIDVelocityMode[i];
400 arm->targetsVel.at(i)->velocity = targetVelocity(jointIdx);
401 // if (!targets.at(i)->isValid() || fabs(targets.at(i)->velocity) > cfg->maxJointVelocity)
402 if (!arm->targetsVel.at(i)->isValid())
403 {
404 arm->targetsVel.at(i)->velocity = 0;
405 }
406 }
407 arm->bufferRtStatusToOnPublish.getWriteBuffer() = arm->rtStatus;
408 arm->bufferRtStatusToOnPublish.commitWrite();
409
410 arm->bufferConfigRtToOnPublish.getWriteBuffer() = arm->rtConfig;
411 arm->bufferConfigRtToOnPublish.commitWrite();
412
413 arm->bufferConfigRtToUser.getWriteBuffer() = arm->rtConfig;
414 arm->bufferConfigRtToUser.commitWrite();
415
416 if (arm->rtFirstRun.load())
417 {
418 arm->rtFirstRun.store(false);
419 arm->rtReady.store(true);
420 }
421 }
422
423 template <typename NJointTaskspaceControllerType>
424 void
426 const double /*deltaT*/)
427 {
428 double time_measure = IceUtil::Time::now().toMicroSecondsDouble();
429 // limbRTUpdateStatus(arm, deltaT);
430 // double time_update_status = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
431
432 arm->controller.run(arm->rtConfig, arm->rtStatus);
433 double time_run_rt = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
434
435 limbRTSetTarget(arm,
436 arm->rtStatus.nDoFTorque,
437 arm->rtStatus.nDoFVelocity,
438 arm->rtStatus.desiredJointTorque,
439 arm->rtStatus.desiredJointVelocity);
440
441 double time_set_target = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
442 time_measure = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
443
444 if (time_measure > 200)
445 {
446 ARMARX_RT_LOGF_WARN("---- rt too slow: "
447 "run_rt_limb: %.2f\n"
448 "set_target_limb: %.2f\n"
449 "time all: %.2f\n",
450 time_run_rt - time_measure, //
451 time_set_target - time_run_rt, //
452 time_measure)
453 .deactivateSpam(1.0f); // 0-1 us
454 }
455 }
456
457 /// some method for coordinator
458 template <typename NJointTaskspaceControllerType>
459 void
461 const std::string& key,
462 const Eigen::Matrix4f& targetPose,
463 const PoseFrameMode& targetPoseMode,
464 const Eigen::Matrix4f& pose,
465 const Eigen::Vector6f& vel,
466 const Eigen::Vector6f& ft,
467 const Eigen::Vector6f& stiffness)
468 {
469 if (coordinatorInputData.find(key) != coordinatorInputData.end())
470 {
471 // Update existing InputData
472 auto& data = coordinatorInputData.at(key);
473 data.pose = pose;
474 data.targetPose = targetPose;
475 data.targetPoseMode = targetPoseMode;
476 data.vel = vel;
477 data.ft = ft;
478 data.stiffness = stiffness;
479 }
480 else
481 {
482 coordinatorInputData.emplace(key,
484 targetPose, targetPoseMode, pose, vel, ft, stiffness));
485 }
486 }
487
488 template <typename NJointTaskspaceControllerType>
489 void
491 {
492 if (not coordinatorEnabled.load() or not coordinator)
493 {
494 return;
495 }
496
497 bool rtReady = false;
498 for (const auto& nodeset : coordinator->getNodesetList())
499 {
500 auto& rts = limb.at(nodeset)->rtStatus;
501 auto& rtc = limb.at(nodeset)->rtConfig;
502 rtReady = limb.at(nodeset)->rtReady.load();
503 /// TODO, fix this for vel controller, as it does not have kpImpedance
504 if constexpr (NJointTaskspaceControllerType::IsCompliant)
505 {
506 updateInputData(nodeset,
507 rtc.desiredPose,
508 rtc.desiredPoseFrameMode,
509 rts.currentPose,
510 rts.currentTwist,
511 rts.currentForceTorque,
512 rtc.kpImpedance);
513 }
514 else
515 {
516 ARMARX_WARNING << "Not implemented yet for controller types without kpImpedance";
517 return;
518 }
519 }
520 if (not rtReady)
521 {
522 return;
523 }
524 coordinator->runRT(coordinatorInputData, deltaT);
525 for (const auto& nodeset : coordinator->getNodesetList())
526 {
527 limb.at(nodeset)->rtConfig.desiredPose = coordinatorInputData.at(nodeset).targetPose;
528 limb.at(nodeset)->rtConfig.desiredPoseFrameMode = PoseFrameMode::root;
529 }
530 }
531
532 template <typename NJointTaskspaceControllerType>
533 void
535 const IceUtil::Time& /*sensorValuesTimestamp*/,
536 const IceUtil::Time& timeSinceLastIteration)
537 {
538 double deltaT = timeSinceLastIteration.toSecondsDouble();
539 for (auto& pair : limb)
540 {
541 limbRTUpdateStatus(pair.second, deltaT);
542 }
543
544 rtRunCoordinator(deltaT);
545
546 for (auto& pair : limb)
547 {
548 limbRT(pair.second, deltaT);
549 }
550 if (hands)
551 {
552 hands->updateRTStatus(deltaT);
553 // hands->setTargets();
554 }
555 }
556
557 /// ------------------------------ update/get config -------------------------------------------
558 template <typename NJointTaskspaceControllerType>
559 void
561 const ::armarx::aron::data::dto::DictPtr& dto,
562 const Ice::Current& /*iceCurrent*/)
563 {
564 auto prevCfg = userConfig;
565 userConfig.fromAron(dto);
566
567 for (auto& pair : userConfig.limbs)
568 {
569 auto& arm = limb.at(pair.first);
570 validateConfigData(pair.second, arm);
571 bool desiredPoseFrameModeSame = prevCfg.limbs.at(pair.first).desiredPoseFrameMode ==
572 pair.second.desiredPoseFrameMode;
573 if (desiredPoseFrameModeSame and common::detectAndReportPoseDeviationWarning(
574 pair.second.desiredPose,
575 prevCfg.limbs.at(pair.first).desiredPose,
576 "new desired pose",
577 "previous desired pose",
578 pair.second.safeDistanceMMToGoal,
579 pair.second.safeRotAngleDegreeToGoal,
580 "updateConfig_" + pair.first))
581 {
582 ARMARX_INFO << deactivateSpam(2) << "-- use the existing target pose.";
583 pair.second.desiredPose = prevCfg.limbs.at(pair.first).desiredPose;
584 }
585 arm->bufferConfigUserToNonRt.getWriteBuffer() = pair.second;
586 if (not isControllerActive())
587 {
588 arm->nonRtConfig = arm->bufferConfigUserToNonRt.getWriteBuffer();
589 }
590 arm->bufferConfigUserToNonRt.commitWrite();
591
592 /// When user updates the controller config before the controller is activated, we need
593 /// to copy the userconfig to rt data struct directly, as upon activation, the rtConfig
594 /// will be validated and used to reinitialize all buffers.
595 if (not isControllerActive())
596 {
597 arm->rtConfig = arm->nonRtConfig;
598 }
599 }
600
601 if (hands)
602 {
603 hands->updateConfig(userConfig.hands);
604 }
605 else
606 {
607 if (not userConfig.hands.empty())
608 {
609 createHands();
610 }
611 }
612 }
613
614 template <typename NJointTaskspaceControllerType>
617 const Ice::Current& /*iceCurrent*/)
618 {
619 for (auto& pair : limb)
620 {
621 userConfig.limbs.at(pair.first) =
622 pair.second->bufferConfigRtToUser.getUpToDateReadBuffer();
623 }
624 if (hands)
625 {
626 hands->getConfig(userConfig.hands);
627 }
628 return userConfig.toAronDTO();
629 }
630
631 template <typename NJointTaskspaceControllerType>
634 const Ice::Current& /*iceCurrent*/)
635 {
636 for (auto& pair : limb)
637 {
638 userConfig.limbs.at(pair.first) =
639 pair.second->bufferConfigRtToUser.getUpToDateReadBuffer();
640 }
641 if (hands)
642 {
643 hands->getConfig(userConfig.hands);
644 }
645 return userConfig.toAronDTO();
646 }
647
648 template <typename NJointTaskspaceControllerType>
649 void
651 const std::string& nodeSetName,
652 const bool forceGuard,
653 const bool torqueGuard,
654 const Ice::Current& /*iceCurrent*/)
655 {
656 auto it = userConfig.limbs.find(nodeSetName);
657 if (it != userConfig.limbs.end())
658 {
659 it->second.ftConfig.enableSafeGuardForce = forceGuard;
660 it->second.ftConfig.enableSafeGuardTorque = torqueGuard;
661 limb.at(nodeSetName)->controller.ftsensor.enableSafeGuard(forceGuard, torqueGuard);
663 << "reset safe guard with force torque sensors: safe? "
664 << limb.at(nodeSetName)->controller.ftsensor.isSafe(it->second.ftConfig);
665 limb.at(nodeSetName)->bufferConfigUserToNonRt.getWriteBuffer() = it->second;
666 limb.at(nodeSetName)->bufferConfigUserToNonRt.commitWrite();
667 }
668 else
669 {
670 ARMARX_WARNING << "no robot node set with name " << nodeSetName
671 << " found in the controllers.";
672 }
673 }
674
675 /// -------------------------------- Other interaces -------------------------------------------
676 template <typename NJointTaskspaceControllerType>
677 bool
679 const std::string& nodeSetName,
680 const Ice::Current& /*iceCurrent*/)
681 {
682 auto it = userConfig.limbs.find(nodeSetName);
683 if (it != userConfig.limbs.end())
684 {
685 return limb.at(nodeSetName)->controller.ftsensor.ftSafe.load();
686 }
687
688 ARMARX_WARNING << "no robot node set with name " << nodeSetName
689 << " found in the controllers.";
690 return false;
691 }
692
693 template <typename NJointTaskspaceControllerType>
694 bool
696 const std::string& nodeSetName,
697 const Ice::Current& /*iceCurrent*/)
698 {
699 auto it = userConfig.limbs.find(nodeSetName);
700 if (it != userConfig.limbs.end())
701 {
702 return limb.at(nodeSetName)->controller.ftsensor.ftWasNotSafe.load();
703 }
704
705 ARMARX_WARNING << "no robot node set with name " << nodeSetName
706 << " found in the controllers.";
707 return false;
708 }
709
710 template <typename NJointTaskspaceControllerType>
711 Ice::FloatSeq
713 const std::string& rns,
714 const Ice::Current& /*iceCurrent*/)
715 {
716 std::vector<float> tcpVel;
717 auto& arm = limb.at(rns);
718 auto s = arm->bufferRtStatusToUser.getUpToDateReadBuffer();
719 tcpVel.reserve(s.currentTwist.size());
720 for (int i = 0; i < s.currentTwist.size(); i++)
721 {
722 tcpVel.push_back(s.currentTwist[i]);
723 }
724 return tcpVel;
725 }
726
727 template <typename NJointTaskspaceControllerType>
728 Ice::DoubleSeq
730 const std::string& nodeSetName,
731 const Ice::Current& /*iceCurrent*/)
732 {
733 auto search = limb.find(nodeSetName);
734 if (search == limb.end())
735 {
736 ARMARX_WARNING << "requested node set " << nodeSetName
737 << "does not exist in the controller";
738 return std::vector<double>{};
739 }
740
741 auto& arm = limb.at(nodeSetName);
742 auto currentPose = arm->bufferRtStatusToOnPublish.getUpToDateReadBuffer().currentPose;
743 ARMARX_DEBUG << "returning current pose" << VAROUT(currentPose);
744 return common::mat4ToDVec(currentPose);
745 }
746
747 template <typename NJointTaskspaceControllerType>
748 bool
750 const TargetPoseMap& targetPoseMap,
751 const TargetNullspaceMap& targetNullspaceMap,
752 const Ice::Current& /*iceCurrent*/)
753 {
754 for (auto& pair : userConfig.limbs)
755 {
756 for (size_t i = 0; i < 4; ++i)
757 {
758 for (int j = 0; j < 4; ++j)
759 {
760 pair.second.desiredPose(i, j) = targetPoseMap.at(pair.first)[i][j];
761 }
762 }
763 if (targetNullspaceMap.at(pair.first).size() > 0)
764 {
765 const size_t nDoF = pair.second.desiredNullspaceJointAngles.value().size();
766 ARMARX_CHECK_EQUAL(targetNullspaceMap.at(pair.first).size(), nDoF)
767 << "the joint numbers does not match";
768 for (size_t i = 0; i < nDoF; ++i)
769 {
770 pair.second.desiredNullspaceJointAngles.value()(i) =
771 targetNullspaceMap.at(pair.first)[i];
772 }
773 }
774 limb.at(pair.first)->bufferConfigUserToNonRt.getWriteBuffer() = pair.second;
775 limb.at(pair.first)->bufferConfigUserToNonRt.commitWrite();
776 }
777 return true;
778 }
779
780 template <typename NJointTaskspaceControllerType>
781 void
783 ArmPtr& arm)
784 {
785 const auto nDoF = arm->jointNames.size();
786 if (!configData.desiredNullspaceJointAngles.has_value())
787 {
788 if (!isControllerActive())
789 {
790 ARMARX_INFO << "-- No user defined nullspace target, reset to zero with "
791 << VAROUT(nDoF);
792 configData.desiredNullspaceJointAngles = Eigen::VectorXf::Zero(nDoF);
793 arm->reInitPreActivate.store(true);
794 }
795 else
796 {
797 auto currentValue =
798 arm->bufferConfigRtToUser.getUpToDateReadBuffer().desiredNullspaceJointAngles;
800 << "Controller is active, but no user defined nullspace target. \n"
801 "You should first get up-to-date config of this controller and then "
802 "update "
803 "it:\n"
804 " auto cfg = ctrl->getConfig(); \n"
805 " cfg.desiredPose = xxx;\n"
806 " ctrl->updateConfig(cfg);\n"
807 "Now, I decide by myself to use the existing values of nullspace "
808 "target\n"
809 << currentValue.value();
810 configData.desiredNullspaceJointAngles = currentValue;
811 }
812 }
813 ARMARX_CHECK_GREATER(configData.safeDistanceMMToGoal, 100.0f);
814 validateConfigDataCheckSize(configData, arm);
815 }
816
817 template <typename NJointTaskspaceControllerType>
818 void
820 ArmPtr& arm,
821 const DebugObserverInterfacePrx& debugObs)
822 {
823 StringVariantBaseMap datafields;
824 auto rtStatus = arm->bufferRtStatusToOnPublish.getUpToDateReadBuffer();
825 auto cfgNonRt = arm->bufferConfigNonRtToPublish.getUpToDateReadBuffer();
826
827 limbPublishConfig(datafields, arm);
828
829 datafields["nDoFTorque"] = new Variant(rtStatus.nDoFTorque);
830 datafields["nDoFVelocity"] = new Variant(rtStatus.nDoFVelocity);
831
832 common::debugEigenVec(datafields, "jointPosition", rtStatus.jointPosition);
833 common::debugEigenVec(datafields, "jointVelocity", rtStatus.jointVelocity);
834 common::debugEigenVec(datafields, "qvelFiltered", rtStatus.qvelFiltered);
835
836 common::debugEigenPose(datafields, "current_pose", rtStatus.currentPose);
837 common::debugEigenPose(datafields, "desired_pose", rtStatus.desiredPose);
838 common::debugEigenPose(datafields, "desired_pose_user", cfgNonRt.desiredPose);
839
840 datafields["cfg.velocity_limit"] = new Variant(cfgNonRt.velocityLimit);
841 datafields["cfg.torque_limit"] = new Variant(cfgNonRt.torqueLimit);
842 datafields["ft.safeGuardForceThreshold"] =
843 new Variant(cfgNonRt.ftConfig.safeGuardForceThreshold);
844 datafields["ft.safeGuardTorqueThreshold"] =
845 new Variant(cfgNonRt.ftConfig.safeGuardTorqueThreshold);
846
847
848 float positionError =
849 (common::getPos(rtStatus.currentPose) - common::getPos(rtStatus.desiredPose)).norm();
850 float angleError =
851 common::getDeltaAngleBetweenPose(rtStatus.currentPose, rtStatus.desiredPose);
852 datafields["poseError_position"] = new Variant(positionError);
853 datafields["poseError_angle"] = new Variant(angleError);
854
855 common::debugEigenVec(datafields, "current_twist", rtStatus.currentTwist);
856 common::debugEigenVec(datafields, "poseErrorImp", rtStatus.poseErrorImp);
857
858 common::debugEigenVec(datafields, "currentForceTorque", rtStatus.currentForceTorque);
859 common::debugEigenVec(datafields, "safeFTGuardOffset", rtStatus.safeFTGuardOffset);
860
861 /// admittance interface
862 common::debugEigenMat(datafields, "inertia", rtStatus.inertia);
863 common::debugEigenMat(datafields, "inertiaVelCtrlJoints", rtStatus.inertiaVelCtrlJoints);
865 datafields, "inertiaInvVelCtrlJoints", rtStatus.inertiaInvVelCtrlJoints);
866 common::debugEigenVec(datafields, "qdVel", rtStatus.qdVel);
867 common::debugEigenVec(datafields, "qdAcc", rtStatus.qdAcc);
868 common::debugEigenVec(datafields, "qTemp", rtStatus.qTemp);
869
870 float currentForceNorm = rtStatus.currentForceTorque.template head<3>().norm();
871 float currentTorqueNorm = rtStatus.currentForceTorque.template tail<3>().norm();
872 float safeForceGuardOffsetNorm = rtStatus.safeFTGuardOffset.template head<3>().norm();
873 float safeTorqueGuardOffsetNorm = rtStatus.safeFTGuardOffset.template tail<3>().norm();
874 datafields["currentForceNorm"] = new Variant(currentForceNorm);
875 datafields["currentTorqueNorm"] = new Variant(currentTorqueNorm);
876 datafields["safeForceGuardOffsetNorm"] = new Variant(safeForceGuardOffsetNorm);
877 datafields["safeTorqueGuardOffsetNorm"] = new Variant(safeTorqueGuardOffsetNorm);
878 datafields["safeForceGuardDifference"] =
879 new Variant(currentForceNorm - safeForceGuardOffsetNorm);
880 datafields["safeTorqueGuardDifference"] =
881 new Variant(currentTorqueNorm - safeTorqueGuardOffsetNorm);
882
883 datafields["rtSafe"] = new Variant(rtStatus.rtSafe * 1.0);
884 datafields["rtTargetSafe"] = new Variant(rtStatus.rtTargetSafe * 1.0);
885 bool forceTrigger = (not rtStatus.rtSafe) and rtStatus.rtTargetSafe;
886 datafields["forceTrigger"] = new Variant(forceTrigger * 1.0);
887 datafields["forceTorqueSafe"] = new Variant(rtStatus.forceTorqueSafe * 1.0);
888
889 common::debugEigenVec(datafields, "forceImpedance", rtStatus.forceImpedance);
890 common::debugEigenVec(datafields, "cartesianVelTarget", rtStatus.cartesianVelTarget);
891
892 common::debugEigenVec(datafields, "desiredJointTorques", rtStatus.desiredJointTorque);
893 common::debugEigenVec(datafields, "desiredJointVelocity", rtStatus.desiredJointVelocity);
894 common::debugEigenVec(datafields, "nullspaceTorque", rtStatus.nullspaceTorque);
895 common::debugEigenVec(datafields, "nullspaceVelocity", rtStatus.nullspaceVelocity);
896 debugObs->setDebugChannel(getClassName() + "_" + arm->kinematicChainName, datafields);
897 }
898
899 template <typename NJointTaskspaceControllerType>
900 void
902 const SensorAndControl& /*unused*/,
903 const DebugDrawerInterfacePrx& /*unused*/,
904 const DebugObserverInterfacePrx& debugObs)
905 {
906 for (auto& pair : limb)
907 {
908 if (not pair.second->rtReady.load())
909 {
910 continue;
911 }
912 limbPublish(pair.second, debugObs);
913 }
914 if (hands)
915 {
916 hands->onPublish(debugObs);
917 }
918 onPublishCoordinator(debugObs);
919
920 if (++skipStepCountArviz_ >= skipStepsArviz_)
921 {
922 skipStepCountArviz_ = 0;
923 commitArviz();
924 }
925 }
926
927 template <typename NJointTaskspaceControllerType>
928 void
930 const DebugObserverInterfacePrx& debugObs)
931 {
932 if (!coordinator)
933 {
934 return;
935 }
936 StringVariantBaseMap datafields;
937 auto& cfg = coordinator->bufferUserCfgToPublish.getUpToDateReadBuffer();
938 auto data = coordinator->bufferDataRtToPublish.getUpToDateReadBuffer();
939 common::debugEigenPose(datafields, "current_pose", data.currentPose);
940 common::debugEigenPose(datafields, "virtualPose", data.virtualPose);
941 common::debugEigenPose(datafields, "targetPose", data.targetPose);
942 common::debugEigenVec(datafields, "currentFT", data.currentFT);
943 common::debugEigenVec(datafields, "pose_error", data.poseError);
944 common::debugEigenVec(datafields, "tempAcc", data.tempAcc);
945 common::debugEigenVec(datafields, "virtualVel", data.virtualVel);
946 common::debugEigenVec(datafields, "virtualAcc", data.virtualAcc);
947 // ARMARX_INFO << VAROUT(data.obj2TcpInMeterL) << VAROUT(data.obj2TcpInMeterL);
948
949 using namespace armarx::control::common::coordination::arondto;
950 auto followerIsolation = cfg.followerConnectionMode == ConnectionMode::follower_isolated;
951 auto leftAsLeader = cfg.leadershipMode == LeadershipMode::left_as_leader;
952 auto rightAsLeader = cfg.leadershipMode == LeadershipMode::right_as_leader;
953 auto followerInLeaderLocalFrame =
954 cfg.followerFrameMode == common::arondto::PoseFrameMode::leader;
955 datafields["followerIsolation"] = new Variant(followerIsolation);
956 datafields["leftAsLeader"] = new Variant(leftAsLeader);
957 datafields["rightAsLeader"] = new Variant(rightAsLeader);
958 datafields["followerInLeaderLocalFrame"] = new Variant(followerInLeaderLocalFrame);
959
960 debugObs->setDebugChannel("SyncModeCoordinator", datafields);
961 }
962
963 template <typename NJointTaskspaceControllerType>
964 void
966 {
967 if (scopedArviz.has_value())
968 {
969 viz::StagedCommit stage = scopedArviz->stage();
970 if (resetArviz)
971 {
972 resetArviz = false;
973 scopedArviz->clear();
974 storedArvizLayers.clear();
975 }
976 collectArviz(stage);
977 scopedArviz->commit(stage);
978 }
979 }
980
981 template <typename NJointTaskspaceControllerType>
982 void
984 viz::StagedCommit& stage) const
985 {
986 if (not scopedArviz.has_value())
987 {
988 return;
989 }
990
991 const double arrowWidth = 2.5F;
992 if (coordinator)
993 {
994 const auto& rtStatus = coordinator->bufferDataRtToPublish.getUpToDateReadBuffer();
995 const Eigen::Matrix4f globalPose = Eigen::Matrix4f::Identity(); // FIXME
996 {
997 viz::Layer layer = scopedArviz->layer("Pose_coordinator");
998 layer.add(
999 viz::Pose("targetPose").pose(globalPose * rtStatus.targetPose).scale(1.5f));
1000 layer.add(
1001 viz::Pose("virtualPose").pose(globalPose * rtStatus.virtualPose).scale(1.25f));
1002 layer.add(
1003 viz::Pose("currentPose").pose(globalPose * rtStatus.currentPose).scale(1.0f));
1004 stage.add(layer);
1005 }
1006
1007 const auto objCenter = common::getPos(globalPose * rtStatus.currentPose);
1008 {
1009 viz::Layer layer = scopedArviz->layer("Status_coordinator");
1010 layer.add(
1011 viz::Arrow("object_vel")
1012 .fromTo(objCenter, objCenter + 1000.0f * rtStatus.virtualVel.head<3>())
1013 .color(simox::Color::blue())
1014 .width(arrowWidth));
1015 layer.add(viz::Arrow("object_pose_error")
1016 .fromTo(objCenter, objCenter + 1000.0f * rtStatus.poseError.head<3>())
1017 .color(simox::Color::black())
1018 .width(arrowWidth));
1019 stage.add(layer);
1020 }
1021 {
1022 viz::Layer layer = scopedArviz->layer("FT_coordinator");
1023 layer.add(viz::Arrow("object_force")
1024 .fromTo(objCenter, objCenter + 100.0f * rtStatus.currentFT.head<3>())
1025 .color(simox::Color::yellow())
1026 .width(arrowWidth));
1027 layer.add(viz::Arrow("object_torque")
1028 .fromTo(objCenter, objCenter + 100.0f * rtStatus.currentFT.tail<3>())
1029 .color(simox::Color::green())
1030 .width(arrowWidth));
1031 stage.add(layer);
1032 }
1033 }
1034 else
1035 {
1036 for (const auto& [_, arm] : limb)
1037 {
1038 const auto& cfgNonRt = arm->bufferConfigNonRtToPublish.getUpToDateReadBuffer();
1039 const auto& rtStatus = arm->bufferRtStatusToOnPublish.getUpToDateReadBuffer();
1040
1041 const Eigen::Matrix4f& globalPose = rtStatus.globalPose;
1042 auto addPose = [&](viz::Layer& layer, const std::string& suffix = "")
1043 {
1044 layer.add(viz::Pose("targetPose" + suffix)
1045 .pose(globalPose * rtStatus.desiredPose)
1046 .scale(1.5f));
1047 layer.add(viz::Pose("currentPose" + suffix)
1048 .pose(globalPose * rtStatus.currentPose)
1049 .scale(1.0f));
1050
1051 const float positionError = (common::getPos(rtStatus.currentPose) -
1052 common::getPos(rtStatus.desiredPose))
1053 .norm();
1054 const float positionErrorNormalized =
1055 std::fmin((positionError / cfgNonRt.safeDistanceMMToGoal), 1.);
1056 layer.add(viz::Arrow("positionError" + suffix)
1057 .fromTo(common::getPos(globalPose * rtStatus.currentPose),
1058 common::getPos(globalPose * rtStatus.desiredPose))
1059 .color(simox::Color(positionErrorNormalized,
1060 1.0f - positionErrorNormalized,
1061 0.0f))
1062 .width(arrowWidth));
1063 };
1064
1065 {
1066 viz::Layer layer = scopedArviz->layer("Pose_" + arm->kinematicChainName);
1067 addPose(layer);
1068 stage.add(layer);
1069 }
1070 const bool enableTrajVisualization = false;
1071 if (enableTrajVisualization)
1072 {
1073 const std::string name = "Traj_" + arm->kinematicChainName;
1074 if (storedArvizLayers.count(name) == 0)
1075 {
1076 storedArvizLayers[name] = scopedArviz->layer(name);
1077 }
1078 viz::Layer& layer = storedArvizLayers.at(name);
1079 int index = layer.size() / 3;
1080 addPose(layer, std::to_string(index));
1081 stage.add(layer);
1082 }
1083 {
1084 viz::Layer layer = scopedArviz->layer("Status_" + arm->kinematicChainName);
1085 layer.add(viz::Arrow("tsImpForce")
1086 .fromTo(common::getPos(globalPose * rtStatus.currentPose),
1087 common::getPos(globalPose * rtStatus.currentPose) +
1088 rtStatus.forceImpedance.template head<3>() * 5.0)
1089 .color(simox::Color::cyan())
1090 .width(arrowWidth));
1091 stage.add(layer);
1092 }
1093 // {
1094 // viz::Layer layer = scopedArviz->layer("FT_" + arm->kinematicChainName);
1095 // const auto curentPos = common::getPos(globalPose * rtStatus.currentPose);
1096 // layer.add(
1097 // viz::Arrow("TCP force")
1098 // .fromTo(curentPos,
1099 // curentPos +
1100 // 100.0f * rtStatus.currentForceTorque.template head<3>())
1101 // .color(simox::Color::yellow())
1102 // .width(arrowWidth));
1103 // layer.add(
1104 // viz::Arrow("TCP torque")
1105 // .fromTo(curentPos,
1106 // curentPos +
1107 // 100.0f * rtStatus.currentForceTorque.template tail<3>())
1108 // .color(simox::Color::green())
1109 // .width(arrowWidth));
1110 // stage.add(layer);
1111 // }
1112 }
1113 }
1114 }
1115
1116 template <typename NJointTaskspaceControllerType>
1117 void
1119 {
1120 for (auto& pair : limb)
1121 {
1122 pair.second->rtReady.store(false);
1123 }
1124 }
1125
1126 template <typename NJointTaskspaceControllerType>
1127 void
1129 const std::string& type,
1130 const ::armarx::aron::data::dto::DictPtr& dto,
1131 const Ice::Current& /*unused*/)
1132 {
1133 ARMARX_INFO << "Adding coordinator of type " << type;
1134 /// TODO think about other types of coordinators
1135 if (!coordinator)
1136 {
1137 /// TODO add check if the current controller has all robotNodeSets
1138 /// that the coordinator requires. currently, use check below.
1139 coordinator = std::make_shared<common::coordination::SyncCoordination>(dto);
1140 }
1141 else
1142 {
1143 coordinator->updateConfig(dto);
1144 }
1145
1146 for (const auto& nodeset : coordinator->getNodesetList())
1147 {
1148 if (limb.find(nodeset) == limb.end())
1149 {
1150 coordinatorEnabled.store(false);
1151 ARMARX_WARNING << "The requested nodeset by coordinator " << nodeset
1152 << " does not exist in the current controller, disable coordinator";
1153 return;
1154 }
1155 }
1156
1157 // for (auto& pair : limb)
1158 // {
1159 // enableSafeGuardForceTorque(pair.first, false, false);
1160 // // pair.second->controller.setForceTorqueGuard(false, false);
1161 // pair.second->controller.ftsensor.enableSafeGuard(false, false);
1162 // }
1163 for (const auto& nodeset : coordinator->getNodesetList())
1164 {
1165 enableSafeGuardForceTorque(nodeset, false, false);
1166 // pair.second->controller.setForceTorqueGuard(false, false);
1167 // pair.second->controller.ftsensor.enableSafeGuard(false, false);
1168 }
1169 coordinatorEnabled.store(true);
1170 // std::map<std::string, Eigen::Matrix4f> initPose;
1171 // for (const auto& nodeset: coord->getNodesetList())
1172 // {
1173 // auto buff = limb.at(nodeset)->bufferConfigRtToUser.getUpToDateReadBuffer();
1174 // initPose[nodeset] = buff.desiredPose;
1175 // ARMARX_INFO << "using node set " << nodeset << " with pose " << buff.desiredPose;
1176 // }
1177 // coord->reset(initPose);
1178 }
1179
1180 template <typename NJointTaskspaceControllerType>
1181 void
1183 const Ice::Current& /*unused*/)
1184 {
1185 ARMARX_INFO << "Disabling coordinator!";
1186 if (not coordinator)
1187 {
1188 ARMARX_INFO << "Coordinator is not created yet, use `useCoordinator` to create!!";
1189 return;
1190 }
1191 for (const auto& nodeset : coordinator->getNodesetList())
1192 {
1193 auto& arm = limb.at(nodeset);
1194 auto& cfgRT = arm->bufferConfigRtToUser.getUpToDateReadBuffer();
1195 arm->bufferConfigUserToNonRt.getWriteBuffer().desiredPose = cfgRT.desiredPose;
1196 arm->bufferConfigUserToNonRt.commitWrite();
1197 usleep(2000);
1198 }
1199 coordinatorEnabled.store(false);
1200 ARMARX_INFO << "Coordinator is disabled!!";
1201 }
1202
1203 template <typename NJointTaskspaceControllerType>
1204 void
1206 {
1207 /// Note: this function will always be called once ctrl_proxy->activateController() is called.
1208 /// For situations where heavy objects are hold in hands in torque control mode, user has
1209 /// to check if this controller is already activated, and only call acitvateContgroller
1210 /// when it is not active.
1211 /// Or you can use the controllerBuilder wrapper, which handles this automatically
1212 ARMARX_RT_LOGF_INFO("--> rtPreActivateController for %s", arm->kinematicChainName.c_str());
1213 VirtualRobot::RobotNodeSetPtr rns = rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
1214 Eigen::Matrix4f currentPose = rns->getTCP()->getPoseInRootFrame();
1215 auto quat = VirtualRobot::MathTools::eigen4f2quat(currentPose);
1216 ARMARX_RT_LOGF_INFO("-- rt preactivate controller with target pose\n\n "
1217 "[ %.2f, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f ].",
1218 currentPose(0, 3),
1219 currentPose(1, 3),
1220 currentPose(2, 3),
1221 quat.w,
1222 quat.x,
1223 quat.y,
1224 quat.z);
1225
1226 arm->desiredPoseSafeOnActivation =
1227 not common::poseDeviationTooLarge(currentPose,
1228 arm->rtConfig.desiredPose,
1229 arm->rtConfig.safeDistanceMMToGoal,
1230 arm->rtConfig.safeRotAngleDegreeToGoal);
1231
1232 /// Is there a case where using current pose to initialize the RT desired pose is not suitable?
1233 if (arm->reInitPreActivate.load())
1234 {
1235 // arm->nonRtConfig.desiredNullspaceJointAngles = rns->getJointValuesEigen();
1236 // arm->nonRtConfig.desiredPose = currentPose;
1237
1238 // arm->bufferConfigUserToNonRt.reinitAllBuffers(arm->nonRtConfig);
1239
1240 arm->rtConfig.desiredNullspaceJointAngles = rns->getJointValuesEigen();
1241
1242 arm->reInitPreActivate.store(false);
1243 }
1244 {
1245 // arm->rtConfig = arm->nonRtConfig;
1246 arm->rtConfig.desiredPose = currentPose;
1247 arm->nonRtConfig = arm->rtConfig;
1248
1249 arm->bufferConfigUserToNonRt.reinitAllBuffers(arm->rtConfig);
1250 arm->bufferConfigNonRtToRt.reinitAllBuffers(arm->rtConfig);
1251 arm->bufferConfigRtToOnPublish.reinitAllBuffers(arm->rtConfig);
1252 arm->bufferConfigNonRtToPublish.reinitAllBuffers(arm->rtConfig);
1253 arm->bufferConfigRtToUser.reinitAllBuffers(arm->rtConfig);
1254 }
1255 {
1256 arm->sensorDevices.updateJointValues(arm->rtStatus.jointPosition,
1257 arm->rtStatus.jointVelocity,
1258 arm->rtStatus.jointTorque);
1259 arm->rtStatus.rtPreActivate(currentPose);
1260 arm->rtStatus.globalPose = rtGetRobot()->getGlobalPose();
1261 arm->rtStatusInNonRT = arm->rtStatus;
1262 arm->nonRTDeltaT = 0.0;
1263 arm->nonRTAccumulateTime = 0.0;
1264 arm->bufferRtStatusToOnPublish.reinitAllBuffers(arm->rtStatus);
1265 arm->bufferRtStatusToNonRt.reinitAllBuffers(arm->rtStatus);
1266 arm->bufferRtStatusToUser.reinitAllBuffers(arm->rtStatus);
1267 }
1268
1269 // arm->controller.preactivateInit(rns);
1270 ARMARX_RT_LOGF_INFO("<-- done.");
1271 }
1272
1273 template <typename NJointTaskspaceControllerType>
1274 void
1276 const Ice::Current& current)
1277 {
1279 << "NJointTaskspaceController<NJointTaskspaceControllerType>::activateController";
1280
1281 if (not scopedArviz.has_value())
1282 {
1283 scopedArviz.emplace(createArVizClient());
1284 scopedArviz->updateComponentName("NJointTaskspaceController");
1285 }
1286 resetArviz = true;
1287
1288 if (hands)
1289 {
1290 ARMARX_INFO << "Calling hands->nonRtActivateController()";
1291 hands->nonRtActivateController();
1292 }
1294 }
1295
1296 template <typename NJointTaskspaceControllerType>
1297 void
1299 const Ice::Current& current)
1300 {
1302 << "NJointTaskspaceController<NJointTaskspaceControllerType>::deactivateController";
1303
1305
1306 resetArviz = true;
1307 }
1308
1309 template <typename NJointTaskspaceControllerType>
1310 void
1312 {
1313 ARMARX_RT_LOGF_IMPORTANT("--> rtPreActivateController");
1314 for (auto& pair : limb)
1315 {
1316
1317 limbReInit(pair.second);
1318 userConfig.limbs.at(pair.first) = pair.second->rtConfig;
1319 }
1320 if (hands)
1321 {
1322 hands->rtPreActivate();
1323 }
1324 ARMARX_RT_LOGF_IMPORTANT("<-- Done");
1325 }
1326
1327 template <typename NJointTaskspaceControllerType>
1328 void
1330 {
1331 for (auto& pair : userConfig.limbs)
1332 {
1333 limb.at(pair.first)->rtPostDeactivate();
1334 }
1335 if (hands)
1336 {
1337 hands->rtPostDeactivate(userConfig.hands);
1338 }
1339
1340 /// @Andre Meixner: introduced the following line, which contradicts the use case where you
1341 /// disabled the controller during a coordination mode and reactivtion will not automatically
1342 /// activate the coordination mode again.
1343 coordinatorEnabled.store(false);
1344 }
1345
1346 template <typename NJointTaskspaceControllerType>
1347 void
1357
1358 /// ----------------------------------- GUI Widget ---------------------------------------------
1359 template <typename NJointTaskspaceControllerType>
1362 const VirtualRobot::RobotPtr& /*robot*/,
1363 const std::map<std::string, ConstControlDevicePtr>& /*controlDevices*/,
1364 const std::map<std::string, ConstSensorDevicePtr>&)
1365 {
1366 using namespace armarx::WidgetDescription;
1367 HBoxLayoutPtr layout = new HBoxLayout;
1368
1369
1370 ::armarx::WidgetDescription::WidgetSeq widgets;
1371
1372 /// select default config
1373 LabelPtr label = new Label;
1374 label->text = "select a controller config";
1375
1376 StringComboBoxPtr cfgBox = new StringComboBox;
1377 cfgBox->name = "config_box";
1378 cfgBox->defaultIndex = 0;
1379 cfgBox->multiSelect = false;
1380
1381 cfgBox->options = std::vector<std::string>{
1382 "default_a7_with_hands",
1383 "default_a7_left",
1384 "default_a7_right",
1385 "default_a7_zero_torque",
1386 "default_a6_left",
1387 "default_a6_with_hands",
1388 "default_a6_right",
1389 "default_a6_zero_torque",
1390 };
1392
1393 layout->children.emplace_back(label);
1394 layout->children.emplace_back(cfgBox);
1396
1397 layout->children.insert(layout->children.end(), widgets.begin(), widgets.end());
1398 ARMARX_INFO_S << "Layout done";
1399 return layout;
1400 }
1401
1402 template <typename NJointTaskspaceControllerType>
1405 const StringVariantBaseMap& values)
1406 {
1407 auto cfgName = values.at("config_box")->getString();
1408 const armarx::PackagePath configPath(
1409 "armarx_control",
1410 "controller_config/" + std::string(NJointTaskspaceControllerType::TypeName) + "/" +
1411 cfgName + ".json");
1412 ARMARX_INFO_S << "Loading config from " << configPath.toSystemPath();
1413 ARMARX_CHECK(std::filesystem::exists(configPath.toSystemPath()));
1414
1415 auto cfgDTO = armarx::readFromJson<ConfigDict>(configPath.toSystemPath());
1416
1418 return new ConfigurableNJointControllerConfig{cfgDTO.toAronDTO()};
1419 }
1420
1421 /////////
1423
1426
1428 const RobotUnitPtr& robotUnit,
1429 const NJointControllerConfigPtr& config,
1430 const VirtualRobot::RobotPtr& robot) :
1431 NJointTaskspaceController<law::TSMixImpVelController>(robotUnit, config, robot)
1432 {
1433 createLimbs();
1434 }
1435
1436 std::string
1438 {
1439 return "TSMixImpVel";
1440 }
1441
1442 void
1444 {
1445 const auto nDoF = static_cast<Eigen::Index>(arm->jointNames.size());
1446
1447 const auto checkSize = [nDoF](const auto& v) { ARMARX_CHECK_EQUAL(v.rows(), nDoF); };
1448 const auto checkNonNegative = [](const auto& v) { ARMARX_CHECK((v.array() >= 0).all()); };
1449 checkSize(configData.desiredNullspaceJointAngles.value());
1450 checkSize(configData.kdNullspaceTorque);
1451 checkSize(configData.kpNullspaceTorque);
1452 checkSize(configData.kdNullspaceVel);
1453 checkSize(configData.kpNullspaceVel);
1454
1455 checkNonNegative(configData.kdNullspaceTorque);
1456 checkNonNegative(configData.kpNullspaceTorque);
1457 checkNonNegative(configData.kpNullspaceVel);
1458 checkNonNegative(configData.kdNullspaceVel);
1459 checkNonNegative(configData.kdImpedance);
1460 checkNonNegative(configData.kpImpedance);
1461 }
1462
1463 void
1465 {
1466 auto cfg = arm->bufferConfigRtToOnPublish.getUpToDateReadBuffer();
1467 common::debugEigenVec(datafields, "kpImpedance", cfg.kpImpedance);
1468 common::debugEigenVec(datafields, "kdImpedance", cfg.kdImpedance);
1469 common::debugEigenVec(datafields, "kpCartesianVel", cfg.kpCartesianVel);
1470 common::debugEigenVec(datafields, "kdCartesianVel", cfg.kdCartesianVel);
1471 if (cfg.desiredNullspaceJointAngles.has_value())
1472 {
1474 datafields, "desiredNullspaceJointAngles", cfg.desiredNullspaceJointAngles.value());
1475 }
1476
1477 datafields["poseError_threshold_position"] = new Variant(cfg.safeDistanceMMToGoal);
1478 datafields["poseError_threshold_angle"] = new Variant(cfg.safeRotAngleDegreeToGoal);
1479 datafields["safeForceGuardThreshold"] = new Variant(cfg.ftConfig.safeGuardForceThreshold);
1480 datafields["safeTorqueGuardThreshold"] = new Variant(cfg.ftConfig.safeGuardTorqueThreshold);
1481 }
1482
1483 /// ================================== TSImp ==================================
1485
1488
1490 const NJointControllerConfigPtr& config,
1491 const VirtualRobot::RobotPtr& robot) :
1492 NJointTaskspaceController<law::TSImpController>(robotUnit, config, robot)
1493 {
1494 createLimbs();
1495 }
1496
1497 std::string
1498 NJointTSImpController::getClassName(const Ice::Current&) const
1499 {
1500 return "TSImp";
1501 }
1502
1503 void
1505 {
1507 const auto nDoF = static_cast<Eigen::Index>(arm->jointNames.size());
1508
1509 const auto checkSize = [nDoF](const auto& v) { ARMARX_CHECK_EQUAL(v.rows(), nDoF); };
1510 const auto checkNonNegative = [](const auto& v) { ARMARX_CHECK((v.array() >= 0).all()); };
1511 checkSize(configData.desiredNullspaceJointAngles.value());
1512 checkSize(configData.kdNullspaceTorque);
1513 checkSize(configData.kpNullspaceTorque);
1514
1515 checkNonNegative(configData.kdNullspaceTorque);
1516 checkNonNegative(configData.kpNullspaceTorque);
1517 checkNonNegative(configData.kdImpedance);
1518 checkNonNegative(configData.kpImpedance);
1519 }
1520
1521 void
1523 {
1524 auto cfg = arm->bufferConfigRtToOnPublish.getUpToDateReadBuffer();
1525 common::debugEigenVec(datafields, "kpImpedance", cfg.kpImpedance);
1526 common::debugEigenVec(datafields, "kdImpedance", cfg.kdImpedance);
1527 if (cfg.desiredNullspaceJointAngles.has_value())
1528 {
1530 datafields, "desiredNullspaceJointAngles", cfg.desiredNullspaceJointAngles.value());
1531 }
1532
1533 datafields["poseError_threshold_position"] = new Variant(cfg.safeDistanceMMToGoal);
1534 datafields["poseError_threshold_angle"] = new Variant(cfg.safeRotAngleDegreeToGoal);
1535 datafields["safeForceGuardThreshold"] = new Variant(cfg.ftConfig.safeGuardForceThreshold);
1536 datafields["safeTorqueGuardThreshold"] = new Variant(cfg.ftConfig.safeGuardTorqueThreshold);
1537 }
1538
1539 /// ================================== TSAdm ==================================
1541
1544
1546 const NJointControllerConfigPtr& config,
1547 const VirtualRobot::RobotPtr& robot) :
1548 NJointTaskspaceController<law::TSAdmController>(robotUnit, config, robot)
1549 {
1550 createLimbs();
1551 }
1552
1553 std::string
1554 NJointTSAdmController::getClassName(const Ice::Current&) const
1555 {
1556 return "TSAdm";
1557 }
1558
1559 void
1561 {
1563 const auto nDoF = static_cast<Eigen::Index>(arm->jointNames.size());
1564
1565 const auto checkSize = [nDoF](const auto& v) { ARMARX_CHECK_EQUAL(v.rows(), nDoF); };
1566 const auto checkNonNegative = [](const auto& v) { ARMARX_CHECK((v.array() >= 0).all()); };
1567 checkSize(configData.desiredNullspaceJointAngles.value());
1568 checkSize(configData.kdNullspaceTorque);
1569 checkSize(configData.kpNullspaceTorque);
1570
1571 checkNonNegative(configData.kdNullspaceTorque);
1572 checkNonNegative(configData.kpNullspaceTorque);
1573 checkNonNegative(configData.kdImpedance);
1574 checkNonNegative(configData.kpImpedance);
1575 }
1576
1577 void
1579 {
1580 auto cfg = arm->bufferConfigRtToOnPublish.getUpToDateReadBuffer();
1581 common::debugEigenVec(datafields, "kpImpedance", cfg.kpImpedance);
1582 common::debugEigenVec(datafields, "kdImpedance", cfg.kdImpedance);
1583 if (cfg.desiredNullspaceJointAngles.has_value())
1584 {
1586 datafields, "desiredNullspaceJointAngles", cfg.desiredNullspaceJointAngles.value());
1587 }
1588
1589 datafields["poseError_threshold_position"] = new Variant(cfg.safeDistanceMMToGoal);
1590 datafields["poseError_threshold_angle"] = new Variant(cfg.safeRotAngleDegreeToGoal);
1591 datafields["safeForceGuardThreshold"] = new Variant(cfg.ftConfig.safeGuardForceThreshold);
1592 datafields["safeTorqueGuardThreshold"] = new Variant(cfg.ftConfig.safeGuardTorqueThreshold);
1593 }
1594
1595 /// ================================== TSVel ==================================
1597
1600
1602 const NJointControllerConfigPtr& config,
1603 const VirtualRobot::RobotPtr& robot) :
1604 NJointTaskspaceController<law::TSVelController>(robotUnit, config, robot)
1605 {
1606 createLimbs();
1607 }
1608
1609 std::string
1610 NJointTSVelController::getClassName(const Ice::Current&) const
1611 {
1612 return "TSVel";
1613 }
1614
1615 void
1617 {
1618 const auto nDoF = static_cast<Eigen::Index>(arm->jointNames.size());
1619
1620 const auto checkSize = [nDoF](const auto& v) { ARMARX_CHECK_EQUAL(v.rows(), nDoF); };
1621 const auto checkNonNegative = [](const auto& v) { ARMARX_CHECK((v.array() >= 0).all()); };
1622 checkSize(configData.desiredNullspaceJointAngles.value());
1623 checkSize(configData.kdNullspaceVel);
1624 checkSize(configData.kpNullspaceVel);
1625
1626 checkNonNegative(configData.kpNullspaceVel);
1627 checkNonNegative(configData.kdNullspaceVel);
1628 }
1629
1630 void
1632 {
1633 auto cfg = arm->bufferConfigRtToOnPublish.getUpToDateReadBuffer();
1634 common::debugEigenVec(datafields, "kpCartesianVel", cfg.kpCartesianVel);
1635 common::debugEigenVec(datafields, "kdCartesianVel", cfg.kdCartesianVel);
1636 if (cfg.desiredNullspaceJointAngles.has_value())
1637 {
1639 datafields, "desiredNullspaceJointAngles", cfg.desiredNullspaceJointAngles.value());
1640 }
1641
1642 datafields["poseError_threshold_position"] = new Variant(cfg.safeDistanceMMToGoal);
1643 datafields["poseError_threshold_angle"] = new Variant(cfg.safeRotAngleDegreeToGoal);
1644 datafields["safeForceGuardThreshold"] = new Variant(cfg.ftConfig.safeGuardForceThreshold);
1645 datafields["safeTorqueGuardThreshold"] = new Variant(cfg.ftConfig.safeGuardTorqueThreshold);
1646 }
1647} // namespace armarx::control::njoint_controller::task_space
#define ARMARX_RT_LOGF_IMPORTANT(...)
#define ARMARX_RT_LOGF_WARN(...)
#define ARMARX_RT_LOGF_INFO(...)
uint8_t index
SpamFilterDataPtr deactivateSpam(SpamFilterDataPtr const &spamFilter, float deactivationDurationSec, const std::string &identifier, bool deactivate)
Definition Logging.cpp:75
#define VAROUT(x)
constexpr T c
Brief description of class JointControlTargetBase.
This util class helps with keeping a cycle time during a control cycle.
Definition CycleUtil.h:41
ArmarXObjectSchedulerPtr getObjectScheduler() const
int getState() const
Retrieve current state of the ManagedIceObject.
bool isControllerActive(const Ice::Current &=Ice::emptyCurrent) const final override
void runTask(const std::string &taskName, Task &&task)
Executes a given task in a separate thread from the Application ThreadPool.
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override=0
void deactivateController(const Ice::Current &=Ice::emptyCurrent) override
const VirtualRobot::RobotPtr & useSynchronizedRtRobot(bool updateCollisionModel=false)
Requests a VirtualRobot for use in rtRun *.
const VirtualRobot::RobotPtr & rtGetRobot()
TODO make protected and use attorneys.
void activateController(const Ice::Current &=Ice::emptyCurrent) override
ControlTargetBase * useControlTarget(const std::string &deviceName, const std::string &controlMode)
Declares to calculate the ControlTarget for the given ControlDevice in the given ControlMode when rtR...
static std::filesystem::path toSystemPath(const data::PackagePath &pp)
The SensorValueBase class.
The Variant class is described here: Variants.
Definition Variant.h:224
static bool pinThreadToCPU(unsigned int cpu)
Pins the calling thread to the CPU with the given id.
Definition RTUtility.cpp:52
static bool elevateThreadPriority(int priority)
Elevate the thread priority of the calling thread to the given priority.
Definition RTUtility.cpp:17
static constexpr int RT_THREAD_PRIORITY
The thread priority for rt-threads.
Definition RTUtility.h:24
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override
Definition Base.cpp:1554
void limbPublishConfig(StringVariantBaseMap &datafields, ArmPtr &arm) override
Definition Base.cpp:1578
void validateConfigDataCheckSize(Config &configData, ArmPtr &arm) override
Definition Base.cpp:1560
NJointTSAdmController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
Definition Base.cpp:1545
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override
================================== TSImp ==================================
Definition Base.cpp:1498
NJointTSImpController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
Definition Base.cpp:1489
void limbPublishConfig(StringVariantBaseMap &datafields, ArmPtr &arm) override
Definition Base.cpp:1522
void validateConfigDataCheckSize(Config &configData, ArmPtr &arm) override
Definition Base.cpp:1504
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override
================================== TSMixImpVel ==================================
Definition Base.cpp:1437
NJointTSMixImpVelController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
Definition Base.cpp:1427
void limbPublishConfig(StringVariantBaseMap &datafields, ArmPtr &arm) override
Definition Base.cpp:1464
void validateConfigDataCheckSize(Config &configData, ArmPtr &arm) override
Definition Base.cpp:1443
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override
Definition Base.cpp:1610
NJointTSVelController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &robot)
Definition Base.cpp:1601
void limbPublishConfig(StringVariantBaseMap &datafields, ArmPtr &arm) override
Definition Base.cpp:1631
void validateConfigDataCheckSize(Config &configData, ArmPtr &arm) override
Definition Base.cpp:1616
Brief description of class NJointTaskspaceController.
Definition Base.h:59
std::map< std::string, VirtualRobot::RobotNodeSetPtr > controllableNodeSets
Definition Base.h:220
void onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &) override
Definition Base.cpp:901
static WidgetDescription::WidgetPtr GenerateConfigDescription(const VirtualRobot::RobotPtr &, const std::map< std::string, ConstControlDevicePtr > &, const std::map< std::string, ConstSensorDevicePtr > &)
--------------------------------— GUI Widget ------------------------------------------—
Definition Base.cpp:1361
Ice::DoubleSeq getCurrentTCPPose(const std::string &nodeSetName, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
Definition Base.cpp:729
std::shared_ptr< common::coordination::SyncCoordination > coordinator
Definition Base.h:224
void onPublishCoordinator(const DebugObserverInterfacePrx &debugObs)
Definition Base.cpp:929
::armarx::aron::data::dto::DictPtr getConfig(const Ice::Current &iceCurrent=Ice::emptyCurrent) override
Definition Base.cpp:616
virtual void collectArviz(viz::StagedCommit &stage) const
Definition Base.cpp:983
NJointTaskspaceController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
Definition Base.cpp:138
Ice::FloatSeq getTCPVel(const std::string &rns, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
Definition Base.cpp:712
void useCoordinator(const std::string &type, const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
Definition Base.cpp:1128
bool isSafeForceTorque(const std::string &nodeSetName, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
-----------------------------— Other interaces ----------------------------------------—
Definition Base.cpp:678
typename NJointTaskspaceControllerType::Config Config
Definition Base.h:63
bool wasNotSafeForceTorque(const std::string &nodeSetName, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
Definition Base.cpp:695
void limbRTSetTarget(ArmPtr &arm, const size_t nDoFTorque, const size_t nDoFVelocity, const Eigen::VectorXf &targetTorque, const Eigen::VectorXf &targetVelocity)
Definition Base.cpp:380
void enableSafeGuardForceTorque(const std::string &nodeSetName, const bool forceGuard, const bool torqueGuard, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
Definition Base.cpp:650
void rtPostDeactivateController() override
This function is called after the controller is deactivated.
Definition Base.cpp:1329
void updateInputData(const std::string &key, const Eigen::Matrix4f &targetPose, const PoseFrameMode &targetPoseMode, const Eigen::Matrix4f &pose, const Eigen::Vector6f &vel, const Eigen::Vector6f &ft, const Eigen::Vector6f &stiffness)
some method for coordinator
Definition Base.cpp:460
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration) override
TODO make protected and use attorneys.
Definition Base.cpp:534
void activateController(const Ice::Current &current=Ice::emptyCurrent) final
NJointControllerBase interface.
Definition Base.cpp:1275
std::map< std::string, common::coordination::InputData > coordinatorInputData
Definition Base.h:225
void updateConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
NJointController interface.
Definition Base.cpp:560
virtual void validateConfigDataCheckSize(Config &configData, ArmPtr &arm)=0
bool updateTargetPose(const TargetPoseMap &targetPoseMap, const TargetNullspaceMap &targetNullspaceMap, const Ice::Current &=Ice::emptyCurrent) override
Definition Base.cpp:749
static ConfigPtrT GenerateConfigFromVariants(const StringVariantBaseMap &values)
Definition Base.cpp:1404
virtual void limbPublishConfig(StringVariantBaseMap &datafields, ArmPtr &arm)=0
void limbPublish(ArmPtr &arm, const DebugObserverInterfacePrx &debugObs)
Definition Base.cpp:819
armarx::control::common::arondto::PoseFrameMode PoseFrameMode
Definition Base.h:67
void deactivateController(const Ice::Current &current=Ice::emptyCurrent) final
Definition Base.cpp:1298
void rtPreActivateController() override
This function is called before the controller is activated.
Definition Base.cpp:1311
void limbRTUpdateStatus(ArmPtr &arm, const double deltaT)
-----------------------------— Real time cotnrol --------------------------------------—
Definition Base.cpp:351
void limbInit(const std::string &nodeSetName, ArmPtr &arm, Config &cfg, VirtualRobot::RobotPtr &nonRtRobotPtr)
Definition Base.cpp:57
DerivedT & color(Color color)
Definition ElementOps.h:218
DerivedT & scale(Eigen::Vector3f scale)
Definition ElementOps.h:254
#define ARMARX_CHECK_GREATER(lhs, rhs)
This macro evaluates whether lhs is greater (>) than rhs and if it turns out to be false it will thro...
#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_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
#define ARMARX_INFO
The normal logging level.
Definition Logging.h:181
#define ARMARX_IMPORTANT
The logging level for always important information, but expected behaviour (in contrast to ARMARX_WAR...
Definition Logging.h:190
#define ARMARX_ERROR
The logging level for unexpected behaviour, that must be fixed.
Definition Logging.h:196
#define ARMARX_INFO_S
Definition Logging.h:202
#define ARMARX_DEBUG
The logging level for output that is only interesting while debugging.
Definition Logging.h:184
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
Definition Logging.h:193
armarx::aron::data::dto::Dict getRTStatus()
Matrix< float, 6, 1 > Vector6f
std::shared_ptr< class Robot > RobotPtr
Definition Bus.h:19
::IceInternal::Handle<::armarx::WidgetDescription::Widget > WidgetPtr
::IceInternal::Handle< Dict > DictPtr
void reportPoseDeviationWarning(const std::string &who, const Eigen::Matrix4f &pose1, const Eigen::Matrix4f &pose2, const std::string &namePose1, const std::string &namePose2)
Definition utils.cpp:754
bool detectAndReportPoseDeviationWarning(const Eigen::Matrix4f &pose1, const Eigen::Matrix4f &pose2, const std::string &namePose1, const std::string &namePose2, float positionThrMM, float angleThrDeg, const std::string &who)
Definition utils.cpp:773
bool poseDeviationTooLarge(const Eigen::Matrix4f &currentPose, const Eigen::Matrix4f &desiredPose, float positionThrMM, float angleThrDeg)
Definition utils.cpp:742
void debugEigenVec(StringVariantBaseMap &datafields, const std::string &name, Eigen::VectorXf vec)
Definition utils.cpp:190
float getDeltaAngleBetweenPose(const Eigen::Matrix4f &pose1, const Eigen::Matrix4f &pose2)
Definition utils.cpp:736
void debugEigenPose(StringVariantBaseMap &datafields, const std::string &name, Eigen::Matrix4f pose)
Definition utils.cpp:140
DVec mat4ToDVec(const Eigen::Matrix4f &mat)
convert Eigen:Matrix4f to 7D double vector.
Definition utils.cpp:359
void debugEigenMat(StringVariantBaseMap &datafields, const std::string &name, const Eigen::MatrixXd &mat)
Definition utils.cpp:152
std::string sVecToString(const std::vector< std::string > &vec, const std::string &delimiter)
Definition utils.cpp:439
Eigen::Block< Eigen::Matrix4f, 3, 1 > getPos(Eigen::Matrix4f &matrix)
Definition utils.cpp:301
NJointControllerRegistration< NJointTSAdmController > registrationControllerNJointTSAdmController("TSAdm")
NJointControllerRegistration< NJointTSImpController > registrationControllerNJointTSImpController("TSImp")
NJointControllerRegistration< NJointTSMixImpVelController > registrationControllerNJointTSMixImpVelController("TSMixImpVel")
NJointControllerRegistration< NJointTSVelController > registrationControllerNJointTSVelController("TSVel")
dictionary< string, Ice::FloatSeq > TargetNullspaceMap
dictionary< string, FloatSeqSeq > TargetPoseMap
::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
double norm(const Point &a)
Definition point.hpp:102
Arrow & width(float w)
Definition Elements.h:211
std::size_t size() const noexcept
Definition Layer.h:52
void add(ElementT const &element)
Definition Layer.h:31
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