30 #include <VirtualRobot/RobotConfig.h>
31 #include <VirtualRobot/XML/RobotIO.h>
32 #include <VirtualRobot/MathTools.h>
34 #include <SimoxUtility/algorithm/string/string_tools.h>
42 using namespace Eigen;
46 TCPControlUnit::TCPControlUnit() :
47 maxJointVelocity(30.f / 180 * 3.141),
50 calculationRunning(false)
57 topicName =
getName() +
"State";
58 usingProxy(getProperty<std::string>(
"KinematicUnitName").getValue());
59 usingProxy(getProperty<std::string>(
"RobotStateComponentName").getValue());
62 usingTopic(getProperty<std::string>(
"RobotStateTopicName").getValue());
64 cycleTime = getProperty<int>(
"CycleTime").getValue();
65 maxJointVelocity = getProperty<float>(
"MaxJointVelocity").getValue();
71 std::unique_lock lock(dataMutex);
73 debugObs = getTopic<DebugObserverInterfacePrx>(
"DebugObserver");
74 kinematicUnitPrx = getProxy<KinematicUnitInterfacePrx>(getProperty<std::string>(
"KinematicUnitName").getValue());
75 robotStateComponentPrx = getProxy<RobotStateComponentInterfacePrx>(getProperty<std::string>(
"RobotStateComponentName").getValue());
79 robotName = robotStateComponentPrx->getRobotName();
80 localRobot =
RemoteRobot::createLocalClone(robotStateComponentPrx, robotStateComponentPrx->getRobotFilename(), robotStateComponentPrx->getArmarXPackages());
81 jointExistenceCheckRobot =
RemoteRobot::createLocalClone(robotStateComponentPrx, robotStateComponentPrx->getRobotFilename(), robotStateComponentPrx->getArmarXPackages());
83 localReportRobot = localRobot->clone(localRobot->getName());
85 std::string nodesetsString = getProperty<std::string>(
"TCPsToReport").getValue();
86 nodesToReport.clear();
87 if (!nodesetsString.empty())
89 if (nodesetsString ==
"*")
91 auto nodesets = localReportRobot->getRobotNodeSets();
93 for (RobotNodeSetPtr&
set : nodesets)
97 nodesToReport.push_back(
set->getTCP());
105 for (
auto& name : nodesetNames)
107 auto node = localReportRobot->getRobotNode(name);
111 nodesToReport.push_back(node);
115 ARMARX_ERROR <<
"Could not find node with name: " << name;
121 std::vector<RobotNodePtr> nodes = localRobot->getRobotNodes();
123 for (
unsigned int i = 0; i < nodes.size(); i++)
130 listener = getTopic<TCPControlUnitListenerPrx>(topicName);
141 execTask->setDelayWarningTolerance(100);
152 catch (std::exception& e)
171 std::unique_lock lock(taskMutex);
172 cycleTime = milliseconds;
176 execTask->changeInterval(cycleTime);
180 void TCPControlUnit::setTCPVelocity(
const std::string& nodeSetName,
const std::string& tcpName,
const FramedDirectionBasePtr& translationVelocity,
const FramedDirectionBasePtr& orientationVelocityRPY,
const Ice::Current&
c)
184 ARMARX_WARNING <<
"Implicitly requesting TCPControlUnit! Please call request before setting TCPVelocities!";
188 std::unique_lock lock(dataMutex);
189 ARMARX_CHECK_EXPRESSION(jointExistenceCheckRobot->hasRobotNodeSet(nodeSetName)) <<
"The robot does not have the node set: " + nodeSetName;
192 if (translationVelocity)
194 ARMARX_DEBUG <<
"Setting new Velocity for " << nodeSetName <<
" in frame " << translationVelocity->frame <<
":\n" << FramedDirectionPtr::dynamicCast(translationVelocity)->toEigen();
197 if (orientationVelocityRPY)
199 ARMARX_DEBUG <<
"Orientation Velo in frame " << orientationVelocityRPY->frame <<
": \n" << FramedDirectionPtr::dynamicCast(orientationVelocityRPY)->toEigen();
202 TCPVelocityData
data;
203 data.nodeSetName = nodeSetName;
204 data.translationVelocity = FramedDirectionPtr::dynamicCast(translationVelocity);
205 data.orientationVelocity = FramedDirectionPtr::dynamicCast(orientationVelocityRPY);
209 data.tcpName = jointExistenceCheckRobot->getRobotNodeSet(nodeSetName)->getTCP()->getName();
213 ARMARX_CHECK_EXPRESSION(jointExistenceCheckRobot->hasRobotNode(tcpName)) <<
"The robot does not have the node: " + tcpName;
215 data.tcpName = tcpName;
218 tcpVelocitiesMap[
data.tcpName] =
data;
238 case eManagedIceObjectStarted:
241 case eManagedIceObjectInitialized:
242 case eManagedIceObjectStarting:
243 return eUnitInitialized;
245 case eManagedIceObjectExiting:
246 case eManagedIceObjectExited:
250 return eUnitConstructed;
267 std::unique_lock lock(dataMutex);
272 execTask->setDelayWarningTolerance(100);
279 std::unique_lock lock(dataMutex);
286 tcpVelocitiesMap.clear();
287 localTcpVelocitiesMap.clear();
301 void TCPControlUnit::periodicExec()
303 std::unique_lock lock(dataMutex, std::defer_lock);
309 localTcpVelocitiesMap.clear();
310 TCPVelocityDataMap::iterator it = tcpVelocitiesMap.begin();
312 for (; it != tcpVelocitiesMap.end(); it++)
314 localTcpVelocitiesMap[it->first] = it->second;
318 DIKMap::iterator itDIK = dIKMap.begin();
320 for (; itDIK != dIKMap.end(); itDIK++)
322 localDIKMap[itDIK->first] = itDIK->second;
342 TCPVelocityDataMap::iterator it = localTcpVelocitiesMap.begin();
344 for (; it != localTcpVelocitiesMap.end(); it++)
346 const TCPVelocityData&
data = it->second;
347 RobotNodeSetPtr nodeSet = localRobot->getRobotNodeSet(
data.nodeSetName);
349 DIKMap::iterator itDIK = localDIKMap.find(
data.nodeSetName);
351 if (itDIK == localDIKMap.end())
353 VirtualRobot::DifferentialIKPtr dIk(
new EDifferentialIK(nodeSet, localRobot->getRootNode(), VirtualRobot::JacobiProvider::eSVDDamped));
354 float lambda = getProperty<float>(
"LambdaDampedSVD").getValue();
355 dIk->setDampedSvdLambda(lambda);
356 localDIKMap[
data.nodeSetName] = dIk;
359 auto dIk = std::dynamic_pointer_cast<EDifferentialIK>(localDIKMap[
data.nodeSetName]);
363 using namespace Eigen;
365 it = localTcpVelocitiesMap.begin();
367 for (; it != localTcpVelocitiesMap.end(); it++)
370 TCPVelocityData&
data = it->second;
372 std::string refFrame = localRobot->getRootNode()->getName();
375 if (
data.translationVelocity &&
data.orientationVelocity)
377 mode = IKSolver::All;
380 else if (
data.translationVelocity && !
data.orientationVelocity)
384 else if (!
data.translationVelocity &&
data.orientationVelocity)
394 RobotNodePtr tcpNode = localRobot->getRobotNode(
data.tcpName);
398 if (
data.orientationVelocity)
401 rotInOriginalFrame = Eigen::AngleAxisf(
data.orientationVelocity->z * cycleTime * 0.001, Eigen::Vector3f::UnitZ())
402 * Eigen::AngleAxisf(
data.orientationVelocity->y * cycleTime * 0.001, Eigen::Vector3f::UnitY())
403 * Eigen::AngleAxisf(
data.orientationVelocity->x * cycleTime * 0.001, Eigen::Vector3f::UnitX());
405 if (
data.orientationVelocity->frame != refFrame)
411 trafoOriginalFrameToGlobal = localRobot->getRobotNode(
data.orientationVelocity->frame)->getGlobalPose();
418 trafoRefFrameToGlobal = localRobot->getRobotNode(refFrame)->getGlobalPose();
421 Eigen::Matrix4f trafoOriginalToRef = trafoRefFrameToGlobal.inverse() * trafoOriginalFrameToGlobal;
422 rotInRefFrame = trafoOriginalToRef.block<3, 3>(0, 0) * rotInOriginalFrame * trafoOriginalToRef.block<3, 3>(0, 0).inverse();
426 rotInRefFrame = rotInOriginalFrame;
429 m.block(0, 0, 3, 3) = rotInRefFrame * (tcpNode->getGlobalPose().block(0, 0, 3, 3));
437 if (
data.translationVelocity)
441 m.block(0, 3, 3, 1) = tcpNode->getGlobalPose().block(0, 3, 3, 1) +
data.translationVelocity->toEigen() * cycleTime * 0.001;
445 DifferentialIKPtr dIK = localDIKMap[
data.nodeSetName];
463 dIK->setGoal(m, tcpNode, mode, 0.001, 0.001 / 180.0f * 3.14159);
470 NameControlModeMap controlModes;
471 DIKMap::iterator itDIK = localDIKMap.begin();
473 for (; itDIK != localDIKMap.end(); itDIK++)
475 RobotNodeSetPtr robotNodeSet = localRobot->getRobotNodeSet(itDIK->first);
477 auto dIK = std::dynamic_pointer_cast<EDifferentialIK>(itDIK->second);
480 Eigen::VectorXf jointDelta;
484 jointDelta /= (cycleTime * 0.001);
486 jointDelta = applyMaxJointVelocity(jointDelta, maxJointVelocity);
488 lastTCPPose = robotNodeSet->getTCP()->getGlobalPose();
492 const std::vector< VirtualRobot::RobotNodePtr > nodes = robotNodeSet->getAllRobotNodes();
493 std::vector< VirtualRobot::RobotNodePtr >::const_iterator iter = nodes.begin();
496 while (iter != nodes.end() && i < jointDelta.rows())
498 if (targetVelocities.find((*iter)->getName()) != targetVelocities.end())
503 targetVelocities.insert(std::make_pair((*iter)->getName(), jointDelta(i)));
505 controlModes.insert(std::make_pair((*iter)->getName(), eVelocityControl));
512 kinematicUnitPrx->switchControlMode(controlModes);
513 kinematicUnitPrx->setJointVelocities(targetVelocities);
518 void TCPControlUnit::ContinuousAngles(
const Eigen::AngleAxisf& oldAngle, Eigen::AngleAxisf& newAngle,
double& offset)
521 const Eigen::Vector3f& v1 = oldAngle.axis();
522 const Eigen::Vector3f& v2 = newAngle.axis();
523 const Eigen::Vector3f& v2i = newAngle.axis() * -1;
524 double angle = acos(v1.dot(v2) / (v1.norm() * v2.norm()));
525 double angleInv = acos(v1.dot(v2i) / (v1.norm() * v2i.norm()));
530 if (
angle > angleInv)
533 newAngle = Eigen::AngleAxisf(2.0 *
M_PI - newAngle.angle(), newAngle.axis() * -1);
538 if (fabs(newAngle.angle() + offset - oldAngle.angle()) > fabs(newAngle.angle() + offset - (oldAngle.angle() +
M_PI * 2)))
542 else if (fabs(newAngle.angle() + offset - oldAngle.angle()) > fabs((newAngle.angle() +
M_PI * 2 + offset) - oldAngle.angle()))
547 newAngle.angle() += offset;
553 std::vector< VirtualRobot::RobotNodePtr > nodes = robotNodeSet->getAllRobotNodes();
554 Eigen::VectorXf actualJointValues(nodes.size());
556 if (desiredJointValues.rows() == 0)
559 desiredJointValues.resize(nodes.size());
561 for (
unsigned int i = 0; i < nodes.size(); i++)
563 VirtualRobot::RobotNodePtr node = nodes.at(i);
564 desiredJointValues(i) = (node->getJointLimitHigh() - node->getJointLimitLow()) * 0.5f + node->getJointLimitLow();
571 Eigen::VectorXf jointCompensationDeltas(desiredJointValues.rows());
573 for (
unsigned int i = 0; i < desiredJointValues.rows(); i++)
575 VirtualRobot::RobotNodePtr node = nodes.at(i);
576 actualJointValues(i) = node->getJointValue();
577 jointCompensationDeltas(i) = (node->getJointValue() - desiredJointValues(i)) / (node->getJointLimitHigh() - node->getJointLimitLow());
578 jointCompensationDeltas(i) = -pow(jointCompensationDeltas(i), 3) * pow(nodes.size() - i, 2);
588 Eigen::MatrixXf I(jacobianInverse.rows(), jacobian.cols());
591 Eigen::MatrixXf nullspaceProjection = I - jacobianInverse * jacobian;
593 Eigen::VectorXf delta = nullspaceProjection * desiredJointDeltas;
597 Eigen::VectorXf TCPControlUnit::applyMaxJointVelocity(
const Eigen::VectorXf& jointVelocity,
float maxJointVelocity)
601 for (
unsigned int i = 0; i < jointVelocity.rows(); i++)
603 currentMaxJointVel =
std::max(
static_cast<double>(
std::abs(jointVelocity(i))), currentMaxJointVel);
606 if (currentMaxJointVel > maxJointVelocity)
609 return jointVelocity * (maxJointVelocity / currentMaxJointVel);
613 return jointVelocity;
627 DifferentialIK(rns, coordSystem, invJacMethod)
638 size_t nDoF = nodes.size();
640 using namespace Eigen;
641 MatrixXf Jacobian(nRows, nDoF);
645 for (
size_t i = 0; i < tcp_set.size(); i++)
649 if (this->targets.find(tcp) != this->targets.end())
652 MatrixXf partJacobian = this->getJacobianMatrix(tcp, mode);
653 Jacobian.block(
index, 0, partJacobian.rows(), nDoF) = partJacobian;
657 VR_ERROR <<
"Internal error?!" << std::endl;
670 tolerancePosition.clear();
671 toleranceRotation.clear();
678 this->coordSystem = coordSystem;
683 if (mode <= IKSolver::Z)
691 else if (mode == IKSolver::All)
697 DifferentialIK::setGoal(goal, tcp, mode, tolerancePosition, toleranceRotation);
708 return computeSteps(jointDelta, stepSize, mininumChange, maxNStep, &DifferentialIK::computeStep);
719 VR_ASSERT(nodes.size() == rns->getSize());
723 std::vector<float> jv(nodes.size(), 0.0f);
724 std::vector<float> jvBest = rns->getJointValues();
728 std::vector<std::pair<float, VectorXf> > jointDeltaIterations;
729 float lastDist = FLT_MAX;
730 VectorXf oldJointValues;
731 rns->getJointValues(oldJointValues);
734 resultJointDelta.resize(nodes.size());
735 resultJointDelta.setZero();
739 VectorXf dTheta = (this->*computeFunction)(stepSize);
748 for (
unsigned int i = 0; i < nodes.size(); i++)
751 jv[i] = (nodes[i]->getJointValue() + dTheta[i]);
753 if (std::isnan(jv[i]) || std::isinf(jv[i]))
763 robot->setJointValues(rns, jv);
765 VectorXf newJointValues;
766 rns->getJointValues(newJointValues);
767 resultJointDelta = newJointValues - oldJointValues;
773 if (checkTolerances())
783 float d = dTheta.norm();
784 float posDist = getMeanErrorPosition();
785 float oriErr = getErrorRotation(rns->getTCP());
787 if (dTheta.norm() < mininumChange)
790 ARMARX_INFO <<
deactivateSpam(1) <<
"Could not improve result any more (dTheta.norm()=" << d <<
"), loop:" << step <<
" Resulting error: pos " << posDist <<
" orientation: " << oriErr << std::endl;
794 if (checkImprovement && posDist > lastDist)
797 ARMARX_INFO <<
deactivateSpam(1) <<
"Could not improve result any more (current position error=" << posDist <<
", last loop's error:" << lastDist <<
"), loop:" << step << std::endl;
798 robot->setJointValues(rns, jvBest);
806 jointDeltaIterations.push_back(std::make_pair(
getWeightedError(), resultJointDelta));
808 while (step < maxNStep);
813 for (
unsigned int i = 0; i < jointDeltaIterations.size(); i++)
815 if (jointDeltaIterations.at(i).first < bestJVError)
817 bestJVError = jointDeltaIterations.at(i).first;
818 resultJointDelta = jointDeltaIterations.at(i).second;
824 robot->setJointValues(rns, oldJointValues + resultJointDelta);
834 if (step >= maxNStep && verbose)
853 size_t nDoF = nodes.size();
855 MatrixXf Jacobian(nRows, nDoF);
856 VectorXf error(nRows);
859 for (
size_t i = 0; i < tcp_set.size(); i++)
863 if (this->targets.find(tcp) != this->targets.end())
865 Eigen::VectorXf delta = getDeltaToGoal(tcp);
868 MatrixXf partJacobian = this->getJacobianMatrix(tcp, mode);
871 Jacobian.block(
index, 0, partJacobian.rows(), nDoF) = partJacobian;
872 Vector3f position = delta.head(3);
873 position *= stepSize;
875 if (mode & IKSolver::X)
877 error(
index) = position(0);
881 if (mode & IKSolver::Y)
883 error(
index) = position(1);
887 if (mode & IKSolver::Z)
889 error(
index) = position(2);
895 error.segment(
index, 3) = delta.tail(3) * stepSize;
902 VR_ERROR <<
"Internal error?!" << std::endl;
910 MatrixXf pseudo = computePseudoInverseJacobianMatrix(Jacobian);
913 return pseudo * error;
924 size_t nDoF = nodes.size();
926 std::map<float, MatrixXf> partJacobians;
928 VectorXf thetaSum(nDoF);
932 for (
size_t i = 0; i < tcp_set.size(); i++)
936 if (this->targets.find(tcp) != this->targets.end())
938 Eigen::VectorXf delta = getDeltaToGoal(tcp);
940 MatrixXf partJacobian = this->getJacobianMatrix(tcp, mode);
946 if (mode <= IKSolver::Z)
954 else if (mode == IKSolver::All)
960 VectorXf partError(tcpDOF);
961 Vector3f position = delta.head(3);
963 position *= stepSize;
965 if (mode & IKSolver::X)
967 partError(
index) = position(0);
971 if (mode & IKSolver::Y)
973 partError(
index) = position(1);
977 if (mode & IKSolver::Z)
979 partError(
index) = position(2);
985 partError.segment(
index, 3) = delta.tail(3) * stepSize;
996 MatrixXf pseudo = computePseudoInverseJacobianMatrix(partJacobian);
999 std::map<VirtualRobot:: SceneObjectPtr, Eigen::VectorXf>::iterator it =
tcpWeights.find(tcp);
1010 if (mode <= IKSolver::Z)
1018 else if (mode == IKSolver::All)
1023 Eigen::VectorXf tmptcpWeightVec(size);
1024 tmptcpWeightVec.setOnes();
1034 weightMat.setIdentity();
1038 pseudo = pseudo * weightMat;
1047 thetaSum += pseudo * partError;
1052 VR_ERROR <<
"Internal error?!" << std::endl;
1063 Eigen::VectorXf jointValuesBefore;
1064 rns->getJointValues(jointValuesBefore);
1065 Eigen::VectorXf resultJointDelta;
1066 Eigen::VectorXf jointDeltaAlternative;
1067 bool result =
computeSteps(resultJointDelta, stepSize, minChange, maxSteps);
1070 if (useAlternativeOnFail && error > 5)
1077 resultJointDelta = jointDeltaAlternative;
1088 weightMat.setIdentity();
1092 Jacobian = Jacobian * weightMat;
1101 std::map<VirtualRobot:: SceneObjectPtr, Eigen::VectorXf>::iterator it =
tcpWeights.find(tcp);
1111 weightMat.setIdentity();
1114 partJacobian = weightMat * partJacobian;
1127 for (
size_t i = 0; i < tcp_set.size(); i++)
1129 std::map<VirtualRobot:: SceneObjectPtr, Eigen::VectorXf>::iterator it =
tcpWeights.find(tcp_set.at(i));
1133 Eigen::VectorXf& tmptcpWeightVec = it->second;
1137 if (oldVec.rows() > 0)
1142 tcpWeightVec.tail(tmptcpWeightVec.rows()) = tmptcpWeightVec;
1149 if (mode <= IKSolver::Z)
1157 else if (mode == IKSolver::All)
1165 if (oldVec.rows() > 0)
1170 Eigen::VectorXf tmptcpWeightVec(size);
1171 tmptcpWeightVec.setOnes();
1181 weightMat.setIdentity();
1185 invJacobian = invJacobian * weightMat;
1197 float result = 0.0f;
1198 float positionOrientationRatio = 3.f / 180.f *
M_PI;
1200 for (
size_t i = 0; i < tcp_set.size(); i++)
1218 tcp = getDefaultTCP();
1221 Vector3f position = targets[tcp].block(0, 3, 3, 1) - tcp->getGlobalPose().block(0, 3, 3, 1);
1224 float result = 0.0f;
1225 Eigen::VectorXf tcpWeight(3);
1233 tcpWeight.setOnes();
1236 int weightIndex = 0;
1238 if (modes[tcp] & IKSolver::X)
1241 result += position(0) * position(0) * tcpWeight(weightIndex++);
1244 if (modes[tcp] & IKSolver::Y)
1247 result += position(1) * position(1) * tcpWeight(weightIndex++);
1250 if (modes[tcp] & IKSolver::Z)
1253 result += position(2) * position(2) * tcpWeight(weightIndex++);
1256 return sqrtf(result);
1261 if (
dofWeights.rows() != plannedJointDeltas.rows())
1263 dofWeights.resize(plannedJointDeltas.rows());
1268 bool result =
false;
1270 for (
unsigned int i = 0; i < nodes.size(); i++)
1272 float angle = nodes[i]->getJointValue() + plannedJointDeltas[i] * 0.1;
1274 if (
angle > nodes[i]->getJointLimitHi() ||
angle < nodes[i]->getJointLimitLo())
1298 std::unique_lock lock(reportMutex);
1300 std::string rootFrame = localReportRobot->getRootNode()->getName();
1309 tempMap.erase(
"timestamp");
1310 localReportRobot->setJointValues(tempMap);
1312 for (
unsigned int i = 0; i < nodesToReport.size(); i++)
1314 RobotNodePtr& node = nodesToReport.at(i);
1315 const std::string& tcpName = node->getName();
1317 tcpPoses[tcpName] =
new FramedPose(currentPose, rootFrame, robotName);
1320 listener->reportTCPPose(tcpPoses);
1331 std::unique_lock lock(reportMutex);
1333 if (!localVelReportRobot)
1335 localVelReportRobot = localReportRobot->clone(robotName);
1339 FramedDirectionMap tcpTranslationVelocities;
1340 FramedDirectionMap tcpOrientationVelocities;
1341 std::string rootFrame = localReportRobot->getRootNode()->getName();
1342 NameValueMap tempJointAngles = localReportRobot->getConfig()->getRobotNodeJointValueMap();
1345 for (
unsigned int i = 0; i < nodesToReport.size(); i++)
1347 RobotNodePtr node = nodesToReport.at(i);
1348 const std::string& tcpName = node->getName();
1350 tcpPoses[tcpName] =
new FramedPose(currentPose, rootFrame, robotName);
1354 double tDelta = 0.001;
1356 for (NameValueMap::iterator it = tempJointAngles.begin(); it != tempJointAngles.end(); it++)
1358 NameValueMap::const_iterator itSrc = jointVel.find(it->first);
1359 if (itSrc != jointVel.end())
1361 if (itSrc->first ==
"timestamp")
1365 it->second += itSrc->second * tDelta;
1369 localVelReportRobot->setJointValues(tempJointAngles);
1371 for (
unsigned int i = 0; i < nodesToReport.size(); i++)
1373 RobotNodePtr node = localVelReportRobot->getRobotNode(nodesToReport.at(i)->getName());
1374 const std::string& tcpName = node->getName();
1378 FramedPosePtr lastPose = FramedPosePtr::dynamicCast(tcpPoses[tcpName]);
1380 tcpTranslationVelocities[tcpName] =
new FramedDirection((currentPose.block(0, 3, 3, 1) - lastPose->toEigen().block(0, 3, 3, 1)) / tDelta, rootFrame, localReportRobot->getName());
1382 const Eigen::Matrix4f mat = currentPose * lastPose->toEigen().inverse();
1384 Eigen::Vector3f rpy;
1385 VirtualRobot::MathTools::eigen4f2rpy(mat, rpy);
1388 tcpOrientationVelocities[tcpName] =
new FramedDirection(rpy / tDelta, rootFrame, robotName);
1393 listener->reportTCPVelocities(tcpTranslationVelocities, tcpOrientationVelocities);