DeprecatedNJointTSDMPController.cpp
Go to the documentation of this file.
2 
3 #include <algorithm>
4 
5 #include <boost/archive/text_iarchive.hpp>
6 #include <boost/archive/text_oarchive.hpp>
7 
8 #include <VirtualRobot/IK/DifferentialIK.h>
9 #include <VirtualRobot/MathTools.h>
10 #include <VirtualRobot/Nodes/RobotNode.h>
11 #include <VirtualRobot/Robot.h>
12 #include <VirtualRobot/RobotNodeSet.h>
13 
16 
23 
25 {
26 
27  struct RTScopeTimer
28  {
29  RTScopeTimer(const std::string& name) : start(armarx::rtNow()), name(name)
30  {
31  }
32 
34  {
35  //float us = (armarx::rtNow() - start).toMicroSecondsDouble();
36  //ARMARX_IMPORTANT << name << " took " << us << " micro seconds";
37  }
38 
40  std::string name;
41  };
42 
44  registrationControllerDeprecatedNJointTSDMPController("DeprecatedNJointTSDMPController");
45 
47  const RobotUnitPtr&,
48  const armarx::NJointControllerConfigPtr& config,
50  {
51  RTScopeTimer timer("DeprecatedNJointTSDMPController_constructor");
52  RT_TIMING_START(DeprecatedNJointTSDMPController_constructor)
54  cfg = DeprecatedNJointTaskSpaceDMPControllerConfigPtr::dynamicCast(config);
55  ARMARX_CHECK_EXPRESSION(!cfg->nodeSetName.empty());
56  VirtualRobot::RobotNodeSetPtr rns = rtGetRobot()->getRobotNodeSet(cfg->nodeSetName);
57  jointNames = rns->getNodeNames();
58  ARMARX_CHECK_EXPRESSION(rns) << cfg->nodeSetName;
59  for (size_t i = 0; i < rns->getSize(); ++i)
60  {
61  std::string jointName = rns->getNode(i)->getName();
62  ControlTargetBase* ct = useControlTarget(jointName, ControlModes::Velocity1DoF);
63  const SensorValueBase* sv = useSensorValue(jointName);
64  targets.push_back(ct->asA<ControlTarget1DoFActuatorVelocity>());
65 
66  const SensorValue1DoFActuatorTorque* torqueSensor =
67  sv->asA<SensorValue1DoFActuatorTorque>();
68  const SensorValue1DoFActuatorVelocity* velocitySensor =
69  sv->asA<SensorValue1DoFActuatorVelocity>();
70  const SensorValue1DoFGravityTorque* gravityTorqueSensor =
71  sv->asA<SensorValue1DoFGravityTorque>();
72  const SensorValue1DoFActuatorPosition* positionSensor =
73  sv->asA<SensorValue1DoFActuatorPosition>();
74  if (!torqueSensor)
75  {
76  ARMARX_WARNING << "No Torque sensor available for " << jointName;
77  }
78  if (!gravityTorqueSensor)
79  {
80  ARMARX_WARNING << "No Gravity Torque sensor available for " << jointName;
81  }
82 
83  torqueSensors.push_back(torqueSensor);
84  gravityTorqueSensors.push_back(gravityTorqueSensor);
85  velocitySensors.push_back(velocitySensor);
86  positionSensors.push_back(positionSensor);
87  };
88  forceSensor = useSensorValue(cfg->forceSensorName)->asA<SensorValueForceTorque>();
89 
91  forceOffset.setZero();
92  filteredForce.setZero();
93  filteredForceInRoot.setZero();
94  forceThreshold.reinitAllBuffers(cfg->forceThreshold);
95  useForceStop = false;
96 
97  if (not cfg->tcpName.empty())
98  {
99  ARMARX_INFO << "Custom TCP " << QUOTED(cfg->tcpName) << " provided.";
100  }
101 
102  tcp = cfg->tcpName.empty() ? rns->getTCP() : rtGetRobot()->getRobotNode(cfg->tcpName);
103 
104  ARMARX_INFO << "Using TCP: " << QUOTED(tcp->getName());
105 
106  refFrame = (cfg->frameName.empty()) ? rns->getRobot()->getRootNode()
107  : rtGetRobot()->getRobotNode(cfg->frameName);
108  ARMARX_CHECK_EXPRESSION(tcp) << cfg->tcpName;
109 
110  // set tcp controller
111  tcpController.reset(new CartesianVelocityController(rns, tcp));
112  nodeSetName = cfg->nodeSetName;
113  torquePIDs.resize(tcpController->rns->getSize(), pidController());
114 
115  ik.reset(new VirtualRobot::DifferentialIK(
116  rns, refFrame, VirtualRobot::JacobiProvider::eSVDDamped));
117 
118 
119  finished = false;
120  tsvmp::TaskSpaceDMPControllerConfig taskSpaceDMPConfig;
121  taskSpaceDMPConfig.motionTimeDuration = cfg->timeDuration;
122  taskSpaceDMPConfig.DMPKernelSize = cfg->kernelSize;
123  taskSpaceDMPConfig.DMPMode = cfg->dmpMode;
124  taskSpaceDMPConfig.DMPStyle = cfg->dmpStyle;
125  taskSpaceDMPConfig.DMPAmplitude = cfg->dmpAmplitude;
126  taskSpaceDMPConfig.phaseStopParas.goDist = cfg->phaseDist0;
127  taskSpaceDMPConfig.phaseStopParas.backDist = cfg->phaseDist1;
128  taskSpaceDMPConfig.phaseStopParas.Kpos = cfg->phaseKpPos;
129  taskSpaceDMPConfig.phaseStopParas.Dpos = 0;
130  taskSpaceDMPConfig.phaseStopParas.Kori = cfg->phaseKpOri;
131  taskSpaceDMPConfig.phaseStopParas.Dori = 0;
132  taskSpaceDMPConfig.phaseStopParas.mm2radi = cfg->posToOriRatio;
133  taskSpaceDMPConfig.phaseStopParas.maxValue = cfg->phaseL;
134  taskSpaceDMPConfig.phaseStopParas.slop = cfg->phaseK;
135 
136  dmpCtrl.reset(new tsvmp::TaskSpaceDMPController("default", taskSpaceDMPConfig, false));
137 
138  // initialize tcp position and orientation
139 
140 
141  RTToControllerData initSensorData;
142  initSensorData.deltaT = 0;
143  initSensorData.currentTime = 0;
144  initSensorData.currentPose.setZero();
145  initSensorData.currentTwist.setZero();
146  rt2CtrlData.reinitAllBuffers(initSensorData);
147 
148  targetVels.setZero(6);
150  initData.targetTSVel.setZero(6);
151  initData.targetPose = refFrame->toLocalCoordinateSystem(tcp->getGlobalPose());
152  initData.nullspaceJointVelocities.resize(tcpController->rns->getSize(), 0);
153  initData.torqueKp.resize(tcpController->rns->getSize(), 0);
154  initData.torqueKd.resize(tcpController->rns->getSize(), 0);
155  initData.mode = ModeFromIce(cfg->mode);
156  reinitTripleBuffer(initData);
157 
158  debugName = cfg->debugName;
159 
160  KpF = cfg->Kp_LinearVel;
161  KoF = cfg->Kp_AngularVel;
162  DpF = cfg->Kd_LinearVel;
163  DoF = cfg->Kd_AngularVel;
164 
165  filtered_qvel.setZero(targets.size());
166  vel_filter_factor = cfg->vel_filter;
167 
168  filtered_position.setZero(3);
169  pos_filter_factor = cfg->pos_filter;
170 
171  // jlhigh = rns->getNode("..")->getJointLimitHi();
172  // jllow = rns->getNode("")->getJointLimitLo();
173  firstRun = true;
174 
175  jointLowLimits.setZero(targets.size());
176  jointHighLimits.setZero(targets.size());
177  for (size_t i = 0; i < rns->getSize(); i++)
178  {
179  VirtualRobot::RobotNodePtr rn = rns->getAllRobotNodes().at(i);
180 
181  jointLowLimits(i) = rn->getJointLimitLo();
182  jointHighLimits(i) = rn->getJointLimitHi();
183  }
184 
185  started = false;
186 
187  RTToUserData initInterfaceData;
188  initInterfaceData.currentTcpPose = Eigen::Matrix4f::Identity();
189  rt2UserData.reinitAllBuffers(initInterfaceData);
190  RT_TIMING_END(DeprecatedNJointTSDMPController_constructor)
191  }
192 
193  std::string
195  {
196  return "DeprecatedNJointTSDMPController";
197  }
198 
199  void
201  {
202  RTScopeTimer timer("controllerRun");
203  if (!started)
204  {
205  return;
206  }
207 
208  if (!rt2CtrlData.updateReadBuffer() || !dmpCtrl)
209  {
210  return;
211  }
212 
213  double deltaT = rt2CtrlData.getReadBuffer().deltaT;
214  Eigen::Matrix4f currentPose = rt2CtrlData.getReadBuffer().currentPose;
215  Eigen::VectorXf currentTwist = rt2CtrlData.getReadBuffer().currentTwist;
216 
217  LockGuardType guard{controllerMutex};
218  dmpCtrl->flow(deltaT, currentPose, currentTwist);
219 
220  if (dmpCtrl->canVal < 1e-8)
221  {
222  finished = true;
223  }
224  targetVels = dmpCtrl->getTargetVelocity();
225  targetPose = dmpCtrl->getTargetPoseMat();
226  std::vector<double> targetState = dmpCtrl->getTargetPose();
227 
228  debugOutputData.getWriteBuffer().latestTargetVelocities["x_vel"] = targetVels(0);
229  debugOutputData.getWriteBuffer().latestTargetVelocities["y_vel"] = targetVels(1);
230  debugOutputData.getWriteBuffer().latestTargetVelocities["z_vel"] = targetVels(2);
231  debugOutputData.getWriteBuffer().latestTargetVelocities["roll_vel"] = targetVels(3);
232  debugOutputData.getWriteBuffer().latestTargetVelocities["pitch_vel"] = targetVels(4);
233  debugOutputData.getWriteBuffer().latestTargetVelocities["yaw_vel"] = targetVels(5);
234  debugOutputData.getWriteBuffer().dmpTargets["dmp_x"] = targetState[0];
235  debugOutputData.getWriteBuffer().dmpTargets["dmp_y"] = targetState[1];
236  debugOutputData.getWriteBuffer().dmpTargets["dmp_z"] = targetState[2];
237  debugOutputData.getWriteBuffer().dmpTargets["dmp_qw"] = targetState[3];
238  debugOutputData.getWriteBuffer().dmpTargets["dmp_qx"] = targetState[4];
239  debugOutputData.getWriteBuffer().dmpTargets["dmp_qy"] = targetState[5];
240  debugOutputData.getWriteBuffer().dmpTargets["dmp_qz"] = targetState[6];
241  debugOutputData.getWriteBuffer().currentPose["currentPose_x"] = currentPose(0, 3);
242  debugOutputData.getWriteBuffer().currentPose["currentPose_y"] = currentPose(1, 3);
243  debugOutputData.getWriteBuffer().currentPose["currentPose_z"] = currentPose(2, 3);
244 
246  VirtualRobot::MathTools::eigen4f2quat(currentPose);
247  debugOutputData.getWriteBuffer().currentPose["currentPose_qw"] = currentQ.w;
248  debugOutputData.getWriteBuffer().currentPose["currentPose_qx"] = currentQ.x;
249  debugOutputData.getWriteBuffer().currentPose["currentPose_qy"] = currentQ.y;
250  debugOutputData.getWriteBuffer().currentPose["currentPose_qz"] = currentQ.z;
251  debugOutputData.getWriteBuffer().currentCanVal = dmpCtrl->debugData.canVal;
252  debugOutputData.getWriteBuffer().mpcFactor = dmpCtrl->debugData.mpcFactor;
253  debugOutputData.getWriteBuffer().error = dmpCtrl->debugData.poseError;
254  debugOutputData.getWriteBuffer().posError = dmpCtrl->debugData.posiError;
255  debugOutputData.getWriteBuffer().oriError = dmpCtrl->debugData.oriError;
256  debugOutputData.getWriteBuffer().deltaT = deltaT;
257 
258  debugOutputData.commitWrite();
259 
260  getWriterControlStruct().targetTSVel = targetVels;
261  getWriterControlStruct().targetPose = targetPose;
263  }
264 
265  Eigen::VectorXf
266  DeprecatedNJointTSDMPController::calcIK(const Eigen::VectorXf& cartesianVel,
267  const Eigen::VectorXf& nullspaceVel,
269  {
270  RTScopeTimer timer("calcIK");
271  Eigen::MatrixXf jacobi = ik->getJacobianMatrix(tcp, mode);
272 
273  Eigen::FullPivLU<Eigen::MatrixXf> lu_decomp(jacobi);
274 
275  Eigen::MatrixXf nullspace = lu_decomp.kernel();
276  Eigen::VectorXf nsv = Eigen::VectorXf::Zero(nullspace.rows());
277  for (int i = 0; i < nullspace.cols(); i++)
278  {
279  float squaredNorm = nullspace.col(i).squaredNorm();
280  // Prevent division by zero
281  if (squaredNorm > 1.0e-32f)
282  {
283  nsv += nullspace.col(i) * nullspace.col(i).dot(nullspaceVel) /
284  nullspace.col(i).squaredNorm();
285  }
286  }
287 
288  Eigen::MatrixXf inv =
289  ik->computePseudoInverseJacobianMatrix(jacobi, ik->getJacobiRegularization(mode));
290  // ARMARX_INFO << "inv: " << inv;
291  Eigen::VectorXf jointVel = inv * cartesianVel;
292  // jointVel += nsv;
293  return jointVel;
294  }
295 
296  void
298  const IceUtil::Time& timeSinceLastIteration)
299  {
300  // RT_TIMING_START(DeprecatedNJointTSDMPController_rtRun)
301  Eigen::Matrix4f currentPose = refFrame->toLocalCoordinateSystem(tcp->getGlobalPose());
302  rt2UserData.getWriteBuffer().currentTcpPose = currentPose;
303  rt2UserData.commitWrite();
304 
305  if (firstRun)
306  {
307  filtered_position = currentPose.block<3, 1>(0, 3);
308 
309  firstRun = false;
310  for (size_t i = 0; i < targets.size(); ++i)
311  {
312  targets.at(i)->velocity = 0;
313  }
314  return;
315  }
316  else
317  {
318  filtered_position = (1 - pos_filter_factor) * filtered_position +
319  pos_filter_factor * currentPose.block<3, 1>(0, 3);
320  if (not started)
321  {
322  forceOffset =
323  (1 - cfg->forceFilter) * forceOffset + cfg->forceFilter * forceSensor->force;
324  timeForCalibration = timeForCalibration + timeSinceLastIteration.toSecondsDouble();
325  }
326  if (started and useForceStop)
327  {
328  /* handle force stop */
329  filteredForce = (1 - cfg->forceFilter) * filteredForce +
330  cfg->forceFilter * (forceSensor->force - forceOffset);
331 
332  for (size_t i = 0; i < 3; ++i)
333  {
334  if (fabs(filteredForce(i)) > cfg->forceDeadZone)
335  {
336  filteredForce(i) -=
337  (filteredForce(i) / fabs(filteredForce(i))) * cfg->forceDeadZone;
338  }
339  else
340  {
341  filteredForce(i) = 0;
342  }
343  }
344  Eigen::Matrix4f forceFrameInRoot =
345  rtGetRobot()->getRobotNode(cfg->forceFrameName)->getPoseInRootFrame();
346  filteredForceInRoot = forceFrameInRoot.block<3, 3>(0, 0) * filteredForce;
347 
348  for (size_t i = 0; i < 3; ++i)
349  {
350  if (fabs(filteredForceInRoot[i]) > forceThreshold.getUpToDateReadBuffer()[i])
351  {
352  started = false;
353  break;
354  }
355  }
356  }
357  }
358 
359  double deltaT = timeSinceLastIteration.toSecondsDouble();
360 
361  Eigen::MatrixXf jacobi =
362  ik->getJacobianMatrix(tcp, VirtualRobot::IKSolver::CartesianSelection::All);
363 
364  Eigen::VectorXf qvel(velocitySensors.size());
365  for (size_t i = 0; i < velocitySensors.size(); ++i)
366  {
367  qvel(i) = velocitySensors[i]->velocity;
368  }
369 
370  filtered_qvel = (1 - vel_filter_factor) * filtered_qvel + vel_filter_factor * qvel;
371  Eigen::VectorXf tcptwist = jacobi * filtered_qvel;
372 
373  rt2CtrlData.getWriteBuffer().currentPose = currentPose;
374  rt2CtrlData.getWriteBuffer().currentTwist = tcptwist;
375  rt2CtrlData.getWriteBuffer().deltaT = deltaT;
376  rt2CtrlData.getWriteBuffer().currentTime += deltaT;
377  rt2CtrlData.commitWrite();
378 
379  rt2UserData.getWriteBuffer().currentTcpPose = currentPose;
380  rt2UserData.commitWrite();
381 
382  Eigen::VectorXf targetVel = rtGetControlStruct().targetTSVel;
383  Eigen::Matrix4f targetPose = rtGetControlStruct().targetPose;
384 
385  Eigen::VectorXf jointTargetVelocities = Eigen::VectorXf::Zero(targets.size());
386  if (started)
387  {
388  // targetVel = rtGetControlStruct().targetTSVel;
389  // targetPose = rtGetControlStruct().targetPose;
390 
391  Eigen::Matrix3f diffMat =
392  targetPose.block<3, 3>(0, 0) * currentPose.block<3, 3>(0, 0).inverse();
393  Eigen::Vector3f errorRPY = VirtualRobot::MathTools::eigen3f2rpy(diffMat);
394 
395  Eigen::Vector6f rtTargetVel;
396  rtTargetVel.block<3, 1>(0, 0) =
397  KpF * (targetPose.block<3, 1>(0, 3) - currentPose.block<3, 1>(0, 3)) +
398  DpF * (-tcptwist.block<3, 1>(0, 0));
399  // rtTargetVel.block<3, 1>(0, 0) = KpF * (targetPose.block<3, 1>(0, 3) - currentPose.block<3, 1>(0, 3)) + DpF * (targetVel.block<3, 1>(0, 0) - tcptwist.block<3, 1>(0, 0));
400  rtTargetVel.block<3, 1>(3, 0) =
401  KoF * errorRPY + DoF * (targetVel.block<3, 1>(3, 0) - tcptwist.block<3, 1>(3, 0));
402  // rtTargetVel = targetVel;
403 
404 
405  float normLinearVelocity = rtTargetVel.block<3, 1>(0, 0).norm();
406  if (normLinearVelocity > cfg->maxLinearVel)
407  {
408  rtTargetVel.block<3, 1>(0, 0) =
409  cfg->maxLinearVel * rtTargetVel.block<3, 1>(0, 0) / normLinearVelocity;
410  }
411 
412  float normAngularVelocity = rtTargetVel.block<3, 1>(3, 0).norm();
413  if (normAngularVelocity > cfg->maxAngularVel)
414  {
415  rtTargetVel.block<3, 1>(3, 0) =
416  cfg->maxAngularVel * rtTargetVel.block<3, 1>(3, 0) / normAngularVelocity;
417  }
418 
419 
420  // cartesian vel controller
421  // Eigen::Vector6f x;
422  // for (size_t i = 0; i < 6; i++)
423  // {
424  // x(i) = rtTargetVel(i);
425  // }
426 
427  Eigen::VectorXf jnv = Eigen::VectorXf::Zero(tcpController->rns->getSize());
428  float jointLimitAvoidanceKp = rtGetControlStruct().avoidJointLimitsKp;
429  if (jointLimitAvoidanceKp > 0)
430  {
431  jnv += jointLimitAvoidanceKp * tcpController->calculateJointLimitAvoidance();
432  }
433  for (size_t i = 0; i < tcpController->rns->getSize(); i++)
434  {
435  jnv(i) += rtGetControlStruct().nullspaceJointVelocities.at(i);
436  }
437 
438  // jointTargetVelocities = tcpController->calculate(x, jnv, VirtualRobot::IKSolver::CartesianSelection::All);
439  jointTargetVelocities =
440  calcIK(rtTargetVel, jnv, VirtualRobot::IKSolver::CartesianSelection::All);
441  // Eigen::VectorXf jointTargetVelocities = tcpController->calculate(x, jnv, VirtualRobot::IKSolver::CartesianSelection::All);
443  ARMARX_CHECK_LESS(targets.size(), 1000);
444  }
445 
446 
447  // If the controller is stopped, set the velocity to 0
448  // and skip the rest of the loop. This ensures that no velocity from the controller
449  // is sent to the targets when the controller is stopped.
450  if (stopped.load())
451  {
452  // ARMARX_INFO << deactivateSpam(1.) << "Controller is stopped. Setting velocity to 0";
453  std::for_each(
454  targets.begin(), targets.end(), [](auto* target) { target->velocity = 0; });
455  }
456  else
457  {
458  for (size_t i = 0; i < targets.size(); ++i)
459  {
460  targets.at(i)->velocity = jointTargetVelocities(i);
461 
462  if (!targets.at(i)->isValid() ||
463  fabs(targets.at(i)->velocity) > cfg->maxJointVelocity)
464  {
465  targets.at(i)->velocity = 0.0f;
466  }
467  }
468  }
469  rtDebugData.getWriteBuffer().targetJointVels = jointTargetVelocities;
470  rtDebugData.commitWrite();
471  // RT_TIMING_CEND(DeprecatedNJointTSDMPController_rtRun, 0.1)
472  }
473 
474  void
475  DeprecatedNJointTSDMPController::learnDMPFromFiles(const Ice::StringSeq& fileNames,
476  const Ice::Current&)
477  {
478  RTScopeTimer timer("learnDMPFromFiles");
479  ARMARX_INFO << "Learning DMP ... ";
480 
481  LockGuardType guard{controllerMutex};
482  dmpCtrl->learnDMPFromFiles(fileNames);
483  }
484 
485  void
487  {
488  RTScopeTimer timer("setSpeed");
489  LockGuardType guard{controllerMutex};
490  dmpCtrl->setSpeed(times);
491  }
492 
493  void
495  const Ice::DoubleSeq& viapoint,
496  const Ice::Current&)
497  {
498  RTScopeTimer timer("setViaPoints");
499  LockGuardType guard{controllerMutex};
500  dmpCtrl->setViaPose(u, viapoint);
501  }
502 
503  void
504  DeprecatedNJointTSDMPController::setTorqueKp(const StringFloatDictionary& torqueKp,
505  const Ice::Current&)
506  {
507  RTScopeTimer timer("setTorqueKp");
509  for (size_t i = 0; i < tcpController->rns->getSize(); i++)
510  {
511  getWriterControlStruct().torqueKp.at(i) =
512  torqueKp.at(tcpController->rns->getNode(i)->getName());
513  }
515  }
516 
517  void
519  const StringFloatDictionary& nullspaceJointVelocities,
520  const Ice::Current&)
521  {
522  RTScopeTimer timer("setNullspaceJointVelocities");
524  for (size_t i = 0; i < tcpController->rns->getSize(); i++)
525  {
526  getWriterControlStruct().nullspaceJointVelocities.at(i) =
527  nullspaceJointVelocities.at(tcpController->rns->getNode(i)->getName());
528  }
530  }
531 
532  void
534  Ice::Float avoidJointLimitsKp,
536  const Ice::Current&)
537  {
538  RTScopeTimer timer("setControllerTarget");
540  getWriterControlStruct().avoidJointLimitsKp = avoidJointLimitsKp;
541  getWriterControlStruct().mode = ModeFromIce(mode);
543  }
544 
545  void
547  {
548  RTScopeTimer timer("removeAllViaPoints");
549  LockGuardType guard{controllerMutex};
550  ARMARX_INFO << "setting via points ";
551  dmpCtrl->removeAllViaPoints();
552  }
553 
554  void
555  DeprecatedNJointTSDMPController::setGoals(const Ice::DoubleSeq& goals, const Ice::Current& ice)
556  {
557  RTScopeTimer timer("setGoals");
558  LockGuardType guard{controllerMutex};
559  dmpCtrl->setGoalPoseVec(goals);
560  }
561 
562  void
564  {
565  RTScopeTimer timer("pauseDMP");
566  dmpCtrl->pauseController();
567  }
568 
569  void
571  {
572  RTScopeTimer timer("resumeDMP");
573  dmpCtrl->resumeController();
574  }
575 
576  void
578  {
579  RTScopeTimer timer("resetDMP");
580  if (started)
581  {
582  ARMARX_INFO << "Cannot reset running DMP";
583  }
584  firstRun = true;
585  }
586 
587  void
589  {
590  RTScopeTimer timer("stopDMP");
591  started = false;
592  stopped = true;
593 
594  // If the NJoint controller is stopped, the underlying controller should be stopped as well.
595  // Note: resumeDMP() does not work if the controller is stopped.
596  pauseDMP(c);
597  }
598 
599  std::string
601  {
602  RTScopeTimer timer("getDMPAsString");
603  return dmpCtrl->saveDMPToString();
604  }
605 
606  std::vector<double>
608  const Ice::Current&)
609  {
610  RTScopeTimer timer("createDMPFromString");
611  dmpCtrl->loadDMPFromString(dmpString);
612  return dmpCtrl->dmpPtr->defaultGoal;
613  }
614 
618  {
619  RTScopeTimer timer("ModeFromIce");
621  {
623  }
625  {
627  }
629  {
630  return VirtualRobot::IKSolver::CartesianSelection::All;
631  }
632  ARMARX_ERROR_S << "invalid mode " << mode;
634  }
635 
636  void
637  DeprecatedNJointTSDMPController::runDMP(const Ice::DoubleSeq& goals,
638  double tau,
639  const Ice::Current&)
640  {
641  RTScopeTimer timer("runDMP");
642  ARMARX_INFO << "------dmp controller: " << VAROUT(goals);
643  firstRun = true;
644 
645  stopped = false;
646  timeForCalibration = 0;
647  while (firstRun || timeForCalibration < cfg->waitTimeForCalibration)
648  {
649  if (stopped.load())
650  {
651  ARMARX_WARNING << "StopDMP has been prematurely called; aborting runDMP";
652  return;
653  }
654  usleep(100);
655  }
656  while (!rt2UserData.updateReadBuffer())
657  {
658  usleep(100);
659  }
660 
661  Eigen::Matrix4f pose = rt2UserData.getReadBuffer().currentTcpPose;
662 
663  LockGuardType guard{controllerMutex};
664  // Eigen::Matrix4f pose = tcp->getPoseInRootFrame();
665  dmpCtrl->prepareExecution(dmpCtrl->eigen4f2vec(pose), goals);
666  dmpCtrl->resumeController();
667 
668  finished = false;
669 
670  ARMARX_INFO << "run DMP";
671  started = true;
672  }
673 
674  void
676  Ice::Double timeDuration,
677  const Ice::Current&)
678  {
679  RTScopeTimer timer("runDMPWithTime");
680  firstRun = true;
681  stopped = false;
682 
683  while (firstRun || timeForCalibration < cfg->waitTimeForCalibration)
684  {
685  if (stopped.load())
686  {
687  ARMARX_WARNING << "StopDMP has been prematurely called; aborting runDMP";
688  return;
689  }
690  usleep(100);
691  }
692  while (!rt2UserData.updateReadBuffer())
693  {
694  usleep(100);
695  }
696 
697  Eigen::Matrix4f pose = rt2UserData.getReadBuffer().currentTcpPose;
698 
699  LockGuardType guard{controllerMutex};
700  dmpCtrl->config.motionTimeDuration = timeDuration;
701  dmpCtrl->prepareExecution(dmpCtrl->eigen4f2vec(pose), goals);
702  dmpCtrl->resumeController();
703 
704  finished = false;
705  started = true;
706  }
707 
708  void
710  {
711  }
712 
713  void
715  {
716  ARMARX_INFO << "controller has been deactivated";
717  }
718 
719  void
722  const DebugObserverInterfacePrx& debugObs)
723  {
724  RTScopeTimer timer("onPublish");
725  std::string datafieldName = debugName;
726  StringVariantBaseMap datafields;
727  auto values = debugOutputData.getUpToDateReadBuffer().latestTargetVelocities;
728  for (auto& pair : values)
729  {
730  datafieldName = pair.first + "_" + debugName;
731  datafields[datafieldName] = new Variant(pair.second);
732  }
733 
734  auto dmpTargets = debugOutputData.getUpToDateReadBuffer().dmpTargets;
735  for (auto& pair : dmpTargets)
736  {
737  datafieldName = pair.first + "_" + debugName;
738  datafields[datafieldName] = new Variant(pair.second);
739  }
740 
741  auto currentPose = debugOutputData.getUpToDateReadBuffer().currentPose;
742  for (auto& pair : currentPose)
743  {
744  datafieldName = pair.first + "_" + debugName;
745  datafields[datafieldName] = new Variant(pair.second);
746  }
747 
748  datafieldName = "canVal_" + debugName;
749  datafields[datafieldName] =
750  new Variant(debugOutputData.getUpToDateReadBuffer().currentCanVal);
751  datafieldName = "mpcFactor_" + debugName;
752  datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().mpcFactor);
753  datafieldName = "error_" + debugName;
754  datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().error);
755  datafieldName = "posError_" + debugName;
756  datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().posError);
757  datafieldName = "oriError_" + debugName;
758  datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().oriError);
759  datafieldName = "deltaT_" + debugName;
760  datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().deltaT);
762  << "Error: " << debugOutputData.getUpToDateReadBuffer().error
763  << "\nPosition Error: " << debugOutputData.getUpToDateReadBuffer().posError
764  << "\nOrientation Error: "
765  << debugOutputData.getUpToDateReadBuffer().oriError;
766 
767  Eigen::VectorXf targetJoints = rtDebugData.getUpToDateReadBuffer().targetJointVels;
768  for (int i = 0; i < targetJoints.size(); ++i)
769  {
770  datafieldName = jointNames[i] + "_velocity";
771  datafields[datafieldName] = new Variant(targetJoints[i]);
772  }
773 
774  datafieldName = "DMPController_" + debugName;
775  debugObs->setDebugChannel(datafieldName, datafields);
776  }
777 
778  void
780  {
781  RTScopeTimer timer("onInitNJointController");
782  ARMARX_INFO << "init ...";
783  started = false;
784  runTask("DeprecatedNJointTSDMPController",
785  [&]
786  {
787  CycleUtil c(1);
788  getObjectScheduler()->waitForObjectStateMinimum(eManagedIceObjectStarted);
789  while (getState() == eManagedIceObjectStarted)
790  {
791  if (isControllerActive())
792  {
793  controllerRun();
794  }
795  c.waitForCycleDuration();
796  }
797  });
798  }
799 
800  void
802  {
803  ARMARX_INFO << "stopped ...";
804  }
805 
806  void
807  DeprecatedNJointTSDMPController::setMPWeights(const DoubleSeqSeq& weights, const Ice::Current&)
808  {
809  RTScopeTimer timer("setMPWeights");
810  dmpCtrl->setWeights(weights);
811  }
812 
813  DoubleSeqSeq
815  {
816  RTScopeTimer timer("getMPWeights");
817  DMP::DVec2d res = dmpCtrl->getWeights();
818  DoubleSeqSeq resvec;
819  for (size_t i = 0; i < res.size(); ++i)
820  {
821  std::vector<double> cvec;
822  for (size_t j = 0; j < res[i].size(); ++j)
823  {
824  cvec.push_back(res[i][j]);
825  }
826  resvec.push_back(cvec);
827  }
828 
829  return resvec;
830  }
831 
832  void
834  {
835  DpF = kd;
836  }
837 
838  void
840  {
841  KpF = kp;
842  }
843 
844  void
846  {
847  DoF = kd;
848  }
849 
850  void
852  {
853  KoF = kp;
854  }
855 
856 } // namespace armarx::control::deprecated_njoint_mp_controller::task_space
armarx::NJointControllerWithTripleBuffer< DeprecatedNJointTSDMPControllerControlData >::reinitTripleBuffer
void reinitTripleBuffer(const DeprecatedNJointTSDMPControllerControlData &initial)
Definition: NJointControllerWithTripleBuffer.h:68
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::onPublish
virtual void onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &) override
Definition: DeprecatedNJointTSDMPController.cpp:720
armarx::ControlTargetBase::asA
const T * asA() const
Definition: ControlTargetBase.h:76
armarx::Variant
The Variant class is described here: Variants.
Definition: Variant.h:223
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPControllerControlData::targetPose
Eigen::Matrix4f targetPose
Definition: DeprecatedNJointTSDMPController.h:43
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::Kori
float Kori
Definition: TaskSpaceVMP.h:54
ARMARX_VERBOSE
#define ARMARX_VERBOSE
Definition: Logging.h:187
armarx::DeprecatedNJointTaskSpaceDMPControllerInterface::resetDMP
void resetDMP()
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::rtPostDeactivateController
void rtPostDeactivateController() override
This function is called after the controller is deactivated.
Definition: DeprecatedNJointTSDMPController.cpp:714
armarx::targets
Brief description of class targets.
Definition: targets.h:38
armarx::VariantType::Float
const VariantTypeId Float
Definition: Variant.h:919
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::ModeFromIce
VirtualRobot::IKSolver::CartesianSelection ModeFromIce(const NJointTaskSpaceDMPControllerMode::CartesianSelection mode)
Definition: DeprecatedNJointTSDMPController.cpp:616
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::DeprecatedNJointTSDMPController
DeprecatedNJointTSDMPController(const RobotUnitPtr &, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
Definition: DeprecatedNJointTSDMPController.cpp:46
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::Dpos
float Dpos
Definition: TaskSpaceVMP.h:53
armarx::TripleBuffer::getWriteBuffer
T & getWriteBuffer()
Definition: TripleBuffer.h:92
armarx::NJointControllerRegistration
Definition: NJointControllerRegistry.h:74
armarx::NJointControllerBase::useSynchronizedRtRobot
const VirtualRobot::RobotPtr & useSynchronizedRtRobot(bool updateCollisionModel=false)
Requests a VirtualRobot for use in rtRun *.
Definition: NJointController.cpp:293
armarx::NJointControllerWithTripleBuffer< DeprecatedNJointTSDMPControllerControlData >::rtGetControlStruct
const DeprecatedNJointTSDMPControllerControlData & rtGetControlStruct() const
Definition: NJointControllerWithTripleBuffer.h:32
armarx::control::deprecated_njoint_mp_controller::tsvmp::TaskSpaceDMPControllerConfig::DMPKernelSize
int DMPKernelSize
Definition: TaskSpaceVMP.h:61
armarx::StringVariantBaseMap
std::map< std::string, VariantBasePtr > StringVariantBaseMap
Definition: ManagedIceObject.h:110
GfxTL::Orientation
ScalarT Orientation(const VectorXD< 2, ScalarT > &p1, const VectorXD< 2, ScalarT > &p2, const VectorXD< 2, ScalarT > &c)
Definition: Orientation.h:10
armarx::SensorValueBase::asA
const T * asA() const
Definition: SensorValueBase.h:82
armarx::SensorValueBase
The SensorValueBase class.
Definition: SensorValueBase.h:40
armarx::ControlTargetBase
Brief description of class JointControlTargetBase.
Definition: ControlTargetBase.h:47
armarx::DeprecatedNJointTaskSpaceDMPControllerInterface::resumeDMP
void resumeDMP()
QUOTED
#define QUOTED(x)
Definition: StringHelpers.h:199
RobotUnit.h
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::setMPWeights
void setMPWeights(const DoubleSeqSeq &weights, const Ice::Current &) override
Definition: DeprecatedNJointTSDMPController.cpp:807
armarx::TripleBuffer::commitWrite
void commitWrite()
Definition: TripleBuffer.h:163
GfxTL::Matrix4f
MatrixXX< 4, 4, float > Matrix4f
Definition: MatrixXX.h:650
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPControllerControlData::targetTSVel
Eigen::Vector6f targetTSVel
Definition: DeprecatedNJointTSDMPController.h:42
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::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::learnDMPFromFiles
void learnDMPFromFiles(const Ice::StringSeq &fileNames, const Ice::Current &) override
Definition: DeprecatedNJointTSDMPController.cpp:475
armarx::control::deprecated_njoint_mp_controller::task_space::RTScopeTimer::name
std::string name
Definition: DeprecatedNJointTSDMPController.cpp:40
armarx::control::deprecated_njoint_mp_controller::task_space
Definition: DeprecatedNJointPeriodicTSDMPCompliantController.cpp:20
RT_TIMING_END
#define RT_TIMING_END(name)
Definition: RtTiming.h:57
boost::target
Vertex target(const detail::edge_base< Directed, Vertex > &e, const PCG &)
Definition: point_cloud_graph.h:668
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
ProsthesisInterface.values
values
Definition: ProsthesisInterface.py:190
armarx::DeprecatedNJointTaskSpaceDMPControllerInterface::removeAllViaPoints
void removeAllViaPoints()
armarx::NJointTaskSpaceDMPControllerMode::ePosition
@ ePosition
Definition: ControllerInterface.ice:36
SensorValueForceTorque.h
ARMARX_CHECK_LESS
#define ARMARX_CHECK_LESS(lhs, rhs)
This macro evaluates whether lhs is less (<) than rhs and if it turns out to be false it will throw a...
Definition: ExpressionException.h:102
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:46
armarx::DeprecatedNJointTaskSpaceDMPControllerInterface::stopDMP
void stopDMP()
armarx::control::deprecated_njoint_mp_controller::tsvmp::TaskSpaceDMPControllerConfig
Definition: TaskSpaceVMP.h:59
armarx::CartesianVelocityController
Definition: CartesianVelocityController.h:36
armarx::control::deprecated_njoint_mp_controller::tsvmp::TaskSpaceDMPControllerConfig::phaseStopParas
PhaseStopParams phaseStopParas
Definition: TaskSpaceVMP.h:67
armarx::NJointControllerWithTripleBuffer< DeprecatedNJointTSDMPControllerControlData >::getWriterControlStruct
DeprecatedNJointTSDMPControllerControlData & getWriterControlStruct()
Definition: NJointControllerWithTripleBuffer.h:54
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::goDist
float goDist
Definition: TaskSpaceVMP.h:48
armarx::NJointControllerWithTripleBuffer< DeprecatedNJointTSDMPControllerControlData >::LockGuardType
std::lock_guard< std::recursive_mutex > LockGuardType
Definition: NJointControllerWithTripleBuffer.h:14
armarx::SensorValueForceTorque::force
Eigen::Vector3f force
Definition: SensorValueForceTorque.h:36
armarx::VariantType::Quaternion
const VariantTypeId Quaternion
Definition: Pose.h:39
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::setViaPoints
void setViaPoints(Ice::Double u, const Ice::DoubleSeq &viapoint, const Ice::Current &) override
Definition: DeprecatedNJointTSDMPController.cpp:494
armarx::control::deprecated_njoint_mp_controller::task_space::RTScopeTimer::start
IceUtil::Time start
Definition: DeprecatedNJointTSDMPController.cpp:39
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::setControllerTarget
void setControllerTarget(Ice::Float avoidJointLimitsKp, NJointTaskSpaceDMPControllerMode::CartesianSelection mode, const Ice::Current &) override
Definition: DeprecatedNJointTSDMPController.cpp:533
armarx::control::deprecated_njoint_mp_controller::tsvmp::TaskSpaceDMPControllerConfig::motionTimeDuration
float motionTimeDuration
Definition: TaskSpaceVMP.h:66
armarx::NJointControllerBase::rtGetRobot
const VirtualRobot::RobotPtr & rtGetRobot()
TODO make protected and use attorneys.
Definition: NJointControllerBase.h:846
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::backDist
float backDist
Definition: TaskSpaceVMP.h:49
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::maxValue
float maxValue
Definition: TaskSpaceVMP.h:50
DeprecatedNJointTSDMPController.h
armarx::detail::ControlThreadOutputBufferEntry
Definition: ControlThreadOutputBuffer.h:182
armarx::VariantType::Double
const VariantTypeId Double
Definition: Variant.h:920
ARMARX_TRACE
#define ARMARX_TRACE
Definition: trace.h:77
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::Dori
float Dori
Definition: TaskSpaceVMP.h:55
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::setSpeed
void setSpeed(Ice::Double times, const Ice::Current &) override
Definition: DeprecatedNJointTSDMPController.cpp:486
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:570
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPControllerControlData::nullspaceJointVelocities
std::vector< float > nullspaceJointVelocities
Definition: DeprecatedNJointTSDMPController.h:45
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPControllerControlData::mode
VirtualRobot::IKSolver::CartesianSelection mode
Definition: DeprecatedNJointTSDMPController.h:49
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPControllerControlData::torqueKd
std::vector< float > torqueKd
Definition: DeprecatedNJointTSDMPController.h:48
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::rtPreActivateController
void rtPreActivateController() override
This function is called before the controller is activated.
Definition: DeprecatedNJointTSDMPController.cpp:709
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::rtRun
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration) override
TODO make protected and use attorneys.
Definition: DeprecatedNJointTSDMPController.cpp:297
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::controllerRun
void controllerRun()
Definition: DeprecatedNJointTSDMPController.cpp:200
armarx::control::deprecated_njoint_mp_controller::task_space::RTScopeTimer
Definition: DeprecatedNJointTSDMPController.cpp:27
armarx::NJointControllerBase::isControllerActive
bool isControllerActive(const Ice::Current &=Ice::emptyCurrent) const final override
Definition: NJointControllerBase.h:778
armarx::DeprecatedNJointTaskSpaceDMPControllerInterface::pauseDMP
void pauseDMP()
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::createDMPFromString
std::vector< double > createDMPFromString(const std::string &dmpString, const Ice::Current &) override
Definition: DeprecatedNJointTSDMPController.cpp:607
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_ERROR_S
#define ARMARX_ERROR_S
Definition: Logging.h:216
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::runDMPWithTime
void runDMPWithTime(const Ice::DoubleSeq &goals, Ice::Double timeDuration, const Ice::Current &) override
Definition: DeprecatedNJointTSDMPController.cpp:675
armarx::NJointTaskSpaceDMPControllerMode::CartesianSelection
CartesianSelection
Definition: ControllerInterface.ice:34
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::setNullspaceJointVelocities
void setNullspaceJointVelocities(const StringFloatDictionary &nullspaceJointVelocities, const Ice::Current &) override
Definition: DeprecatedNJointTSDMPController.cpp:518
armarx::NJointControllerWithTripleBuffer< DeprecatedNJointTSDMPControllerControlData >::writeControlStruct
void writeControlStruct()
Definition: NJointControllerWithTripleBuffer.h:44
armarx::TripleBuffer::getReadBuffer
const T & getReadBuffer() const
Definition: TripleBuffer.h:108
ArmarXObjectScheduler.h
ControlTarget1DoFActuator.h
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::onDisconnectNJointController
void onDisconnectNJointController() override
Definition: DeprecatedNJointTSDMPController.cpp:801
armarx::NJointControllerWithTripleBuffer< DeprecatedNJointTSDMPControllerControlData >::controlDataMutex
MutexType controlDataMutex
Definition: NJointControllerWithTripleBuffer.h:73
armarx::control::deprecated_njoint_mp_controller::task_space::RTScopeTimer::RTScopeTimer
RTScopeTimer(const std::string &name)
Definition: DeprecatedNJointTSDMPController.cpp:29
RT_TIMING_START
#define RT_TIMING_START(name)
Definition: RtTiming.h:50
armarx::control::deprecated_njoint_mp_controller::tsvmp::TaskSpaceDMPControllerConfig::DMPAmplitude
float DMPAmplitude
Definition: TaskSpaceVMP.h:64
armarx::armem::Time
armarx::core::time::DateTime Time
Definition: forward_declarations.h:13
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::slop
float slop
Definition: TaskSpaceVMP.h:51
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::Kpos
float Kpos
Definition: TaskSpaceVMP.h:52
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::setAngularVelocityKp
void setAngularVelocityKp(Ice::Float kp, const Ice::Current &=Ice::emptyCurrent) override
Definition: DeprecatedNJointTSDMPController.cpp:851
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::setAngularVelocityKd
void setAngularVelocityKd(Ice::Float kd, const Ice::Current &=Ice::emptyCurrent) override
Definition: DeprecatedNJointTSDMPController.cpp:845
CartesianVelocityController.h
NJointController.h
armarx::WriteBufferedTripleBuffer::reinitAllBuffers
void reinitAllBuffers(const T &init)
Definition: TripleBuffer.h:390
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::NJointTaskSpaceDMPControllerMode::eAll
@ eAll
Definition: ControllerInterface.ice:38
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:181
VAROUT
#define VAROUT(x)
Definition: StringHelpers.h:198
armarx::NJointTaskSpaceDMPControllerMode::eOrientation
@ eOrientation
Definition: ControllerInterface.ice:37
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPControllerControlData
Definition: DeprecatedNJointTSDMPController.h:39
IceUtil::Handle< class RobotUnit >
armarx::DeprecatedNJointTaskSpaceDMPControllerInterface::getMPWeights
DoubleSeqSeq getMPWeights()
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::calcIK
Eigen::VectorXf calcIK(const Eigen::VectorXf &cartesianVel, const Eigen::VectorXf &nullspace, VirtualRobot::IKSolver::CartesianSelection mode)
Definition: DeprecatedNJointTSDMPController.cpp:266
armarx::control::deprecated_njoint_mp_controller::tsvmp::TaskSpaceDMPControllerConfig::DMPStyle
std::string DMPStyle
Definition: TaskSpaceVMP.h:63
IceInternal::ProxyHandle<::IceProxy::armarx::DebugDrawerInterface >
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::runDMP
void runDMP(const Ice::DoubleSeq &goals, Ice::Double tau, const Ice::Current &) override
Definition: DeprecatedNJointTSDMPController.cpp:637
armarx::control::deprecated_njoint_mp_controller::tsvmp::TaskSpaceDMPControllerConfig::DMPMode
std::string DMPMode
Definition: TaskSpaceVMP.h:62
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::setLinearVelocityKp
void setLinearVelocityKp(Ice::Float kp, const Ice::Current &=Ice::emptyCurrent) override
Definition: DeprecatedNJointTSDMPController.cpp:839
armarx::Logging::deactivateSpam
SpamFilterDataPtr deactivateSpam(float deactivationDurationSec=10.0f, const std::string &identifier="", bool deactivate=true) const
disables the logging for the current line for the given amount of seconds.
Definition: Logging.cpp:99
Eigen::Matrix< float, 6, 1 >
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::mm2radi
float mm2radi
Definition: TaskSpaceVMP.h:56
armarx::DeprecatedNJointTaskSpaceDMPControllerInterface::getDMPAsString
string getDMPAsString()
Logging.h
armarx::navigation::core::Position
Eigen::Vector3f Position
Definition: basic_types.h:36
GfxTL::Matrix3f
MatrixXX< 3, 3, float > Matrix3f
Definition: MatrixXX.h:649
armarx::TripleBuffer::getUpToDateReadBuffer
const T & getUpToDateReadBuffer() const
Definition: TripleBuffer.h:116
armarx::SensorValueForceTorque
Definition: SensorValueForceTorque.h:32
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::setTorqueKp
void setTorqueKp(const StringFloatDictionary &torqueKp, const Ice::Current &) override
Definition: DeprecatedNJointTSDMPController.cpp:504
armarx::WriteBufferedTripleBuffer::getUpToDateReadBuffer
const T & getUpToDateReadBuffer() const
Definition: TripleBuffer.h:346
ARMARX_WARNING
#define ARMARX_WARNING
Definition: Logging.h:193
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPControllerControlData::torqueKp
std::vector< float > torqueKp
Definition: DeprecatedNJointTSDMPController.h:47
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::setLinearVelocityKd
void setLinearVelocityKd(Ice::Float kd, const Ice::Current &=Ice::emptyCurrent) override
Definition: DeprecatedNJointTSDMPController.cpp:833
armarx::control::deprecated_njoint_mp_controller::task_space::RTScopeTimer::~RTScopeTimer
~RTScopeTimer()
Definition: DeprecatedNJointTSDMPController.cpp:33
armarx::TripleBuffer::reinitAllBuffers
std::enable_if< std::is_copy_constructible< U >::value >::type reinitAllBuffers(const T &init)
Definition: TripleBuffer.h:171
armarx::control::deprecated_njoint_mp_controller::tsvmp::TaskSpaceDMPController
Brief description of class TaskSpaceDMPController.
Definition: TaskSpaceVMP.h:90
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::setGoals
void setGoals(const Ice::DoubleSeq &goals, const Ice::Current &) override
Definition: DeprecatedNJointTSDMPController.cpp:555
armarx
This file offers overloads of toIce() and fromIce() functions for STL container types.
Definition: ArmarXTimeserver.cpp:27
armarx::control::deprecated_njoint_mp_controller::task_space::registrationControllerDeprecatedNJointTSDMPController
NJointControllerRegistration< DeprecatedNJointTSDMPController > registrationControllerDeprecatedNJointTSDMPController("DeprecatedNJointTSDMPController")
armarx::ManagedIceObject::getObjectScheduler
ArmarXObjectSchedulerPtr getObjectScheduler() const
Definition: ManagedIceObject.cpp:776
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::onInitNJointController
void onInitNJointController() override
Definition: DeprecatedNJointTSDMPController.cpp:779
SensorValue1DoFActuator.h
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
armarx::control::deprecated_njoint_mp_controller::task_space::DeprecatedNJointTSDMPController::getClassName
std::string getClassName(const Ice::Current &) const override
Definition: DeprecatedNJointTSDMPController.cpp:194
armarx::TripleBuffer::updateReadBuffer
bool updateReadBuffer() const
Swaps in the hidden buffer if it contains new data.
Definition: TripleBuffer.h:143
norm
double norm(const Point &a)
Definition: point.hpp:102
armarx::rtNow
IceUtil::Time rtNow()
Definition: RtTiming.h:40