AdmittanceController.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
24
25#include <VirtualRobot/MathTools.h>
26#include <VirtualRobot/Nodes/RobotNode.h>
27#include <VirtualRobot/RobotNodeSet.h>
28
30#include <ArmarXCore/core/PackagePath.h> // for GUI
34
38
42
44{
47 "NJointTaskspaceAdmittanceController");
48
49 void
50 NJointTaskspaceAdmittanceController::limbInit(const std::string nodeSetName,
51 ArmPtr& arm,
52 Config& cfg,
53 VirtualRobot::RobotPtr& nonRtRobotPtr)
54 {
55 arm->kinematicChainName = nodeSetName;
56 VirtualRobot::RobotNodeSetPtr rtRns =
57 rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
58 VirtualRobot::RobotNodeSetPtr nonRtRns =
59 nonRtRobotPtr->getRobotNodeSet(arm->kinematicChainName);
60 ARMARX_CHECK_EXPRESSION(rtRns) << arm->kinematicChainName;
61 ARMARX_CHECK_EXPRESSION(nonRtRns) << arm->kinematicChainName;
62 ARMARX_IMPORTANT << "Creating Taskspace Impedance controller with kinematic chain: "
63 << arm->kinematicChainName << " with num of joints: (RT robot) "
64 << rtRns->getSize() << ", and (non-RT robot) " << nonRtRns->getSize();
65
66 arm->controller.initialize(nonRtRns, rtRns);
67 arm->controller.ftsensor.initialize(rtRns, robotUnit, cfg.ftConfig);
68 arm->jointNames.clear();
69 std::vector<size_t> jointIDTorqueMode;
70 std::vector<size_t> jointIDVelocityMode;
71 for (size_t i = 0; i < rtRns->getSize(); ++i)
72 {
73 std::string jointName = rtRns->getNode(i)->getName();
74 arm->jointNames.push_back(jointName);
75
76 ControlTargetBase* ct = useControlTarget(jointName, ControlModes::Torque1DoF);
78 auto* casted_ct = ct->asA<ControlTarget1DoFActuatorTorque>();
79 ARMARX_CHECK_EXPRESSION(casted_ct);
80 arm->targets.push_back(casted_ct);
81
82 const SensorValueBase* sv = useSensorValue(jointName);
84 arm->sensorDevices.append(sv, jointName);
85 jointIDTorqueMode.push_back(i);
86 };
87
88 validateConfigData(cfg, arm);
89 arm->rtConfig = cfg;
90 arm->nonRtConfig = cfg;
91 auto nDoF = rtRns->getSize();
92 arm->rtStatus.reset(nDoF, jointIDTorqueMode, jointIDVelocityMode);
93 }
94
97 const NJointControllerConfigPtr& config,
100 {
102
103 ConfigPtrT cfg = ConfigPtrT::dynamicCast(config);
105 userConfig.fromAron(cfg->config);
106
108 nonRtRobot = robotUnit->cloneRobot();
109 robotUnit->updateVirtualRobot(nonRtRobot);
110
111 for (auto& pair : userConfig.limbs)
112 {
113 limb.emplace(pair.first, std::make_unique<ArmData>());
114 limbInit(pair.first, limb.at(pair.first), pair.second, nonRtRobot);
115 controllableNodeSets.emplace(pair.first, nonRtRobot->getRobotNodeSet(pair.first));
116 }
117
118 if (not userConfig.hands.empty())
119 {
120 hands =
121 std::make_shared<core::HandControlBase>(robotUnit, nonRtRobot, userConfig.hands);
122 for (auto& pair : userConfig.hands)
123 {
124 ARMARX_INFO << "construction of hand "
125 << hands->hands.at(pair.first)->kinematicChainName;
126 controllableNodeSets.emplace(pair.first, nonRtRobot->getRobotNodeSet(pair.first));
127 }
128 }
129 }
130
131 std::string
133 {
134 return "NJointTaskspaceAdmittanceController";
135 }
136
137 void
139 {
140 std::string taskName = getClassName() + "AdditionalTask";
141 runTask(taskName,
142 [&]
143 {
145 4); // please don't set this to 0 as it is the rtRun/control thread
148
149 CycleUtil c(1);
150 getObjectScheduler()->waitForObjectStateMinimum(eManagedIceObjectStarted);
151 ARMARX_IMPORTANT << "Create a new thread for " << getClassName();
152 while (getState() == eManagedIceObjectStarted)
153 {
154 if (isControllerActive())
155 {
157 }
158 c.waitForCycleDuration();
159 }
160 });
161 }
162
163 void
165 {
166 arm->bufferConfigNonRtToRt.getWriteBuffer() = arm->nonRtConfig;
167 arm->bufferConfigNonRtToRt.commitWrite();
168 }
169
170 void
172 {
173 bool rtSafe = additionalTaskUpdateStatus();
175 if (not rtSafe)
176 {
178 }
179 }
180
181 bool
183 {
184 robotUnit->updateVirtualRobot(nonRtRobot);
185 bool rtSafe = true;
186 for (auto& pair : limb)
187 {
188 auto& arm = pair.second;
189 arm->nonRtConfig = arm->bufferConfigUserToNonRt.getUpToDateReadBuffer();
190 arm->rtStatusInNonRT = arm->bufferRtStatusToNonRt.getUpToDateReadBuffer();
191 rtSafe = rtSafe and pair.second->rtStatusInNonRT.rtSafe;
192 }
193 if (hands)
194 {
195 hands->nonRTUpdateStatus();
196 }
197 return rtSafe;
198 }
199
200 void
202 {
203 for (auto& pair : limb)
204 {
205 limbNonRT(pair.second);
206 }
207 if (hands)
208 {
209 hands->nonRTSetTarget();
210 }
211 }
212
213 void
215 {
216 for (auto& pair : limb)
217 {
218 if (not pair.second->rtReady)
219 continue;
220
221 if (not pair.second->rtStatusInNonRT.rtTargetSafe)
222 {
223 pair.second->rtStatusInNonRT =
224 pair.second->bufferRtStatusToNonRt.getUpToDateReadBuffer();
226 pair.second->rtStatusInNonRT.currentPose,
227 pair.second->nonRtConfig.desiredPose,
228 "current pose",
229 "desired pose");
230 }
231 }
232 }
233
234 /// -------------------------------- Real time cotnrol -----------------------------------------
235 void
237 {
238 arm->rtConfig = arm->bufferConfigNonRtToRt.getUpToDateReadBuffer();
239 arm->rtStatus.deltaT = deltaT;
240 arm->rtStatus.accumulateTime += deltaT;
241
242 if (arm->rtFirstRun.load())
243 {
244 arm->controller.firstRun();
245 }
246
247 arm->controller.ftsensor.updateStatus(arm->rtConfig.ftConfig,
248 arm->rtStatus.currentForceTorque,
249 arm->rtStatus.deltaT,
250 arm->rtFirstRun.load());
251
252 arm->sensorDevices.updateJointValues(
253 arm->rtStatus.jointPosition, arm->rtStatus.jointVelocity, arm->rtStatus.jointTorque);
254
255
256 arm->bufferRtStatusToNonRt.getWriteBuffer() = arm->rtStatus;
257 arm->bufferRtStatusToNonRt.commitWrite();
258 arm->bufferRtStatusToUser.getWriteBuffer() = arm->rtStatus;
259 arm->bufferRtStatusToUser.commitWrite();
260 }
261
262 void
264 const Eigen::VectorXf& targetTorque)
265 {
266 for (unsigned int i = 0; i < targetTorque.size(); i++)
267 {
268 arm->targets.at(i)->torque = targetTorque(i);
269 if (!arm->targets.at(i)->isValid())
270 {
271 arm->targets.at(i)->torque = 0;
272 }
273 }
274 arm->bufferRtStatusToOnPublish.getWriteBuffer() = arm->rtStatus;
275 arm->bufferRtStatusToOnPublish.commitWrite();
276
277 arm->bufferConfigRtToOnPublish.getWriteBuffer() = arm->rtConfig;
278 arm->bufferConfigRtToOnPublish.commitWrite();
279
280 arm->bufferConfigRtToUser.getWriteBuffer() = arm->rtConfig;
281 arm->bufferConfigRtToUser.commitWrite();
282
283 if (arm->rtFirstRun.load())
284 {
285 arm->rtFirstRun.store(false);
286 arm->rtReady.store(true);
287 }
288 }
289
290 void
292 {
293 double time_measure = IceUtil::Time::now().toMicroSecondsDouble();
294 limbRTUpdateStatus(arm, deltaT);
295 double time_update_status = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
296
297 arm->controller.run(arm->rtConfig, arm->rtStatus);
298 double time_run_rt = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
299
300 limbRTSetTarget(arm, arm->rtStatus.desiredJointTorque);
301
302 double time_set_target = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
303 time_measure = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
304
305 if (time_measure > 100)
306 {
307 ARMARX_RT_LOGF_WARN("---- rt too slow: "
308 "time_update_status: %.2f\n"
309 "run_rt_limb: %.2f\n"
310 "set_target_limb: %.2f\n"
311 "time all: %.2f\n",
312 time_update_status, // 0-1 us
313 time_run_rt - time_update_status, //
314 time_set_target - time_run_rt, //
315 time_measure)
316 .deactivateSpam(1.0f); // 0-1 us
317 }
318 }
319
320 void
321 NJointTaskspaceAdmittanceController::rtRun(const IceUtil::Time& /*sensorValuesTimestamp*/,
322 const IceUtil::Time& timeSinceLastIteration)
323 {
324 double deltaT = timeSinceLastIteration.toSecondsDouble();
325 for (auto& pair : limb)
326 {
327 limbRT(pair.second, deltaT);
328 }
329 if (hands)
330 {
331 hands->updateRTStatus(deltaT);
332 }
333 }
334
335 /// ------------------------------ update/get config -------------------------------------------
336 void
337 NJointTaskspaceAdmittanceController::updateConfig(const ::armarx::aron::data::dto::DictPtr& dto,
338 const Ice::Current& iceCurrent)
339 {
340 auto prevCfg = userConfig;
341 userConfig.fromAron(dto);
342
343 for (auto& pair : userConfig.limbs)
344 {
345 validateConfigData(pair.second, limb.at(pair.first));
347 pair.second.desiredPose,
348 prevCfg.limbs.at(pair.first).desiredPose,
349 "new desired pose",
350 "previous desired pose",
351 pair.second.safeDistanceMMToGoal,
352 pair.second.safeRotAngleDegreeToGoal,
353 "updateConfig_" + pair.first))
354 {
355 ARMARX_INFO << "use the existing target pose";
356 pair.second.desiredPose = prevCfg.limbs.at(pair.first).desiredPose;
357 }
358 limb.at(pair.first)->bufferConfigUserToNonRt.getWriteBuffer() = pair.second;
359 limb.at(pair.first)->bufferConfigUserToNonRt.commitWrite();
360 }
361 if (hands)
362 {
363 hands->updateConfig(userConfig.hands);
364 }
365 }
366
369 {
370 for (auto& pair : limb)
371 {
372 userConfig.limbs.at(pair.first) =
373 pair.second->bufferConfigRtToUser.getUpToDateReadBuffer();
374 }
375 if (hands)
376 {
377 hands->getConfig(userConfig.hands);
378 }
379 return userConfig.toAronDTO();
380 }
381
382 void
384 const bool forceGuard,
385 const bool torqueGuard,
386 const Ice::Current& iceCurrent)
387 {
388 auto it = userConfig.limbs.find(nodeSetName);
389 if (it != userConfig.limbs.end())
390 {
391 it->second.ftConfig.enableSafeGuardForce = forceGuard;
392 it->second.ftConfig.enableSafeGuardTorque = torqueGuard;
393 limb.at(nodeSetName)->controller.ftsensor.enableSafeGuard(forceGuard, torqueGuard);
395 << "reset safe guard with force torque sensors: safe? "
396 << limb.at(nodeSetName)->controller.ftsensor.isSafe(it->second.ftConfig);
397 limb.at(nodeSetName)->bufferConfigUserToNonRt.getWriteBuffer() = it->second;
398 limb.at(nodeSetName)->bufferConfigUserToNonRt.commitWrite();
399 }
400 else
401 {
402 ARMARX_WARNING << "no robot node set with name " << nodeSetName
403 << " found in the controllers.";
404 }
405 }
406
407 /// -------------------------------- Other interaces -------------------------------------------
408 bool
410 const Ice::Current& iceCurrent)
411 {
412 auto it = userConfig.limbs.find(nodeSetName);
413 if (it != userConfig.limbs.end())
414 {
415 return limb.at(nodeSetName)->controller.ftsensor.ftSafe.load();
416 }
417 else
418 {
419 ARMARX_WARNING << "no robot node set with name " << nodeSetName
420 << " found in the controllers.";
421 }
422 return false;
423 }
424
425 Ice::FloatSeq
427 const Ice::Current& iceCurrent)
428 {
429 std::vector<float> tcpVel;
430 auto& arm = limb.at(rns);
431 auto s = arm->bufferRtStatusToUser.getUpToDateReadBuffer();
432 for (int i = 0; i < s.currentTwist.size(); i++)
433 {
434 tcpVel.push_back(s.currentTwist[i]);
435 }
436 return tcpVel;
437 }
438
439 bool
441 const TargetPoseMap& targetPoseMap,
442 const TargetNullspaceMap& targetNullspaceMap,
443 const Ice::Current& iceCurrent)
444 {
445 for (auto& pair : userConfig.limbs)
446 {
447 for (size_t i = 0; i < 4; ++i)
448 {
449 for (int j = 0; j < 4; ++j)
450 {
451 pair.second.desiredPose(i, j) = targetPoseMap.at(pair.first)[i][j];
452 }
453 }
454 if (targetNullspaceMap.at(pair.first).size() > 0)
455 {
456 const size_t nDoF = pair.second.desiredNullspaceJointAngles.value().size();
457 ARMARX_CHECK_EQUAL(targetNullspaceMap.at(pair.first).size(), nDoF)
458 << "the joint numbers does not match";
459 for (size_t i = 0; i < nDoF; ++i)
460 {
461 pair.second.desiredNullspaceJointAngles.value()(i) =
462 targetNullspaceMap.at(pair.first)[i];
463 }
464 }
465 limb.at(pair.first)->bufferConfigUserToNonRt.getWriteBuffer() = pair.second;
466 limb.at(pair.first)->bufferConfigUserToNonRt.commitWrite();
467 }
468 return true;
469 }
470
471 void
473 {
474 const auto nDoF = arm->jointNames.size();
475
476 const auto checkSize = [nDoF](const auto& v) { ARMARX_CHECK_EQUAL(v.rows(), nDoF); };
477 const auto checkNonNegative = [](const auto& v) { ARMARX_CHECK((v.array() >= 0).all()); };
478
479 if (!configData.desiredNullspaceJointAngles.has_value())
480 {
481 if (!isControllerActive())
482 {
483 ARMARX_INFO << "No user defined nullspace target, reset to zero with "
484 << VAROUT(nDoF);
485 configData.desiredNullspaceJointAngles = Eigen::VectorXf::Zero(nDoF);
486 arm->reInitPreActivate.store(true);
487 }
488 else
489 {
490 auto currentValue =
491 arm->bufferConfigRtToUser.getUpToDateReadBuffer().desiredNullspaceJointAngles;
493 << "Controller is active, but no user defined nullspace target. \n"
494 "You should first get up-to-date config of this controller and then update "
495 "it:\n"
496 " auto cfg = ctrl->getConfig(); \n"
497 " cfg.desiredPose = xxx;\n"
498 " ctrl->updateConfig(cfg);\n"
499 "Now, I decide by myself to use the existing values of nullspace target\n"
500 << currentValue.value();
501 configData.desiredNullspaceJointAngles = currentValue;
502 }
503 }
504 ARMARX_CHECK_GREATER(configData.safeDistanceMMToGoal, 100.0f);
505 checkSize(configData.desiredNullspaceJointAngles.value());
506 checkSize(configData.kdNullspaceTorque);
507 checkSize(configData.kpNullspaceTorque);
508
509 checkNonNegative(configData.kdNullspaceTorque);
510 checkNonNegative(configData.kpNullspaceTorque);
511 checkNonNegative(configData.kdImpedance);
512 checkNonNegative(configData.kpImpedance);
513 }
514
515 void
517 const DebugObserverInterfacePrx& debugObs)
518 {
519 StringVariantBaseMap datafields;
520 auto rtData = arm->bufferConfigRtToOnPublish.getUpToDateReadBuffer();
521 auto rtStatus = arm->bufferRtStatusToOnPublish.getUpToDateReadBuffer();
522
523
524 common::debugEigenPose(datafields, "current_pose", rtStatus.currentPose);
525 common::debugEigenPose(datafields, "desired_pose", rtStatus.desiredPose);
526 common::debugEigenVec(datafields, "kpImpedance", rtData.kpImpedance);
527 common::debugEigenVec(datafields, "kdImpedance", rtData.kdImpedance);
528
529 common::debugEigenPose(datafields, "virtual_pose", rtStatus.virtualPose);
530 common::debugEigenVec(datafields, "virtual_vel", rtStatus.virtualVel);
531 common::debugEigenVec(datafields, "virtual_acc", rtStatus.virtualAcc);
532 common::debugEigenVec(datafields, "currentForceTorque", rtStatus.currentForceTorque);
533
534 common::debugEigenVec(datafields, "forceImpedance", rtStatus.forceImpedance);
535 common::debugEigenVec(datafields, "nullspaceTorque", rtStatus.nullspaceTorque);
536 common::debugEigenVec(datafields, "desiredJointTorques", rtStatus.desiredJointTorque);
537 debugObs->setDebugChannel(getClassName() + "_" + arm->kinematicChainName, datafields);
538 }
539
540 void
543 const DebugObserverInterfacePrx& debugObs)
544 {
545 for (auto& pair : limb)
546 {
547 if (not pair.second->rtReady.load())
548 continue;
549 limbPublish(pair.second, debugObs);
550 }
551 }
552
553 void
555 {
556 for (auto& pair : limb)
557 {
558 pair.second->rtReady.store(false);
559 }
560 }
561
562 void
564 const Ice::Current&)
565 {
566 for (auto& pair : limb)
567 {
568 pair.second->rtReady.store(false);
569 }
570 }
571
572 void
574 {
575 VirtualRobot::RobotNodeSetPtr rns = rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
576 const auto& currentPose = rns->getTCP()->getPoseInRootFrame();
577 auto quat = VirtualRobot::MathTools::eigen4f2quat(currentPose);
578 ARMARX_RT_LOGF_INFO("rt preactivate controller with target pose\n\n "
579 "[ %.2f, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f ].",
580 currentPose(0, 3),
581 currentPose(1, 3),
582 currentPose(2, 3),
583 quat.w,
584 quat.x,
585 quat.y,
586 quat.z);
587
588 if (arm->reInitPreActivate.load())
589 {
590 arm->rtConfig.desiredNullspaceJointAngles.value() = rns->getJointValuesEigen();
591 arm->rtConfig.desiredPose = currentPose;
592
593 arm->bufferConfigUserToNonRt.reinitAllBuffers(arm->rtConfig);
594 arm->reInitPreActivate.store(false);
595 }
596 {
597 arm->nonRtConfig = arm->rtConfig;
598 arm->bufferConfigNonRtToRt.reinitAllBuffers(arm->rtConfig);
599 arm->bufferConfigRtToOnPublish.reinitAllBuffers(arm->rtConfig);
600 arm->bufferConfigRtToUser.reinitAllBuffers(arm->rtConfig);
601 }
602 {
603 arm->sensorDevices.updateJointValues(arm->rtStatus.jointPosition,
604 arm->rtStatus.jointVelocity,
605 arm->rtStatus.jointTorque);
606 arm->rtStatus.rtPreActivate(currentPose);
607
608 arm->rtStatusInNonRT = arm->rtStatus;
609 arm->nonRTDeltaT = 0.0;
610 arm->nonRTAccumulateTime = 0.0;
611 arm->bufferRtStatusToOnPublish.reinitAllBuffers(arm->rtStatus);
612 arm->bufferRtStatusToNonRt.reinitAllBuffers(arm->rtStatus);
613 arm->bufferRtStatusToUser.reinitAllBuffers(arm->rtStatus);
614 }
615
616 arm->controller.preactivateInit(rns);
617 }
618
619 void
621 {
622 for (auto& pair : limb)
623 {
624 ARMARX_RT_LOGF_INFO("rtPreActivateController for %s", pair.first.c_str());
625 limbReInit(pair.second);
626 userConfig.limbs.at(pair.first) = pair.second->rtConfig;
627 }
628 if (hands)
629 {
630 hands->rtPreActivate();
631 }
632 }
633
634 void
636 {
637 // for (auto& pair : limb)
638 // {
639 // pair.second->controller.isInitialized.store(false);
640 // }
641 }
642
643 /// ----------------------------------- GUI Widget ---------------------------------------------
646 const VirtualRobot::RobotPtr& robot,
647 const std::map<std::string, ConstControlDevicePtr>& controlDevices,
648 const std::map<std::string, ConstSensorDevicePtr>&)
649 {
650 using namespace armarx::WidgetDescription;
651 HBoxLayoutPtr layout = new HBoxLayout;
652
653
654 ::armarx::WidgetDescription::WidgetSeq widgets;
655
656 /// select default config
657 LabelPtr label = new Label;
658 label->text = "select a controller config";
659
660 StringComboBoxPtr cfgBox = new StringComboBox;
661 cfgBox->name = "config_box";
662 cfgBox->defaultIndex = 0;
663 cfgBox->multiSelect = false;
664
665 cfgBox->options = std::vector<std::string>{"default", "default_right", "default_right_a7"};
667
668 layout->children.emplace_back(label);
669 layout->children.emplace_back(cfgBox);
671
672 layout->children.insert(layout->children.end(), widgets.begin(), widgets.end());
673 ARMARX_INFO_S << "Layout done";
674 return layout;
675 }
676
679 const StringVariantBaseMap& values)
680 {
681 auto cfgName = values.at("config_box")->getString();
682 const armarx::PackagePath configPath(
683 "armarx_control",
684 "controller_config/NJointTaskspaceAdmittanceController/" + cfgName + ".json");
685 ARMARX_INFO_S << "Loading config from " << configPath.toSystemPath();
686 ARMARX_CHECK(std::filesystem::exists(configPath.toSystemPath()));
687
688 auto cfgDTO = armarx::readFromJson<ConfigDict>(configPath.toSystemPath());
689
691 return new ConfigurableNJointControllerConfig{cfgDTO.toAronDTO()};
692 }
693
694} // namespace armarx::control::njoint_controller::task_space
#define ARMARX_RT_LOGF_WARN(...)
#define ARMARX_RT_LOGF_INFO(...)
#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
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.
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
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 ------------------------------------------—
::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
bool isSafeForceTorque(const std::string &nodeSetName, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
-----------------------------— Other interaces ----------------------------------------—
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 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
NJointTaskspaceAdmittanceController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
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 --------------------------------------—
void toggleGravityCompensation(const bool toggle, const Ice::Current &) override
ft sensor
#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
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
void debugEigenPose(StringVariantBaseMap &datafields, const std::string &name, Eigen::Matrix4f pose)
Definition utils.cpp:140
NJointControllerRegistration< NJointTaskspaceAdmittanceController > registrationControllerNJointTaskspaceAdmittanceController("NJointTaskspaceAdmittanceController")
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
#define ARMARX_TRACE
Definition trace.h:77