NJointPeriodicTSDMPCompliantController.cpp
Go to the documentation of this file.
2 
3 #include <VirtualRobot/IK/DifferentialIK.h>
4 #include <VirtualRobot/Manipulability/SingleChainManipulability.h>
5 #include <VirtualRobot/Manipulability/SingleChainManipulabilityTracking.h>
6 #include <VirtualRobot/MathTools.h>
7 #include <VirtualRobot/Nodes/RobotNode.h>
8 #include <VirtualRobot/Nodes/Sensor.h>
9 #include <VirtualRobot/Robot.h>
10 #include <VirtualRobot/RobotNodeSet.h>
11 
13 
21 
23 {
24  NJointControllerRegistration<NJointPeriodicTSDMPCompliantController>
26  "NJointPeriodicTSDMPCompliantController");
27 
29  const RobotUnitPtr& robUnit,
30  const armarx::NJointControllerConfigPtr& config,
32  {
34  cfg = NJointPeriodicTSDMPCompliantControllerConfigPtr::dynamicCast(config);
35  ARMARX_CHECK_EXPRESSION(!cfg->nodeSetName.empty());
36  VirtualRobot::RobotNodeSetPtr rns = rtGetRobot()->getRobotNodeSet(cfg->nodeSetName);
37 
38  ARMARX_CHECK_EXPRESSION(rns) << cfg->nodeSetName;
39  for (size_t i = 0; i < rns->getSize(); ++i)
40  {
41  std::string jointName = rns->getNode(i)->getName();
42  ControlTargetBase* ct = useControlTarget(jointName, ControlModes::Torque1DoF);
43  const SensorValueBase* sv = useSensorValue(jointName);
44  targets.push_back(ct->asA<ControlTarget1DoFActuatorTorque>());
45 
46  const SensorValue1DoFActuatorVelocity* velocitySensor =
47  sv->asA<SensorValue1DoFActuatorVelocity>();
48  const SensorValue1DoFActuatorPosition* positionSensor =
49  sv->asA<SensorValue1DoFActuatorPosition>();
50 
51  velocitySensors.push_back(velocitySensor);
52  positionSensors.push_back(positionSensor);
53  };
54 
55  tcp = rns->getTCP();
56  // set tcp controller
57  nodeSetName = cfg->nodeSetName;
58  ik.reset(new VirtualRobot::DifferentialIK(
59  rns, rns->getRobot()->getRootNode(), VirtualRobot::JacobiProvider::eSVDDamped));
60 
61  tsvmp::TaskSpaceDMPControllerConfig taskSpaceDMPConfig;
62  taskSpaceDMPConfig.motionTimeDuration = cfg->timeDuration;
63  taskSpaceDMPConfig.DMPKernelSize = cfg->kernelSize;
64  taskSpaceDMPConfig.DMPAmplitude = cfg->dmpAmplitude;
65  taskSpaceDMPConfig.DMPMode = "Linear";
66  taskSpaceDMPConfig.DMPStyle = "Periodic";
67  taskSpaceDMPConfig.phaseStopParas.goDist = cfg->phaseDist0;
68  taskSpaceDMPConfig.phaseStopParas.backDist = cfg->phaseDist1;
69  taskSpaceDMPConfig.phaseStopParas.Kpos = cfg->phaseKpPos;
70  taskSpaceDMPConfig.phaseStopParas.Kori = cfg->phaseKpOri;
71  taskSpaceDMPConfig.phaseStopParas.mm2radi = cfg->posToOriRatio;
72  taskSpaceDMPConfig.phaseStopParas.maxValue = cfg->phaseL;
73  taskSpaceDMPConfig.phaseStopParas.slop = cfg->phaseK;
74  taskSpaceDMPConfig.phaseStopParas.Dpos = 0;
75  taskSpaceDMPConfig.phaseStopParas.Dori = 0;
76 
77 
78  dmpCtrl.reset(new tsvmp::TaskSpaceDMPController("periodicDMP", taskSpaceDMPConfig, false));
79 
81  initData.targetTSVel.resize(6);
82  for (size_t i = 0; i < 6; ++i)
83  {
84  initData.targetTSVel(i) = 0;
85  }
86  reinitTripleBuffer(initData);
87 
88  firstRun = true;
89  dmpRunning = false;
90 
91 
92  ARMARX_CHECK_EQUAL(cfg->Kpos.size(), 3);
93  ARMARX_CHECK_EQUAL(cfg->Dpos.size(), 3);
94  ARMARX_CHECK_EQUAL(cfg->Kori.size(), 3);
95  ARMARX_CHECK_EQUAL(cfg->Dori.size(), 3);
96 
97  kpos << cfg->Kpos[0], cfg->Kpos[1], cfg->Kpos[2];
98  dpos << cfg->Dpos[0], cfg->Dpos[1], cfg->Dpos[2];
99  kori << cfg->Kori[0], cfg->Kori[1], cfg->Kori[2];
100  dori << cfg->Dori[0], cfg->Dori[1], cfg->Dori[2];
101 
102  kpf = cfg->Kpf;
103  knull = cfg->Knull;
104  dnull = cfg->Dnull;
105 
106 
107  nullSpaceJointsVec.resize(cfg->desiredNullSpaceJointValues.size());
108  for (size_t i = 0; i < cfg->desiredNullSpaceJointValues.size(); ++i)
109  {
110  nullSpaceJointsVec(i) = cfg->desiredNullSpaceJointValues.at(i);
111  }
112 
113 
114  const SensorValueBase* svlf =
115  robUnit->getSensorDevice(cfg->forceSensorName)->getSensorValue();
116  forceSensor = svlf->asA<SensorValueForceTorque>();
117 
118  forceOffset.setZero();
119  filteredForce.setZero();
120  filteredForceInRoot.setZero();
121 
122 
123  UserToRTData initUserData;
124  initUserData.targetForce = 0;
125  user2rtData.reinitAllBuffers(initUserData);
126 
127  oriToolDir << 0, 0, 1;
128 
129  qvel_filtered.setZero(targets.size());
130 
131  ARMARX_CHECK_EQUAL(cfg->ws_x.size(), 2);
132  ARMARX_CHECK_EQUAL(cfg->ws_y.size(), 2);
133  ARMARX_CHECK_EQUAL(cfg->ws_z.size(), 2);
134 
135  // only for ARMAR-6 (safe-guard)
136  if (!cfg->ignoreWSLimitChecks)
137  {
138  ARMARX_CHECK_LESS(cfg->ws_x[0], cfg->ws_x[1]);
139  ARMARX_CHECK_LESS(cfg->ws_x[0], 1000);
140  ARMARX_CHECK_LESS(-200, cfg->ws_x[1]);
141 
142  ARMARX_CHECK_LESS(cfg->ws_y[0], cfg->ws_y[1]);
143  ARMARX_CHECK_LESS(cfg->ws_y[0], 1200);
144  ARMARX_CHECK_LESS(0, cfg->ws_y[1]);
145 
146  ARMARX_CHECK_LESS(cfg->ws_z[0], cfg->ws_z[1]);
147  ARMARX_CHECK_LESS(cfg->ws_z[0], 1800);
148  ARMARX_CHECK_LESS(300, cfg->ws_z[1]);
149  }
150 
151  adaptK = kpos;
152  lastDiff = 0;
153  changeTimer = 0;
154 
155 
156  isManipulability = cfg->isManipulability;
157 
158 
159  ARMARX_CHECK_EQUAL(cfg->maniWeight.size(), rns->getNodeNames().size());
160  Eigen::VectorXd maniWeightVec;
161  maniWeightVec.setOnes(rns->getNodeNames().size());
162  for (size_t i = 0; i < cfg->maniWeight.size(); ++i)
163  {
164  maniWeightVec(i) = cfg->maniWeight[i];
165  }
166 
167  Eigen::MatrixXd maniWeightMat = maniWeightVec.asDiagonal();
168  VirtualRobot::SingleRobotNodeSetManipulabilityPtr manipulability(
169  new VirtualRobot::SingleRobotNodeSetManipulability(
170  rns,
171  rns->getTCP(),
173  VirtualRobot::AbstractManipulability::Type::Velocity,
174  rns->getRobot()->getRootNode(),
175  maniWeightMat));
176  manipulabilityTracker.reset(
177  new VirtualRobot::SingleChainManipulabilityTracking(manipulability));
178 
179  ARMARX_CHECK_EQUAL(cfg->positionManipulability.size(), 9);
180  targetManipulability.setZero(3, 3);
181  targetManipulability << cfg->positionManipulability[0], cfg->positionManipulability[1],
182  cfg->positionManipulability[2], cfg->positionManipulability[3],
183  cfg->positionManipulability[4], cfg->positionManipulability[5],
184  cfg->positionManipulability[6], cfg->positionManipulability[7],
185  cfg->positionManipulability[8];
186 
187 
188  Eigen::VectorXd kmaniVec;
189  kmaniVec.setZero(cfg->kmani.size());
190  for (size_t i = 0; i < cfg->kmani.size(); ++i)
191  {
192  kmaniVec[i] = cfg->kmani[i];
193  }
194 
195  kmani = kmaniVec.asDiagonal();
196  }
197 
198  void
200  {
201  ARMARX_INFO << "init ...";
202 
203 
204  RTToControllerData initSensorData;
205  initSensorData.deltaT = 0;
206  initSensorData.currentTime = 0;
207  initSensorData.currentPose = tcp->getPoseInRootFrame();
208  initSensorData.currentTwist.setZero();
209  initSensorData.isPhaseStop = false;
210  rt2CtrlData.reinitAllBuffers(initSensorData);
211 
212  RTToUserData initInterfaceData;
213  initInterfaceData.currentTcpPose = tcp->getPoseInRootFrame();
214  initInterfaceData.waitTimeForCalibration = 0;
215  rt2UserData.reinitAllBuffers(initInterfaceData);
216 
217 
218  ARMARX_IMPORTANT << "read force sensor ...";
219 
220  forceOffset = forceSensor->force;
221 
222  ARMARX_IMPORTANT << "force offset: " << forceOffset;
223 
224  started = false;
225 
226  runTask("NJointPeriodicTSDMPCompliantController",
227  [&]
228  {
229  CycleUtil c(1);
230  getObjectScheduler()->waitForObjectStateMinimum(eManagedIceObjectStarted);
231  while (getState() == eManagedIceObjectStarted)
232  {
233  if (isControllerActive())
234  {
235  controllerRun();
236  }
237  c.waitForCycleDuration();
238  }
239  });
240 
241  ARMARX_IMPORTANT << "started controller ";
242  }
243 
244  std::string
246  {
247  return "NJointPeriodicTSDMPCompliantController";
248  }
249 
250  void
252  {
253  if (!started)
254  {
255  return;
256  }
257 
258  if (!dmpCtrl)
259  {
260  return;
261  }
262 
263  Eigen::VectorXf targetVels(6);
264  bool isPhaseStop = rt2CtrlData.getUpToDateReadBuffer().isPhaseStop;
265  if (isPhaseStop)
266  {
267  targetVels.setZero();
268  }
269  else
270  {
271 
272  double deltaT = rt2CtrlData.getUpToDateReadBuffer().deltaT;
273  Eigen::Matrix4f currentPose = rt2CtrlData.getUpToDateReadBuffer().currentPose;
274  Eigen::VectorXf currentTwist = rt2CtrlData.getUpToDateReadBuffer().currentTwist;
275 
276  LockGuardType guard{controllerMutex};
277  dmpCtrl->flow(deltaT, currentPose, currentTwist);
278 
279  targetVels = dmpCtrl->getTargetVelocity();
280 
281  debugOutputData.getWriteBuffer().latestTargetVelocities["x_vel"] = targetVels(0);
282  debugOutputData.getWriteBuffer().latestTargetVelocities["y_vel"] = targetVels(1);
283  debugOutputData.getWriteBuffer().latestTargetVelocities["z_vel"] = targetVels(2);
284  debugOutputData.getWriteBuffer().latestTargetVelocities["roll_vel"] = targetVels(3);
285  debugOutputData.getWriteBuffer().latestTargetVelocities["pitch_vel"] = targetVels(4);
286  debugOutputData.getWriteBuffer().latestTargetVelocities["yaw_vel"] = targetVels(5);
287  debugOutputData.getWriteBuffer().currentPose["currentPose_x"] = currentPose(0, 3);
288  debugOutputData.getWriteBuffer().currentPose["currentPose_y"] = currentPose(1, 3);
289  debugOutputData.getWriteBuffer().currentPose["currentPose_z"] = currentPose(2, 3);
291  VirtualRobot::MathTools::eigen4f2quat(currentPose);
292  debugOutputData.getWriteBuffer().currentPose["currentPose_qw"] = currentQ.w;
293  debugOutputData.getWriteBuffer().currentPose["currentPose_qx"] = currentQ.x;
294  debugOutputData.getWriteBuffer().currentPose["currentPose_qy"] = currentQ.y;
295  debugOutputData.getWriteBuffer().currentPose["currentPose_qz"] = currentQ.z;
296  debugOutputData.getWriteBuffer().currentCanVal = dmpCtrl->debugData.canVal;
297  debugOutputData.getWriteBuffer().mpcFactor = dmpCtrl->debugData.mpcFactor;
298  debugOutputData.getWriteBuffer().error = dmpCtrl->debugData.poseError;
299  debugOutputData.getWriteBuffer().posError = dmpCtrl->debugData.posiError;
300  debugOutputData.getWriteBuffer().oriError = dmpCtrl->debugData.oriError;
301  debugOutputData.getWriteBuffer().deltaT = deltaT;
302  debugOutputData.commitWrite();
303  }
304 
305  getWriterControlStruct().targetTSVel = targetVels;
307 
308  dmpRunning = true;
309  }
310 
311  void
313  const IceUtil::Time& timeSinceLastIteration)
314  {
315  double deltaT = timeSinceLastIteration.toSecondsDouble();
316 
317  Eigen::Matrix4f currentPose = tcp->getPoseInRootFrame();
318  rt2UserData.getWriteBuffer().currentTcpPose = currentPose;
319  rt2UserData.getWriteBuffer().waitTimeForCalibration += deltaT;
320  rt2UserData.commitWrite();
321 
322 
323  Eigen::MatrixXf jacobi =
324  ik->getJacobianMatrix(tcp, VirtualRobot::IKSolver::CartesianSelection::All);
325 
326  Eigen::VectorXf qpos(positionSensors.size());
327  Eigen::VectorXf qvel(velocitySensors.size());
328  for (size_t i = 0; i < positionSensors.size(); ++i)
329  {
330  qpos(i) = positionSensors[i]->position;
331  qvel(i) = velocitySensors[i]->velocity;
332  }
333 
334  qvel_filtered = (1 - cfg->velFilter) * qvel_filtered + cfg->velFilter * qvel;
335  Eigen::VectorXf currentTwist = jacobi * qvel_filtered;
336 
337  Eigen::VectorXf targetVel(6);
338  targetVel.setZero();
339  if (firstRun || !dmpRunning)
340  {
341  lastPosition = currentPose.block<2, 1>(0, 3);
342  targetPose = currentPose;
343  firstRun = false;
344  filteredForce.setZero();
345 
346  origHandOri = currentPose.block<3, 3>(0, 0);
347  toolTransform = origHandOri.transpose();
348  // force calibration
349  if (!dmpRunning)
350  {
351  forceOffset =
352  (1 - cfg->forceFilter) * forceOffset + cfg->forceFilter * forceSensor->force;
353  }
354 
355  targetVel.setZero();
356  }
357  else
358  {
359  /// Note: communicate with DMP controller
361  targetVel = rtGetControlStruct().targetTSVel;
362  targetVel(2) = 0;
363 
364  /// Note: force detection and filtering
365  filteredForce = (1 - cfg->forceFilter) * filteredForce +
366  cfg->forceFilter * (forceSensor->force - forceOffset);
367 
368  for (size_t i = 0; i < 3; ++i)
369  {
370  if (fabs(filteredForce(i)) > cfg->forceDeadZone)
371  {
372  filteredForce(i) -=
373  (filteredForce(i) / fabs(filteredForce(i))) * cfg->forceDeadZone;
374  }
375  else
376  {
377  filteredForce(i) = 0;
378  }
379  }
380  Eigen::Matrix4f forceFrameInRoot =
381  rtGetRobot()->getSensor(cfg->forceSensorName)->getRobotNode()->getPoseInRootFrame();
382 
383  filteredForceInRoot = forceFrameInRoot.block<3, 3>(0, 0) * filteredForce;
384  /// Note: obtain user configured target force.
385  float targetForce = user2rtData.getUpToDateReadBuffer().targetForce;
386 
387  /// Note: P-controller for regulating the desired force in z-direction, generating a acceleration
388  // Eigen::Matrix3f currentHandOri = currentPose.block<3, 3>(0, 0);
389  // Eigen::Matrix3f currentToolOri = toolTransform * currentHandOri;
390  float desiredZVel = kpf * (targetForce - filteredForceInRoot(2));
391  targetVel(2) -= desiredZVel;
392  // targetVel.block<3, 1>(0, 0) = currentToolOri * targetVel.block<3, 1>(0, 0);
393 
394 
395  // Eigen::Vector3f currentToolDir = currentToolOri * oriToolDir;
396  /// Note: reset orientational velocity target to zero
397  for (int i = 3; i < 6; ++i)
398  {
399  targetVel(i) = 0;
400  }
401 
402  // rotation changes
403 
404  // if (filteredForceInRoot.norm() > fabs(cfg->minimumReactForce))
405  // {
406  // Eigen::Vector3f desiredToolDir = filteredForceInRoot / filteredForceInRoot.norm();
407  // currentToolDir = currentToolDir / currentToolDir.norm();
408  // Eigen::Vector3f axis = currentToolDir.cross(desiredToolDir);
409  // float angle = acosf(currentToolDir.dot(desiredToolDir));
410 
411  // if (fabs(angle) < M_PI / 2)
412  // {
413  // Eigen::AngleAxisf desiredToolRot(angle, axis);
414  // Eigen::Matrix3f desiredRotMat = desiredToolRot * Eigen::Matrix3f::Identity();
415 
416  // targetPose.block<3, 3>(0, 0) = desiredRotMat * currentHandOri;
417 
418  // Eigen::Vector3f desiredRPY = VirtualRobot::MathTools::eigen3f2rpy(desiredRotMat);
419  // Eigen::Vector3f checkedToolDir = desiredRotMat * currentToolDir;
420  // ARMARX_IMPORTANT << "axis: " << axis;
421  // ARMARX_IMPORTANT << "angle: " << angle * 180 / 3.1415;
422  // ARMARX_IMPORTANT << "desiredRotMat: " << desiredRotMat;
423 
424  // ARMARX_IMPORTANT << "desiredToolDir: " << desiredToolDir;
425  // ARMARX_IMPORTANT << "currentToolDir: " << currentToolDir;
426  // ARMARX_IMPORTANT << "checkedToolDir: " << checkedToolDir;
427  // }
428 
429  // }
430 
431 
432  // integrate for targetPose
433  }
434 
435  bool isPhaseStop = false;
436 
437  float diff = (targetPose.block<2, 1>(0, 3) - currentPose.block<2, 1>(0, 3)).norm();
438  if (diff > cfg->phaseDist0)
439  {
440  isPhaseStop = true;
441  }
442 
443  float dTf = (float)deltaT;
444 
445 
446  /// Note: based on the detected force, adapting the impedance parameter (no adaption for z-direction and orientation)
447  if (filteredForceInRoot.block<2, 1>(0, 0).norm() > cfg->dragForceDeadZone)
448  {
449  Eigen::Vector2f dragForce = filteredForceInRoot.block<2, 1>(0, 0) -
450  cfg->dragForceDeadZone *
451  filteredForceInRoot.block<2, 1>(0, 0) /
452  filteredForceInRoot.block<2, 1>(0, 0).norm();
453  adaptK(0) = fmax(adaptK(0) - dTf * cfg->adaptForceCoeff * dragForce.norm(), 0);
454  adaptK(1) = fmax(adaptK(1) - dTf * cfg->adaptForceCoeff * dragForce.norm(), 0);
455  lastDiff = diff;
456  }
457  else
458  {
459  adaptK(0) = fmin(adaptK(0) + fabs(dTf * cfg->adaptCoeff), kpos(0));
460  adaptK(1) = fmin(adaptK(1) + fabs(dTf * cfg->adaptCoeff), kpos(1));
461  }
462  adaptK(2) = kpos(2);
463 
464  // adaptive control with distance
465 
466 
467  /// Note: integration to get the target pose
468  targetPose.block<3, 1>(0, 3) =
469  targetPose.block<3, 1>(0, 3) + dTf * targetVel.block<3, 1>(0, 0);
470 
471  /// Note: in the phase stop mode, aggregate timer until it reach the threshold as recognizing the intention
472  /// to wipe a different place, by setting target pose to current pose.
473  if (isPhaseStop)
474  {
475  Eigen::Vector2f currentXY = currentPose.block<2, 1>(0, 3);
476  if ((lastPosition - currentXY).norm() < cfg->changePositionTolerance)
477  {
478  changeTimer += deltaT;
479  }
480  else
481  {
482  lastPosition = currentPose.block<2, 1>(0, 3);
483  changeTimer = 0;
484  }
485 
486  if (changeTimer > cfg->changeTimerThreshold)
487  {
488  targetPose(0, 3) = currentPose(0, 3);
489  targetPose(1, 3) = currentPose(1, 3);
490  isPhaseStop = false;
491  changeTimer = 0;
492  }
493  }
494  else
495  {
496  changeTimer = 0;
497  }
498 
499  /// Note: ensure target pose lies in the workspace
500  targetPose(0, 3) = targetPose(0, 3) > cfg->ws_x[0] ? targetPose(0, 3) : cfg->ws_x[0];
501  targetPose(0, 3) = targetPose(0, 3) < cfg->ws_x[1] ? targetPose(0, 3) : cfg->ws_x[1];
502 
503  targetPose(1, 3) = targetPose(1, 3) > cfg->ws_y[0] ? targetPose(1, 3) : cfg->ws_y[0];
504  targetPose(1, 3) = targetPose(1, 3) < cfg->ws_y[1] ? targetPose(1, 3) : cfg->ws_y[1];
505 
506  targetPose(2, 3) = targetPose(2, 3) > cfg->ws_z[0] ? targetPose(2, 3) : cfg->ws_z[0];
507  targetPose(2, 3) = targetPose(2, 3) < cfg->ws_z[1] ? targetPose(2, 3) : cfg->ws_z[1];
508 
509 
510  debugRT.getWriteBuffer().targetPose = targetPose;
511  debugRT.getWriteBuffer().currentPose = currentPose;
512  debugRT.getWriteBuffer().filteredForce = filteredForceInRoot;
513  debugRT.getWriteBuffer().targetVel = targetVel;
514  debugRT.getWriteBuffer().adaptK = adaptK;
515  debugRT.getWriteBuffer().isPhaseStop = isPhaseStop;
516  debugRT.getWriteBuffer().currentTwist = currentTwist;
517 
518  rt2CtrlData.getWriteBuffer().currentPose = currentPose;
519  rt2CtrlData.getWriteBuffer().currentTwist = currentTwist;
520  rt2CtrlData.getWriteBuffer().deltaT = deltaT;
521  rt2CtrlData.getWriteBuffer().currentTime += deltaT;
522  rt2CtrlData.getWriteBuffer().isPhaseStop = isPhaseStop;
523  rt2CtrlData.commitWrite();
524 
525  // Eigen::Matrix3f rotVel = VirtualRobot::MathTools::rpy2eigen3f(targetVel(3) * dTf, targetVel(4) * dTf, targetVel(5) * dTf);
526  // targetPose.block<3, 3>(0, 0) = rotVel * targetPose.block<3, 3>(0, 0);
527 
528  /// Note: inverse dynamic controller
529  for (size_t ki = 0; ki < 3; ++ki)
530  {
531  jacobi.row(ki) = 0.001 * jacobi.row(ki); // convert mm to m
532  }
533 
534  Eigen::Vector6f jointControlWrench;
535  {
536  Eigen::Vector3f targetTCPLinearVelocity;
537  targetTCPLinearVelocity << 0.001 * targetVel(0), 0.001 * targetVel(1),
538  0.001 * targetVel(2);
539  Eigen::Vector3f currentTCPLinearVelocity;
540  currentTCPLinearVelocity << 0.001 * currentTwist(0), 0.001 * currentTwist(1),
541  0.001 * currentTwist(2);
542  Eigen::Vector3f currentTCPPosition = currentPose.block<3, 1>(0, 3);
543  Eigen::Vector3f desiredPosition = targetPose.block<3, 1>(0, 3);
544 
545  Eigen::Vector3f linearVel = adaptK.cwiseProduct(desiredPosition - currentTCPPosition);
546 
547  // if (isPhaseStop)
548  // {
549  // linearVel = ((float)cfg->phaseKpPos) * (desiredPosition - currentTCPPosition);
550  // for (size_t i = 0; i < 3; ++i)
551  // {
552  // linearVel(i) = fmin(cfg->maxLinearVel, linearVel(i));
553  // }
554  // }
555  // else
556  // {
557  // linearVel = kpos.cwiseProduct(desiredPosition - currentTCPPosition);
558  // }
559  Eigen::Vector3f tcpDesiredForce =
560  0.001 * linearVel + dpos.cwiseProduct(-currentTCPLinearVelocity);
561 
562  Eigen::Vector3f currentTCPAngularVelocity;
563  currentTCPAngularVelocity << currentTwist(3), currentTwist(4), currentTwist(5);
564  Eigen::Matrix3f currentRotMat = currentPose.block<3, 3>(0, 0);
565  Eigen::Matrix3f diffMat = targetPose.block<3, 3>(0, 0) * currentRotMat.inverse();
566  Eigen::Vector3f rpy = VirtualRobot::MathTools::eigen3f2rpy(diffMat);
567  Eigen::Vector3f tcpDesiredTorque =
568  kori.cwiseProduct(rpy) + dori.cwiseProduct(-currentTCPAngularVelocity);
569  jointControlWrench << tcpDesiredForce, tcpDesiredTorque;
570  }
571 
572 
573  Eigen::MatrixXf I = Eigen::MatrixXf::Identity(targets.size(), targets.size());
574  Eigen::VectorXf nullspaceTorque;
575 
576  float manidist = 0;
577  if (isManipulability)
578  {
579  nullspaceTorque =
580  manipulabilityTracker->calculateVelocity(targetManipulability, kmani, true);
581  manidist = manipulabilityTracker->computeDistance(targetManipulability);
582  }
583  else
584  {
585  nullspaceTorque = knull * (nullSpaceJointsVec - qpos) - dnull * qvel;
586  }
587 
588  Eigen::MatrixXf jtpinv = ik->computePseudoInverseJacobianMatrix(jacobi.transpose(), 2.0);
589  Eigen::VectorXf jointDesiredTorques = jacobi.transpose() * jointControlWrench +
590  (I - jacobi.transpose() * jtpinv) * nullspaceTorque;
591 
592  // torque filter (maybe)
593  for (size_t i = 0; i < targets.size(); ++i)
594  {
595  targets.at(i)->torque = jointDesiredTorques(i);
596 
597  if (!targets.at(i)->isValid())
598  {
599  targets.at(i)->torque = 0.0f;
600  }
601  else
602  {
603  if (fabs(targets.at(i)->torque) > fabs(cfg->maxJointTorque))
604  {
605  targets.at(i)->torque = fabs(cfg->maxJointTorque) *
606  (targets.at(i)->torque / fabs(targets.at(i)->torque));
607  }
608  }
609  }
610 
611  debugRT.getWriteBuffer().manidist = manidist;
612 
613  debugRT.commitWrite();
614  }
615 
616  void
618  const Ice::Current&)
619  {
620  ARMARX_INFO << "Learning DMP ... ";
621 
622  LockGuardType guard{controllerMutex};
623  dmpCtrl->learnDMPFromFiles(fileNames);
624  }
625 
626  void
628  const TrajectoryBasePtr& trajectory,
629  const Ice::Current&)
630  {
631  ARMARX_INFO << "Learning DMP ... ";
632  ARMARX_CHECK_EXPRESSION(trajectory);
633  TrajectoryPtr dmpTraj = TrajectoryPtr::dynamicCast(trajectory);
634  ARMARX_CHECK_EXPRESSION(dmpTraj);
635 
636  LockGuardType guard{controllerMutex};
637  dmpCtrl->learnDMPFromTrajectory(dmpTraj);
638  }
639 
640  void
642  {
643  LockGuardType guard{controllerMutex};
644  dmpCtrl->setSpeed(times);
645  }
646 
647  void
649  const Ice::Current& ice)
650  {
651  LockGuardType guard{controllerMutex};
652  dmpCtrl->setGoalPoseVec(goals);
653  }
654 
655  void
657  {
658  LockGuardType guard{controllerMutex};
659  dmpCtrl->setAmplitude(amp);
660  }
661 
662  void
664  const Ice::Current&)
665  {
667  user2rtData.getWriteBuffer().targetForce = targetForce;
668  user2rtData.commitWrite();
669  }
670 
671  void
673  Ice::Double tau,
674  const Ice::Current&)
675  {
676  firstRun = true;
677  while (firstRun || rt2UserData.getUpToDateReadBuffer().waitTimeForCalibration <
678  cfg->waitTimeForCalibration)
679  {
680  usleep(100);
681  }
682 
683 
684  Eigen::Matrix4f pose = rt2UserData.getUpToDateReadBuffer().currentTcpPose;
685 
686  LockGuardType guard{controllerMutex};
687  dmpCtrl->prepareExecution(dmpCtrl->eigen4f2vec(pose), goals);
688  dmpCtrl->setSpeed(tau);
689 
690  ARMARX_IMPORTANT << "run DMP";
691  started = true;
692  dmpRunning = false;
693  }
694 
695  void
698  const DebugObserverInterfacePrx& debugObs)
699  {
700  std::string datafieldName;
701  std::string debugName = "Periodic";
702  StringVariantBaseMap datafields;
703 
704  Eigen::Matrix4f targetPoseDebug = debugRT.getUpToDateReadBuffer().targetPose;
705  datafields["target_x"] = new Variant(targetPoseDebug(0, 3));
706  datafields["target_y"] = new Variant(targetPoseDebug(1, 3));
707  datafields["target_z"] = new Variant(targetPoseDebug(2, 3));
708 
709  Eigen::Matrix4f currentPoseDebug = debugRT.getUpToDateReadBuffer().currentPose;
710  datafields["current_x"] = new Variant(currentPoseDebug(0, 3));
711  datafields["current_y"] = new Variant(currentPoseDebug(1, 3));
712  datafields["current_z"] = new Variant(currentPoseDebug(2, 3));
713 
714  Eigen::Vector3f filteredForce = debugRT.getUpToDateReadBuffer().filteredForce;
715  datafields["filteredforce_x"] = new Variant(filteredForce(0));
716  datafields["filteredforce_y"] = new Variant(filteredForce(1));
717  datafields["filteredforce_z"] = new Variant(filteredForce(2));
718 
719 
720  Eigen::Vector3f reactForce = debugRT.getUpToDateReadBuffer().reactForce;
721  datafields["reactForce_x"] = new Variant(reactForce(0));
722  datafields["reactForce_y"] = new Variant(reactForce(1));
723  datafields["reactForce_z"] = new Variant(reactForce(2));
724 
725  Eigen::VectorXf targetVel = debugRT.getUpToDateReadBuffer().targetVel;
726  datafields["targetVel_x"] = new Variant(targetVel(0));
727  datafields["targetVel_y"] = new Variant(targetVel(1));
728  datafields["targetVel_z"] = new Variant(targetVel(2));
729 
730  Eigen::VectorXf currentVel = debugRT.getUpToDateReadBuffer().currentTwist;
731  datafields["currentVel_x"] = new Variant(currentVel(0));
732  datafields["currentVel_y"] = new Variant(currentVel(1));
733  datafields["currentVel_z"] = new Variant(currentVel(2));
734 
735  Eigen::Vector3f adaptK = debugRT.getUpToDateReadBuffer().adaptK;
736  datafields["adaptK_x"] = new Variant(adaptK(0));
737  datafields["adaptK_y"] = new Variant(adaptK(1));
738 
739  datafields["canVal"] = new Variant(debugOutputData.getUpToDateReadBuffer().currentCanVal);
740  datafields["deltaT"] = new Variant(debugOutputData.getUpToDateReadBuffer().deltaT);
741 
742  datafields["PhaseStop"] = new Variant(debugRT.getUpToDateReadBuffer().isPhaseStop);
743  datafields["manidist"] = new Variant(debugRT.getUpToDateReadBuffer().manidist);
744 
745 
746  // datafields["targetVel_rx"] = new Variant(targetVel(3));
747  // datafields["targetVel_ry"] = new Variant(targetVel(4));
748  // datafields["targetVel_rz"] = new Variant(targetVel(5));
749 
750  // auto values = debugOutputData.getUpToDateReadBuffer().latestTargetVelocities;
751  // for (auto& pair : values)
752  // {
753  // datafieldName = pair.first + "_" + debugName;
754  // datafields[datafieldName] = new Variant(pair.second);
755  // }
756 
757  // auto currentPose = debugOutputData.getUpToDateReadBuffer().currentPose;
758  // for (auto& pair : currentPose)
759  // {
760  // datafieldName = pair.first + "_" + debugName;
761  // datafields[datafieldName] = new Variant(pair.second);
762  // }
763 
764  // datafieldName = "canVal_" + debugName;
765  // datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().currentCanVal);
766  // datafieldName = "mpcFactor_" + debugName;
767  // datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().mpcFactor);
768  // datafieldName = "error_" + debugName;
769  // datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().error);
770  // datafieldName = "posError_" + debugName;
771  // datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().posError);
772  // datafieldName = "oriError_" + debugName;
773  // datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().oriError);
774  // datafieldName = "deltaT_" + debugName;
775  // datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().deltaT);
776 
777  datafieldName = "PeriodicDMP";
778  debugObs->setDebugChannel(datafieldName, datafields);
779  }
780 
781  void
783  {
784  ARMARX_INFO << "stopped ...";
785  }
786 
787 
788 } // namespace armarx::control::deprecated_njoint_mp_controller::task_space
armarx::NJointControllerWithTripleBuffer< NJointPeriodicTSDMPCompliantControllerControlData >::reinitTripleBuffer
void reinitTripleBuffer(const NJointPeriodicTSDMPCompliantControllerControlData &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:223
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::Kori
float Kori
Definition: TaskSpaceVMP.h:54
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::Dpos
float Dpos
Definition: TaskSpaceVMP.h:53
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPCompliantController::learnDMPFromTrajectory
void learnDMPFromTrajectory(const TrajectoryBasePtr &trajectory, const Ice::Current &)
Definition: NJointPeriodicTSDMPCompliantController.cpp:627
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPCompliantController::getClassName
std::string getClassName(const Ice::Current &) const
Definition: NJointPeriodicTSDMPCompliantController.cpp:245
armarx::TripleBuffer::getWriteBuffer
T & getWriteBuffer()
Definition: TripleBuffer.h:92
armarx::NJointControllerBase::useSynchronizedRtRobot
const VirtualRobot::RobotPtr & useSynchronizedRtRobot(bool updateCollisionModel=false)
Requests a VirtualRobot for use in rtRun *.
Definition: NJointController.cpp:293
armarx::NJointControllerWithTripleBuffer< NJointPeriodicTSDMPCompliantControllerControlData >::rtGetControlStruct
const NJointPeriodicTSDMPCompliantControllerControlData & 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
ARMARX_IMPORTANT
#define ARMARX_IMPORTANT
Definition: Logging.h:190
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPCompliantControllerControlData::targetTSVel
Eigen::VectorXf targetTSVel
Definition: NJointPeriodicTSDMPCompliantController.h:40
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
RobotUnit.h
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::NJointPeriodicTSDMPCompliantController::NJointPeriodicTSDMPCompliantController
NJointPeriodicTSDMPCompliantController(const RobotUnitPtr &, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
Definition: NJointPeriodicTSDMPCompliantController.cpp:28
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:20
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPCompliantController::onInitNJointController
void onInitNJointController()
Definition: NJointPeriodicTSDMPCompliantController.cpp:199
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
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::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPCompliantControllerControlData
Definition: NJointPeriodicTSDMPCompliantController.h:37
armarx::control::deprecated_njoint_mp_controller::tsvmp::TaskSpaceDMPControllerConfig
Definition: TaskSpaceVMP.h:59
armarx::control::deprecated_njoint_mp_controller::tsvmp::TaskSpaceDMPControllerConfig::phaseStopParas
PhaseStopParams phaseStopParas
Definition: TaskSpaceVMP.h:67
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPCompliantController::onDisconnectNJointController
void onDisconnectNJointController()
Definition: NJointPeriodicTSDMPCompliantController.cpp:782
armarx::NJointControllerWithTripleBuffer< NJointPeriodicTSDMPCompliantControllerControlData >::getWriterControlStruct
NJointPeriodicTSDMPCompliantControllerControlData & getWriterControlStruct()
Definition: NJointControllerWithTripleBuffer.h:54
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::goDist
float goDist
Definition: TaskSpaceVMP.h:48
armarx::NJointControllerWithTripleBuffer< NJointPeriodicTSDMPCompliantControllerControlData >::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::tsvmp::TaskSpaceDMPControllerConfig::motionTimeDuration
float motionTimeDuration
Definition: TaskSpaceVMP.h:66
IceInternal::Handle< Trajectory >
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
armarx::control::deprecated_njoint_mp_controller::task_space::registrationControllerNJointPeriodicTSDMPCompliantController
NJointControllerRegistration< NJointPeriodicTSDMPCompliantController > registrationControllerNJointPeriodicTSDMPCompliantController("NJointPeriodicTSDMPCompliantController")
armarx::detail::ControlThreadOutputBufferEntry
Definition: ControlThreadOutputBuffer.h:182
armarx::VariantType::Double
const VariantTypeId Double
Definition: Variant.h:920
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::Dori
float Dori
Definition: TaskSpaceVMP.h:55
NJointPeriodicTSDMPCompliantController.h
GfxTL::Identity
void Identity(MatrixXX< N, N, T > *a)
Definition: MatrixXX.h:570
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPCompliantController::controllerRun
void controllerRun()
Definition: NJointPeriodicTSDMPCompliantController.cpp:251
armarx::NJointControllerBase::isControllerActive
bool isControllerActive(const Ice::Current &=Ice::emptyCurrent) const final override
Definition: NJointControllerBase.h:778
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::NJointControllerWithTripleBuffer< NJointPeriodicTSDMPCompliantControllerControlData >::rtUpdateControlStruct
bool rtUpdateControlStruct()
Definition: NJointControllerWithTripleBuffer.h:38
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPCompliantController::learnDMPFromFiles
void learnDMPFromFiles(const Ice::StringSeq &fileNames, const Ice::Current &)
Definition: NJointPeriodicTSDMPCompliantController.cpp:617
armarx::NJointControllerWithTripleBuffer< NJointPeriodicTSDMPCompliantControllerControlData >::writeControlStruct
void writeControlStruct()
Definition: NJointControllerWithTripleBuffer.h:44
ArmarXObjectScheduler.h
ControlTarget1DoFActuator.h
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPCompliantController::setSpeed
void setSpeed(Ice::Double times, const Ice::Current &)
Definition: NJointPeriodicTSDMPCompliantController.cpp:641
armarx::NJointControllerWithTripleBuffer< NJointPeriodicTSDMPCompliantControllerControlData >::controlDataMutex
MutexType controlDataMutex
Definition: NJointControllerWithTripleBuffer.h:73
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::NJointPeriodicTSDMPCompliantController::runDMP
void runDMP(const Ice::DoubleSeq &goals, Ice::Double tau, const Ice::Current &)
Definition: NJointPeriodicTSDMPCompliantController.cpp:672
CartesianVelocityController.h
NJointController.h
Trajectory.h
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
float
#define float
Definition: 16_Level.h:22
ARMARX_INFO
#define ARMARX_INFO
Definition: Logging.h:181
IceUtil::Handle< class RobotUnit >
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::tsvmp::TaskSpaceDMPControllerConfig::DMPMode
std::string DMPMode
Definition: TaskSpaceVMP.h:62
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPCompliantController::setAmplitude
void setAmplitude(Ice::Double amp, const Ice::Current &)
Definition: NJointPeriodicTSDMPCompliantController.cpp:656
Eigen::Matrix< float, 6, 1 >
armarx::control::deprecated_njoint_mp_controller::tsvmp::PhaseStopParams::mm2radi
float mm2radi
Definition: TaskSpaceVMP.h:56
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPCompliantController::onPublish
virtual void onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &)
Definition: NJointPeriodicTSDMPCompliantController.cpp:696
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPCompliantController::setTargetForceInRootFrame
void setTargetForceInRootFrame(Ice::Float force, const Ice::Current &)
Definition: NJointPeriodicTSDMPCompliantController.cpp:663
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_CHECK_EQUAL
#define ARMARX_CHECK_EQUAL(lhs, rhs)
This macro evaluates whether lhs is equal (==) rhs and if it turns out to be false it will throw an E...
Definition: ExpressionException.h:130
armarx::SensorValueForceTorque
Definition: SensorValueForceTorque.h:32
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::ManagedIceObject::getObjectScheduler
ArmarXObjectSchedulerPtr getObjectScheduler() const
Definition: ManagedIceObject.cpp:776
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::NJointPeriodicTSDMPCompliantController::setGoals
void setGoals(const Ice::DoubleSeq &goals, const Ice::Current &)
Definition: NJointPeriodicTSDMPCompliantController.cpp:648
armarx::control::deprecated_njoint_mp_controller::task_space::NJointPeriodicTSDMPCompliantController::rtRun
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration)
TODO make protected and use attorneys.
Definition: NJointPeriodicTSDMPCompliantController.cpp:312
norm
double norm(const Point &a)
Definition: point.hpp:102