5 #include <boost/archive/text_iarchive.hpp>
6 #include <boost/archive/text_oarchive.hpp>
8 #include <VirtualRobot/IK/DifferentialIK.h>
9 #include <VirtualRobot/MathTools.h>
10 #include <VirtualRobot/Nodes/RobotNode.h>
11 #include <VirtualRobot/Robot.h>
12 #include <VirtualRobot/RobotNodeSet.h>
48 const armarx::NJointControllerConfigPtr& config,
51 RTScopeTimer timer(
"DeprecatedNJointTSDMPController_constructor");
54 cfg = DeprecatedNJointTaskSpaceDMPControllerConfigPtr::dynamicCast(config);
56 VirtualRobot::RobotNodeSetPtr rns =
rtGetRobot()->getRobotNodeSet(cfg->nodeSetName);
57 jointNames = rns->getNodeNames();
59 for (
size_t i = 0; i < rns->getSize(); ++i)
61 std::string jointName = rns->getNode(i)->getName();
64 targets.push_back(ct->
asA<ControlTarget1DoFActuatorVelocity>());
66 const SensorValue1DoFActuatorTorque* torqueSensor =
67 sv->
asA<SensorValue1DoFActuatorTorque>();
68 const SensorValue1DoFActuatorVelocity* velocitySensor =
69 sv->
asA<SensorValue1DoFActuatorVelocity>();
70 const SensorValue1DoFGravityTorque* gravityTorqueSensor =
71 sv->
asA<SensorValue1DoFGravityTorque>();
72 const SensorValue1DoFActuatorPosition* positionSensor =
73 sv->
asA<SensorValue1DoFActuatorPosition>();
78 if (!gravityTorqueSensor)
80 ARMARX_WARNING <<
"No Gravity Torque sensor available for " << jointName;
83 torqueSensors.push_back(torqueSensor);
84 gravityTorqueSensors.push_back(gravityTorqueSensor);
85 velocitySensors.push_back(velocitySensor);
86 positionSensors.push_back(positionSensor);
91 forceOffset.setZero();
92 filteredForce.setZero();
93 filteredForceInRoot.setZero();
97 if (not cfg->tcpName.empty())
102 tcp = cfg->tcpName.empty() ? rns->getTCP() :
rtGetRobot()->getRobotNode(cfg->tcpName);
106 refFrame = (cfg->frameName.empty()) ? rns->getRobot()->getRootNode()
112 nodeSetName = cfg->nodeSetName;
113 torquePIDs.resize(tcpController->rns->getSize(), pidController());
115 ik.reset(
new VirtualRobot::DifferentialIK(
116 rns, refFrame, VirtualRobot::JacobiProvider::eSVDDamped));
123 taskSpaceDMPConfig.
DMPMode = cfg->dmpMode;
124 taskSpaceDMPConfig.
DMPStyle = cfg->dmpStyle;
141 RTToControllerData initSensorData;
142 initSensorData.deltaT = 0;
143 initSensorData.currentTime = 0;
144 initSensorData.currentPose.setZero();
145 initSensorData.currentTwist.setZero();
148 targetVels.setZero(6);
151 initData.
targetPose = refFrame->toLocalCoordinateSystem(tcp->getGlobalPose());
153 initData.
torqueKp.resize(tcpController->rns->getSize(), 0);
154 initData.
torqueKd.resize(tcpController->rns->getSize(), 0);
158 debugName = cfg->debugName;
160 KpF = cfg->Kp_LinearVel;
161 KoF = cfg->Kp_AngularVel;
162 DpF = cfg->Kd_LinearVel;
163 DoF = cfg->Kd_AngularVel;
165 filtered_qvel.setZero(
targets.size());
166 vel_filter_factor = cfg->vel_filter;
168 filtered_position.setZero(3);
169 pos_filter_factor = cfg->pos_filter;
175 jointLowLimits.setZero(
targets.size());
176 jointHighLimits.setZero(
targets.size());
177 for (
size_t i = 0; i < rns->getSize(); i++)
179 VirtualRobot::RobotNodePtr rn = rns->getAllRobotNodes().at(i);
181 jointLowLimits(i) = rn->getJointLimitLo();
182 jointHighLimits(i) = rn->getJointLimitHi();
187 RTToUserData initInterfaceData;
196 return "DeprecatedNJointTSDMPController";
215 Eigen::VectorXf currentTwist = rt2CtrlData.
getReadBuffer().currentTwist;
218 dmpCtrl->flow(deltaT, currentPose, currentTwist);
220 if (dmpCtrl->canVal < 1e-8)
224 targetVels = dmpCtrl->getTargetVelocity();
225 targetPose = dmpCtrl->getTargetPoseMat();
226 std::vector<double> targetState = dmpCtrl->getTargetPose();
228 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"x_vel"] = targetVels(0);
229 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"y_vel"] = targetVels(1);
230 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"z_vel"] = targetVels(2);
231 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"roll_vel"] = targetVels(3);
232 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"pitch_vel"] = targetVels(4);
233 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"yaw_vel"] = targetVels(5);
234 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_x"] = targetState[0];
235 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_y"] = targetState[1];
236 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_z"] = targetState[2];
237 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_qw"] = targetState[3];
238 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_qx"] = targetState[4];
239 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_qy"] = targetState[5];
240 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_qz"] = targetState[6];
241 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_x"] = currentPose(0, 3);
242 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_y"] = currentPose(1, 3);
243 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_z"] = currentPose(2, 3);
246 VirtualRobot::MathTools::eigen4f2quat(currentPose);
247 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qw"] = currentQ.w;
248 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qx"] = currentQ.x;
249 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qy"] = currentQ.y;
250 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qz"] = currentQ.z;
251 debugOutputData.
getWriteBuffer().currentCanVal = dmpCtrl->debugData.canVal;
252 debugOutputData.
getWriteBuffer().mpcFactor = dmpCtrl->debugData.mpcFactor;
253 debugOutputData.
getWriteBuffer().error = dmpCtrl->debugData.poseError;
254 debugOutputData.
getWriteBuffer().posError = dmpCtrl->debugData.posiError;
255 debugOutputData.
getWriteBuffer().oriError = dmpCtrl->debugData.oriError;
267 const Eigen::VectorXf& nullspaceVel,
271 Eigen::MatrixXf jacobi = ik->getJacobianMatrix(tcp, mode);
273 Eigen::FullPivLU<Eigen::MatrixXf> lu_decomp(jacobi);
275 Eigen::MatrixXf nullspace = lu_decomp.kernel();
276 Eigen::VectorXf nsv = Eigen::VectorXf::Zero(nullspace.rows());
277 for (
int i = 0; i < nullspace.cols(); i++)
279 float squaredNorm = nullspace.col(i).squaredNorm();
281 if (squaredNorm > 1.0e-32f)
283 nsv += nullspace.col(i) * nullspace.col(i).dot(nullspaceVel) /
284 nullspace.col(i).squaredNorm();
288 Eigen::MatrixXf inv =
289 ik->computePseudoInverseJacobianMatrix(jacobi, ik->getJacobiRegularization(mode));
291 Eigen::VectorXf jointVel = inv * cartesianVel;
301 Eigen::Matrix4f currentPose = refFrame->toLocalCoordinateSystem(tcp->getGlobalPose());
307 filtered_position = currentPose.block<3, 1>(0, 3);
310 for (
size_t i = 0; i <
targets.size(); ++i)
318 filtered_position = (1 - pos_filter_factor) * filtered_position +
319 pos_filter_factor * currentPose.block<3, 1>(0, 3);
323 (1 - cfg->forceFilter) * forceOffset + cfg->forceFilter * forceSensor->
force;
324 timeForCalibration = timeForCalibration + timeSinceLastIteration.toSecondsDouble();
326 if (started and useForceStop)
329 filteredForce = (1 - cfg->forceFilter) * filteredForce +
330 cfg->forceFilter * (forceSensor->
force - forceOffset);
332 for (
size_t i = 0; i < 3; ++i)
334 if (fabs(filteredForce(i)) > cfg->forceDeadZone)
337 (filteredForce(i) / fabs(filteredForce(i))) * cfg->forceDeadZone;
341 filteredForce(i) = 0;
345 rtGetRobot()->getRobotNode(cfg->forceFrameName)->getPoseInRootFrame();
346 filteredForceInRoot = forceFrameInRoot.block<3, 3>(0, 0) * filteredForce;
348 for (
size_t i = 0; i < 3; ++i)
359 double deltaT = timeSinceLastIteration.toSecondsDouble();
361 Eigen::MatrixXf jacobi =
362 ik->getJacobianMatrix(tcp, VirtualRobot::IKSolver::CartesianSelection::All);
364 Eigen::VectorXf qvel(velocitySensors.size());
365 for (
size_t i = 0; i < velocitySensors.size(); ++i)
367 qvel(i) = velocitySensors[i]->velocity;
370 filtered_qvel = (1 - vel_filter_factor) * filtered_qvel + vel_filter_factor * qvel;
371 Eigen::VectorXf tcptwist = jacobi * filtered_qvel;
385 Eigen::VectorXf jointTargetVelocities = Eigen::VectorXf::Zero(
targets.size());
392 targetPose.block<3, 3>(0, 0) * currentPose.block<3, 3>(0, 0).inverse();
393 Eigen::Vector3f errorRPY = VirtualRobot::MathTools::eigen3f2rpy(diffMat);
396 rtTargetVel.block<3, 1>(0, 0) =
397 KpF * (targetPose.block<3, 1>(0, 3) - currentPose.block<3, 1>(0, 3)) +
398 DpF * (-tcptwist.block<3, 1>(0, 0));
400 rtTargetVel.block<3, 1>(3, 0) =
401 KoF * errorRPY + DoF * (targetVel.block<3, 1>(3, 0) - tcptwist.block<3, 1>(3, 0));
405 float normLinearVelocity = rtTargetVel.block<3, 1>(0, 0).
norm();
406 if (normLinearVelocity > cfg->maxLinearVel)
408 rtTargetVel.block<3, 1>(0, 0) =
409 cfg->maxLinearVel * rtTargetVel.block<3, 1>(0, 0) / normLinearVelocity;
412 float normAngularVelocity = rtTargetVel.block<3, 1>(3, 0).
norm();
413 if (normAngularVelocity > cfg->maxAngularVel)
415 rtTargetVel.block<3, 1>(3, 0) =
416 cfg->maxAngularVel * rtTargetVel.block<3, 1>(3, 0) / normAngularVelocity;
427 Eigen::VectorXf jnv = Eigen::VectorXf::Zero(tcpController->rns->getSize());
429 if (jointLimitAvoidanceKp > 0)
431 jnv += jointLimitAvoidanceKp * tcpController->calculateJointLimitAvoidance();
433 for (
size_t i = 0; i < tcpController->rns->getSize(); i++)
439 jointTargetVelocities =
440 calcIK(rtTargetVel, jnv, VirtualRobot::IKSolver::CartesianSelection::All);
458 for (
size_t i = 0; i <
targets.size(); ++i)
460 targets.at(i)->velocity = jointTargetVelocities(i);
462 if (!
targets.at(i)->isValid() ||
463 fabs(
targets.at(i)->velocity) > cfg->maxJointVelocity)
465 targets.at(i)->velocity = 0.0f;
469 rtDebugData.
getWriteBuffer().targetJointVels = jointTargetVelocities;
482 dmpCtrl->learnDMPFromFiles(fileNames);
490 dmpCtrl->setSpeed(times);
495 const Ice::DoubleSeq& viapoint,
500 dmpCtrl->setViaPose(u, viapoint);
509 for (
size_t i = 0; i < tcpController->rns->getSize(); i++)
512 torqueKp.at(tcpController->rns->getNode(i)->getName());
519 const StringFloatDictionary& nullspaceJointVelocities,
524 for (
size_t i = 0; i < tcpController->rns->getSize(); i++)
527 nullspaceJointVelocities.at(tcpController->rns->getNode(i)->getName());
551 dmpCtrl->removeAllViaPoints();
559 dmpCtrl->setGoalPoseVec(goals);
566 dmpCtrl->pauseController();
573 dmpCtrl->resumeController();
603 return dmpCtrl->saveDMPToString();
611 dmpCtrl->loadDMPFromString(dmpString);
612 return dmpCtrl->dmpPtr->defaultGoal;
630 return VirtualRobot::IKSolver::CartesianSelection::All;
646 timeForCalibration = 0;
647 while (firstRun || timeForCalibration < cfg->waitTimeForCalibration)
651 ARMARX_WARNING <<
"StopDMP has been prematurely called; aborting runDMP";
665 dmpCtrl->prepareExecution(dmpCtrl->eigen4f2vec(pose), goals);
666 dmpCtrl->resumeController();
683 while (firstRun || timeForCalibration < cfg->waitTimeForCalibration)
687 ARMARX_WARNING <<
"StopDMP has been prematurely called; aborting runDMP";
700 dmpCtrl->config.motionTimeDuration = timeDuration;
701 dmpCtrl->prepareExecution(dmpCtrl->eigen4f2vec(pose), goals);
702 dmpCtrl->resumeController();
725 std::string datafieldName = debugName;
730 datafieldName = pair.first +
"_" + debugName;
731 datafields[datafieldName] =
new Variant(pair.second);
735 for (
auto& pair : dmpTargets)
737 datafieldName = pair.first +
"_" + debugName;
738 datafields[datafieldName] =
new Variant(pair.second);
742 for (
auto& pair : currentPose)
744 datafieldName = pair.first +
"_" + debugName;
745 datafields[datafieldName] =
new Variant(pair.second);
748 datafieldName =
"canVal_" + debugName;
749 datafields[datafieldName] =
751 datafieldName =
"mpcFactor_" + debugName;
753 datafieldName =
"error_" + debugName;
755 datafieldName =
"posError_" + debugName;
757 datafieldName =
"oriError_" + debugName;
759 datafieldName =
"deltaT_" + debugName;
764 <<
"\nOrientation Error: "
768 for (
int i = 0; i < targetJoints.size(); ++i)
770 datafieldName = jointNames[i] +
"_velocity";
771 datafields[datafieldName] =
new Variant(targetJoints[i]);
774 datafieldName =
"DMPController_" + debugName;
775 debugObs->setDebugChannel(datafieldName, datafields);
784 runTask(
"DeprecatedNJointTSDMPController",
789 while (
getState() == eManagedIceObjectStarted)
795 c.waitForCycleDuration();
810 dmpCtrl->setWeights(weights);
817 DMP::DVec2d res = dmpCtrl->getWeights();
819 for (
size_t i = 0; i < res.size(); ++i)
821 std::vector<double> cvec;
822 for (
size_t j = 0; j < res[i].size(); ++j)
824 cvec.push_back(res[i][j]);
826 resvec.push_back(cvec);