8 #include <SimoxUtility/math/convert/mat4f_to_pos.h>
9 #include <SimoxUtility/math/convert/mat4f_to_rpy.h>
14 #include <ArmarXCore/interface/serialization/Eigen/Eigen_fdi.h>
23 #include <armarx/navigation/trajectory_control/global/aron/TrajectoryFollowingControllerParams.aron.generated.h>
40 arondto::TrajectoryFollowingControllerParams dto;
51 arondto::TrajectoryFollowingControllerParams dto;
64 pidPos(params.pidPos.Kp,
67 std::numeric_limits<double>::
max(),
68 std::numeric_limits<double>::
max(),
70 std::vector<bool>{
false,
false,
false}),
71 pidPosTarget(params.pidPos.Kp,
77 std::vector<bool>{
false,
false,
false}),
78 pidOri(params.pidOri.Kp,
84 std::vector<bool>{
true,
true,
true}),
85 pidOriTarget(params.pidOri.Kp,
91 std::vector<bool>{
true,
true,
true})
94 <<
VAROUT(params.limits.linear) <<
", " <<
VAROUT(params.limits.angular);
103 .angular = Eigen::Vector3f::Zero()};
116 const float scalePos = twist.
linear.norm() / limits.linear.norm();
117 const auto scaleOri = twist.
angular.cwiseAbs().cwiseQuotient(limits.angular.cwiseAbs());
122 const float scaleMax =
std::max(scalePos, scaleOri.maxCoeff());
158 using simox::math::mat4f_to_pos;
159 using simox::math::mat4f_to_rpy;
162 const float currentOrientation = mat4f_to_rpy(currentPose.matrix()).z();
164 if (trajectory.
points().empty())
170 .isFinalSegment =
true,
171 .currentOrientation = currentOrientation,
172 .desiredOrientation = currentOrientation,
173 .orientationError = 0,
182 pidPos.
update(mat4f_to_pos(currentPose.matrix()),
183 mat4f_to_pos(projectedPose.projection.waypoint.pose.matrix()));
184 pidOri.
update(mat4f_to_rpy(currentPose.matrix()),
185 mat4f_to_rpy(projectedPose.projection.waypoint.pose.matrix()));
187 const float desiredOrientation =
188 mat4f_to_rpy(projectedPose.projection.waypoint.pose.matrix()).z();
201 pidPosTarget.
update(currentPose.translation(),
202 trajectory.
points().back().waypoint.pose.translation());
205 mat4f_to_rpy(currentPose.matrix()),
206 mat4f_to_rpy(trajectory.
points().back().waypoint.pose.matrix()));
214 pidPosTarget.
reset();
217 const Eigen::Vector3f desiredMovementDirection =
218 (projectedPose.wayPointAfter.waypoint.pose.translation() -
219 projectedPose.wayPointBefore.waypoint.pose.translation())
222 const float ffVel = projectedPose.projection.velocity;
226 const auto feedforwardVelocity = desiredMovementDirection * ffVel;
229 << feedforwardVelocity.normalized();
242 const auto& twistGlobal = twistLimited;
245 twistLocal.
linear = global_T_robot.linear().inverse() * twistGlobal.linear;
247 twistLocal.
angular = twistGlobal.angular;
254 .dropPoint = projectedPose.projection,
255 .isFinalSegment = isFinalSegment,
256 .currentOrientation = currentOrientation,
257 .desiredOrientation = desiredOrientation,
258 .orientationError =
std::abs(currentOrientation - desiredOrientation),
259 .positionError = (global_T_robot.translation() -
260 trajectory.
points().back().waypoint.pose.translation())