NJointPeriodicTSDMPForwardVelController.cpp
Go to the documentation of this file.
2 
4 
6 {
7  NJointControllerRegistration<NJointPeriodicTSDMPForwardVelController>
9  "NJointPeriodicTSDMPForwardVelController");
10 
12  const RobotUnitPtr& robUnit,
13  const armarx::NJointControllerConfigPtr& config,
15  {
17  cfg = NJointPeriodicTSDMPControllerConfigPtr::dynamicCast(config);
18  ARMARX_CHECK_EXPRESSION(!cfg->nodeSetName.empty());
19  VirtualRobot::RobotNodeSetPtr rns = rtGetRobot()->getRobotNodeSet(cfg->nodeSetName);
20 
21  ARMARX_CHECK_EXPRESSION(rns) << cfg->nodeSetName;
22  for (size_t i = 0; i < rns->getSize(); ++i)
23  {
24  std::string jointName = rns->getNode(i)->getName();
25  ControlTargetBase* ct = useControlTarget(jointName, ControlModes::Velocity1DoF);
26  const SensorValueBase* sv = useSensorValue(jointName);
27  targets.push_back(ct->asA<ControlTarget1DoFActuatorVelocity>());
28 
29  const SensorValue1DoFActuatorVelocity* velocitySensor =
30  sv->asA<SensorValue1DoFActuatorVelocity>();
31  const SensorValue1DoFActuatorPosition* positionSensor =
32  sv->asA<SensorValue1DoFActuatorPosition>();
33 
34  velocitySensors.push_back(velocitySensor);
35  positionSensors.push_back(positionSensor);
36  };
37 
38  tcp = rns->getTCP();
39  // set tcp controller
40  tcpController.reset(new CartesianVelocityController(rns, tcp));
41  nodeSetName = cfg->nodeSetName;
42  ik.reset(new VirtualRobot::DifferentialIK(
43  rns, rns->getRobot()->getRootNode(), VirtualRobot::JacobiProvider::eSVDDamped));
44 
45 
46  tsvmp::TaskSpaceDMPControllerConfig taskSpaceDMPConfig;
47  taskSpaceDMPConfig.motionTimeDuration = cfg->timeDuration;
48  taskSpaceDMPConfig.DMPKernelSize = cfg->kernelSize;
49  taskSpaceDMPConfig.DMPAmplitude = cfg->dmpAmplitude;
50 
51  taskSpaceDMPConfig.DMPMode = "Linear";
52  taskSpaceDMPConfig.DMPStyle = "Periodic";
53  taskSpaceDMPConfig.phaseStopParas.goDist = cfg->phaseDist0;
54  taskSpaceDMPConfig.phaseStopParas.backDist = cfg->phaseDist1;
55  taskSpaceDMPConfig.phaseStopParas.Kpos = cfg->phaseKpPos;
56  taskSpaceDMPConfig.phaseStopParas.Kori = cfg->phaseKpOri;
57  taskSpaceDMPConfig.phaseStopParas.mm2radi = cfg->posToOriRatio;
58  taskSpaceDMPConfig.phaseStopParas.maxValue = cfg->phaseL;
59  taskSpaceDMPConfig.phaseStopParas.slop = cfg->phaseK;
60  taskSpaceDMPConfig.phaseStopParas.Dpos = 0;
61  taskSpaceDMPConfig.phaseStopParas.Dori = 0;
62 
63 
64  dmpCtrl.reset(new tsvmp::TaskSpaceDMPController("periodicDMP", taskSpaceDMPConfig, false));
65 
67  initData.targetPose = tcp->getPoseInRootFrame();
68  initData.targetTSVel.resize(6);
69  for (size_t i = 0; i < 6; ++i)
70  {
71  initData.targetTSVel(i) = 0;
72  }
73  reinitTripleBuffer(initData);
74 
75  finished = false;
76  firstRun = true;
77 
78 
79  const SensorValueBase* svlf =
80  robUnit->getSensorDevice(cfg->forceSensorName)->getSensorValue();
81  forceSensor = svlf->asA<SensorValueForceTorque>();
82 
83  forceOffset.setZero();
84  filteredForce.setZero();
85 
86  UserToRTData initUserData;
87  initUserData.targetForce = 0;
88  user2rtData.reinitAllBuffers(initUserData);
89 
90  oriToolDir << 0, 0, 1;
91 
92  kpf = cfg->Kpf;
93  }
94 
95  std::string
97  {
98  return "NJointPeriodicTSDMPForwardVelController";
99  }
100 
101  void
103  {
104  if (!started)
105  {
106  return;
107  }
108 
109  if (!rt2CtrlData.updateReadBuffer() || !dmpCtrl)
110  {
111  return;
112  }
113 
114  double deltaT = rt2CtrlData.getReadBuffer().deltaT;
115  Eigen::Matrix4f currentPose = rt2CtrlData.getReadBuffer().currentPose;
116  Eigen::VectorXf currentTwist = rt2CtrlData.getReadBuffer().currentTwist;
117 
118  LockGuardType guard{controllerMutex};
119  dmpCtrl->flow(deltaT, currentPose, currentTwist);
120 
121  Eigen::VectorXf targetVels = dmpCtrl->getTargetVelocity();
122  Eigen::Matrix4f targetPose = dmpCtrl->getIntegratedPoseMat();
123 
124  debugOutputData.getWriteBuffer().latestTargetVelocities["x_vel"] = targetVels(0);
125  debugOutputData.getWriteBuffer().latestTargetVelocities["y_vel"] = targetVels(1);
126  debugOutputData.getWriteBuffer().latestTargetVelocities["z_vel"] = targetVels(2);
127  debugOutputData.getWriteBuffer().latestTargetVelocities["roll_vel"] = targetVels(3);
128  debugOutputData.getWriteBuffer().latestTargetVelocities["pitch_vel"] = targetVels(4);
129  debugOutputData.getWriteBuffer().latestTargetVelocities["yaw_vel"] = targetVels(5);
130  debugOutputData.getWriteBuffer().currentPose["currentPose_x"] = currentPose(0, 3);
131  debugOutputData.getWriteBuffer().currentPose["currentPose_y"] = currentPose(1, 3);
132  debugOutputData.getWriteBuffer().currentPose["currentPose_z"] = currentPose(2, 3);
134  VirtualRobot::MathTools::eigen4f2quat(currentPose);
135  debugOutputData.getWriteBuffer().currentPose["currentPose_qw"] = currentQ.w;
136  debugOutputData.getWriteBuffer().currentPose["currentPose_qx"] = currentQ.x;
137  debugOutputData.getWriteBuffer().currentPose["currentPose_qy"] = currentQ.y;
138  debugOutputData.getWriteBuffer().currentPose["currentPose_qz"] = currentQ.z;
139  debugOutputData.getWriteBuffer().currentCanVal = dmpCtrl->debugData.canVal;
140  debugOutputData.getWriteBuffer().mpcFactor = dmpCtrl->debugData.mpcFactor;
141  debugOutputData.getWriteBuffer().error = dmpCtrl->debugData.poseError;
142  debugOutputData.getWriteBuffer().posError = dmpCtrl->debugData.posiError;
143  debugOutputData.getWriteBuffer().oriError = dmpCtrl->debugData.oriError;
144  debugOutputData.getWriteBuffer().deltaT = deltaT;
145  debugOutputData.commitWrite();
146 
147  getWriterControlStruct().targetTSVel = targetVels;
148  getWriterControlStruct().targetPose = targetPose;
150 
151  dmpRunning = true;
152  }
153 
154 
155  void
157  const IceUtil::Time& timeSinceLastIteration)
158  {
159  double deltaT = timeSinceLastIteration.toSecondsDouble();
160 
161  Eigen::Matrix4f currentPose = tcp->getPoseInRootFrame();
162  rt2UserData.getWriteBuffer().currentTcpPose = currentPose;
163  rt2UserData.getWriteBuffer().waitTimeForCalibration += deltaT;
164  rt2UserData.commitWrite();
165 
166  if (firstRun || !dmpRunning)
167  {
168  targetPose = currentPose;
169  for (size_t i = 0; i < targets.size(); ++i)
170  {
171  targets.at(i)->velocity = 0.0f;
172  }
173  firstRun = false;
174  filteredForce.setZero();
175 
176  Eigen::Matrix3f currentHandOri = currentPose.block<3, 3>(0, 0);
177  toolTransform = currentHandOri.transpose();
178  // force calibration
179  if (!dmpRunning)
180  {
181  forceOffset =
182  (1 - cfg->forceFilter) * forceOffset + cfg->forceFilter * forceSensor->force;
183  }
184  }
185  else
186  {
187 
188  Eigen::MatrixXf jacobi =
189  ik->getJacobianMatrix(tcp, VirtualRobot::IKSolver::CartesianSelection::All);
190 
191  Eigen::VectorXf qvel;
192  qvel.resize(velocitySensors.size());
193  for (size_t i = 0; i < velocitySensors.size(); ++i)
194  {
195  qvel(i) = velocitySensors[i]->velocity;
196  }
197 
198  Eigen::VectorXf tcptwist = jacobi * qvel;
199 
200  rt2CtrlData.getWriteBuffer().currentPose = currentPose;
201  rt2CtrlData.getWriteBuffer().currentTwist = tcptwist;
202  rt2CtrlData.getWriteBuffer().deltaT = deltaT;
203  rt2CtrlData.getWriteBuffer().currentTime += deltaT;
204  rt2CtrlData.commitWrite();
205 
206 
207  // forward controller
209  Eigen::VectorXf targetVel = rtGetControlStruct().targetTSVel;
210  // Eigen::Matrix4f targetPose = rtGetControlStruct().targetPose;
211 
212  // force detection
213  // filteredForce = (1 - cfg->forceFilter) * filteredForce + cfg->forceFilter * (forceSensor->force - forceOffset);
214  // Eigen::Vector3f filteredForceInRoot = rtGetRobot()->getRobotNode(cfg->forceFrameName)->toGlobalCoordinateSystemVec(filteredForce);
215  // filteredForceInRoot = rtGetRobot()->getRootNode()->toLocalCoordinateSystemVec(filteredForceInRoot);
216  // float targetForce = user2rtData.getUpToDateReadBuffer().targetForce;
217 
218  // Eigen::Matrix3f currentHandOri = currentPose.block<3, 3>(0, 0);
219  // Eigen::Matrix3f currentToolOri = toolTransform * currentHandOri;
220  // targetVel.block<3, 1>(0, 0) = currentToolOri * targetVel.block<3, 1>(0, 0);
221  // Eigen::Vector3f currentToolDir = currentToolOri * oriToolDir;
222 
223  // ARMARX_IMPORTANT << "original force: " << forceSensor->force;
224  // ARMARX_IMPORTANT << "filteredForce: " << filteredForce;
225  // ARMARX_IMPORTANT << "filteredForceInRoot: " << filteredForceInRoot;
226  // ARMARX_IMPORTANT << "forceOffset: " << forceOffset;
227  // ARMARX_IMPORTANT << "currentToolOri: " << currentToolOri;
228 
229  for (size_t i = 3; i < 6; ++i)
230  {
231  targetVel(i) = 0;
232  }
233 
234  // float forceCtrl = kpf * (targetForce - filteredForceInRoot.norm());
235  // Eigen::Vector3f desiredZVel = - forceCtrl * (currentToolDir / currentToolDir.norm());
236  // targetVel.block<3, 1>(0, 0) += desiredZVel;
237 
238  // dead zone for force
239  // if (filteredForceInRoot.norm() > cfg->minimumReactForce)
240  // {
241  // // rotation changes
242  // Eigen::Vector3f axis = oriToolDir.cross(filteredForceInRoot);
243  // float angle = oriToolDir.dot(filteredForceInRoot);
244  // Eigen::AngleAxisf desiredToolOri(angle, axis);
245  // Eigen::Matrix3f desiredHandOri = toolTransform.transpose() * desiredToolOri;
246  // Eigen::Matrix3f desiredRotMat = desiredHandOri * currentHandOri.transpose();
247  // Eigen::Vector3f desiredRPY = VirtualRobot::MathTools::eigen3f2rpy(desiredRotMat);
248  // for (size_t i = 3; i < 6; ++i)
249  // {
250  // targetVel(i) = desiredRPY(i - 3);
251  // }
252  // }}
253 
254  // ARMARX_IMPORTANT << "targetVel: " << targetVel;
255  // ARMARX_IMPORTANT << "targetPose: " << targetPose;
256 
257  // targetPose.block<3, 1>(0, 3) += deltaT * targetVel.block<3, 1>(0, 0);
258  // Eigen::Matrix3f rotVel = VirtualRobot::MathTools::rpy2eigen3f(targetVel(3) * deltaT, targetVel(4) * deltaT, targetVel(5) * deltaT);
259  // targetPose.block<3, 3>(0, 0) = rotVel * targetPose.block<3, 3>(0, 0);
260 
261  float dTf = (float)deltaT;
262  targetPose.block<3, 1>(0, 3) =
263  targetPose.block<3, 1>(0, 3) + dTf * targetVel.block<3, 1>(0, 0);
264  Eigen::Matrix3f rotVel = VirtualRobot::MathTools::rpy2eigen3f(
265  targetVel(3) * dTf, targetVel(4) * dTf, targetVel(5) * dTf);
266  targetPose.block<3, 3>(0, 0) = rotVel * targetPose.block<3, 3>(0, 0);
267 
268  ARMARX_IMPORTANT << "targetVel: " << targetVel.block<3, 1>(0, 0);
269  ARMARX_IMPORTANT << "targetPose: " << targetPose;
270  ARMARX_IMPORTANT << "deltaT: " << deltaT;
271 
272  Eigen::Matrix3f diffMat =
273  targetPose.block<3, 3>(0, 0) * currentPose.block<3, 3>(0, 0).inverse();
274  Eigen::Vector3f errorRPY = VirtualRobot::MathTools::eigen3f2rpy(diffMat);
275 
276  Eigen::VectorXf rtTargetVel = targetVel;
277  rtTargetVel.block<3, 1>(0, 0) +=
278  cfg->Kpos * (targetPose.block<3, 1>(0, 3) - currentPose.block<3, 1>(0, 3));
279  rtTargetVel.block<3, 1>(3, 0) += cfg->Kori * errorRPY;
280 
281  float normLinearVelocity = rtTargetVel.block<3, 1>(0, 0).norm();
282  if (normLinearVelocity > fabs(cfg->maxLinearVel))
283  {
284  rtTargetVel.block<3, 1>(0, 0) =
285  fabs(cfg->maxLinearVel) * rtTargetVel.block<3, 1>(0, 0) / normLinearVelocity;
286  }
287 
288  float normAngularVelocity = rtTargetVel.block<3, 1>(3, 0).norm();
289  if (normAngularVelocity > fabs(cfg->maxAngularVel))
290  {
291  rtTargetVel.block<3, 1>(3, 0) =
292  fabs(cfg->maxAngularVel) * rtTargetVel.block<3, 1>(3, 0) / normAngularVelocity;
293  }
294 
295 
296  // cartesian vel controller
297 
298  Eigen::VectorXf jnv = Eigen::VectorXf::Zero(tcpController->rns->getSize());
299  if (cfg->avoidJointLimitsKp > 0)
300  {
301  jnv += cfg->avoidJointLimitsKp * tcpController->calculateJointLimitAvoidance();
302  }
303 
304  Eigen::VectorXf jointTargetVelocities = tcpController->calculate(
305  rtTargetVel, jnv, VirtualRobot::IKSolver::CartesianSelection::All);
306  for (size_t i = 0; i < targets.size(); ++i)
307  {
308  targets.at(i)->velocity = jointTargetVelocities(i);
309  if (!targets.at(i)->isValid())
310  {
311  targets.at(i)->velocity = 0.0f;
312  }
313  else
314  {
315  if (fabs(targets.at(i)->velocity) > fabs(cfg->maxJointVel))
316  {
317  targets.at(i)->velocity =
318  fabs(cfg->maxJointVel) *
319  (targets.at(i)->velocity / fabs(targets.at(i)->velocity));
320  }
321  }
322  }
323  }
324  }
325 
326 
327  void
329  const Ice::Current&)
330  {
331  ARMARX_INFO << "Learning DMP ... ";
332 
333  LockGuardType guard{controllerMutex};
334  dmpCtrl->learnDMPFromFiles(fileNames);
335  }
336 
337  void
339  {
340  LockGuardType guard{controllerMutex};
341  dmpCtrl->setSpeed(times);
342  }
343 
344 
345  void
347  const Ice::Current& ice)
348  {
349  LockGuardType guard{controllerMutex};
350  dmpCtrl->setGoalPoseVec(goals);
351  }
352 
353  void
355  {
356  LockGuardType guard{controllerMutex};
357  dmpCtrl->setAmplitude(amp);
358  }
359 
360  void
362  double tau,
363  const Ice::Current&)
364  {
365  firstRun = true;
366  while (firstRun || rt2UserData.getUpToDateReadBuffer().waitTimeForCalibration <
367  cfg->waitTimeForCalibration)
368  {
369  usleep(100);
370  }
371 
372  Eigen::Matrix4f pose = rt2UserData.getUpToDateReadBuffer().currentTcpPose;
373  LockGuardType guard{controllerMutex};
374  dmpCtrl->prepareExecution(dmpCtrl->eigen4f2vec(pose), goals);
375  dmpCtrl->setSpeed(tau);
376  finished = false;
377 
378  ARMARX_INFO << "run DMP";
379  started = true;
380  dmpRunning = false;
381  }
382 
383 
384  void
387  const DebugObserverInterfacePrx& debugObs)
388  {
389  std::string datafieldName;
390  std::string debugName = "Periodic";
391  StringVariantBaseMap datafields;
392  auto values = debugOutputData.getUpToDateReadBuffer().latestTargetVelocities;
393  for (auto& pair : values)
394  {
395  datafieldName = pair.first + "_" + debugName;
396  datafields[datafieldName] = new Variant(pair.second);
397  }
398 
399  auto currentPose = debugOutputData.getUpToDateReadBuffer().currentPose;
400  for (auto& pair : currentPose)
401  {
402  datafieldName = pair.first + "_" + debugName;
403  datafields[datafieldName] = new Variant(pair.second);
404  }
405 
406  datafieldName = "canVal_" + debugName;
407  datafields[datafieldName] =
408  new Variant(debugOutputData.getUpToDateReadBuffer().currentCanVal);
409  datafieldName = "mpcFactor_" + debugName;
410  datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().mpcFactor);
411  datafieldName = "error_" + debugName;
412  datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().error);
413  datafieldName = "posError_" + debugName;
414  datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().posError);
415  datafieldName = "oriError_" + debugName;
416  datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().oriError);
417  datafieldName = "deltaT_" + debugName;
418  datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().deltaT);
419  datafieldName = "DMPController_" + debugName;
420 
421  debugObs->setDebugChannel(datafieldName, datafields);
422  }
423 
424  void
426  {
427  ARMARX_INFO << "init ...";
428 
429  RTToControllerData initSensorData;
430  initSensorData.deltaT = 0;
431  initSensorData.currentTime = 0;
432  initSensorData.currentPose = tcp->getPoseInRootFrame();
433  initSensorData.currentTwist.setZero();
434  rt2CtrlData.reinitAllBuffers(initSensorData);
435 
436  RTToUserData initInterfaceData;
437  initInterfaceData.currentTcpPose = tcp->getPoseInRootFrame();
438  rt2UserData.reinitAllBuffers(initInterfaceData);
439 
440 
441  started = false;
442  runTask("NJointPeriodicTSDMPForwardVelController",
443  [&]
444  {
445  CycleUtil c(1);
446  getObjectScheduler()->waitForObjectStateMinimum(eManagedIceObjectStarted);
447  while (getState() == eManagedIceObjectStarted)
448  {
449  if (isControllerActive())
450  {
451  controllerRun();
452  }
453  c.waitForCycleDuration();
454  }
455  });
456  }
457 
458  void
460  {
461  ARMARX_INFO << "stopped ...";
462  }
463 
464 
465 } // namespace armarx::ctrl::njoint_ctrl::dmp
armarx::NJointControllerWithTripleBuffer< NJointPeriodicTSDMPForwardVelControllerControlData >::reinitTripleBuffer
void reinitTripleBuffer(const NJointPeriodicTSDMPForwardVelControllerControlData &initial)
Definition: NJointControllerWithTripleBuffer.h:68
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::NJointPeriodicTSDMPForwardVelController::setSpeed
void setSpeed(Ice::Double times, const Ice::Current &)
Definition: NJointPeriodicTSDMPForwardVelController.cpp:338
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::Kori
float Kori
Definition: TaskSpaceVMP.h:47
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPForwardVelController::getClassName
std::string getClassName(const Ice::Current &) const
Definition: NJointPeriodicTSDMPForwardVelController.cpp:96
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::NJointControllerBase::useSynchronizedRtRobot
const VirtualRobot::RobotPtr & useSynchronizedRtRobot(bool updateCollisionModel=false)
Requests a VirtualRobot for use in rtRun *.
Definition: NJointController.cpp:293
armarx::NJointControllerWithTripleBuffer< NJointPeriodicTSDMPForwardVelControllerControlData >::rtGetControlStruct
const NJointPeriodicTSDMPForwardVelControllerControlData & rtGetControlStruct() const
Definition: NJointControllerWithTripleBuffer.h:32
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPForwardVelController::runDMP
void runDMP(const Ice::DoubleSeq &goals, double tau, const Ice::Current &)
Definition: NJointPeriodicTSDMPForwardVelController.cpp:361
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
ARMARX_IMPORTANT
#define ARMARX_IMPORTANT
Definition: Logging.h:183
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::TripleBuffer::commitWrite
void commitWrite()
Definition: TripleBuffer.h:146
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPForwardVelController::controllerRun
void controllerRun()
Definition: NJointPeriodicTSDMPForwardVelController.cpp:102
armarx::control::deprecated_njoint_mp_controller::task_space::registrationControllerNJointPeriodicTSDMPForwardVelController
NJointControllerRegistration< NJointPeriodicTSDMPForwardVelController > registrationControllerNJointPeriodicTSDMPForwardVelController("NJointPeriodicTSDMPForwardVelController")
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
Definition: DeprecatedNJointPeriodicTSDMPCompliantController.cpp:6
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPForwardVelControllerControlData::targetPose
Eigen::Matrix4f targetPose
Definition: NJointPeriodicTSDMPForwardVelController.h:33
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::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPForwardVelController::rtRun
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration)
TODO make protected and use attorneys.
Definition: NJointPeriodicTSDMPForwardVelController.cpp:156
c
constexpr T c
Definition: UnscentedKalmanFilterTest.cpp:43
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPForwardVelController::setGoals
void setGoals(const Ice::DoubleSeq &goals, const Ice::Current &)
Definition: NJointPeriodicTSDMPForwardVelController.cpp:346
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< NJointPeriodicTSDMPForwardVelControllerControlData >::getWriterControlStruct
NJointPeriodicTSDMPForwardVelControllerControlData & getWriterControlStruct()
Definition: NJointControllerWithTripleBuffer.h:54
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::goDist
float goDist
Definition: TaskSpaceVMP.h:41
armarx::NJointControllerWithTripleBuffer< NJointPeriodicTSDMPForwardVelControllerControlData >::LockGuardType
std::lock_guard< std::recursive_mutex > LockGuardType
Definition: NJointControllerWithTripleBuffer.h:14
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPForwardVelController::onDisconnectNJointController
void onDisconnectNJointController()
Definition: NJointPeriodicTSDMPForwardVelController.cpp:459
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::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
armarx::detail::ControlThreadOutputBufferEntry
Definition: ControlThreadOutputBuffer.h:177
armarx::VariantType::Double
const VariantTypeId Double
Definition: Variant.h:919
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::Dori
float Dori
Definition: TaskSpaceVMP.h:48
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPForwardVelController::NJointPeriodicTSDMPForwardVelController
NJointPeriodicTSDMPForwardVelController(const RobotUnitPtr &, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
Definition: NJointPeriodicTSDMPForwardVelController.cpp:11
armarx::NJointControllerBase::isControllerActive
bool isControllerActive(const Ice::Current &=Ice::emptyCurrent) const final override
Definition: NJointControllerBase.h:777
armarx::NJointControllerBase::runTask
void runTask(const std::string &taskName, Task &&task)
Executes a given task in a separate thread from the Application ThreadPool.
Definition: NJointControllerBase.h:753
armarx::NJointControllerWithTripleBuffer< NJointPeriodicTSDMPForwardVelControllerControlData >::rtUpdateControlStruct
bool rtUpdateControlStruct()
Definition: NJointControllerWithTripleBuffer.h:38
armarx::NJointControllerWithTripleBuffer< NJointPeriodicTSDMPForwardVelControllerControlData >::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::NJointPeriodicTSDMPForwardVelController::onPublish
virtual void onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &)
Definition: NJointPeriodicTSDMPForwardVelController.cpp:385
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPForwardVelController::setAmplitude
void setAmplitude(Ice::Double amp, const Ice::Current &)
Definition: NJointPeriodicTSDMPForwardVelController.cpp:354
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::NJointPeriodicTSDMPForwardVelController::learnDMPFromFiles
void learnDMPFromFiles(const Ice::StringSeq &fileNames, const Ice::Current &)
Definition: NJointPeriodicTSDMPForwardVelController.cpp:328
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
NJointPeriodicTSDMPForwardVelController.h
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPForwardVelControllerControlData::targetTSVel
Eigen::VectorXf targetTSVel
Definition: NJointPeriodicTSDMPForwardVelController.h:32
float
#define float
Definition: 16_Level.h:22
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:174
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::NJointPeriodicTSDMPForwardVelController::onInitNJointController
void onInitNJointController()
Definition: NJointPeriodicTSDMPForwardVelController.cpp:425
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPForwardVelControllerControlData
Definition: NJointPeriodicTSDMPForwardVelController.h:29
armarx::control::deprecated_njoint_mp_controller::tsvmp::TaskSpaceDMPControllerConfig::DMPMode
std::string DMPMode
Definition: TaskSpaceVMP.h:55
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::mm2radi
float mm2radi
Definition: TaskSpaceVMP.h:49
armarx::TripleBuffer::getUpToDateReadBuffer
const T & getUpToDateReadBuffer() const
Definition: TripleBuffer.h:108
armarx::SensorValueForceTorque
Definition: SensorValueForceTorque.h:31
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::ManagedIceObject::getObjectScheduler
ArmarXObjectSchedulerPtr getObjectScheduler() const
Definition: ManagedIceObject.cpp:731
armarx::NJointControllerBase::useSensorValue
const SensorValueBase * useSensorValue(const std::string &sensorDeviceName) const
Get a const ptr to the given SensorDevice's SensorValue.
Definition: NJointController.cpp:383
VirtualRobot::RobotPtr
std::shared_ptr< class Robot > RobotPtr
Definition: Bus.h:18
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