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