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