7 NJointControllerRegistration<NJointPeriodicTSDMPForwardVelController>
9 "NJointPeriodicTSDMPForwardVelController");
12 const RobotUnitPtr& robUnit,
13 const armarx::NJointControllerConfigPtr& config,
17 cfg = NJointPeriodicTSDMPControllerConfigPtr::dynamicCast(config);
19 VirtualRobot::RobotNodeSetPtr rns =
rtGetRobot()->getRobotNodeSet(cfg->nodeSetName);
22 for (
size_t i = 0; i < rns->getSize(); ++i)
24 std::string jointName = rns->getNode(i)->getName();
27 targets.push_back(ct->
asA<ControlTarget1DoFActuatorVelocity>());
29 const SensorValue1DoFActuatorVelocity* velocitySensor =
30 sv->
asA<SensorValue1DoFActuatorVelocity>();
31 const SensorValue1DoFActuatorPosition* positionSensor =
32 sv->
asA<SensorValue1DoFActuatorPosition>();
34 velocitySensors.push_back(velocitySensor);
35 positionSensors.push_back(positionSensor);
41 nodeSetName = cfg->nodeSetName;
42 ik.reset(
new VirtualRobot::DifferentialIK(
43 rns, rns->getRobot()->getRootNode(), VirtualRobot::JacobiProvider::eSVDDamped));
51 taskSpaceDMPConfig.
DMPMode =
"Linear";
52 taskSpaceDMPConfig.
DMPStyle =
"Periodic";
67 initData.
targetPose = tcp->getPoseInRootFrame();
69 for (
size_t i = 0; i < 6; ++i)
80 robUnit->getSensorDevice(cfg->forceSensorName)->getSensorValue();
83 forceOffset.setZero();
84 filteredForce.setZero();
86 UserToRTData initUserData;
87 initUserData.targetForce = 0;
90 oriToolDir << 0, 0, 1;
98 return "NJointPeriodicTSDMPForwardVelController";
116 Eigen::VectorXf currentTwist = rt2CtrlData.
getReadBuffer().currentTwist;
119 dmpCtrl->flow(deltaT, currentPose, currentTwist);
121 Eigen::VectorXf targetVels = dmpCtrl->getTargetVelocity();
124 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"x_vel"] = targetVels(0);
125 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"y_vel"] = targetVels(1);
126 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"z_vel"] = targetVels(2);
127 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"roll_vel"] = targetVels(3);
128 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"pitch_vel"] = targetVels(4);
129 debugOutputData.
getWriteBuffer().latestTargetVelocities[
"yaw_vel"] = targetVels(5);
130 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_x"] = currentPose(0, 3);
131 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_y"] = currentPose(1, 3);
132 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_z"] = currentPose(2, 3);
134 VirtualRobot::MathTools::eigen4f2quat(currentPose);
135 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qw"] = currentQ.w;
136 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qx"] = currentQ.x;
137 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qy"] = currentQ.y;
138 debugOutputData.
getWriteBuffer().currentPose[
"currentPose_qz"] = currentQ.z;
139 debugOutputData.
getWriteBuffer().currentCanVal = dmpCtrl->debugData.canVal;
140 debugOutputData.
getWriteBuffer().mpcFactor = dmpCtrl->debugData.mpcFactor;
141 debugOutputData.
getWriteBuffer().error = dmpCtrl->debugData.poseError;
142 debugOutputData.
getWriteBuffer().posError = dmpCtrl->debugData.posiError;
143 debugOutputData.
getWriteBuffer().oriError = dmpCtrl->debugData.oriError;
159 double deltaT = timeSinceLastIteration.toSecondsDouble();
166 if (firstRun || !dmpRunning)
168 targetPose = currentPose;
169 for (
size_t i = 0; i < targets.size(); ++i)
171 targets.at(i)->velocity = 0.0f;
174 filteredForce.setZero();
177 toolTransform = currentHandOri.transpose();
182 (1 - cfg->forceFilter) * forceOffset + cfg->forceFilter * forceSensor->
force;
188 Eigen::MatrixXf jacobi =
189 ik->getJacobianMatrix(tcp, VirtualRobot::IKSolver::CartesianSelection::All);
191 Eigen::VectorXf qvel;
192 qvel.resize(velocitySensors.size());
193 for (
size_t i = 0; i < velocitySensors.size(); ++i)
195 qvel(i) = velocitySensors[i]->velocity;
198 Eigen::VectorXf tcptwist = jacobi * qvel;
229 for (
size_t i = 3; i < 6; ++i)
261 float dTf = (
float)deltaT;
262 targetPose.block<3, 1>(0, 3) =
263 targetPose.block<3, 1>(0, 3) + dTf * targetVel.block<3, 1>(0, 0);
265 targetVel(3) * dTf, targetVel(4) * dTf, targetVel(5) * dTf);
266 targetPose.block<3, 3>(0, 0) = rotVel * targetPose.block<3, 3>(0, 0);
273 targetPose.block<3, 3>(0, 0) * currentPose.block<3, 3>(0, 0).inverse();
274 Eigen::Vector3f errorRPY = VirtualRobot::MathTools::eigen3f2rpy(diffMat);
276 Eigen::VectorXf rtTargetVel = targetVel;
277 rtTargetVel.block<3, 1>(0, 0) +=
278 cfg->Kpos * (targetPose.block<3, 1>(0, 3) - currentPose.block<3, 1>(0, 3));
279 rtTargetVel.block<3, 1>(3, 0) += cfg->Kori * errorRPY;
281 float normLinearVelocity = rtTargetVel.block<3, 1>(0, 0).norm();
282 if (normLinearVelocity > fabs(cfg->maxLinearVel))
284 rtTargetVel.block<3, 1>(0, 0) =
285 fabs(cfg->maxLinearVel) * rtTargetVel.block<3, 1>(0, 0) / normLinearVelocity;
288 float normAngularVelocity = rtTargetVel.block<3, 1>(3, 0).
norm();
289 if (normAngularVelocity > fabs(cfg->maxAngularVel))
291 rtTargetVel.block<3, 1>(3, 0) =
292 fabs(cfg->maxAngularVel) * rtTargetVel.block<3, 1>(3, 0) / normAngularVelocity;
298 Eigen::VectorXf jnv = Eigen::VectorXf::Zero(tcpController->rns->getSize());
299 if (cfg->avoidJointLimitsKp > 0)
301 jnv += cfg->avoidJointLimitsKp * tcpController->calculateJointLimitAvoidance();
304 Eigen::VectorXf jointTargetVelocities = tcpController->calculate(
305 rtTargetVel, jnv, VirtualRobot::IKSolver::CartesianSelection::All);
306 for (
size_t i = 0; i < targets.size(); ++i)
308 targets.at(i)->velocity = jointTargetVelocities(i);
309 if (!targets.at(i)->isValid())
311 targets.at(i)->velocity = 0.0f;
315 if (fabs(targets.at(i)->velocity) > fabs(cfg->maxJointVel))
317 targets.at(i)->velocity =
318 fabs(cfg->maxJointVel) *
319 (targets.at(i)->velocity / fabs(targets.at(i)->velocity));
334 dmpCtrl->learnDMPFromFiles(fileNames);
341 dmpCtrl->setSpeed(times);
347 const Ice::Current& ice)
350 dmpCtrl->setGoalPoseVec(goals);
357 dmpCtrl->setAmplitude(amp);
367 cfg->waitTimeForCalibration)
374 dmpCtrl->prepareExecution(dmpCtrl->eigen4f2vec(pose), goals);
375 dmpCtrl->setSpeed(tau);
389 std::string datafieldName;
390 std::string debugName =
"Periodic";
395 datafieldName = pair.first +
"_" + debugName;
396 datafields[datafieldName] =
new Variant(pair.second);
400 for (
auto& pair : currentPose)
402 datafieldName = pair.first +
"_" + debugName;
403 datafields[datafieldName] =
new Variant(pair.second);
406 datafieldName =
"canVal_" + debugName;
407 datafields[datafieldName] =
409 datafieldName =
"mpcFactor_" + debugName;
411 datafieldName =
"error_" + debugName;
413 datafieldName =
"posError_" + debugName;
415 datafieldName =
"oriError_" + debugName;
417 datafieldName =
"deltaT_" + debugName;
419 datafieldName =
"DMPController_" + debugName;
421 debugObs->setDebugChannel(datafieldName, datafields);
429 RTToControllerData initSensorData;
430 initSensorData.deltaT = 0;
431 initSensorData.currentTime = 0;
432 initSensorData.currentPose = tcp->getPoseInRootFrame();
433 initSensorData.currentTwist.setZero();
436 RTToUserData initInterfaceData;
437 initInterfaceData.currentTcpPose = tcp->getPoseInRootFrame();
442 runTask(
"NJointPeriodicTSDMPForwardVelController",
447 while (
getState() == eManagedIceObjectStarted)
453 c.waitForCycleDuration();