3 #include <boost/archive/text_iarchive.hpp>
4 #include <boost/archive/text_oarchive.hpp>
6 #include <VirtualRobot/IK/DifferentialIK.h>
7 #include <VirtualRobot/MathTools.h>
8 #include <VirtualRobot/Nodes/RobotNode.h>
9 #include <VirtualRobot/Robot.h>
10 #include <VirtualRobot/RobotNodeSet.h>
45 const armarx::NJointControllerConfigPtr& config,
48 RTScopeTimer timer(
"DeprecatedNJointTSDMPController_constructor");
51 cfg = DeprecatedNJointTaskSpaceDMPControllerConfigPtr::dynamicCast(config);
53 VirtualRobot::RobotNodeSetPtr rns =
rtGetRobot()->getRobotNodeSet(cfg->nodeSetName);
54 jointNames = rns->getNodeNames();
56 for (
size_t i = 0; i < rns->getSize(); ++i)
58 std::string jointName = rns->getNode(i)->getName();
61 targets.push_back(ct->
asA<ControlTarget1DoFActuatorVelocity>());
63 const SensorValue1DoFActuatorTorque* torqueSensor =
64 sv->
asA<SensorValue1DoFActuatorTorque>();
65 const SensorValue1DoFActuatorVelocity* velocitySensor =
66 sv->
asA<SensorValue1DoFActuatorVelocity>();
67 const SensorValue1DoFGravityTorque* gravityTorqueSensor =
68 sv->
asA<SensorValue1DoFGravityTorque>();
69 const SensorValue1DoFActuatorPosition* positionSensor =
70 sv->
asA<SensorValue1DoFActuatorPosition>();
75 if (!gravityTorqueSensor)
77 ARMARX_WARNING <<
"No Gravity Torque sensor available for " << jointName;
80 torqueSensors.push_back(torqueSensor);
81 gravityTorqueSensors.push_back(gravityTorqueSensor);
82 velocitySensors.push_back(velocitySensor);
83 positionSensors.push_back(positionSensor);
88 forceOffset.setZero();
89 filteredForce.setZero();
90 filteredForceInRoot.setZero();
94 if(not cfg->tcpName.empty())
99 tcp = cfg->tcpName.empty() ? rns->getTCP() :
rtGetRobot()->getRobotNode(cfg->tcpName);
103 refFrame = (cfg->frameName.empty()) ? rns->getRobot()->getRootNode()
109 nodeSetName = cfg->nodeSetName;
110 torquePIDs.resize(tcpController->rns->getSize(), pidController());
112 ik.reset(
new VirtualRobot::DifferentialIK(
113 rns, refFrame, VirtualRobot::JacobiProvider::eSVDDamped));
120 taskSpaceDMPConfig.
DMPMode = cfg->dmpMode;
121 taskSpaceDMPConfig.
DMPStyle = cfg->dmpStyle;
138 RTToControllerData initSensorData;
139 initSensorData.deltaT = 0;
140 initSensorData.currentTime = 0;
141 initSensorData.currentPose.setZero();
142 initSensorData.currentTwist.setZero();
145 targetVels.setZero(6);
148 initData.
targetPose = refFrame->toLocalCoordinateSystem(tcp->getGlobalPose());
150 initData.
torqueKp.resize(tcpController->rns->getSize(), 0);
151 initData.
torqueKd.resize(tcpController->rns->getSize(), 0);
155 debugName = cfg->debugName;
157 KpF = cfg->Kp_LinearVel;
158 KoF = cfg->Kp_AngularVel;
159 DpF = cfg->Kd_LinearVel;
160 DoF = cfg->Kd_AngularVel;
162 filtered_qvel.setZero(targets.size());
163 vel_filter_factor = cfg->vel_filter;
165 filtered_position.setZero(3);
166 pos_filter_factor = cfg->pos_filter;
172 jointLowLimits.setZero(targets.size());
173 jointHighLimits.setZero(targets.size());
174 for (
size_t i = 0; i < rns->getSize(); i++)
176 VirtualRobot::RobotNodePtr rn = rns->getAllRobotNodes().at(i);
178 jointLowLimits(i) = rn->getJointLimitLo();
179 jointHighLimits(i) = rn->getJointLimitHi();
184 RTToUserData initInterfaceData;
193 return "DeprecatedNJointTSDMPController";
212 Eigen::VectorXf currentTwist = rt2CtrlData.
getReadBuffer().currentTwist;
215 dmpCtrl->flow(deltaT, currentPose, currentTwist);
217 if (dmpCtrl->canVal < 1e-8)
221 targetVels = dmpCtrl->getTargetVelocity();
222 targetPose = dmpCtrl->getTargetPoseMat();
223 std::vector<double> targetState = dmpCtrl->getTargetPose();
225 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"x_vel"] = targetVels(0);
226 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"y_vel"] = targetVels(1);
227 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"z_vel"] = targetVels(2);
228 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"roll_vel"] = targetVels(3);
229 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"pitch_vel"] = targetVels(4);
230 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"yaw_vel"] = targetVels(5);
231 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_x"] = targetState[0];
232 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_y"] = targetState[1];
233 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_z"] = targetState[2];
234 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_qw"] = targetState[3];
235 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_qx"] = targetState[4];
236 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_qy"] = targetState[5];
237 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_qz"] = targetState[6];
238 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_x"] = currentPose(0, 3);
239 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_y"] = currentPose(1, 3);
240 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_z"] = currentPose(2, 3);
243 VirtualRobot::MathTools::eigen4f2quat(currentPose);
244 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qw"] = currentQ.w;
245 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qx"] = currentQ.x;
246 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qy"] = currentQ.y;
247 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qz"] = currentQ.z;
248 debugOutputData.
getWriteBuffer().currentCanVal = dmpCtrl->debugData.canVal;
249 debugOutputData.
getWriteBuffer().mpcFactor = dmpCtrl->debugData.mpcFactor;
250 debugOutputData.
getWriteBuffer().error = dmpCtrl->debugData.poseError;
251 debugOutputData.
getWriteBuffer().posError = dmpCtrl->debugData.posiError;
252 debugOutputData.
getWriteBuffer().oriError = dmpCtrl->debugData.oriError;
264 const Eigen::VectorXf& nullspaceVel,
268 Eigen::MatrixXf jacobi = ik->getJacobianMatrix(tcp, mode);
270 Eigen::FullPivLU<Eigen::MatrixXf> lu_decomp(jacobi);
272 Eigen::MatrixXf nullspace = lu_decomp.kernel();
273 Eigen::VectorXf nsv = Eigen::VectorXf::Zero(nullspace.rows());
274 for (
int i = 0; i < nullspace.cols(); i++)
276 float squaredNorm = nullspace.col(i).squaredNorm();
278 if (squaredNorm > 1.0e-32f)
280 nsv += nullspace.col(i) * nullspace.col(i).dot(nullspaceVel) /
281 nullspace.col(i).squaredNorm();
285 Eigen::MatrixXf inv =
286 ik->computePseudoInverseJacobianMatrix(jacobi, ik->getJacobiRegularization(mode));
288 Eigen::VectorXf jointVel = inv * cartesianVel;
298 Eigen::Matrix4f currentPose = refFrame->toLocalCoordinateSystem(tcp->getGlobalPose());
304 filtered_position = currentPose.block<3, 1>(0, 3);
307 for (
size_t i = 0; i < targets.size(); ++i)
309 targets.at(i)->velocity = 0;
315 filtered_position = (1 - pos_filter_factor) * filtered_position +
316 pos_filter_factor * currentPose.block<3, 1>(0, 3);
320 (1 - cfg->forceFilter) * forceOffset + cfg->forceFilter * forceSensor->
force;
321 timeForCalibration = timeForCalibration + timeSinceLastIteration.toSecondsDouble();
323 if (started and useForceStop)
326 filteredForce = (1 - cfg->forceFilter) * filteredForce +
327 cfg->forceFilter * (forceSensor->
force - forceOffset);
329 for (
size_t i = 0; i < 3; ++i)
331 if (fabs(filteredForce(i)) > cfg->forceDeadZone)
334 (filteredForce(i) / fabs(filteredForce(i))) * cfg->forceDeadZone;
338 filteredForce(i) = 0;
342 rtGetRobot()->getRobotNode(cfg->forceFrameName)->getPoseInRootFrame();
343 filteredForceInRoot = forceFrameInRoot.block<3, 3>(0, 0) * filteredForce;
345 for (
size_t i = 0; i < 3; ++i)
356 double deltaT = timeSinceLastIteration.toSecondsDouble();
358 Eigen::MatrixXf jacobi =
359 ik->getJacobianMatrix(tcp, VirtualRobot::IKSolver::CartesianSelection::All);
361 Eigen::VectorXf qvel(velocitySensors.size());
362 for (
size_t i = 0; i < velocitySensors.size(); ++i)
364 qvel(i) = velocitySensors[i]->velocity;
367 filtered_qvel = (1 - vel_filter_factor) * filtered_qvel + vel_filter_factor * qvel;
368 Eigen::VectorXf tcptwist = jacobi * filtered_qvel;
382 Eigen::VectorXf jointTargetVelocities = Eigen::VectorXf::Zero(targets.size());
389 targetPose.block<3, 3>(0, 0) * currentPose.block<3, 3>(0, 0).inverse();
390 Eigen::Vector3f errorRPY = VirtualRobot::MathTools::eigen3f2rpy(diffMat);
393 rtTargetVel.block<3, 1>(0, 0) =
394 KpF * (targetPose.block<3, 1>(0, 3) - currentPose.block<3, 1>(0, 3)) +
395 DpF * (-tcptwist.block<3, 1>(0, 0));
397 rtTargetVel.block<3, 1>(3, 0) =
398 KoF * errorRPY + DoF * (targetVel.block<3, 1>(3, 0) - tcptwist.block<3, 1>(3, 0));
402 float normLinearVelocity = rtTargetVel.block<3, 1>(0, 0).
norm();
403 if (normLinearVelocity > cfg->maxLinearVel)
405 rtTargetVel.block<3, 1>(0, 0) =
406 cfg->maxLinearVel * rtTargetVel.block<3, 1>(0, 0) / normLinearVelocity;
409 float normAngularVelocity = rtTargetVel.block<3, 1>(3, 0).
norm();
410 if (normAngularVelocity > cfg->maxAngularVel)
412 rtTargetVel.block<3, 1>(3, 0) =
413 cfg->maxAngularVel * rtTargetVel.block<3, 1>(3, 0) / normAngularVelocity;
424 Eigen::VectorXf jnv = Eigen::VectorXf::Zero(tcpController->rns->getSize());
426 if (jointLimitAvoidanceKp > 0)
428 jnv += jointLimitAvoidanceKp * tcpController->calculateJointLimitAvoidance();
430 for (
size_t i = 0; i < tcpController->rns->getSize(); i++)
436 jointTargetVelocities =
437 calcIK(rtTargetVel, jnv, VirtualRobot::IKSolver::CartesianSelection::All);
443 for (
size_t i = 0; i < targets.size(); ++i)
445 targets.at(i)->velocity = jointTargetVelocities(i);
447 if (!targets.at(i)->isValid() || fabs(targets.at(i)->velocity) > cfg->maxJointVelocity)
449 targets.at(i)->velocity = 0.0f;
452 rtDebugData.
getWriteBuffer().targetJointVels = jointTargetVelocities;
465 dmpCtrl->learnDMPFromFiles(fileNames);
473 dmpCtrl->setSpeed(times);
478 const Ice::DoubleSeq& viapoint,
483 dmpCtrl->setViaPose(u, viapoint);
492 for (
size_t i = 0; i < tcpController->rns->getSize(); i++)
495 torqueKp.at(tcpController->rns->getNode(i)->getName());
502 const StringFloatDictionary& nullspaceJointVelocities,
507 for (
size_t i = 0; i < tcpController->rns->getSize(); i++)
510 nullspaceJointVelocities.at(tcpController->rns->getNode(i)->getName());
534 dmpCtrl->removeAllViaPoints();
542 dmpCtrl->setGoalPoseVec(goals);
549 dmpCtrl->pauseController();
556 dmpCtrl->resumeController();
582 return dmpCtrl->saveDMPToString();
590 dmpCtrl->loadDMPFromString(dmpString);
591 return dmpCtrl->dmpPtr->defaultGoal;
609 return VirtualRobot::IKSolver::CartesianSelection::All;
625 timeForCalibration = 0;
626 while (firstRun || timeForCalibration < cfg->waitTimeForCalibration)
630 ARMARX_WARNING <<
"StopDMP has been prematurely called; aborting runDMP";
644 dmpCtrl->prepareExecution(dmpCtrl->eigen4f2vec(pose), goals);
658 while (firstRun || timeForCalibration < cfg->waitTimeForCalibration)
662 ARMARX_WARNING <<
"StopDMP has been prematurely called; aborting runDMP";
675 dmpCtrl->config.motionTimeDuration = timeDuration;
676 dmpCtrl->prepareExecution(dmpCtrl->eigen4f2vec(pose), goals);
699 std::string datafieldName = debugName;
704 datafieldName = pair.first +
"_" + debugName;
705 datafields[datafieldName] =
new Variant(pair.second);
709 for (
auto& pair : dmpTargets)
711 datafieldName = pair.first +
"_" + debugName;
712 datafields[datafieldName] =
new Variant(pair.second);
716 for (
auto& pair : currentPose)
718 datafieldName = pair.first +
"_" + debugName;
719 datafields[datafieldName] =
new Variant(pair.second);
722 datafieldName =
"canVal_" + debugName;
723 datafields[datafieldName] =
725 datafieldName =
"mpcFactor_" + debugName;
727 datafieldName =
"error_" + debugName;
729 datafieldName =
"posError_" + debugName;
731 datafieldName =
"oriError_" + debugName;
733 datafieldName =
"deltaT_" + debugName;
738 <<
"\nOrientation Error: "
742 for (
int i = 0; i < targetJoints.size(); ++i)
744 datafieldName = jointNames[i] +
"_velocity";
745 datafields[datafieldName] =
new Variant(targetJoints[i]);
748 datafieldName =
"DMPController_" + debugName;
749 debugObs->setDebugChannel(datafieldName, datafields);
758 runTask(
"DeprecatedNJointTSDMPController",
763 while (
getState() == eManagedIceObjectStarted)
769 c.waitForCycleDuration();
784 dmpCtrl->setWeights(weights);
791 DMP::DVec2d res = dmpCtrl->getWeights();
793 for (
size_t i = 0; i < res.size(); ++i)
795 std::vector<double> cvec;
796 for (
size_t j = 0; j < res[i].size(); ++j)
798 cvec.push_back(res[i][j]);
800 resvec.push_back(cvec);