5 #include <VirtualRobot/MathTools.h>
11 tcp_control::arondto::MoveTCPToTargetPoseAcceptedType GetDefaultParameterization()
13 tcp_control::arondto::MoveTCPToTargetPoseAcceptedType
ret;
14 ret.orientationalAccuracy = 0.01;
15 ret.positionalAccuracy = 25;
21 "MoveTCPToTargetPose",
"Move the TCP to a target pose",
23 tcp_control::arondto::MoveTCPToTargetPoseAcceptedType::ToAronType(),
24 GetDefaultParameterization().toAron()
29 mixin::RobotReadingSkillMixin(mns),
30 PeriodicSimpleSpecializedSkill<tcp_control::arondto::MoveTCPToTargetPoseAcceptedType>(Description,
armarx::core::time::
Frequency::Hertz(100))
38 tcpControlUnitRequestedOnStart =
true;
41 tcpControlUnitRequestedOnStart =
false;
49 PeriodicSkill::StepResult MoveTCPToTargetPose::step(
const SpecializedMainInput& in)
54 ARMARX_WARNING <<
"Unable to get robot from robotstatememory. Abort.";
58 std::string handRootNodeName =
"Hand L Base";
59 std::string robotAPIHandFileName =
"RobotAPI/robots/Armar3/ArmarIII-LeftHand.xml";
62 handRootNodeName =
"Hand R Base";
63 robotAPIHandFileName =
"RobotAPI/robots/Armar3/ArmarIII-RightHand.xml";
66 std::string tcpName = robot->getRobotNodeSet(in.parameters.kinematicChainName)->getTCP()->getName();
68 const Eigen::Matrix4f tcpPoseGlobal = robot->getRobotNode(tcpName)->getGlobalPose();
69 const Eigen::Matrix4f handRootPoseGlobal = robot->getRobotNode(handRootNodeName)->getGlobalPose();
70 const Eigen::Matrix4f tcpInHandRoot = handRootPoseGlobal.inverse() * tcpPoseGlobal;
73 auto currentTCPPoseGlobal = robot->getRobotNode(tcpName)->getGlobalPose();
75 const auto tcpTargetPoseGlobal = in.parameters.targetPoseGlobal;
76 const Eigen::Matrix4f handRootTargetPoseGlobal = tcpTargetPoseGlobal * tcpInHandRoot.inverse();
78 const float baseSpeedFactor = 1.5;
79 const float maxTranslationSpeed = baseSpeedFactor * 30;
80 const float minTranslationSpeed = maxTranslationSpeed * 0.1;
81 const float maxRotationSpeed = baseSpeedFactor * 0.7;
82 const float minRotationSpeed = maxRotationSpeed * 0.1;
85 Eigen::Vector3f diffPos = tcpTargetPoseGlobal.block<3, 1>(0, 3) - currentTCPPoseGlobal.block<3, 1>(0, 3);
86 float diffPosError = diffPos.norm();
88 float sig = 1 / (1 + pow(M_E, -diffPos.norm() / 5.f + 1.0));
89 diffPos = baseSpeedFactor * diffPos * sig;
92 if (diffPosError < minTranslationSpeed && diffPosError != 0)
94 diffPos *= (minTranslationSpeed / diffPosError);
97 else if (diffPosError > maxTranslationSpeed && diffPosError != 0)
99 diffPos *= (maxTranslationSpeed / diffPosError);
102 if (diffPosError < in.parameters.positionalAccuracy)
104 diffPos = Eigen::Vector3f::Zero();
112 a.pose(currentTCPPoseGlobal);
113 a.direction(diffPos);
114 a.length(diffPos.norm()*3);
118 b.pose(tcpTargetPoseGlobal);
119 b.radius(diffPos.norm());
123 o.file(
"RobotAPI", robotAPIHandFileName);
124 o.pose(handRootTargetPoseGlobal);
130 Eigen::Vector3f angles(0, 0, 0);
134 Eigen::Matrix3f diffRot = tcpTargetPoseGlobal.block<3, 3>(0, 0) * currentTCPPoseGlobal.block<3, 3>(0, 0).inverse();
135 angles = VirtualRobot::MathTools::eigen3f2rpy(diffRot);
136 float anglesError = angles.norm();
147 if (anglesError < minRotationSpeed && anglesError != 0)
149 angles *= (minRotationSpeed / anglesError);
152 else if (anglesError > maxRotationSpeed && anglesError != 0)
154 angles *= (maxRotationSpeed / anglesError);
157 if (anglesError < in.parameters.orientationalAccuracy)
159 angles = Eigen::Vector3f::Zero();
172 auto cartesianError = diffPosError;
173 auto angleError = anglesError;
177 "Current Thresholds: " << in.parameters.positionalAccuracy <<
"mm, " << in.parameters.orientationalAccuracy * 180.0f /
M_PI <<
"deg";
179 ARMARX_INFO <<
deactivateSpam(0.5) <<
"Request to move TCP: angle vel: (" << angleVelocity.x <<
", " << angleVelocity.y <<
", " << angleVelocity.z <<
")\n"
180 <<
"catesian vel: " << cartesianVelocity.x <<
", " << cartesianVelocity.y <<
", " << cartesianVelocity.z <<
")";
182 if (angleError <= in.parameters.orientationalAccuracy && cartesianError <= in.parameters.positionalAccuracy)
191 Skill::ExitResult MoveTCPToTargetPose::exit(
const SpecializedExitInput &in)
198 ARMARX_WARNING <<
"Unable to get robot from robotstatememory. Abort exit method.";
202 std::string tcpName = robot->getRobotNodeSet(in.parameters.kinematicChainName)->getTCP()->getName();
206 if (!tcpControlUnitRequestedOnStart)