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