DeprecatedNJointPeriodicTSDMPCompliantController.cpp
Go to the documentation of this file.
2
3#include <VirtualRobot/IK/DifferentialIK.h>
4#include <VirtualRobot/MathTools.h>
5#include <VirtualRobot/Nodes/RobotNode.h>
6#include <VirtualRobot/Robot.h>
7#include <VirtualRobot/RobotNodeSet.h>
8
10
19
21{
24 "DeprecatedNJointPeriodicTSDMPCompliantController");
25
28 const RobotUnitPtr& robUnit,
29 const armarx::NJointControllerConfigPtr& config,
31 {
32 ARMARX_INFO << "creating periodic task-space impedance dmp controller";
33
35 cfg = DeprecatedNJointPeriodicTSDMPCompliantControllerConfigPtr::dynamicCast(config);
36 ARMARX_CHECK_EXPRESSION(!cfg->nodeSetName.empty());
37
38 VirtualRobot::RobotNodeSetPtr rns = rtGetRobot()->getRobotNodeSet(cfg->nodeSetName);
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
44 ControlTargetBase* ct = useControlTarget(jointName, ControlModes::Torque1DoF);
45 const SensorValueBase* sv = useSensorValue(jointName);
46 targets.push_back(ct->asA<ControlTarget1DoFActuatorTorque>());
47
48 const SensorValue1DoFActuatorVelocity* velocitySensor =
49 sv->asA<SensorValue1DoFActuatorVelocity>();
50 const SensorValue1DoFActuatorPosition* positionSensor =
51 sv->asA<SensorValue1DoFActuatorPosition>();
52
53 if (!velocitySensor)
54 {
55 ARMARX_WARNING << "No velocitySensor available for " << jointName;
56 }
57 if (!positionSensor)
58 {
59 ARMARX_WARNING << "No positionSensor available for " << jointName;
60 }
61
62 velocitySensors.push_back(velocitySensor);
63 positionSensors.push_back(positionSensor);
64 };
65
66 tcp = rns->getTCP();
67 ik.reset(new VirtualRobot::DifferentialIK(
68 rns, rns->getRobot()->getRootNode(), VirtualRobot::JacobiProvider::eSVDDamped));
69 ik->setDampedSvdLambda(0.0001);
70 numOfJoints = targets.size();
71 qvel_filtered.setZero(targets.size());
72 torqueLimit = cfg->jointTorqueLimit;
73
74 /// setup force sensor and filters
75 const SensorValueBase* svlf =
76 robUnit->getSensorDevice(cfg->forceSensorName)->getSensorValue();
77 forceSensor = svlf->asA<SensorValueForceTorque>();
78
79 float tcpMass = 0.0f;
80 Eigen::Vector3f tcpCoMInForceSensorFrame;
81 tcpCoMInForceSensorFrame.setZero();
82
83 enableTCPGravityCompensation.store(cfg->enableTCPGravityCompensation);
84 ARMARX_INFO << VAROUT(enableTCPGravityCompensation);
85 if (enableTCPGravityCompensation.load())
86 {
87 tcpMass = cfg->tcpMass;
88 tcpCoMInForceSensorFrame = cfg->tcpCoMInForceSensorFrame;
89 }
90
91 forceOffset.setZero();
92 torqueOffset.setZero();
93 filteredForce.setZero();
94 filteredTorque.setZero();
95 filteredForceInRoot.setZero();
96 filteredTorqueInRoot.setZero();
97
98 /// Setup tool
99 toolFrameInRoot = cfg->toolFrameInRoot;
100 forcePID.reset(new PIDController(
101 cfg->pidForce[0], cfg->pidForce[1], cfg->pidForce[2], cfg->pidForce[3]));
102
103 /// setup DMP
104 tsvmp::TaskSpaceDMPControllerConfig taskSpaceDMPConfig;
105 taskSpaceDMPConfig.motionTimeDuration = cfg->timeDuration;
106 taskSpaceDMPConfig.DMPKernelSize = cfg->kernelSize;
107 taskSpaceDMPConfig.DMPAmplitude = cfg->dmpAmplitude;
108 taskSpaceDMPConfig.DMPMode = "Linear";
109 taskSpaceDMPConfig.DMPStyle = "Periodic";
110 taskSpaceDMPConfig.phaseStopParas.goDist = cfg->phaseDist0;
111 taskSpaceDMPConfig.phaseStopParas.backDist = cfg->phaseDist1;
112 taskSpaceDMPConfig.phaseStopParas.Kpos = cfg->phaseKpPos;
113 taskSpaceDMPConfig.phaseStopParas.Dpos = 0;
114 taskSpaceDMPConfig.phaseStopParas.Kori = cfg->phaseKpOri;
115 taskSpaceDMPConfig.phaseStopParas.Dori = 0;
116 taskSpaceDMPConfig.phaseStopParas.mm2radi = cfg->posToOriRatio;
117 taskSpaceDMPConfig.phaseStopParas.maxValue = cfg->phaseL;
118 taskSpaceDMPConfig.phaseStopParas.slop = cfg->phaseK;
119
120 dmpCtrl.reset(new tsvmp::TaskSpaceDMPController("periodicDMP", taskSpaceDMPConfig, false));
121 kinematic_chain = cfg->nodeSetName;
122
123 // /// - null space
124 // useNullSpaceJointDMP = cfg->useNullSpaceJointDMP;
125 // nullSpaceJointDMPPtr.reset(new DMP::UMIDMP(100));
126 // isNullSpaceJointDMPLearned = false;
127 // ARMARX_CHECK_EQUAL(cfg->targetNullSpaceJointValues.size(), targets.size());
128
129 /// initialize control parameters and buffers
130 /// - control parameter
131 ARMARX_CHECK_EQUAL(cfg->Knull.size(), targets.size());
132 ARMARX_CHECK_EQUAL(cfg->Dnull.size(), targets.size());
133 CtrlParams initParams = {cfg->kpImpedance,
134 cfg->kdImpedance,
135 cfg->Knull,
136 cfg->Dnull,
137 cfg->pidForce,
138 tcpMass,
139 tcpCoMInForceSensorFrame};
140 ctrlParams.reinitAllBuffers(initParams);
141
142
143 ARMARX_CHECK_EQUAL(cfg->ws_x.size(), 2);
144 ARMARX_CHECK_EQUAL(cfg->ws_y.size(), 2);
145 ARMARX_CHECK_EQUAL(cfg->ws_z.size(), 2);
146
147 // only for ARMAR-6 (safe-guard)
148 if (!cfg->ignoreWSLimitChecks)
149 {
150 ARMARX_CHECK_LESS(cfg->ws_x[0], cfg->ws_x[1]);
151 ARMARX_CHECK_LESS(cfg->ws_x[0], 1000);
152 ARMARX_CHECK_LESS(-200, cfg->ws_x[1]);
153
154 ARMARX_CHECK_LESS(cfg->ws_y[0], cfg->ws_y[1]);
155 ARMARX_CHECK_LESS(cfg->ws_y[0], 1200);
156 ARMARX_CHECK_LESS(0, cfg->ws_y[1]);
157
158 ARMARX_CHECK_LESS(cfg->ws_z[0], cfg->ws_z[1]);
159 ARMARX_CHECK_LESS(cfg->ws_z[0], 1800);
160 ARMARX_CHECK_LESS(300, cfg->ws_z[1]);
161 }
162
163 changeTimer = 0;
164 }
165
166 void
168 {
169 ARMARX_INFO << "init ...";
170 /// initialize control parameters and buffers
171 /// - control target
173 initData.targetTSVel = Eigen::Vector6f::Zero();
174 initData.targetForce = 0.0f;
175 initData.targetNullSpaceJointValues = cfg->targetNullSpaceJointValues;
176 reinitTripleBuffer(initData);
177
178 /// - rt to interface
179 RT2InterfaceData rt2InterfaceData;
180 rt2InterfaceData.currentTcpPose = tcp->getPoseInRootFrame();
181 rt2InterfaceData.waitTimeForCalibration = 0;
182 rt2InterfaceBuffer.reinitAllBuffers(rt2InterfaceData);
183
184 /// - rt to mp
185 RT2MPData rt2MPData;
186 rt2MPData.deltaT = 0;
187 rt2MPData.currentTime = 0;
188 rt2MPData.currentPose = tcp->getPoseInRootFrame();
189 rt2MPData.currentTwist.setZero();
190 rt2MPData.isPhaseStop = false;
191 rt2MPBuffer.reinitAllBuffers(rt2MPData);
192
193
194 // ARMARX_IMPORTANT << "read force sensor ...";
195 // forceOffset = forceSensor->force;
196 // ARMARX_IMPORTANT << "force offset: " << forceOffset;
197 // started = false;
198
199 /// start mp thread
200 runTask("DeprecatedNJointPeriodicTSDMPCompliantController",
201 [&]
202 {
203 CycleUtil c(1);
204 getObjectScheduler()->waitForObjectStateMinimum(eManagedIceObjectStarted);
205 while (getState() == eManagedIceObjectStarted)
206 {
207 if (isControllerActive())
208 {
210 }
211 c.waitForCycleDuration();
212 }
213 });
214
215 ARMARX_IMPORTANT << "started controller ";
216 }
217
218 std::string
220 {
221 return "DeprecatedNJointPeriodicTSDMPCompliantController";
222 }
223
224 void
226 {
227 if (!dmpCtrl || !rt2MPBuffer.updateReadBuffer())
228 {
229 return;
230 }
231
232 Eigen::Vector6f targetVels = Eigen::Vector6f::Zero();
233 bool isPhaseStop = rt2MPBuffer.getUpToDateReadBuffer().isPhaseStop;
234 if (!isPhaseStop && mpRunning.load())
235 {
236 double deltaT = rt2MPBuffer.getUpToDateReadBuffer().deltaT;
237 Eigen::Matrix4f currentPose = rt2MPBuffer.getUpToDateReadBuffer().currentPose;
238 Eigen::VectorXf currentTwist = rt2MPBuffer.getUpToDateReadBuffer().currentTwist;
239
240
241 LockGuardType guardMP{mpMutex};
242 dmpCtrl->flow(deltaT, currentPose, currentTwist);
243
244 targetVels = dmpCtrl->getTargetVelocity();
245 {
246 debugMPBuffer.getWriteBuffer().currentPose["currentPose_x"] = currentPose(0, 3);
247 debugMPBuffer.getWriteBuffer().currentPose["currentPose_y"] = currentPose(1, 3);
248 debugMPBuffer.getWriteBuffer().currentPose["currentPose_z"] = currentPose(2, 3);
249 VirtualRobot::MathTools::Quaternion currentQ =
250 VirtualRobot::MathTools::eigen4f2quat(currentPose);
251 debugMPBuffer.getWriteBuffer().currentPose["currentPose_qw"] = currentQ.w;
252 debugMPBuffer.getWriteBuffer().currentPose["currentPose_qx"] = currentQ.x;
253 debugMPBuffer.getWriteBuffer().currentPose["currentPose_qy"] = currentQ.y;
254 debugMPBuffer.getWriteBuffer().currentPose["currentPose_qz"] = currentQ.z;
255 debugMPBuffer.getWriteBuffer().currentCanVal = dmpCtrl->debugData.canVal;
256 debugMPBuffer.getWriteBuffer().mpcFactor = dmpCtrl->debugData.mpcFactor;
257 debugMPBuffer.getWriteBuffer().error = dmpCtrl->debugData.poseError;
258 debugMPBuffer.getWriteBuffer().posError = dmpCtrl->debugData.posiError;
259 debugMPBuffer.getWriteBuffer().oriError = dmpCtrl->debugData.oriError;
260 debugMPBuffer.getWriteBuffer().deltaT = deltaT;
261 }
262
264 getWriterControlStruct().targetTSVel = targetVels;
265 getWriterControlStruct().targetTSPose = dmpCtrl->getTargetPoseMat();
267 }
268 else
269 {
271 if (isPhaseStop)
272 {
273 getWriterControlStruct().targetTSPose =
274 rt2MPBuffer.getUpToDateReadBuffer().currentPose;
275 }
276 getWriterControlStruct().targetTSVel = targetVels;
278 }
279
280 {
281 debugMPBuffer.getWriteBuffer().latestTargetVelocities["x_vel"] = targetVels(0);
282 debugMPBuffer.getWriteBuffer().latestTargetVelocities["y_vel"] = targetVels(1);
283 debugMPBuffer.getWriteBuffer().latestTargetVelocities["z_vel"] = targetVels(2);
284 debugMPBuffer.getWriteBuffer().latestTargetVelocities["roll_vel"] = targetVels(3);
285 debugMPBuffer.getWriteBuffer().latestTargetVelocities["pitch_vel"] = targetVels(4);
286 debugMPBuffer.getWriteBuffer().latestTargetVelocities["yaw_vel"] = targetVels(5);
287 debugMPBuffer.commitWrite();
288 }
289 }
290
291 void
293 const IceUtil::Time& sensorValuesTimestamp,
294 const IceUtil::Time& timeSinceLastIteration)
295 {
296 /// ---------------------------- get current kinematics ---------------------------------------------
297 Eigen::Matrix4f currentPose = tcp->getPoseInRootFrame();
298 Eigen::MatrixXf jacobi =
299 ik->getJacobianMatrix(tcp, VirtualRobot::IKSolver::CartesianSelection::All);
300
301 Eigen::VectorXf qpos(positionSensors.size());
302 Eigen::VectorXf qvel(velocitySensors.size());
303 for (size_t i = 0; i < positionSensors.size(); ++i)
304 {
305 qpos(i) = positionSensors[i]->position;
306 qvel(i) = velocitySensors[i]->velocity;
307 }
308 qvel_filtered = (1 - cfg->qvelFilter) * qvel_filtered + cfg->qvelFilter * qvel;
309 Eigen::VectorXf currentTwist = jacobi * qvel_filtered;
310 jacobi.block(0, 0, 3, numOfJoints) =
311 0.001 * jacobi.block(0, 0, 3, numOfJoints); // convert mm to m
312
313 double deltaT = timeSinceLastIteration.toSecondsDouble();
314
315 /// ---------------------------- update control parameters ---------------------------------------------
316 Eigen::Vector6f kpImpedance = ctrlParams.getUpToDateReadBuffer().kpImpedance;
317 Eigen::Vector6f kdImpedance = ctrlParams.getUpToDateReadBuffer().kdImpedance;
318 Eigen::VectorXf knull = ctrlParams.getUpToDateReadBuffer().knull;
319 Eigen::VectorXf dnull = ctrlParams.getUpToDateReadBuffer().dnull;
320 Eigen::Vector4f pidForce = ctrlParams.getUpToDateReadBuffer().pidForce;
321 forcePID->Kp = pidForce(0);
322 forcePID->Ki = pidForce(1);
323 forcePID->Kd = pidForce(2);
324 forcePID->maxControlValue = pidForce(3);
325
326 float tcpMass = ctrlParams.getUpToDateReadBuffer().tcpMass;
327 Eigen::Vector3f tcpCoMInFTFrame =
328 ctrlParams.getUpToDateReadBuffer().tcpCoMInForceSensorFrame;
329
330
331 /// ---------------------------- get current force torque value ---------------------------------------------
332 Eigen::Vector3f forceBaseline = Eigen::Vector3f::Zero();
333 Eigen::Vector3f torqueBaseline = Eigen::Vector3f::Zero();
334 Eigen::Vector6f forceTorque;
335 Eigen::Vector6f tcpGravityCompensation;
336 forceTorque.setZero();
337 tcpGravityCompensation.setZero();
338
339 /// ---------------------------- get control targets ---------------------------------------------
340 Eigen::Matrix4f targetPose;
341 Eigen::Vector6f targetVel = Eigen::Vector6f::Zero();
342 Eigen::VectorXf targetNullSpaceJointValues =
343 rtGetControlStruct().targetNullSpaceJointValues;
344 Eigen::Vector3f targetVelInTool = Eigen::Vector3f::Zero();
345 Eigen::Matrix3f currentToolOriInRoot = Eigen::Matrix3f::Identity();
346
347 float targetForce = 0.0f;
348 if (rtFirstRun.load())
349 {
350 rtReady.store(false);
351 rtFirstRun.store(false);
352 timeForCalibration = 0;
353 forceOffset.setZero();
354 torqueOffset.setZero();
355 forcePID->reset();
356
357 Eigen::Matrix4f forceFrameInRoot =
358 rtGetRobot()->getRobotNode(cfg->forceFrameName)->getPoseInRootFrame();
359 forceFrameInTCP.block<3, 3>(0, 0) =
360 currentPose.block<3, 3>(0, 0).transpose() * forceFrameInRoot.block<3, 3>(0, 0);
361 tcpCoMInTCPFrame = forceFrameInTCP.block<3, 3>(0, 0) * tcpCoMInFTFrame;
362
363 targetPose = currentPose;
364 previousTargetPose = currentPose;
365 toolOriInHand =
366 currentPose.block<3, 3>(0, 0).transpose() * toolFrameInRoot.block<3, 3>(0, 0);
367
368 ARMARX_IMPORTANT << "impedance control first run with " << VAROUT(targetPose);
369
371 getWriterControlStruct().targetTSPose = currentPose;
373 }
374 else
375 {
376 if (enableTCPGravityCompensation.load())
377 {
378 tcpGravityCompensation = getTCPGravityCompensation(currentPose, tcpMass);
379 }
380 if (!rtReady.load())
381 {
382 targetPose = previousTargetPose;
383 forceOffset =
384 (1 - cfg->forceFilter) * forceOffset +
385 cfg->forceFilter * (forceSensor->force - tcpGravityCompensation.head<3>());
386 torqueOffset =
387 (1 - cfg->forceFilter) * torqueOffset +
388 cfg->forceFilter * (forceSensor->torque - tcpGravityCompensation.tail<3>());
389 timeForCalibration = timeForCalibration + deltaT;
390 if (timeForCalibration > cfg->waitTimeForCalibration)
391 {
392 /// rt is ready only if the FT sensor is calibrated, and the rt2interface buffer is updated (see above)
393 ARMARX_IMPORTANT << "FT calibration done, RT is ready! \n"
394 << VAROUT(forceOffset) << "\n"
395 << VAROUT(torqueOffset) << "\n"
396 << VAROUT(targetPose);
397 rtReady.store(true);
398 }
399 }
400 else
401 {
402 /// update tool information
403 currentToolOriInRoot = currentPose.block<3, 3>(0, 0) * toolOriInHand;
404 forceTorque =
405 getFilteredForceTorque(forceBaseline, torqueBaseline, tcpGravityCompensation);
406 Eigen::VectorXf ftInTool = forceTorque;
407 ftInTool.head<3>() = currentToolOriInRoot.transpose() * ftInTool.head<3>();
408
409 targetForce = rtGetControlStruct().targetForce;
410 targetVel = rtGetControlStruct().targetTSVel;
411 targetPose = rtGetControlStruct().targetTSPose;
412
413 forcePID->update(deltaT, ftInTool(2), targetForce);
414 float forcePIDVel =
415 -1000.0f * (float)forcePID->getControlValue(); /// convert to mm/s as in ArmarX
416
417 targetVelInTool(2) = forcePIDVel;
418 targetVel.head<3>() += currentToolOriInRoot * targetVelInTool;
419
420
421 targetPose.block<3, 1>(0, 3) =
422 targetPose.block<3, 1>(0, 3) + (float)deltaT * targetVel.block<3, 1>(0, 0);
423 if ((previousTargetPose.block<3, 1>(0, 3) - targetPose.block<3, 1>(0, 3)).norm() >
424 100.0f)
425 {
426 ARMARX_WARNING << "new target \n"
427 << VAROUT(targetPose) << "\nis too far away from\n"
428 << VAROUT(previousTargetPose);
429 targetPose = previousTargetPose;
430 }
431 previousTargetPose = targetPose;
432 }
433 }
434
435 bool isPhaseStop = false;
436 float diff = (targetPose.block<2, 1>(0, 3) - currentPose.block<2, 1>(0, 3)).norm();
437 if (diff > cfg->phaseDist0)
438 {
439 isPhaseStop = true;
440 }
441
442 if (isPhaseStop)
443 {
444 Eigen::Vector2f currentXY = currentPose.block<2, 1>(0, 3);
445 if ((lastPosition - currentXY).norm() < cfg->changePositionTolerance)
446 {
447 changeTimer += deltaT;
448 }
449 else
450 {
451 lastPosition = currentPose.block<2, 1>(0, 3);
452 changeTimer = 0;
453 }
454
455 if (changeTimer > cfg->changeTimerThreshold)
456 {
457 targetPose(0, 3) = currentPose(0, 3);
458 targetPose(1, 3) = currentPose(1, 3);
459 isPhaseStop = false;
460 changeTimer = 0;
461 }
462 }
463 else
464 {
465 changeTimer = 0;
466 }
467
468 targetPose(0, 3) = std::clamp(targetPose(0, 3), cfg->ws_x[0], cfg->ws_x[1]);
469 targetPose(1, 3) = std::clamp(targetPose(1, 3), cfg->ws_y[0], cfg->ws_y[1]);
470 targetPose(2, 3) = std::clamp(targetPose(2, 3), cfg->ws_z[0], cfg->ws_z[1]);
471
472 // write rt buffers
473 {
474 rt2InterfaceBuffer.getWriteBuffer().currentTcpPose = currentPose;
475 rt2InterfaceBuffer.getWriteBuffer().waitTimeForCalibration += deltaT;
476 rt2InterfaceBuffer.commitWrite();
477
478 debugRTBuffer.getWriteBuffer().targetPose = targetPose;
479 debugRTBuffer.getWriteBuffer().currentPose = currentPose;
480 debugRTBuffer.getWriteBuffer().filteredForce = filteredForceInRoot;
481 debugRTBuffer.getWriteBuffer().targetVel = targetVel;
482 debugRTBuffer.getWriteBuffer().isPhaseStop = isPhaseStop;
483 debugRTBuffer.getWriteBuffer().targetVelInTool = targetVelInTool;
484
485 rt2MPBuffer.getWriteBuffer().currentPose = currentPose;
486 rt2MPBuffer.getWriteBuffer().currentTwist = currentTwist;
487 rt2MPBuffer.getWriteBuffer().deltaT = deltaT;
488 rt2MPBuffer.getWriteBuffer().currentTime += deltaT;
489 rt2MPBuffer.getWriteBuffer().isPhaseStop = isPhaseStop;
490 rt2MPBuffer.commitWrite();
491 }
492
493 /// ----------------------------- Impedance control ---------------------------------------------
494 /// calculate pose error between virtual pose and current pose
495 /// !!! This is very important: you have to keep postion and orientation both
496 /// with UI unit (meter, radian) to calculate impedance force.
497 Eigen::Vector6f poseErrorImp;
498 Eigen::Matrix3f diffMat =
499 targetPose.block<3, 3>(0, 0) * currentPose.block<3, 3>(0, 0).transpose();
500 poseErrorImp.head<3>() =
501 0.001 * (targetPose.block<3, 1>(0, 3) - currentPose.block<3, 1>(0, 3));
502 currentTwist.head<3>() *= 0.001;
503 poseErrorImp.tail<3>() = VirtualRobot::MathTools::eigen3f2rpy(diffMat);
504 Eigen::Vector6f forceImpedance =
505 kpImpedance.cwiseProduct(poseErrorImp) - kdImpedance.cwiseProduct(currentTwist);
506
507 /// ----------------------------- Nullspace PD Control --------------------------------------------------
508 Eigen::VectorXf nullspaceTorque =
509 knull.cwiseProduct(targetNullSpaceJointValues - qpos) - dnull.cwiseProduct(qvel);
510
511 /// ----------------------------- Map TS target force to JS --------------------------------------------------
512 Eigen::MatrixXf I = Eigen::MatrixXf::Identity(targets.size(), targets.size());
513 Eigen::MatrixXf jtpinv = ik->computePseudoInverseJacobianMatrix(jacobi.transpose(), 2.0);
514 Eigen::VectorXf jointDesiredTorques = jacobi.transpose() * forceImpedance +
515 (I - jacobi.transpose() * jtpinv) * nullspaceTorque;
516
517 /// ----------------------------- Send torque command to joint device --------------------------------------------------
518 ARMARX_CHECK_EXPRESSION(!targets.empty());
519 for (size_t i = 0; i < targets.size(); ++i)
520 {
521 targets.at(i)->torque = jointDesiredTorques(i);
522 if (!targets.at(i)->isValid() || isnan(targets.at(i)->torque))
523 {
524 targets.at(i)->torque = 0.0f;
525 }
526 else
527 {
528 if (fabs(targets.at(i)->torque) > fabs(torqueLimit))
529 {
530 targets.at(i)->torque =
531 fabs(torqueLimit) * (targets.at(i)->torque / fabs(targets.at(i)->torque));
532 }
533 }
534 }
535
536 debugRTBuffer.commitWrite();
537 }
538
541 Eigen::Matrix4f& currentPose,
542 float tcpMass)
543 {
544 // static compensation
545 Eigen::Vector3f gravity;
546 gravity << 0.0, 0.0, -9.8;
547 Eigen::Vector3f localGravity = currentPose.block<3, 3>(0, 0).transpose() * gravity;
548 Eigen::Vector3f localForceVec = tcpMass * localGravity;
549 Eigen::Vector3f localTorqueVec = tcpCoMInTCPFrame.cross(localForceVec);
550
551 Eigen::Vector6f tcpGravityCompensation;
552 tcpGravityCompensation << localForceVec, localTorqueVec;
553 return tcpGravityCompensation;
554 }
555
558 Eigen::Vector3f& forceBaseline,
559 Eigen::Vector3f& torqueBaseline,
560 Eigen::Vector6f& handCompensatedFT)
561 {
562 filteredForce =
563 (1 - cfg->forceFilter) * filteredForce + cfg->forceFilter * forceSensor->force;
564 filteredTorque =
565 (1 - cfg->forceFilter) * filteredTorque + cfg->forceFilter * forceSensor->torque;
566
567 Eigen::Matrix4f forceFrameInRoot =
568 rtGetRobot()->getRobotNode(cfg->forceFrameName)->getPoseInRootFrame();
569 filteredForceInRoot = forceFrameInRoot.block<3, 3>(0, 0) *
570 (filteredForce - forceOffset - handCompensatedFT.head<3>()) -
571 forceBaseline;
572 filteredTorqueInRoot = forceFrameInRoot.block<3, 3>(0, 0) *
573 (filteredTorque - torqueOffset - handCompensatedFT.tail<3>()) -
574 torqueBaseline;
575
576 for (size_t i = 0; i < 3; ++i)
577 {
578 if (fabs(filteredForceInRoot(i)) > cfg->forceDeadZone)
579 {
580 filteredForceInRoot(i) -=
581 (filteredForceInRoot(i) / fabs(filteredForceInRoot(i))) * cfg->forceDeadZone;
582 }
583 else
584 {
585 filteredForceInRoot(i) = 0;
586 }
587
588 if (fabs(filteredTorqueInRoot(i)) > cfg->torqueDeadZone)
589 {
590 filteredTorqueInRoot(i) -=
591 (filteredTorqueInRoot(i) / fabs(filteredTorqueInRoot(i))) * cfg->torqueDeadZone;
592 }
593 else
594 {
595 filteredTorqueInRoot(i) = 0;
596 }
597 }
598
599 Eigen::Vector6f forceTorque;
600 forceTorque << filteredForceInRoot, filteredTorqueInRoot;
601 return forceTorque;
602 }
603
604 void
606 const Eigen::Vector6f& kpImpedance,
607 const Ice::Current&)
608 {
609 LockGuardType guard(mpMutex);
610 ctrlParams.getWriteBuffer().kpImpedance = kpImpedance;
611 ctrlParams.commitWrite();
612 }
613
614 void
616 const Eigen::Vector6f& kdImpedance,
617 const Ice::Current&)
618 {
619 LockGuardType guard(mpMutex);
620 ctrlParams.getWriteBuffer().kdImpedance = kdImpedance;
621 ctrlParams.commitWrite();
622 }
623
624 std::string
626 {
627 return kinematic_chain;
628 }
629
630 void
632 const Ice::StringSeq& fileNames,
633 const Ice::Current&)
634 {
635 ARMARX_INFO << "Learning DMP ... ";
636
637 LockGuardType guard{mpMutex};
638 dmpCtrl->learnDMPFromFiles(fileNames);
639 }
640
641 void
643 const TrajectoryBasePtr& trajectory,
644 const Ice::Current&)
645 {
646 ARMARX_INFO << "Learning DMP ... ";
648 TrajectoryPtr dmpTraj = TrajectoryPtr::dynamicCast(trajectory);
650
651 LockGuardType guard{mpMutex};
652 dmpCtrl->learnDMPFromTrajectory(dmpTraj);
653 }
654
655 bool
657 {
658 return false;
659 }
660
661 void
663 const Ice::Current&)
664 {
665 LockGuardType guard{mpMutex};
666 dmpCtrl->setSpeed(times);
667 }
668
669 void
671 const Ice::Current& ice)
672 {
673 LockGuardType guard{mpMutex};
674 dmpCtrl->setGoalPoseVec(goals);
675 }
676
677 void
679 const Ice::Current&)
680 {
681 LockGuardType guard{mpMutex};
682 dmpCtrl->setAmplitude(amp);
683 }
684
685 void
687 const Ice::Current&)
688 {
690 getWriterControlStruct().targetForce = targetForce;
692 }
693
694 void
696 Ice::Double tau,
697 const Ice::Current&)
698 {
699 rtFirstRun.store(true);
700 while (rtFirstRun.load() || !rtReady.load() || !rt2InterfaceBuffer.updateReadBuffer())
701 {
702 usleep(100);
703 }
704
705 Eigen::Matrix4f pose = rt2InterfaceBuffer.getUpToDateReadBuffer().currentTcpPose;
706
707 LockGuardType guard{mpMutex};
708 dmpCtrl->prepareExecution(dmpCtrl->eigen4f2vec(pose), goals);
709 dmpCtrl->setSpeed(tau);
710
711 mpRunning.store(true);
712 dmpCtrl->resumeController();
713 ARMARX_INFO << "start mp ...";
714 }
715
716 double
718 {
719 return dmpCtrl->canVal;
720 }
721
722 void
724 {
725 // if (started)
726 if (mpRunning.load())
727 {
728 ARMARX_INFO << "Cannot reset running DMP";
729 }
730 rtFirstRun = true;
731 }
732
733 void
735 {
736 mpRunning.store(false);
737 // oldPose = interfaceData.getUpToDateReadBuffer().currentTcpPose;
738 // started = false;
739 // stopped = true;
740 }
741
742 void
744 {
745 dmpCtrl->pauseController();
746 }
747
748 void
750 {
751 dmpCtrl->resumeController();
752 // stopped = false;
753 }
754
755 void
757 const SensorAndControl&,
759 const DebugObserverInterfacePrx& debugObs)
760 {
761 std::string datafieldName;
762 std::string debugName = "Periodic";
763 StringVariantBaseMap datafields;
764
765 Eigen::Matrix4f targetPoseDebug = debugRTBuffer.getUpToDateReadBuffer().targetPose;
766 datafields["target_x"] = new Variant(targetPoseDebug(0, 3));
767 datafields["target_y"] = new Variant(targetPoseDebug(1, 3));
768 datafields["target_z"] = new Variant(targetPoseDebug(2, 3));
769
770 Eigen::Vector3f targetVelInTool = debugRTBuffer.getUpToDateReadBuffer().targetVelInTool;
771 datafields["targetVelInTool_x"] = new Variant(targetVelInTool(0));
772 datafields["targetVelInTool_y"] = new Variant(targetVelInTool(1));
773 datafields["targetVelInTool_z"] = new Variant(targetVelInTool(2));
774
775 Eigen::Matrix4f currentPoseDebug = debugRTBuffer.getUpToDateReadBuffer().currentPose;
776 datafields["current_x"] = new Variant(currentPoseDebug(0, 3));
777 datafields["current_y"] = new Variant(currentPoseDebug(1, 3));
778 datafields["current_z"] = new Variant(currentPoseDebug(2, 3));
779
780 Eigen::Vector3f filteredForce = debugRTBuffer.getUpToDateReadBuffer().filteredForce;
781 datafields["filteredforce_x"] = new Variant(filteredForce(0));
782 datafields["filteredforce_y"] = new Variant(filteredForce(1));
783 datafields["filteredforce_z"] = new Variant(filteredForce(2));
784
785
786 Eigen::Vector3f reactForce = debugRTBuffer.getUpToDateReadBuffer().reactForce;
787 datafields["reactForce_x"] = new Variant(reactForce(0));
788 datafields["reactForce_y"] = new Variant(reactForce(1));
789 datafields["reactForce_z"] = new Variant(reactForce(2));
790
791 Eigen::VectorXf targetVel = debugRTBuffer.getUpToDateReadBuffer().targetVel;
792 datafields["targetVel_x"] = new Variant(targetVel(0));
793 datafields["targetVel_y"] = new Variant(targetVel(1));
794 datafields["targetVel_z"] = new Variant(targetVel(2));
795
796 datafields["canVal"] = new Variant(debugMPBuffer.getUpToDateReadBuffer().currentCanVal);
797 datafields["deltaT"] = new Variant(debugMPBuffer.getUpToDateReadBuffer().deltaT);
798
799 datafields["PhaseStop"] = new Variant(debugRTBuffer.getUpToDateReadBuffer().isPhaseStop);
800
801
802 // datafields["targetVel_rx"] = new Variant(targetVel(3));
803 // datafields["targetVel_ry"] = new Variant(targetVel(4));
804 // datafields["targetVel_rz"] = new Variant(targetVel(5));
805
806 // auto values = debugOutputData.getUpToDateReadBuffer().latestTargetVelocities;
807 // for (auto& pair : values)
808 // {
809 // datafieldName = pair.first + "_" + debugName;
810 // datafields[datafieldName] = new Variant(pair.second);
811 // }
812
813 // auto currentPose = debugOutputData.getUpToDateReadBuffer().currentPose;
814 // for (auto& pair : currentPose)
815 // {
816 // datafieldName = pair.first + "_" + debugName;
817 // datafields[datafieldName] = new Variant(pair.second);
818 // }
819
820 // datafieldName = "canVal_" + debugName;
821 // datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().currentCanVal);
822 // datafieldName = "mpcFactor_" + debugName;
823 // datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().mpcFactor);
824 // datafieldName = "error_" + debugName;
825 // datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().error);
826 // datafieldName = "posError_" + debugName;
827 // datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().posError);
828 // datafieldName = "oriError_" + debugName;
829 // datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().oriError);
830 // datafieldName = "deltaT_" + debugName;
831 // datafields[datafieldName] = new Variant(debugOutputData.getUpToDateReadBuffer().deltaT);
832
833 datafieldName = "PeriodicDMP";
834 debugObs->setDebugChannel(datafieldName, datafields);
835 }
836
837 void
842
843
844} // namespace armarx::control::deprecated_njoint_mp_controller::task_space
#define float
Definition 16_Level.h:22
#define VAROUT(x)
constexpr T c
Brief description of class JointControlTargetBase.
This util class helps with keeping a cycle time during a control cycle.
Definition CycleUtil.h:41
ArmarXObjectSchedulerPtr getObjectScheduler() const
int getState() const
Retrieve current state of the ManagedIceObject.
bool isControllerActive(const Ice::Current &=Ice::emptyCurrent) const final override
const SensorValueBase * useSensorValue(const std::string &sensorDeviceName) const
Get a const ptr to the given SensorDevice's SensorValue.
void runTask(const std::string &taskName, Task &&task)
Executes a given task in a separate thread from the Application ThreadPool.
const VirtualRobot::RobotPtr & useSynchronizedRtRobot(bool updateCollisionModel=false)
Requests a VirtualRobot for use in rtRun *.
const VirtualRobot::RobotPtr & rtGetRobot()
TODO make protected and use attorneys.
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...
void reinitTripleBuffer(const DeprecatedNJointPeriodicTSDMPCompliantControllerControlData &initial)
The SensorValueBase class.
const T * asA() const
The Variant class is described here: Variants.
Definition Variant.h:224
void rtRun(const IceUtil::Time &sensorValuesTimestamp, const IceUtil::Time &timeSinceLastIteration)
TODO make protected and use attorneys.
Eigen::Vector6f getFilteredForceTorque(Eigen::Vector3f &forceBaseline, Eigen::Vector3f &torqueBaseline, Eigen::Vector6f &handCompensatedFT)
DeprecatedNJointPeriodicTSDMPCompliantController(const RobotUnitPtr &, const NJointControllerConfigPtr &config, const VirtualRobot::RobotPtr &)
virtual void onPublish(const SensorAndControl &, const DebugDrawerInterfacePrx &, const DebugObserverInterfacePrx &)
#define ARMARX_CHECK_EXPRESSION(expression)
This macro evaluates the expression and if it turns out to be false it will throw an ExpressionExcept...
#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...
#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...
#define ARMARX_INFO
The normal logging level.
Definition Logging.h:181
#define ARMARX_IMPORTANT
The logging level for always important information, but expected behaviour (in contrast to ARMARX_WAR...
Definition Logging.h:190
#define ARMARX_WARNING
The logging level for unexpected behaviour, but not a serious problem.
Definition Logging.h:193
Matrix< float, 6, 1 > Vector6f
std::shared_ptr< class Robot > RobotPtr
Definition Bus.h:19
NJointControllerRegistration< DeprecatedNJointPeriodicTSDMPCompliantController > registrationControllerDeprecatedNJointPeriodicTSDMPCompliantController("DeprecatedNJointPeriodicTSDMPCompliantController")
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugObserverInterface > DebugObserverInterfacePrx
std::map< std::string, VariantBasePtr > StringVariantBaseMap
IceInternal::Handle< Trajectory > TrajectoryPtr
Definition Trajectory.h:52
std::vector< std::vector< T > > transpose(const std::vector< std::vector< T > > &src, Thrower thrower)
IceUtil::Handle< class RobotUnit > RobotUnitPtr
Definition FTSensor.h:34
::IceInternal::ProxyHandle<::IceProxy::armarx::DebugDrawerInterface > DebugDrawerInterfacePrx
detail::ControlThreadOutputBufferEntry SensorAndControl
double norm(const Point &a)
Definition point.hpp:102