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