MixedImpedanceVelocityController.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 2024
19 * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
20 * GNU General Public License
21 */
22
24
25#include <SimoxUtility/color/Color.h>
26#include <VirtualRobot/MathTools.h>
27#include <VirtualRobot/Nodes/RobotNode.h>
28#include <VirtualRobot/RobotNodeSet.h>
29
31#include <ArmarXCore/core/PackagePath.h> // for GUI
35
41
45
47{
48 NJointControllerRegistration<NJointTaskspaceMixedImpedanceVelocityController>
50 "NJointTaskspaceMixedImpedanceVelocityController");
51
52 void
54 ArmPtr& arm,
55 Config& cfg,
56 VirtualRobot::RobotPtr& nonRtRobotPtr)
57 {
58 arm->kinematicChainName = nodeSetName;
59 VirtualRobot::RobotNodeSetPtr rtRns =
60 rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
61 VirtualRobot::RobotNodeSetPtr nonRtRns =
62 nonRtRobotPtr->getRobotNodeSet(arm->kinematicChainName);
63 ARMARX_CHECK_EXPRESSION(rtRns) << arm->kinematicChainName;
64 ARMARX_CHECK_EXPRESSION(nonRtRns) << arm->kinematicChainName;
65 ARMARX_IMPORTANT << "Creating Taskspace Impedance controller with kinematic chain: "
66 << arm->kinematicChainName << " with num of joints: (RT robot) "
67 << rtRns->getSize() << ", and (non-RT robot) " << nonRtRns->getSize();
68
69 std::vector<size_t> jointIDTorqueMode;
70 std::vector<size_t> jointIDVelocityMode;
71 arm->jointNames.clear();
72 for (size_t i = 0; i < rtRns->getSize(); ++i)
73 {
74 std::string jointName = rtRns->getNode(i)->getName();
75 arm->jointNames.push_back(jointName);
76
77 bool foundControlDevice = false;
78 auto it = std::find(
79 cfg.jointNameListTorque.begin(), cfg.jointNameListTorque.end(), jointName);
80 if (it != cfg.jointNameListTorque.end())
81 {
82 ControlTargetBase* ct = useControlTarget(jointName, ControlModes::Torque1DoF);
84 << "Could not get control target for " << QUOTED(jointName) << ". "
85 << "If this joint is currently not available (e.g., belonging to an "
86 << "unavailable arm), make sure to select a controller config that respects "
87 "this.";
88 auto* casted_ct = ct->asA<ControlTarget1DoFActuatorTorque>();
89 ARMARX_CHECK_EXPRESSION(casted_ct);
90 arm->targetsTorque.push_back(casted_ct);
91 jointIDTorqueMode.push_back(i);
92 foundControlDevice = true;
93 }
94
95 it = std::find(
96 cfg.jointNameListVelocity.begin(), cfg.jointNameListVelocity.end(), jointName);
97 if (it != cfg.jointNameListVelocity.end())
98 {
99 ControlTargetBase* ct = useControlTarget(jointName, ControlModes::Velocity1DoF);
101 auto* casted_ct = ct->asA<ControlTarget1DoFActuatorVelocity>();
102 ARMARX_CHECK_EXPRESSION(casted_ct);
103 arm->targetsVel.push_back(casted_ct);
104 jointIDVelocityMode.push_back(i);
105 foundControlDevice = true;
106 }
107 if (not foundControlDevice)
108 {
109 auto namesTorque = armarx::control::common::sVecToString(cfg.jointNameListTorque);
110 auto namesVelocity =
111 armarx::control::common::sVecToString(cfg.jointNameListVelocity);
112 ARMARX_ERROR << "Does not found valid control device for joint name: " << jointName
113 << "Please check torque controlled joints: [" << namesTorque
114 << "] and velocity controlled joints: [" << namesVelocity << "].";
115 }
116
117 const SensorValueBase* sv = useSensorValue(jointName);
119 arm->sensorDevices.append(sv, jointName);
120 };
121 ARMARX_DEBUG << "Number of torque controlled joints " << jointIDTorqueMode.size();
122 ARMARX_DEBUG << "Number of velocity controlled joints " << jointIDVelocityMode.size();
123 ARMARX_CHECK_EQUAL(rtRns->getNodeNames().size(),
124 jointIDTorqueMode.size() + jointIDVelocityMode.size());
125
126 arm->controller.initialize(nonRtRns, rtRns, jointIDTorqueMode, jointIDVelocityMode);
127 arm->controller.ftsensor.initialize(rtRns, robotUnit, cfg.ftConfig);
128
129 validateConfigData(cfg, arm);
130 arm->rtConfig = cfg;
131 arm->nonRtConfig = cfg;
132 arm->rtStatus.reset(rtRns->getSize(), jointIDTorqueMode, jointIDVelocityMode);
133 }
134
137 const NJointControllerConfigPtr& config,
138 const VirtualRobot::RobotPtr&) :
140 {
142
143 ConfigPtrT cfg = ConfigPtrT::dynamicCast(config);
145 userConfig.fromAron(cfg->config);
146
148 nonRtRobot = robotUnit->cloneRobot();
149 robotUnit->updateVirtualRobot(nonRtRobot);
150
151 for (auto& pair : userConfig.limbs)
152 {
153 limb.emplace(pair.first, std::make_unique<ArmData>());
154 limbInit(pair.first, limb.at(pair.first), pair.second, nonRtRobot);
155 controllableNodeSets.emplace(pair.first, nonRtRobot->getRobotNodeSet(pair.first));
156 }
157
158 if (not userConfig.hands.empty())
159 {
160 hands =
161 std::make_shared<core::HandControlBase>(robotUnit, nonRtRobot, userConfig.hands);
162 for (auto& pair : userConfig.hands)
163 {
164 ARMARX_INFO << "construction of hand "
165 << hands->hands.at(pair.first)->kinematicChainName;
166 controllableNodeSets.emplace(pair.first, nonRtRobot->getRobotNodeSet(pair.first));
167 }
168 }
169 }
170
171 std::string
173 {
174 return "NJointTaskspaceMixedImpedanceVelocityController";
175 }
176
177 void
179 {
180 std::string taskName = getClassName() + "AdditionalTask";
181 runTask(taskName,
182 [&]
183 {
185 4); // please don't set this to 0 as it is the rtRun/control thread
188
189 CycleUtil c(1);
190 getObjectScheduler()->waitForObjectStateMinimum(eManagedIceObjectStarted);
191 ARMARX_IMPORTANT << "Create a new thread for " << getClassName();
192 while (getState() == eManagedIceObjectStarted)
193 {
194 if (isControllerActive())
195 {
197 }
198 c.waitForCycleDuration();
199 }
200 });
201 }
202
203 void
205 {
206 arm->bufferConfigNonRtToRt.getWriteBuffer() = arm->nonRtConfig;
207 arm->bufferConfigNonRtToRt.commitWrite();
208 }
209
210 void
212 {
213 // bool rtSafe = additionalTaskUpdateStatus();
214 auto [rtTargetSafe, ftSafe] = additionalTaskUpdateStatus();
216 if (not rtTargetSafe)
217 {
219 }
220 }
221
222 std::tuple<bool, bool>
224 {
225 robotUnit->updateVirtualRobot(nonRtRobot);
226 bool rtSafe = true;
227 bool rtTargetSafe = true;
228 bool forceTorqueSafe = true;
229 for (auto& pair : limb)
230 {
231 auto& arm = pair.second;
232 arm->nonRtConfig = arm->bufferConfigUserToNonRt.getUpToDateReadBuffer();
233 arm->rtStatusInNonRT = arm->bufferRtStatusToNonRt.getUpToDateReadBuffer();
234 rtSafe = rtSafe and pair.second->rtStatusInNonRT.rtSafe;
235 rtTargetSafe = rtTargetSafe and pair.second->rtStatusInNonRT.rtTargetSafe;
236 forceTorqueSafe = forceTorqueSafe and pair.second->rtStatusInNonRT.forceTorqueSafe;
237 }
238 if (hands)
239 {
240 hands->nonRTUpdateStatus();
241 }
242 return std::make_tuple(rtTargetSafe, forceTorqueSafe);
243 }
244
245 void
247 {
248 for (auto& pair : limb)
249 {
250 limbNonRT(pair.second);
251 }
252 if (hands)
253 {
254 hands->nonRTSetTarget();
255 }
256 }
257
258 void
260 {
261 for (auto& pair : limb)
262 {
263 if (not pair.second->rtReady)
264 continue;
265
266 if (not pair.second->rtStatusInNonRT.rtTargetSafe)
267 {
269 pair.second->rtStatusInNonRT.currentPose,
270 pair.second->rtStatusInNonRT.desiredPoseUnsafe,
271 "current pose",
272 "desired pose");
273 }
274 }
275 }
276
277 /// -------------------------------- Real time cotnrol -----------------------------------------
278 void
280 const double deltaT)
281 {
282 arm->rtConfig = arm->bufferConfigNonRtToRt.getUpToDateReadBuffer();
283 arm->rtStatus.deltaT = deltaT;
284 arm->rtStatus.accumulateTime += deltaT;
285
286 arm->controller.ftsensor.updateStatus(arm->rtConfig.ftConfig,
287 arm->rtStatus.currentForceTorque,
288 arm->rtStatus.deltaT,
289 arm->rtFirstRun.load());
290 arm->rtStatus.safeFTGuardOffset.head<3>() =
291 arm->controller.ftsensor.getSafeGuardForceOffset();
292
293 arm->sensorDevices.updateJointValues(
294 arm->rtStatus.jointPosition, arm->rtStatus.jointVelocity, arm->rtStatus.jointTorque);
295 // rtGetRobot()->getRobotNodeSet(arm->kinematicChainName)
296
297
298 arm->bufferRtStatusToNonRt.getWriteBuffer() = arm->rtStatus;
299 arm->bufferRtStatusToNonRt.commitWrite();
300 arm->bufferRtStatusToUser.getWriteBuffer() = arm->rtStatus;
301 arm->bufferRtStatusToUser.commitWrite();
302 }
303
304 void
306 ArmPtr& arm,
307 const size_t nDoFTorque,
308 const size_t nDoFVelocity,
309 const Eigen::VectorXf& targetTorque,
310 const Eigen::VectorXf& targetVelocity)
311 {
312 for (size_t i = 0; i < nDoFTorque; i++)
313 {
314 auto jointIdx = arm->controller.jointIDTorqueMode[i];
315 arm->targetsTorque.at(i)->torque = targetTorque(jointIdx);
316 if (!arm->targetsTorque.at(i)->isValid())
317 {
318 arm->targetsTorque.at(i)->torque = 0;
319 }
320 }
321 for (size_t i = 0; i < nDoFVelocity; i++)
322 {
323 auto jointIdx = arm->controller.jointIDVelocityMode[i];
324 arm->targetsVel.at(i)->velocity = targetVelocity(jointIdx);
325 // if (!targets.at(i)->isValid() || fabs(targets.at(i)->velocity) > cfg->maxJointVelocity)
326 if (!arm->targetsVel.at(i)->isValid())
327 {
328 arm->targetsVel.at(i)->velocity = 0;
329 }
330 }
331 arm->bufferRtStatusToOnPublish.getWriteBuffer() = arm->rtStatus;
332 arm->bufferRtStatusToOnPublish.commitWrite();
333
334 arm->bufferConfigRtToOnPublish.getWriteBuffer() = arm->rtConfig;
335 arm->bufferConfigRtToOnPublish.commitWrite();
336
337 arm->bufferConfigRtToUser.getWriteBuffer() = arm->rtConfig;
338 arm->bufferConfigRtToUser.commitWrite();
339
340 if (arm->rtFirstRun.load())
341 {
342 arm->rtFirstRun.store(false);
343 arm->rtReady.store(true);
344 }
345 }
346
347 void
349 {
350 double time_measure = IceUtil::Time::now().toMicroSecondsDouble();
351 // limbRTUpdateStatus(arm, deltaT);
352 // double time_update_status = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
353
354 arm->controller.run(arm->rtConfig, arm->rtStatus);
355 double time_run_rt = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
356
357 limbRTSetTarget(arm,
358 arm->rtStatus.nDoFTorque,
359 arm->rtStatus.nDoFVelocity,
360 arm->rtStatus.desiredJointTorque,
361 arm->rtStatus.desiredJointVelocity);
362
363 double time_set_target = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
364 time_measure = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
365
366 if (time_measure > 200)
367 {
368 ARMARX_RT_LOGF_WARN("---- rt too slow: "
369 "run_rt_limb: %.2f\n"
370 "set_target_limb: %.2f\n"
371 "time all: %.2f\n",
372 time_run_rt - time_measure, //
373 time_set_target - time_run_rt, //
374 time_measure)
375 .deactivateSpam(1.0f); // 0-1 us
376 }
377 }
378
379 /// some method for coordinator
380 void
382 const std::string& key,
383 const Eigen::Matrix4f& targetPose,
384 const PoseFrameMode& targetPoseMode,
385 const Eigen::Matrix4f& pose,
386 const Eigen::Vector6f& vel,
387 const Eigen::Vector6f& ft,
388 const Eigen::Vector6f& stiffness)
389 {
390 if (coordinatorInputData.find(key) != coordinatorInputData.end())
391 {
392 // Update existing InputData
393 auto& data = coordinatorInputData.at(key);
394 data.pose = pose;
395 data.targetPose = targetPose;
396 data.targetPoseMode = targetPoseMode;
397 data.vel = vel;
398 data.ft = ft;
399 data.stiffness = stiffness;
400 }
401 else
402 {
403 coordinatorInputData.emplace(key,
405 targetPose, targetPoseMode, pose, vel, ft, stiffness));
406 }
407 }
408
409 void
411 {
412 if (not coordinatorEnabled.load() or not coordinator)
413 {
414 return;
415 }
416
417 bool rtReady = false;
418 for (const auto& nodeset : coordinator->getNodesetList())
419 {
420 auto& rts = limb.at(nodeset)->rtStatus;
421 auto& rtc = limb.at(nodeset)->rtConfig;
422 rtReady = limb.at(nodeset)->rtReady.load();
423 updateInputData(nodeset,
424 rtc.desiredPose,
425 rtc.desiredPoseFrameMode,
426 rts.currentPose,
427 rts.currentTwist,
428 rts.currentForceTorque,
429 rtc.kpImpedance);
430 }
431 if (not rtReady)
432 {
433 return;
434 }
435 coordinator->runRT(coordinatorInputData, deltaT);
436 for (const auto& nodeset : coordinator->getNodesetList())
437 {
438 limb.at(nodeset)->rtConfig.desiredPose = coordinatorInputData.at(nodeset).targetPose;
439 limb.at(nodeset)->rtConfig.desiredPoseFrameMode = PoseFrameMode::root;
440 }
441 }
442
443 void
445 const IceUtil::Time& /*sensorValuesTimestamp*/,
446 const IceUtil::Time& timeSinceLastIteration)
447 {
448 double deltaT = timeSinceLastIteration.toSecondsDouble();
449 for (auto& pair : limb)
450 {
451 limbRTUpdateStatus(pair.second, deltaT);
452 }
453
454 rtRunCoordinator(deltaT);
455
456 for (auto& pair : limb)
457 {
458 limbRT(pair.second, deltaT);
459 }
460 if (hands)
461 {
462 hands->updateRTStatus(deltaT);
463 }
464 }
465
466 /// ------------------------------ update/get config -------------------------------------------
467 void
469 const ::armarx::aron::data::dto::DictPtr& dto,
470 const Ice::Current& iceCurrent)
471 {
472 auto prevCfg = userConfig;
473 userConfig.fromAron(dto);
474
475 for (auto& pair : userConfig.limbs)
476 {
477 validateConfigData(pair.second, limb.at(pair.first));
478 bool desiredPoseFrameModeSame = prevCfg.limbs.at(pair.first).desiredPoseFrameMode ==
479 pair.second.desiredPoseFrameMode;
480 if (desiredPoseFrameModeSame and common::detectAndReportPoseDeviationWarning(
481 pair.second.desiredPose,
482 prevCfg.limbs.at(pair.first).desiredPose,
483 "new desired pose",
484 "previous desired pose",
485 pair.second.safeDistanceMMToGoal,
486 pair.second.safeRotAngleDegreeToGoal,
487 "updateConfig_" + pair.first))
488 {
489 ARMARX_INFO << "use the existing target pose";
490 pair.second.desiredPose = prevCfg.limbs.at(pair.first).desiredPose;
491 }
492 limb.at(pair.first)->bufferConfigUserToNonRt.getWriteBuffer() = pair.second;
493 limb.at(pair.first)->bufferConfigUserToNonRt.commitWrite();
494 }
495 if (hands)
496 {
497 hands->updateConfig(userConfig.hands);
498 }
499 }
500
503 {
504 for (auto& pair : limb)
505 {
506 userConfig.limbs.at(pair.first) =
507 pair.second->bufferConfigRtToUser.getUpToDateReadBuffer();
508 }
509 if (hands)
510 {
511 hands->getConfig(userConfig.hands);
512 }
513 return userConfig.toAronDTO();
514 }
515
518 {
519 for (auto& pair : limb)
520 {
521 userConfig.limbs.at(pair.first) =
522 pair.second->bufferConfigRtToUser.getUpToDateReadBuffer();
523 }
524 if (hands)
525 {
526 hands->getConfig(userConfig.hands);
527 }
528 return userConfig.toAronDTO();
529 }
530
531 void
533 const std::string& nodeSetName,
534 const bool forceGuard,
535 const bool torqueGuard,
536 const Ice::Current& iceCurrent)
537 {
538 auto it = userConfig.limbs.find(nodeSetName);
539 if (it != userConfig.limbs.end())
540 {
541 it->second.ftConfig.enableSafeGuardForce = forceGuard;
542 it->second.ftConfig.enableSafeGuardTorque = torqueGuard;
543 limb.at(nodeSetName)->controller.ftsensor.enableSafeGuard(forceGuard, torqueGuard);
545 << "reset safe guard with force torque sensors: safe? "
546 << limb.at(nodeSetName)->controller.ftsensor.isSafe(it->second.ftConfig);
547 limb.at(nodeSetName)->bufferConfigUserToNonRt.getWriteBuffer() = it->second;
548 limb.at(nodeSetName)->bufferConfigUserToNonRt.commitWrite();
549 }
550 else
551 {
552 ARMARX_WARNING << "no robot node set with name " << nodeSetName
553 << " found in the controllers.";
554 }
555 }
556
557 /// -------------------------------- Other interaces -------------------------------------------
558 bool
560 const std::string& nodeSetName,
561 const Ice::Current& iceCurrent)
562 {
563 auto it = userConfig.limbs.find(nodeSetName);
564 if (it != userConfig.limbs.end())
565 {
566 return limb.at(nodeSetName)->controller.ftsensor.ftSafe.load();
567 }
568
569 ARMARX_WARNING << "no robot node set with name " << nodeSetName
570 << " found in the controllers.";
571 return false;
572 }
573
574 Ice::FloatSeq
576 const Ice::Current& iceCurrent)
577 {
578 std::vector<float> tcpVel;
579 auto& arm = limb.at(rns);
580 auto s = arm->bufferRtStatusToUser.getUpToDateReadBuffer();
581 for (int i = 0; i < s.currentTwist.size(); i++)
582 {
583 tcpVel.push_back(s.currentTwist[i]);
584 }
585 return tcpVel;
586 }
587
588 Ice::DoubleSeq
590 const std::string& nodeSetName,
591 const Ice::Current& iceCurrent)
592 {
593 auto search = limb.find(nodeSetName);
594 if (search == limb.end())
595 {
596 ARMARX_WARNING << "requested node set " << nodeSetName
597 << "does not exist in the controller";
598 return std::vector<double>{};
599 }
600
601 auto& arm = limb.at(nodeSetName);
602 auto currentPose = arm->bufferRtStatusToOnPublish.getUpToDateReadBuffer().currentPose;
603 ARMARX_DEBUG << "returning current pose" << VAROUT(currentPose);
604 return common::mat4ToDVec(currentPose);
605 }
606
607 bool
609 const TargetPoseMap& targetPoseMap,
610 const TargetNullspaceMap& targetNullspaceMap,
611 const Ice::Current& iceCurrent)
612 {
613 for (auto& pair : userConfig.limbs)
614 {
615 for (size_t i = 0; i < 4; ++i)
616 {
617 for (int j = 0; j < 4; ++j)
618 {
619 pair.second.desiredPose(i, j) = targetPoseMap.at(pair.first)[i][j];
620 }
621 }
622 if (targetNullspaceMap.at(pair.first).size() > 0)
623 {
624 const size_t nDoF = pair.second.desiredNullspaceJointAngles.value().size();
625 ARMARX_CHECK_EQUAL(targetNullspaceMap.at(pair.first).size(), nDoF)
626 << "the joint numbers does not match";
627 for (size_t i = 0; i < nDoF; ++i)
628 {
629 pair.second.desiredNullspaceJointAngles.value()(i) =
630 targetNullspaceMap.at(pair.first)[i];
631 }
632 }
633 limb.at(pair.first)->bufferConfigUserToNonRt.getWriteBuffer() = pair.second;
634 limb.at(pair.first)->bufferConfigUserToNonRt.commitWrite();
635 }
636 return true;
637 }
638
639 void
641 ArmPtr& arm)
642 {
643 const auto nDoF = arm->jointNames.size();
644
645 const auto checkSize = [nDoF](const auto& v) { ARMARX_CHECK_EQUAL(v.rows(), nDoF); };
646 const auto checkNonNegative = [](const auto& v) { ARMARX_CHECK((v.array() >= 0).all()); };
647
648 if (!configData.desiredNullspaceJointAngles.has_value())
649 {
650 if (!isControllerActive())
651 {
652 ARMARX_INFO << "No user defined nullspace target, reset to zero with "
653 << VAROUT(nDoF);
654 configData.desiredNullspaceJointAngles = Eigen::VectorXf::Zero(nDoF);
655 arm->reInitPreActivate.store(true);
656 }
657 else
658 {
659 auto currentValue =
660 arm->bufferConfigRtToUser.getUpToDateReadBuffer().desiredNullspaceJointAngles;
662 << "Controller is active, but no user defined nullspace target. \n"
663 "You should first get up-to-date config of this controller and then update "
664 "it:\n"
665 " auto cfg = ctrl->getConfig(); \n"
666 " cfg.desiredPose = xxx;\n"
667 " ctrl->updateConfig(cfg);\n"
668 "Now, I decide by myself to use the existing values of nullspace target\n"
669 << currentValue.value();
670 configData.desiredNullspaceJointAngles = currentValue;
671 }
672 }
673 ARMARX_CHECK_GREATER(configData.safeDistanceMMToGoal, 100.0f);
674 checkSize(configData.desiredNullspaceJointAngles.value());
675 checkSize(configData.kdNullspaceTorque);
676 checkSize(configData.kpNullspaceTorque);
677 checkSize(configData.kdNullspaceVel);
678 checkSize(configData.kpNullspaceVel);
679
680 checkNonNegative(configData.kdNullspaceTorque);
681 checkNonNegative(configData.kpNullspaceTorque);
682 checkNonNegative(configData.kpNullspaceVel);
683 checkNonNegative(configData.kdNullspaceVel);
684 checkNonNegative(configData.kdImpedance);
685 checkNonNegative(configData.kpImpedance);
686 }
687
688 void
690 ArmPtr& arm,
691 const DebugObserverInterfacePrx& debugObs)
692 {
693 StringVariantBaseMap datafields;
694 auto rtData = arm->bufferConfigRtToOnPublish.getUpToDateReadBuffer();
695 auto rtStatus = arm->bufferRtStatusToOnPublish.getUpToDateReadBuffer();
696
697 common::debugEigenVec(datafields, "kpImpedance", rtData.kpImpedance);
698 common::debugEigenVec(datafields, "kdImpedance", rtData.kdImpedance);
699 if (rtData.desiredNullspaceJointAngles.has_value())
700 {
701 common::debugEigenVec(datafields,
702 "desiredNullspaceJointAngles",
703 rtData.desiredNullspaceJointAngles.value());
704 }
705
706 common::debugEigenVec(datafields, "jointPosition", rtStatus.jointPosition);
707 common::debugEigenVec(datafields, "jointVelocity", rtStatus.jointVelocity);
708 common::debugEigenVec(datafields, "qvelFiltered", rtStatus.qvelFiltered);
709
710 common::debugEigenPose(datafields, "current_pose", rtStatus.currentPose);
711 common::debugEigenPose(datafields, "desired_pose", rtStatus.desiredPose);
712 float positionError =
713 (common::getPos(rtStatus.currentPose) - common::getPos(rtStatus.desiredPose)).norm();
714 float angleError =
715 common::getDeltaAngleBetweenPose(rtStatus.currentPose, rtStatus.desiredPose);
716 datafields["poseError_position"] = new Variant(positionError);
717 datafields["poseError_angle"] = new Variant(angleError);
718 datafields["poseError_threshold_position"] = new Variant(rtData.safeDistanceMMToGoal);
719 datafields["poseError_threshold_angle"] = new Variant(rtData.safeRotAngleDegreeToGoal);
720
721 common::debugEigenVec(datafields, "current_twist", rtStatus.currentTwist);
722 common::debugEigenVec(datafields, "poseErrorImp", rtStatus.poseErrorImp);
723
724 common::debugEigenVec(datafields, "currentForceTorque", rtStatus.currentForceTorque);
725 common::debugEigenVec(datafields, "safeFTGuardOffset", rtStatus.safeFTGuardOffset);
726
727 float currentForceNorm = rtStatus.currentForceTorque.head<3>().norm();
728 float currentTorqueNorm = rtStatus.currentForceTorque.tail<3>().norm();
729 float safeForceGuardOffsetNorm = rtStatus.safeFTGuardOffset.head<3>().norm();
730 float safeTorqueGuardOffsetNorm = rtStatus.safeFTGuardOffset.tail<3>().norm();
731 datafields["currentForceNorm"] = new Variant(currentForceNorm);
732 datafields["currentTorqueNorm"] = new Variant(currentTorqueNorm);
733 datafields["safeForceGuardOffsetNorm"] = new Variant(safeForceGuardOffsetNorm);
734 datafields["safeTorqueGuardOffsetNorm"] = new Variant(safeTorqueGuardOffsetNorm);
735 datafields["safeForceGuardDifference"] =
736 new Variant(currentForceNorm - safeForceGuardOffsetNorm);
737 datafields["safeTorqueGuardDifference"] =
738 new Variant(currentTorqueNorm - safeTorqueGuardOffsetNorm);
739 datafields["safeForceGuardThreshold"] =
740 new Variant(rtData.ftConfig.safeGuardForceThreshold);
741 datafields["safeTorqueGuardThreshold"] =
742 new Variant(rtData.ftConfig.safeGuardTorqueThreshold);
743
744 datafields["rtSafe"] = new Variant(rtStatus.rtSafe * 1.0);
745 datafields["rtTargetSafe"] = new Variant(rtStatus.rtTargetSafe * 1.0);
746 bool forceTrigger = (not rtStatus.rtSafe) and rtStatus.rtTargetSafe;
747 datafields["forceTrigger"] = new Variant(forceTrigger * 1.0);
748 datafields["forceTorqueSafe"] = new Variant(rtStatus.forceTorqueSafe * 1.0);
749
750 common::debugEigenVec(datafields, "forceImpedance", rtStatus.forceImpedance);
751 common::debugEigenVec(datafields, "cartesianVelTarget", rtStatus.cartesianVelTarget);
752
753 common::debugEigenVec(datafields, "desiredJointTorques", rtStatus.desiredJointTorque);
754 common::debugEigenVec(datafields, "desiredJointVelocity", rtStatus.desiredJointVelocity);
755 common::debugEigenVec(datafields, "nullspaceTorque", rtStatus.nullspaceTorque);
756 common::debugEigenVec(datafields, "nullspaceVelocity", rtStatus.nullspaceVelocity);
757 debugObs->setDebugChannel(getClassName() + "_" + arm->kinematicChainName, datafields);
758
759 viz::Layer layer = arviz.layer(getClassName() + "_" + arm->kinematicChainName);
760 layer.add(viz::Arrow("tsImpForce")
761 .fromTo(common::getPos(rtStatus.currentPose),
762 common::getPos(rtStatus.currentPose) +
763 rtStatus.forceImpedance.head<3>() * 5.0)
764 .color(simox::Color::green()));
765 // arviz.commit(layer);
766 }
767
768 void
770 const SensorAndControl&,
772 const DebugObserverInterfacePrx& debugObs)
773 {
774 for (auto& pair : limb)
775 {
776 if (not pair.second->rtReady.load())
777 continue;
778 limbPublish(pair.second, debugObs);
779 }
780 if (hands)
781 {
782 hands->onPublish(debugObs);
783 }
784 onPublishCoordinator(debugObs);
785 }
786
787 void
789 const DebugObserverInterfacePrx& debugObs)
790 {
791 if (!coordinator)
792 {
793 return;
794 }
795 StringVariantBaseMap datafields;
796 auto& cfg = coordinator->bufferUserCfgToPublish.getUpToDateReadBuffer();
797 auto data = coordinator->bufferDataRtToPublish.getUpToDateReadBuffer();
798 common::debugEigenPose(datafields, "current_pose", data.currentPose);
799 common::debugEigenPose(datafields, "virtualPose", data.virtualPose);
800 common::debugEigenPose(datafields, "targetPose", data.targetPose);
801 common::debugEigenVec(datafields, "currentFT", data.currentFT);
802 common::debugEigenVec(datafields, "pose_error", data.poseError);
803 common::debugEigenVec(datafields, "tempAcc", data.tempAcc);
804 common::debugEigenVec(datafields, "virtualVel", data.virtualVel);
805 common::debugEigenVec(datafields, "virtualAcc", data.virtualAcc);
806 // ARMARX_INFO << VAROUT(data.obj2TcpInMeterL) << VAROUT(data.obj2TcpInMeterL);
807
808 using namespace armarx::control::common::coordination::arondto;
809 auto followerIsolation = cfg.followerConnectionMode == ConnectionMode::follower_isolated;
810 auto leftAsLeader = cfg.leadershipMode == LeadershipMode::left_as_leader;
811 auto rightAsLeader = cfg.leadershipMode == LeadershipMode::right_as_leader;
812 auto followerInLeaderLocalFrame =
813 cfg.followerFrameMode == common::arondto::PoseFrameMode::leader;
814 datafields["followerIsolation"] = new Variant(followerIsolation);
815 datafields["leftAsLeader"] = new Variant(leftAsLeader);
816 datafields["rightAsLeader"] = new Variant(rightAsLeader);
817 datafields["followerInLeaderLocalFrame"] = new Variant(followerInLeaderLocalFrame);
818
819 debugObs->setDebugChannel("SyncModeCoordinator", datafields);
820
821 /// TODO To viz debug in arviz, commented out when controller is stable
822 viz::Layer layer = arviz.layer("coordinator");
823 layer.add(viz::Pose("targetPose").pose(data.targetPose).scale(1.0f));
824 layer.add(viz::Pose("virtualPose").pose(data.virtualPose).scale(1.5f));
825 layer.add(viz::Pose("currentPose").pose(data.currentPose).scale(0.8f));
826
827 arviz.commit(layer);
828
829 viz::Layer layerFT = arviz.layer("coordinator_ft");
830 const auto& objCenter = common::getPos(data.currentPose);
831 layerFT.add(viz::Arrow("object_force")
832 .fromTo(objCenter, objCenter + 100.0f * data.currentFT.head<3>())
833 .color(simox::Color::yellow()));
834 layerFT.add(viz::Arrow("object_torque")
835 .fromTo(objCenter, objCenter + 100.0f * data.currentFT.tail<3>())
836 .color(simox::Color::green()));
837 arviz.commit(layerFT);
838
839
840 viz::Layer layerVirtualStatus = arviz.layer("coordinator_virtual_status");
841 layerVirtualStatus.add(
842 viz::Arrow("object_vel")
843 .fromTo(objCenter, objCenter + 1000.0f * data.virtualVel.head<3>())
844 .color(simox::Color::blue()));
845 layerVirtualStatus.add(
846 viz::Arrow("object_pose_error")
847 .fromTo(objCenter, objCenter + 1000.0f * data.poseError.head<3>())
848 .color(simox::Color::black()));
849 arviz.commit(layerVirtualStatus);
850 ///
851 }
852
853 void
855 {
856 for (auto& pair : limb)
857 {
858 pair.second->rtReady.store(false);
859 }
860 }
861
862 void
864 const std::string& type,
865 const ::armarx::aron::data::dto::DictPtr& dto,
866 const Ice::Current& /*unused*/)
867 {
868 ARMARX_INFO << "Adding coordinator of type " << type;
869 /// TODO think about other types of coordinators
870 if (!coordinator)
871 {
872 /// TODO add check if the current controller has all robotNodeSets
873 /// that the coordinator requires. currently, use check below.
874 coordinator = std::make_shared<common::coordination::SyncCoordination>(dto);
875 }
876 else
877 {
878 coordinator->updateConfig(dto);
879 }
880
881 for (const auto& nodeset : coordinator->getNodesetList())
882 {
883 if (limb.find(nodeset) == limb.end())
884 {
885 coordinatorEnabled.store(false);
886 ARMARX_WARNING << "The requested nodeset by coordinator " << nodeset
887 << " does not exist in the current controller, disable coordinator";
888 return;
889 }
890 }
891 coordinatorEnabled.store(true);
892 // std::map<std::string, Eigen::Matrix4f> initPose;
893 // for (const auto& nodeset: coord->getNodesetList())
894 // {
895 // auto buff = limb.at(nodeset)->bufferConfigRtToUser.getUpToDateReadBuffer();
896 // initPose[nodeset] = buff.desiredPose;
897 // ARMARX_INFO << "using node set " << nodeset << " with pose " << buff.desiredPose;
898 // }
899 // coord->reset(initPose);
900 }
901
902 void
904 {
905 ARMARX_INFO << "Disabling coordinator ...";
906 if (not coordinator)
907 {
908 ARMARX_WARNING << "Coordinator is not created yet, use `useCoordinator` to create!";
909 return;
910 }
911
912 for (const auto& nodeset : coordinator->getNodesetList())
913 {
914 auto& arm = limb.at(nodeset);
915 auto& cfgRT = arm->bufferConfigRtToUser.getUpToDateReadBuffer();
916 arm->bufferConfigUserToNonRt.getWriteBuffer().desiredPose = cfgRT.desiredPose;
917 arm->bufferConfigUserToNonRt.commitWrite();
918 usleep(2000);
919 }
920 // usleep(2000);
921 coordinatorEnabled.store(false);
922 ARMARX_INFO << "Coordinator is disabled!!";
923 }
924
925 void
927 {
928 VirtualRobot::RobotNodeSetPtr rns = rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
929 Eigen::Matrix4f currentPose = rns->getTCP()->getPoseInRootFrame();
930 auto quat = VirtualRobot::MathTools::eigen4f2quat(currentPose);
931 ARMARX_RT_LOGF_INFO("rt preactivate controller with target pose\n\n "
932 "[ %.2f, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f ].",
933 currentPose(0, 3),
934 currentPose(1, 3),
935 currentPose(2, 3),
936 quat.w,
937 quat.x,
938 quat.y,
939 quat.z);
940
941 if (arm->reInitPreActivate.load())
942 {
943 arm->rtConfig.desiredNullspaceJointAngles.value() = rns->getJointValuesEigen();
944 arm->rtConfig.desiredPose = currentPose;
945
946 arm->bufferConfigUserToNonRt.reinitAllBuffers(arm->rtConfig);
947 arm->reInitPreActivate.store(false);
948 }
949 {
950 arm->nonRtConfig = arm->rtConfig;
951 arm->bufferConfigNonRtToRt.reinitAllBuffers(arm->rtConfig);
952 arm->bufferConfigRtToOnPublish.reinitAllBuffers(arm->rtConfig);
953 arm->bufferConfigRtToUser.reinitAllBuffers(arm->rtConfig);
954 }
955 {
956 arm->sensorDevices.updateJointValues(arm->rtStatus.jointPosition,
957 arm->rtStatus.jointVelocity,
958 arm->rtStatus.jointTorque);
959 arm->rtStatus.rtPreActivate(currentPose);
960
961 arm->rtStatusInNonRT = arm->rtStatus;
962 arm->nonRTDeltaT = 0.0;
963 arm->nonRTAccumulateTime = 0.0;
964 arm->bufferRtStatusToOnPublish.reinitAllBuffers(arm->rtStatus);
965 arm->bufferRtStatusToNonRt.reinitAllBuffers(arm->rtStatus);
966 arm->bufferRtStatusToUser.reinitAllBuffers(arm->rtStatus);
967 }
968
969 arm->controller.preactivateInit(rns);
970 }
971
972 void
974 {
975 for (auto& pair : limb)
976 {
977 ARMARX_RT_LOGF_INFO("rtPreActivateController for %s", pair.first.c_str());
978 limbReInit(pair.second);
979 userConfig.limbs.at(pair.first) = pair.second->rtConfig;
980 }
981 if (hands)
982 {
983 hands->rtPreActivate();
984 }
985 }
986
987 void
989 {
990 // for (auto& pair : limb)
991 // {
992 // pair.second->controller.isInitialized.store(false);
993 // }
994 // if (hands)
995 // {
996 // hands->rtPostDeactivate();
997 // }
998 coordinatorEnabled.store(false);
999 }
1000
1001 /// ----------------------------------- GUI Widget ---------------------------------------------
1004 const VirtualRobot::RobotPtr& robot,
1005 const std::map<std::string, ConstControlDevicePtr>& controlDevices,
1006 const std::map<std::string, ConstSensorDevicePtr>&)
1007 {
1008 using namespace armarx::WidgetDescription;
1009 HBoxLayoutPtr layout = new HBoxLayout;
1010
1011
1012 ::armarx::WidgetDescription::WidgetSeq widgets;
1013
1014 /// select default config
1015 LabelPtr label = new Label;
1016 label->text = "select a controller config";
1017
1018 StringComboBoxPtr cfgBox = new StringComboBox;
1019 cfgBox->name = "config_box";
1020 cfgBox->defaultIndex = 0;
1021 cfgBox->multiSelect = false;
1022
1023 cfgBox->options = std::vector<std::string>{
1024 "default", "default_right", "default_a7_right", "default_a6_right"};
1026
1027 layout->children.emplace_back(label);
1028 layout->children.emplace_back(cfgBox);
1030
1031 layout->children.insert(layout->children.end(), widgets.begin(), widgets.end());
1032 ARMARX_INFO_S << "Layout done";
1033 return layout;
1034 }
1035
1038 const StringVariantBaseMap& values)
1039 {
1040 auto cfgName = values.at("config_box")->getString();
1041 const armarx::PackagePath configPath(
1042 "armarx_control",
1043 "controller_config/NJointTaskspaceMixedImpedanceVelocityController/" + cfgName +
1044 ".json");
1045 ARMARX_INFO_S << "Loading config from " << configPath.toSystemPath();
1046 ARMARX_CHECK(std::filesystem::exists(configPath.toSystemPath()));
1047
1048 auto cfgDTO = armarx::readFromJson<ConfigDict>(configPath.toSystemPath());
1049
1051 return new ConfigurableNJointControllerConfig{cfgDTO.toAronDTO()};
1052 }
1053
1054} // namespace armarx::control::njoint_controller::task_space
#define ARMARX_RT_LOGF_WARN(...)
#define ARMARX_RT_LOGF_INFO(...)
#define VAROUT(x)
#define QUOTED(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
const SensorValueBase * useSensorValue(const std::string &sensorDeviceName) const
Get a const ptr to the given SensorDevice's SensorValue.
void runTask(const std::string &taskName, Task &&task)
Executes a given task in a separate thread from the Application ThreadPool.
const VirtualRobot::RobotPtr & useSynchronizedRtRobot(bool updateCollisionModel=false)
Requests a VirtualRobot for use in rtRun *.
const VirtualRobot::RobotPtr & rtGetRobot()
TODO make protected and use attorneys.
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
void onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &) override
static WidgetDescription::WidgetPtr GenerateConfigDescription(const VirtualRobot::RobotPtr &, const std::map< std::string, ConstControlDevicePtr > &, const std::map< std::string, ConstSensorDevicePtr > &)
--------------------------------— GUI Widget ------------------------------------------—
Ice::DoubleSeq getCurrentTCPPose(const std::string &nodeSetName, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
::armarx::aron::data::dto::DictPtr getConfig(const Ice::Current &iceCurrent=Ice::emptyCurrent) override
Ice::FloatSeq getTCPVel(const std::string &rns, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
void useCoordinator(const std::string &type, const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
bool isSafeForceTorque(const std::string &nodeSetName, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
-----------------------------— Other interaces ----------------------------------------—
void limbRTSetTarget(ArmPtr &arm, const size_t nDoFTorque, const size_t nDoFVelocity, const Eigen::VectorXf &targetTorque, const Eigen::VectorXf &targetVelocity)
void enableSafeGuardForceTorque(const std::string &nodeSetName, const bool forceGuard, const bool torqueGuard, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
void rtPostDeactivateController() override
This function is called after the controller is deactivated.
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
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration) override
TODO make protected and use attorneys.
void limbInit(const std::string nodeSetName, ArmPtr &arm, Config &cfg, VirtualRobot::RobotPtr &nonRtRobotPtr)
void updateConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
NJointController interface.
bool updateTargetPose(const TargetPoseMap &targetPoseMap, const TargetNullspaceMap &targetNullspaceMap, const Ice::Current &=Ice::emptyCurrent) override
NJointTaskspaceMixedImpedanceVelocityController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
void rtPreActivateController() override
This function is called before the controller is activated.
void limbRTUpdateStatus(ArmPtr &arm, const double deltaT)
-----------------------------— Real time cotnrol --------------------------------------—
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
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
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
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< NJointTaskspaceMixedImpedanceVelocityController > registrationControllerNJointTaskspaceMixedImpedanceVelocityController("NJointTaskspaceMixedImpedanceVelocityController")
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
void add(ElementT const &element)
Definition Layer.h:31
#define ARMARX_TRACE
Definition trace.h:77