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 
23 #include "AdmittanceController.h"
24 
25 #include <VirtualRobot/MathTools.h>
26 
28 #include <ArmarXCore/core/PackagePath.h> // for GUI
32 
33 #include <armarx/control/common/aron_conversions.h> // for GUI
36 
38 {
41  "NJointTaskspaceAdmittanceController");
42 
43  void
44  NJointTaskspaceAdmittanceController::limbInit(const std::string nodeSetName,
45  ArmPtr& arm,
46  Config& cfg,
47  VirtualRobot::RobotPtr& nonRtRobotPtr)
48  {
49  arm->kinematicChainName = nodeSetName;
50  VirtualRobot::RobotNodeSetPtr rtRns =
51  rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
52  VirtualRobot::RobotNodeSetPtr nonRtRns =
53  nonRtRobotPtr->getRobotNodeSet(arm->kinematicChainName);
54  ARMARX_CHECK_EXPRESSION(rtRns) << arm->kinematicChainName;
55  ARMARX_CHECK_EXPRESSION(nonRtRns) << arm->kinematicChainName;
56  ARMARX_IMPORTANT << "Creating Taskspace Impedance controller with kinematic chain: "
57  << arm->kinematicChainName << " with num of joints: (RT robot) "
58  << rtRns->getSize() << ", and (non-RT robot) " << nonRtRns->getSize();
59 
60  arm->controller.initialize(nonRtRns, rtRns);
61  arm->controller.ftsensor.initialize(rtRns, robotUnit, cfg.ftConfig);
62  arm->jointNames.clear();
63  for (size_t i = 0; i < rtRns->getSize(); ++i)
64  {
65  std::string jointName = rtRns->getNode(i)->getName();
66  arm->jointNames.push_back(jointName);
67 
68  ControlTargetBase* ct = useControlTarget(jointName, ControlModes::Torque1DoF);
70  auto* casted_ct = ct->asA<ControlTarget1DoFActuatorTorque>();
71  ARMARX_CHECK_EXPRESSION(casted_ct);
72  arm->targets.push_back(casted_ct);
73 
74  const SensorValueBase* sv = useSensorValue(jointName);
76  arm->sensorDevices.append(sv, jointName);
77  };
78 
79  validateConfigData(cfg, arm);
80  arm->rtConfig = cfg;
81  arm->nonRtConfig = cfg;
82  arm->rtStatus.reset(rtRns->getSize());
83  }
84 
86  const RobotUnitPtr& robotUnit,
87  const NJointControllerConfigPtr& config,
88  const VirtualRobot::RobotPtr&) :
89  robotUnit(robotUnit)
90  {
92 
93  ConfigPtrT cfg = ConfigPtrT::dynamicCast(config);
95  userConfig.fromAron(cfg->config);
96 
98  nonRtRobot = robotUnit->cloneRobot();
99  robotUnit->updateVirtualRobot(nonRtRobot);
100 
101  for (auto& pair : userConfig.limbs)
102  {
103  limb.emplace(pair.first, std::make_unique<ArmData>());
104  limbInit(pair.first, limb.at(pair.first), pair.second, nonRtRobot);
105  controllableNodeSets.emplace(pair.first, nonRtRobot->getRobotNodeSet(pair.first));
106  }
107 
108  if (not userConfig.hands.empty())
109  {
110  hands = std::make_shared<core::HandControlBase>(nonRtRobot, userConfig.hands);
111  for (auto& pair : userConfig.hands)
112  {
113  for (auto& jointName : hands->hands.at(pair.first)->jointNames)
114  {
115  hands->appendDevice(pair.first,
116  useSensorValue(jointName),
117  useControlTarget(jointName, ControlModes::Position1DoF),
118  jointName);
119  }
120  ARMARX_INFO << "construction of hand "
121  << hands->hands.at(pair.first)->kinematicChainName;
122  controllableNodeSets.emplace(pair.first, nonRtRobot->getRobotNodeSet(pair.first));
123  }
124  }
125  }
126 
127  std::string
129  {
130  return "NJointTaskspaceAdmittanceController";
131  }
132 
133  void
135  {
136  std::string taskName = getClassName() + "AdditionalTask";
137  runTask(taskName,
138  [&]
139  {
141  4); // please don't set this to 0 as it is the rtRun/control thread
144 
145  CycleUtil c(1);
146  getObjectScheduler()->waitForObjectStateMinimum(eManagedIceObjectStarted);
147  ARMARX_IMPORTANT << "Create a new thread for " << getClassName();
148  while (getState() == eManagedIceObjectStarted)
149  {
150  if (isControllerActive())
151  {
152  additionalTask();
153  }
154  c.waitForCycleDuration();
155  }
156  });
157  }
158 
159  void
161  {
162  arm->bufferConfigNonRtToRt.getWriteBuffer() = arm->nonRtConfig;
163  arm->bufferConfigNonRtToRt.commitWrite();
164  }
165 
166  void
168  {
169  bool rtSafe = additionalTaskUpdateStatus();
171  if (not rtSafe)
172  {
174  }
175  }
176 
177  bool
179  {
180  robotUnit->updateVirtualRobot(nonRtRobot);
181  bool rtSafe = true;
182  for (auto& pair : limb)
183  {
184  auto& arm = pair.second;
185  arm->nonRtConfig = arm->bufferConfigUserToNonRt.getUpToDateReadBuffer();
186  arm->rtStatusInNonRT = arm->bufferRtStatusToNonRt.getUpToDateReadBuffer();
187  rtSafe = rtSafe and pair.second->rtStatusInNonRT.rtSafe;
188  }
189  if (hands)
190  {
191  hands->nonRTUpdateStatus();
192  }
193  return rtSafe;
194  }
195 
196  void
198  {
199  for (auto& pair : limb)
200  {
201  limbNonRT(pair.second);
202  }
203  if (hands)
204  {
205  hands->nonRTSetTarget();
206  }
207  }
208 
209  void
211  {
212  for (auto& pair : limb)
213  {
214  if (not pair.second->rtReady)
215  continue;
216 
217  if (not pair.second->rtStatusInNonRT.rtTargetSafe)
218  {
219  pair.second->rtStatusInNonRT =
220  pair.second->bufferRtStatusToNonRt.getUpToDateReadBuffer();
222  pair.second->rtStatusInNonRT.currentPose,
223  pair.second->nonRtConfig.desiredPose,
224  "current pose", "desired pose");
225  }
226  }
227  }
228 
229  /// -------------------------------- Real time cotnrol -----------------------------------------
230  void
232  {
233  arm->rtConfig = arm->bufferConfigNonRtToRt.getUpToDateReadBuffer();
234  arm->rtStatus.deltaT = deltaT;
235 
236  if (arm->rtFirstRun.load())
237  {
238  arm->controller.firstRun();
239  }
240 
241  arm->controller.ftsensor.updateStatus(
242  arm->rtConfig.ftConfig, arm->rtStatus.currentForceTorque, arm->rtStatus.deltaT, arm->rtFirstRun.load());
243 
244  arm->sensorDevices.updateJointValues(
245  arm->rtStatus.jointPos, arm->rtStatus.jointVel, arm->rtStatus.jointTor);
246 
247 
248  arm->bufferRtStatusToNonRt.getWriteBuffer() = arm->rtStatus;
249  arm->bufferRtStatusToNonRt.commitWrite();
250  arm->bufferRtStatusToUser.getWriteBuffer() = arm->rtStatus;
251  arm->bufferRtStatusToUser.commitWrite();
252  }
253 
254  void
256  const Eigen::VectorXf& targetTorque)
257  {
258  for (unsigned int i = 0; i < targetTorque.size(); i++)
259  {
260  arm->targets.at(i)->torque = targetTorque(i);
261  if (!arm->targets.at(i)->isValid())
262  {
263  arm->targets.at(i)->torque = 0;
264  }
265  }
266  arm->bufferRtStatusToOnPublish.getWriteBuffer() = arm->rtStatus;
267  arm->bufferRtStatusToOnPublish.commitWrite();
268 
269  arm->bufferConfigRtToOnPublish.getWriteBuffer() = arm->rtConfig;
270  arm->bufferConfigRtToOnPublish.commitWrite();
271 
272  arm->bufferConfigRtToUser.getWriteBuffer() = arm->rtConfig;
273  arm->bufferConfigRtToUser.commitWrite();
274 
275  if (arm->rtFirstRun.load())
276  {
277  arm->rtFirstRun.store(false);
278  arm->rtReady.store(true);
279  }
280  }
281 
282  void
284  {
285  double time_measure = IceUtil::Time::now().toMicroSecondsDouble();
286  limbRTUpdateStatus(arm, deltaT);
287  double time_update_status = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
288 
289  arm->controller.run(arm->rtConfig, arm->rtStatus);
290  double time_run_rt = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
291 
292  limbRTSetTarget(arm, arm->rtStatus.desiredJointTorques);
293 
294  double time_set_target = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
295  time_measure = IceUtil::Time::now().toMicroSecondsDouble() - time_measure;
296 
297  if (time_measure > 100)
298  {
299  ARMARX_RT_LOGF_WARN("---- rt too slow: "
300  "time_update_status: %.2f\n"
301  "run_rt_limb: %.2f\n"
302  "set_target_limb: %.2f\n"
303  "time all: %.2f\n",
304  time_update_status, // 0-1 us
305  time_run_rt - time_update_status, //
306  time_set_target - time_run_rt, //
307  time_measure)
308  .deactivateSpam(1.0f); // 0-1 us
309  }
310  }
311 
312  void
314  const IceUtil::Time& timeSinceLastIteration)
315  {
316  double deltaT = timeSinceLastIteration.toSecondsDouble();
317  for (auto& pair : limb)
318  {
319  limbRT(pair.second, deltaT);
320  }
321  if (hands)
322  {
323  hands->updateRTStatus(deltaT);
324  hands->setTargets();
325  }
326  }
327 
328  /// ------------------------------ update/get config -------------------------------------------
329  void
331  const Ice::Current& iceCurrent)
332  {
333  auto prevCfg = userConfig;
334  userConfig.fromAron(dto);
335 
336  for (auto& pair : userConfig.limbs)
337  {
338  validateConfigData(pair.second, limb.at(pair.first));
339  if (common::detectAndReportPoseDeviationWarning(pair.second.desiredPose,
340  prevCfg.limbs.at(pair.first).desiredPose,
341  "new desired pose", "previous desired pose",
342  pair.second.safeDistanceMMToGoal,
343  pair.second.safeRotAngleDegreeToGoal,
344  "updateConfig_" + pair.first))
345  {
346  ARMARX_INFO << "use the existing target pose";
347  pair.second.desiredPose = prevCfg.limbs.at(pair.first).desiredPose;
348  }
349  limb.at(pair.first)->bufferConfigUserToNonRt.getWriteBuffer() = pair.second;
350  limb.at(pair.first)->bufferConfigUserToNonRt.commitWrite();
351  }
352  if (hands)
353  {
354  hands->updateConfig(userConfig.hands);
355  }
356  }
357 
359  NJointTaskspaceAdmittanceController::getConfig(const Ice::Current& iceCurrent)
360  {
361  for (auto& pair : limb)
362  {
363  userConfig.limbs.at(pair.first) =
364  pair.second->bufferConfigRtToUser.getUpToDateReadBuffer();
365  }
366  if (hands)
367  {
368  hands->getConfig(userConfig.hands);
369  }
370  return userConfig.toAronDTO();
371  }
372 
373  void
375  const bool forceGuard,
376  const bool torqueGuard,
377  const Ice::Current& iceCurrent)
378  {
379  auto it = userConfig.limbs.find(nodeSetName);
380  if (it != userConfig.limbs.end())
381  {
382  it->second.ftConfig.enableSafeGuardForce = forceGuard;
383  it->second.ftConfig.enableSafeGuardTorque = torqueGuard;
384  limb.at(nodeSetName)->controller.ftsensor.enableSafeGuard(forceGuard, torqueGuard);
386  << "reset safe guard with force torque sensors: safe? "
387  << limb.at(nodeSetName)->controller.ftsensor.isSafe(it->second.ftConfig);
388  limb.at(nodeSetName)->bufferConfigUserToNonRt.getWriteBuffer() = it->second;
389  limb.at(nodeSetName)->bufferConfigUserToNonRt.commitWrite();
390  }
391  else
392  {
393  ARMARX_WARNING << "no robot node set with name " << nodeSetName
394  << " found in the controllers.";
395  }
396  }
397 
398  /// -------------------------------- Other interaces -------------------------------------------
399  bool
401  const Ice::Current& iceCurrent)
402  {
403  auto it = userConfig.limbs.find(nodeSetName);
404  if (it != userConfig.limbs.end())
405  {
406  return limb.at(nodeSetName)->controller.ftsensor.ftSafe.load();
407  }
408  else
409  {
410  ARMARX_WARNING << "no robot node set with name " << nodeSetName
411  << " found in the controllers.";
412  }
413  return false;
414  }
415 
416  Ice::FloatSeq
418  const Ice::Current& iceCurrent)
419  {
420  std::vector<float> tcpVel;
421  auto& arm = limb.at(rns);
422  auto s = arm->bufferRtStatusToUser.getUpToDateReadBuffer();
423  for (int i = 0; i < s.currentTwist.size(); i++)
424  {
425  tcpVel.push_back(s.currentTwist[i]);
426  }
427  return tcpVel;
428  }
429 
430  bool
432  const TargetPoseMap& targetPoseMap,
433  const TargetNullspaceMap& targetNullspaceMap,
434  const Ice::Current& iceCurrent)
435  {
436  for (auto& pair : userConfig.limbs)
437  {
438  for (size_t i = 0; i < 4; ++i)
439  {
440  for (int j = 0; j < 4; ++j)
441  {
442  pair.second.desiredPose(i, j) = targetPoseMap.at(pair.first)[i][j];
443  }
444  }
445  if (targetNullspaceMap.at(pair.first).size() > 0)
446  {
447  const size_t nDoF = pair.second.desiredNullspaceJointAngles.value().size();
448  ARMARX_CHECK_EQUAL(targetNullspaceMap.at(pair.first).size(), nDoF)
449  << "the joint numbers does not match";
450  for (size_t i = 0; i < nDoF; ++i)
451  {
452  pair.second.desiredNullspaceJointAngles.value()(i) =
453  targetNullspaceMap.at(pair.first)[i];
454  }
455  }
456  limb.at(pair.first)->bufferConfigUserToNonRt.getWriteBuffer() = pair.second;
457  limb.at(pair.first)->bufferConfigUserToNonRt.commitWrite();
458  }
459  return true;
460  }
461 
462  void
464  {
465  const auto nDoF = arm->controller.numOfJoints;
466 
467  const auto checkSize = [nDoF](const auto& v) { ARMARX_CHECK_EQUAL(v.rows(), nDoF); };
468  const auto checkNonNegative = [](const auto& v) { ARMARX_CHECK((v.array() >= 0).all()); };
469 
470  if (!configData.desiredNullspaceJointAngles.has_value())
471  {
472  if (!isControllerActive())
473  {
474  ARMARX_INFO << "No user defined nullspace target, reset to zero with "
475  << VAROUT(nDoF);
476  configData.desiredNullspaceJointAngles = Eigen::VectorXf::Zero(nDoF);
477  arm->reInitPreActivate.store(true);
478  }
479  else
480  {
481  auto currentValue =
482  arm->bufferConfigRtToUser.getUpToDateReadBuffer().desiredNullspaceJointAngles;
484  << "Controller is active, but no user defined nullspace target. \n"
485  "You should first get up-to-date config of this controller and then update "
486  "it:\n"
487  " auto cfg = ctrl->getConfig(); \n"
488  " cfg.desiredPose = xxx;\n"
489  " ctrl->updateConfig(cfg);\n"
490  "Now, I decide by myself to use the existing values of nullspace target\n"
491  << currentValue.value();
492  configData.desiredNullspaceJointAngles = currentValue;
493  }
494  }
495  ARMARX_CHECK_GREATER(configData.safeDistanceMMToGoal, 100.0f);
496  checkSize(configData.desiredNullspaceJointAngles.value());
497  checkSize(configData.kdNullspace);
498  checkSize(configData.kpNullspace);
499 
500  checkNonNegative(configData.kdNullspace);
501  checkNonNegative(configData.kpNullspace);
502  checkNonNegative(configData.kdImpedance);
503  checkNonNegative(configData.kpImpedance);
504  }
505 
506  void
508  const DebugObserverInterfacePrx& debugObs)
509  {
510  StringVariantBaseMap datafields;
511  auto rtData = arm->bufferConfigRtToOnPublish.getUpToDateReadBuffer();
512  auto rtStatus = arm->bufferRtStatusToOnPublish.getUpToDateReadBuffer();
513 
514 
515  common::debugEigenPose(datafields, "current_pose", rtStatus.currentPose);
516  common::debugEigenPose(datafields, "desired_pose", rtStatus.desiredPose);
517  common::debugEigenVec(datafields, "kpImpedance", rtData.kpImpedance);
518  common::debugEigenVec(datafields, "kdImpedance", rtData.kdImpedance);
519 
520  common::debugEigenPose(datafields, "virtual_pose", rtStatus.virtualPose);
521  common::debugEigenVec(datafields, "virtual_vel", rtStatus.virtualVel);
522  common::debugEigenVec(datafields, "virtual_acc", rtStatus.virtualAcc);
523  common::debugEigenVec(datafields, "currentForceTorque", rtStatus.currentForceTorque);
524 
525  common::debugEigenVec(datafields, "forceImpedance", rtStatus.forceImpedance);
526  common::debugEigenVec(datafields, "nullspaceTorque", rtStatus.nullspaceTorque);
527  common::debugEigenVec(datafields, "desiredJointTorques", rtStatus.desiredJointTorques);
528  debugObs->setDebugChannel(getClassName() + "_" + arm->kinematicChainName, datafields);
529  }
530 
531  void
534  const DebugObserverInterfacePrx& debugObs)
535  {
536  for (auto& pair : limb)
537  {
538  if (not pair.second->rtReady.load())
539  continue;
540  limbPublish(pair.second, debugObs);
541  }
542  }
543 
544  void
546  {
547  for (auto& pair : limb)
548  {
549  pair.second->rtReady.store(false);
550  }
551  }
552 
553  void
555  const Ice::Current&)
556  {
557  for (auto& pair : limb)
558  {
559  pair.second->rtReady.store(false);
560  }
561  }
562 
563  void
565  {
566  VirtualRobot::RobotNodeSetPtr rns = rtGetRobot()->getRobotNodeSet(arm->kinematicChainName);
567  const auto& currentPose = rns->getTCP()->getPoseInRootFrame();
568  auto quat = VirtualRobot::MathTools::eigen4f2quat(currentPose);
569  ARMARX_RT_LOGF_INFO("rt preactivate controller with target pose\n\n "
570  "[ %.2f, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f ].",
571  currentPose(0, 3),
572  currentPose(1, 3),
573  currentPose(2, 3),
574  quat.w,
575  quat.x,
576  quat.y,
577  quat.z);
578 
579  if (arm->reInitPreActivate.load())
580  {
581  arm->rtConfig.desiredNullspaceJointAngles.value() = rns->getJointValuesEigen();
582  arm->rtConfig.desiredPose = currentPose;
583 
584  arm->bufferConfigUserToNonRt.reinitAllBuffers(arm->rtConfig);
585  arm->reInitPreActivate.store(false);
586  }
587  {
588  arm->nonRtConfig = arm->rtConfig;
589  arm->bufferConfigNonRtToRt.reinitAllBuffers(arm->rtConfig);
590  arm->bufferConfigRtToOnPublish.reinitAllBuffers(arm->rtConfig);
591  arm->bufferConfigRtToUser.reinitAllBuffers(arm->rtConfig);
592  }
593  {
594  arm->sensorDevices.updateJointValues(
595  arm->rtStatus.jointPos, arm->rtStatus.jointVel, arm->rtStatus.jointTor);
596  arm->rtStatus.rtPreActivate(currentPose);
597 
598  arm->rtStatusInNonRT = arm->rtStatus;
599  arm->bufferRtStatusToOnPublish.reinitAllBuffers(arm->rtStatus);
600  arm->bufferRtStatusToNonRt.reinitAllBuffers(arm->rtStatus);
601  arm->bufferRtStatusToUser.reinitAllBuffers(arm->rtStatus);
602  }
603 
604  arm->controller.preactivateInit(rns);
605  }
606 
607  void
609  {
610  for (auto& pair : limb)
611  {
612  ARMARX_RT_LOGF_INFO("rtPreActivateController for %s", pair.first.c_str());
613  limbReInit(pair.second);
614  userConfig.limbs.at(pair.first) = pair.second->rtConfig;
615  }
616  if (hands)
617  {
618  hands->rtPreActivate();
619  }
620  }
621 
622  void
624  {
625  // for (auto& pair : limb)
626  // {
627  // pair.second->controller.isInitialized.store(false);
628  // }
629  }
630 
631  /// ----------------------------------- GUI Widget ---------------------------------------------
634  const VirtualRobot::RobotPtr& robot,
635  const std::map<std::string, ConstControlDevicePtr>& controlDevices,
636  const std::map<std::string, ConstSensorDevicePtr>&)
637  {
638  using namespace armarx::WidgetDescription;
639  HBoxLayoutPtr layout = new HBoxLayout;
640 
641 
642  ::armarx::WidgetDescription::WidgetSeq widgets;
643 
644  /// select default config
645  LabelPtr label = new Label;
646  label->text = "select a controller config";
647 
648  StringComboBoxPtr cfgBox = new StringComboBox;
649  cfgBox->name = "config_box";
650  cfgBox->defaultIndex = 0;
651  cfgBox->multiSelect = false;
652 
653  cfgBox->options = std::vector<std::string>{"default", "default_right", "default_right_a7"};
654  ARMARX_TRACE;
655 
656  layout->children.emplace_back(label);
657  layout->children.emplace_back(cfgBox);
658  ARMARX_TRACE;
659 
660  layout->children.insert(layout->children.end(), widgets.begin(), widgets.end());
661  ARMARX_INFO_S << "Layout done";
662  return layout;
663  }
664 
668  {
669  auto cfgName = values.at("config_box")->getString();
670  const armarx::PackagePath configPath(
671  "armarx_control",
672  "controller_config/NJointTaskspaceAdmittanceController/" + cfgName + ".json");
673  ARMARX_INFO_S << "Loading config from " << configPath.toSystemPath();
674  ARMARX_CHECK(std::filesystem::exists(configPath.toSystemPath()));
675 
676  auto cfgDTO = armarx::readFromJson<ConfigDict>(configPath.toSystemPath());
677 
678  ARMARX_TRACE;
679  return new ConfigurableNJointControllerConfig{cfgDTO.toAronDTO()};
680  }
681 
682 } // namespace armarx::control::njoint_controller::task_space
armarx::ControlTargetBase::asA
const T * asA() const
Definition: ControlTargetBase.h:76
ARMARX_RT_LOGF_INFO
#define ARMARX_RT_LOGF_INFO(...)
Definition: ControlThreadOutputBuffer.h:339
SingleTypeVariantList.h
armarx::control::common::debugEigenPose
void debugEigenPose(StringVariantBaseMap &datafields, const std::string &name, Eigen::Matrix4f pose)
Definition: utils.cpp:113
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::limb
std::map< std::string, ArmPtr > limb
Definition: AdmittanceController.h:161
armarx::control::ethercat::RTUtility::RT_THREAD_PRIORITY
static constexpr int RT_THREAD_PRIORITY
The thread priority for rt-threads.
Definition: RTUtility.h:24
armarx::NJointControllerRegistration
Definition: NJointControllerRegistry.h:74
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::toggleGravityCompensation
void toggleGravityCompensation(const bool toggle, const Ice::Current &) override
ft sensor
Definition: AdmittanceController.cpp:554
armarx::NJointControllerBase::useSynchronizedRtRobot
const VirtualRobot::RobotPtr & useSynchronizedRtRobot(bool updateCollisionModel=false)
Requests a VirtualRobot for use in rtRun *.
Definition: NJointController.cpp:293
armarx::StringVariantBaseMap
std::map< std::string, VariantBasePtr > StringVariantBaseMap
Definition: ManagedIceObject.h:111
ARMARX_IMPORTANT
#define ARMARX_IMPORTANT
Definition: Logging.h:183
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::robotUnit
RobotUnitPtr robotUnit
Definition: AdmittanceController.h:163
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::limbNonRT
void limbNonRT(ArmPtr &arm)
Definition: AdmittanceController.cpp:160
armarx::SensorValueBase
The SensorValueBase class.
Definition: SensorValueBase.h:40
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::rtPostDeactivateController
void rtPostDeactivateController() override
This function is called after the controller is deactivated.
Definition: AdmittanceController.cpp:623
armarx::ControlTargetBase
Brief description of class JointControlTargetBase.
Definition: ControlTargetBase.h:47
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::controllableNodeSets
std::map< std::string, VirtualRobot::RobotNodeSetPtr > controllableNodeSets
Definition: AdmittanceController.h:166
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::limbRTUpdateStatus
void limbRTUpdateStatus(ArmPtr &arm, const double deltaT)
-----------------------------— Real time cotnrol --------------------------------------—
Definition: AdmittanceController.cpp:231
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::isSafeForceTorque
bool isSafeForceTorque(const std::string &nodeSetName, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
-----------------------------— Other interaces ----------------------------------------—
Definition: AdmittanceController.cpp:400
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::limbInit
void limbInit(const std::string nodeSetName, ArmPtr &arm, Config &cfg, VirtualRobot::RobotPtr &nonRtRobotPtr)
Definition: AdmittanceController.cpp:44
armarx::NJointControllerBase::useControlTarget
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...
Definition: NJointController.cpp:410
armarx::control::common::detectAndReportPoseDeviationWarning
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:600
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::onPublish
void onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &) override
Definition: AdmittanceController.cpp:532
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::additionalTaskSetTarget
void additionalTaskSetTarget()
Definition: AdmittanceController.cpp:197
armarx::control::njoint_controller::task_space
Definition: AdmittanceController.cpp:37
armarx::control::ethercat::RTUtility::pinThreadToCPU
static bool pinThreadToCPU(unsigned int cpu)
Pins the calling thread to the CPU with the given id.
Definition: RTUtility.cpp:52
ARMARX_CHECK_GREATER
#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...
Definition: ExpressionException.h:116
armarx::CycleUtil
This util class helps with keeping a cycle time during a control cycle.
Definition: CycleUtil.h:40
armarx::ManagedIceObject::getState
int getState() const
Retrieve current state of the ManagedIceObject.
Definition: ManagedIceObject.cpp:725
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::userConfig
ConfigDict userConfig
Definition: AdmittanceController.h:164
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::ArmPtr
std::unique_ptr< ArmData > ArmPtr
Definition: AdmittanceController.h:97
ProsthesisInterface.values
values
Definition: ProsthesisInterface.py:190
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::enableSafeGuardForceTorque
void enableSafeGuardForceTorque(const std::string &nodeSetName, const bool forceGuard, const bool torqueGuard, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
Definition: AdmittanceController.cpp:374
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:43
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::nonRtRobot
VirtualRobot::RobotPtr nonRtRobot
Definition: AdmittanceController.h:162
armarx::NJointControllerBase::ConfigPtrT
NJointControllerConfigPtr ConfigPtrT
Definition: NJointControllerBase.h:586
aron_conversions.h
armarx::control::common::reportPoseDeviationWarning
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:581
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::rtPreActivateController
void rtPreActivateController() override
This function is called before the controller is activated.
Definition: AdmittanceController.cpp:608
armarx::control::njoint_controller::task_space::registrationControllerNJointTaskspaceAdmittanceController
NJointControllerRegistration< NJointTaskspaceAdmittanceController > registrationControllerNJointTaskspaceAdmittanceController("NJointTaskspaceAdmittanceController")
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::rtRun
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration) override
TODO make protected and use attorneys.
Definition: AdmittanceController.cpp:313
ARMARX_CHECK
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
Definition: ExpressionException.h:82
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::hands
core::HandControlPtr hands
Definition: AdmittanceController.h:165
IceInternal::Handle
Definition: forward_declarations.h:8
armarx::NJointControllerBase::rtGetRobot
const VirtualRobot::RobotPtr & rtGetRobot()
TODO make protected and use attorneys.
Definition: NJointControllerBase.h:845
armarx::detail::ControlThreadOutputBufferEntry
Definition: ControlThreadOutputBuffer.h:177
visionx::voxelgrid::Label
uint32_t Label
Type of an object label.
Definition: types.h:7
armarx::control::TargetNullspaceMap
dictionary< string, Ice::FloatSeq > TargetNullspaceMap
Definition: ControllerInterface.ice:40
armarx::WidgetDescription
Definition: DefaultWidgetDescriptions.cpp:27
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::additionalTask
virtual void additionalTask()
Definition: AdmittanceController.cpp:167
ARMARX_TRACE
#define ARMARX_TRACE
Definition: trace.h:69
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::limbRTSetTarget
void limbRTSetTarget(ArmPtr &arm, const Eigen::VectorXf &targetTorque)
Definition: AdmittanceController.cpp:255
armarx::PackagePath::toSystemPath
static std::filesystem::path toSystemPath(const data::PackagePath &pp)
Definition: PackagePath.cpp:54
AdmittanceController.h
armarx::NJointControllerBase::isControllerActive
bool isControllerActive(const Ice::Current &=Ice::emptyCurrent) const final override
Definition: NJointControllerBase.h:777
armarx::NJointControllerBase::runTask
void runTask(const std::string &taskName, Task &&task)
Executes a given task in a separate thread from the Application ThreadPool.
Definition: NJointControllerBase.h:753
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::ConfigPtrT
ConfigurableNJointControllerConfigPtr ConfigPtrT
Definition: AdmittanceController.h:56
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::limbRT
void limbRT(ArmPtr &arm, const double deltaT)
Definition: AdmittanceController.cpp:283
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::limbPublish
void limbPublish(ArmPtr &arm, const DebugObserverInterfacePrx &debugObs)
Definition: AdmittanceController.cpp:507
ArmarXObjectScheduler.h
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::additionalTaskUpdateStatus
bool additionalTaskUpdateStatus()
Definition: AdmittanceController.cpp:178
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::GenerateConfigDescription
static WidgetDescription::WidgetPtr GenerateConfigDescription(const VirtualRobot::RobotPtr &, const std::map< std::string, ConstControlDevicePtr > &, const std::map< std::string, ConstSensorDevicePtr > &)
--------------------------------— GUI Widget ------------------------------------------—
Definition: AdmittanceController.cpp:633
armarx::control::ethercat::RTUtility::elevateThreadPriority
static bool elevateThreadPriority(int priority)
Elevate the thread priority of the calling thread to the given priority.
Definition: RTUtility.cpp:17
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
armarx::control::common::debugEigenVec
void debugEigenVec(StringVariantBaseMap &datafields, const std::string &name, Eigen::VectorXf vec)
Definition: utils.cpp:125
utils.h
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::handleRTNotSafeInNonRT
void handleRTNotSafeInNonRT()
Definition: AdmittanceController.cpp:210
CycleUtil.h
armarx::RemoteGui::Client::HBoxLayout
Definition: Widgets.h:160
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::limbReInit
void limbReInit(ArmPtr &arm)
Definition: AdmittanceController.cpp:564
armarx::aron::data::DictPtr
std::shared_ptr< Dict > DictPtr
Definition: Dict.h:41
armarx::ctrlutil::v
double v(double t, double v0, double a0, double j)
Definition: CtrlUtil.h:39
ARMARX_CHECK_EXPRESSION
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
Definition: ExpressionException.h:73
TimeUtil.h
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::getConfig
::armarx::aron::data::dto::DictPtr getConfig(const Ice::Current &iceCurrent=Ice::emptyCurrent) override
Definition: AdmittanceController.cpp:359
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::updateTargetPose
bool updateTargetPose(const TargetPoseMap &targetPoseMap, const TargetNullspaceMap &targetNullspaceMap, const Ice::Current &=Ice::emptyCurrent) override
Definition: AdmittanceController.cpp:431
VAROUT
#define VAROUT(x)
Definition: StringHelpers.h:182
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::getTCPVel
Ice::FloatSeq getTCPVel(const std::string &rns, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
Definition: AdmittanceController.cpp:417
IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface >
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::updateConfig
void updateConfig(const ::armarx::aron::data::dto::DictPtr &dto, const Ice::Current &iceCurrent=Ice::emptyCurrent) override
NJointController interface.
Definition: AdmittanceController.cpp:330
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::getClassName
std::string getClassName(const Ice::Current &=Ice::emptyCurrent) const override
Definition: AdmittanceController.cpp:128
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::validateConfigData
void validateConfigData(Config &config, ArmPtr &arm)
Definition: AdmittanceController.cpp:463
armarx::control::TargetPoseMap
dictionary< string, FloatSeqSeq > TargetPoseMap
Definition: ControllerInterface.ice:39
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::Config
law::TaskspaceAdmittanceController::Config Config
Definition: AdmittanceController.h:57
armarx::control::NJointTaskspaceAdmittanceControllerInterface::calibrateFTSensor
void calibrateFTSensor()
ARMARX_INFO_S
#define ARMARX_INFO_S
Definition: Logging.h:195
ARMARX_CHECK_EQUAL
#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...
Definition: ExpressionException.h:130
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:186
ARMARX_RT_LOGF_WARN
#define ARMARX_RT_LOGF_WARN(...)
Definition: ControlThreadOutputBuffer.h:345
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::onInitNJointController
void onInitNJointController() override
NJointControllerBase interface.
Definition: AdmittanceController.cpp:134
armarx::PackagePath
Definition: PackagePath.h:55
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::GenerateConfigFromVariants
static ConfigPtrT GenerateConfigFromVariants(const StringVariantBaseMap &values)
Definition: AdmittanceController.cpp:666
armarx::ctrlutil::s
double s(double t, double s0, double v0, double a0, double j)
Definition: CtrlUtil.h:33
armarx::control::njoint_controller::task_space::NJointTaskspaceAdmittanceController::NJointTaskspaceAdmittanceController
NJointTaskspaceAdmittanceController(const RobotUnitPtr &robotUnit, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
Definition: AdmittanceController.cpp:85
RTUtility.h
armarx::ManagedIceObject::getObjectScheduler
ArmarXObjectSchedulerPtr getObjectScheduler() const
Definition: ManagedIceObject.cpp:731
armarx::NJointControllerBase::useSensorValue
const SensorValueBase * useSensorValue(const std::string &sensorDeviceName) const
Get a const ptr to the given SensorDevice's SensorValue.
Definition: NJointController.cpp:383
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:18
PackagePath.h