3 #include <boost/archive/text_iarchive.hpp>
4 #include <boost/archive/text_oarchive.hpp>
29 const armarx::NJointControllerConfigPtr& config,
32 RTScopeTimer timer(
"DeprecatedNJointTSDMPController_constructor");
35 cfg = DeprecatedNJointTaskSpaceDMPControllerConfigPtr::dynamicCast(config);
37 VirtualRobot::RobotNodeSetPtr rns =
rtGetRobot()->getRobotNodeSet(cfg->nodeSetName);
38 jointNames = rns->getNodeNames();
40 for (
size_t i = 0; i < rns->getSize(); ++i)
42 std::string jointName = rns->getNode(i)->getName();
45 targets.push_back(ct->
asA<ControlTarget1DoFActuatorVelocity>());
47 const SensorValue1DoFActuatorTorque* torqueSensor =
48 sv->
asA<SensorValue1DoFActuatorTorque>();
49 const SensorValue1DoFActuatorVelocity* velocitySensor =
50 sv->
asA<SensorValue1DoFActuatorVelocity>();
51 const SensorValue1DoFGravityTorque* gravityTorqueSensor =
52 sv->
asA<SensorValue1DoFGravityTorque>();
53 const SensorValue1DoFActuatorPosition* positionSensor =
54 sv->
asA<SensorValue1DoFActuatorPosition>();
59 if (!gravityTorqueSensor)
61 ARMARX_WARNING <<
"No Gravity Torque sensor available for " << jointName;
64 torqueSensors.push_back(torqueSensor);
65 gravityTorqueSensors.push_back(gravityTorqueSensor);
66 velocitySensors.push_back(velocitySensor);
67 positionSensors.push_back(positionSensor);
72 forceOffset.setZero();
73 filteredForce.setZero();
74 filteredForceInRoot.setZero();
78 tcp = (cfg->tcpName.empty()) ? rns->getTCP() :
rtGetRobot()->getRobotNode(cfg->tcpName);
79 refFrame = (cfg->frameName.empty()) ? rns->getRobot()->getRootNode()
85 nodeSetName = cfg->nodeSetName;
86 torquePIDs.resize(tcpController->rns->getSize(), pidController());
88 ik.reset(
new VirtualRobot::DifferentialIK(
89 rns, refFrame, VirtualRobot::JacobiProvider::eSVDDamped));
96 taskSpaceDMPConfig.
DMPMode = cfg->dmpMode;
97 taskSpaceDMPConfig.
DMPStyle = cfg->dmpStyle;
114 RTToControllerData initSensorData;
115 initSensorData.deltaT = 0;
116 initSensorData.currentTime = 0;
117 initSensorData.currentPose.setZero();
118 initSensorData.currentTwist.setZero();
121 targetVels.setZero(6);
124 initData.
targetPose = refFrame->toLocalCoordinateSystem(tcp->getGlobalPose());
126 initData.
torqueKp.resize(tcpController->rns->getSize(), 0);
127 initData.
torqueKd.resize(tcpController->rns->getSize(), 0);
131 debugName = cfg->debugName;
133 KpF = cfg->Kp_LinearVel;
134 KoF = cfg->Kp_AngularVel;
135 DpF = cfg->Kd_LinearVel;
136 DoF = cfg->Kd_AngularVel;
138 filtered_qvel.setZero(targets.size());
139 vel_filter_factor = cfg->vel_filter;
141 filtered_position.setZero(3);
142 pos_filter_factor = cfg->pos_filter;
148 jointLowLimits.setZero(targets.size());
149 jointHighLimits.setZero(targets.size());
150 for (
size_t i = 0; i < rns->getSize(); i++)
152 VirtualRobot::RobotNodePtr rn = rns->getAllRobotNodes().at(i);
154 jointLowLimits(i) = rn->getJointLimitLo();
155 jointHighLimits(i) = rn->getJointLimitHi();
160 RTToUserData initInterfaceData;
169 return "DeprecatedNJointTSDMPController";
188 Eigen::VectorXf currentTwist = rt2CtrlData.
getReadBuffer().currentTwist;
191 dmpCtrl->flow(deltaT, currentPose, currentTwist);
193 if (dmpCtrl->canVal < 1e-8)
197 targetVels = dmpCtrl->getTargetVelocity();
198 targetPose = dmpCtrl->getTargetPoseMat();
199 std::vector<double> targetState = dmpCtrl->getTargetPose();
201 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"x_vel"] = targetVels(0);
202 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"y_vel"] = targetVels(1);
203 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"z_vel"] = targetVels(2);
204 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"roll_vel"] = targetVels(3);
205 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"pitch_vel"] = targetVels(4);
206 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"yaw_vel"] = targetVels(5);
207 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_x"] = targetState[0];
208 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_y"] = targetState[1];
209 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_z"] = targetState[2];
210 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_qw"] = targetState[3];
211 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_qx"] = targetState[4];
212 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_qy"] = targetState[5];
213 debugOutputData.
getWriteBuffer().dmpTargets[
"dmp_qz"] = targetState[6];
214 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_x"] = currentPose(0, 3);
215 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_y"] = currentPose(1, 3);
216 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_z"] = currentPose(2, 3);
219 VirtualRobot::MathTools::eigen4f2quat(currentPose);
220 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qw"] = currentQ.w;
221 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qx"] = currentQ.x;
222 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qy"] = currentQ.y;
223 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qz"] = currentQ.z;
224 debugOutputData.
getWriteBuffer().currentCanVal = dmpCtrl->debugData.canVal;
225 debugOutputData.
getWriteBuffer().mpcFactor = dmpCtrl->debugData.mpcFactor;
226 debugOutputData.
getWriteBuffer().error = dmpCtrl->debugData.poseError;
227 debugOutputData.
getWriteBuffer().posError = dmpCtrl->debugData.posiError;
228 debugOutputData.
getWriteBuffer().oriError = dmpCtrl->debugData.oriError;
240 const Eigen::VectorXf& nullspaceVel,
244 Eigen::MatrixXf jacobi = ik->getJacobianMatrix(tcp, mode);
246 Eigen::FullPivLU<Eigen::MatrixXf> lu_decomp(jacobi);
248 Eigen::MatrixXf nullspace = lu_decomp.kernel();
249 Eigen::VectorXf nsv = Eigen::VectorXf::Zero(nullspace.rows());
250 for (
int i = 0; i < nullspace.cols(); i++)
252 float squaredNorm = nullspace.col(i).squaredNorm();
254 if (squaredNorm > 1.0e-32f)
256 nsv += nullspace.col(i) * nullspace.col(i).dot(nullspaceVel) /
257 nullspace.col(i).squaredNorm();
261 Eigen::MatrixXf inv =
262 ik->computePseudoInverseJacobianMatrix(jacobi, ik->getJacobiRegularization(mode));
264 Eigen::VectorXf jointVel = inv * cartesianVel;
274 Eigen::Matrix4f currentPose = refFrame->toLocalCoordinateSystem(tcp->getGlobalPose());
280 filtered_position = currentPose.block<3, 1>(0, 3);
283 for (
size_t i = 0; i < targets.size(); ++i)
285 targets.at(i)->velocity = 0;
291 filtered_position = (1 - pos_filter_factor) * filtered_position +
292 pos_filter_factor * currentPose.block<3, 1>(0, 3);
296 (1 - cfg->forceFilter) * forceOffset + cfg->forceFilter * forceSensor->
force;
297 timeForCalibration = timeForCalibration + timeSinceLastIteration.toSecondsDouble();
299 if (started and useForceStop)
302 filteredForce = (1 - cfg->forceFilter) * filteredForce +
303 cfg->forceFilter * (forceSensor->
force - forceOffset);
305 for (
size_t i = 0; i < 3; ++i)
307 if (fabs(filteredForce(i)) > cfg->forceDeadZone)
310 (filteredForce(i) / fabs(filteredForce(i))) * cfg->forceDeadZone;
314 filteredForce(i) = 0;
318 rtGetRobot()->getRobotNode(cfg->forceFrameName)->getPoseInRootFrame();
319 filteredForceInRoot = forceFrameInRoot.block<3, 3>(0, 0) * filteredForce;
321 for (
size_t i = 0; i < 3; ++i)
332 double deltaT = timeSinceLastIteration.toSecondsDouble();
334 Eigen::MatrixXf jacobi =
335 ik->getJacobianMatrix(tcp, VirtualRobot::IKSolver::CartesianSelection::All);
337 Eigen::VectorXf qvel(velocitySensors.size());
338 for (
size_t i = 0; i < velocitySensors.size(); ++i)
340 qvel(i) = velocitySensors[i]->velocity;
343 filtered_qvel = (1 - vel_filter_factor) * filtered_qvel + vel_filter_factor * qvel;
344 Eigen::VectorXf tcptwist = jacobi * filtered_qvel;
358 Eigen::VectorXf jointTargetVelocities = Eigen::VectorXf::Zero(targets.size());
365 targetPose.block<3, 3>(0, 0) * currentPose.block<3, 3>(0, 0).inverse();
366 Eigen::Vector3f errorRPY = VirtualRobot::MathTools::eigen3f2rpy(diffMat);
369 rtTargetVel.block<3, 1>(0, 0) =
370 KpF * (targetPose.block<3, 1>(0, 3) - currentPose.block<3, 1>(0, 3)) +
371 DpF * (-tcptwist.block<3, 1>(0, 0));
373 rtTargetVel.block<3, 1>(3, 0) =
374 KoF * errorRPY + DoF * (targetVel.block<3, 1>(3, 0) - tcptwist.block<3, 1>(3, 0));
378 float normLinearVelocity = rtTargetVel.block<3, 1>(0, 0).
norm();
379 if (normLinearVelocity > cfg->maxLinearVel)
381 rtTargetVel.block<3, 1>(0, 0) =
382 cfg->maxLinearVel * rtTargetVel.block<3, 1>(0, 0) / normLinearVelocity;
385 float normAngularVelocity = rtTargetVel.block<3, 1>(3, 0).
norm();
386 if (normAngularVelocity > cfg->maxAngularVel)
388 rtTargetVel.block<3, 1>(3, 0) =
389 cfg->maxAngularVel * rtTargetVel.block<3, 1>(3, 0) / normAngularVelocity;
400 Eigen::VectorXf jnv = Eigen::VectorXf::Zero(tcpController->rns->getSize());
402 if (jointLimitAvoidanceKp > 0)
404 jnv += jointLimitAvoidanceKp * tcpController->calculateJointLimitAvoidance();
406 for (
size_t i = 0; i < tcpController->rns->getSize(); i++)
412 jointTargetVelocities =
413 calcIK(rtTargetVel, jnv, VirtualRobot::IKSolver::CartesianSelection::All);
419 for (
size_t i = 0; i < targets.size(); ++i)
421 targets.at(i)->velocity = jointTargetVelocities(i);
423 if (!targets.at(i)->isValid() || fabs(targets.at(i)->velocity) > cfg->maxJointVelocity)
425 targets.at(i)->velocity = 0.0f;
428 rtDebugData.
getWriteBuffer().targetJointVels = jointTargetVelocities;
441 dmpCtrl->learnDMPFromFiles(fileNames);
449 dmpCtrl->setSpeed(times);
454 const Ice::DoubleSeq& viapoint,
459 dmpCtrl->setViaPose(u, viapoint);
468 for (
size_t i = 0; i < tcpController->rns->getSize(); i++)
471 torqueKp.at(tcpController->rns->getNode(i)->getName());
478 const StringFloatDictionary& nullspaceJointVelocities,
483 for (
size_t i = 0; i < tcpController->rns->getSize(); i++)
486 nullspaceJointVelocities.at(tcpController->rns->getNode(i)->getName());
510 dmpCtrl->removeAllViaPoints();
518 dmpCtrl->setGoalPoseVec(goals);
525 dmpCtrl->pauseController();
532 dmpCtrl->resumeController();
558 return dmpCtrl->saveDMPToString();
566 dmpCtrl->loadDMPFromString(dmpString);
567 return dmpCtrl->dmpPtr->defaultGoal;
585 return VirtualRobot::IKSolver::CartesianSelection::All;
601 timeForCalibration = 0;
602 while (firstRun || timeForCalibration < cfg->waitTimeForCalibration)
606 ARMARX_WARNING <<
"StopDMP has been prematurely called; aborting runDMP";
620 dmpCtrl->prepareExecution(dmpCtrl->eigen4f2vec(pose), goals);
634 while (firstRun || timeForCalibration < cfg->waitTimeForCalibration)
638 ARMARX_WARNING <<
"StopDMP has been prematurely called; aborting runDMP";
651 dmpCtrl->config.motionTimeDuration = timeDuration;
652 dmpCtrl->prepareExecution(dmpCtrl->eigen4f2vec(pose), goals);
675 std::string datafieldName = debugName;
680 datafieldName = pair.first +
"_" + debugName;
681 datafields[datafieldName] =
new Variant(pair.second);
685 for (
auto& pair : dmpTargets)
687 datafieldName = pair.first +
"_" + debugName;
688 datafields[datafieldName] =
new Variant(pair.second);
692 for (
auto& pair : currentPose)
694 datafieldName = pair.first +
"_" + debugName;
695 datafields[datafieldName] =
new Variant(pair.second);
698 datafieldName =
"canVal_" + debugName;
699 datafields[datafieldName] =
701 datafieldName =
"mpcFactor_" + debugName;
703 datafieldName =
"error_" + debugName;
705 datafieldName =
"posError_" + debugName;
707 datafieldName =
"oriError_" + debugName;
709 datafieldName =
"deltaT_" + debugName;
714 <<
"\nOrientation Error: "
718 for (
int i = 0; i < targetJoints.size(); ++i)
720 datafieldName = jointNames[i] +
"_velocity";
721 datafields[datafieldName] =
new Variant(targetJoints[i]);
724 datafieldName =
"DMPController_" + debugName;
725 debugObs->setDebugChannel(datafieldName, datafields);
734 runTask(
"DeprecatedNJointTSDMPController",
739 while (
getState() == eManagedIceObjectStarted)
745 c.waitForCycleDuration();
760 dmpCtrl->setWeights(weights);
767 DMP::DVec2d res = dmpCtrl->getWeights();
769 for (
size_t i = 0; i < res.size(); ++i)
771 std::vector<double> cvec;
772 for (
size_t j = 0; j < res[i].size(); ++j)
774 cvec.push_back(res[i][j]);
776 resvec.push_back(cvec);