5 #include <SimoxUtility/math/convert/mat4f_to_pos.h>
6 #include <SimoxUtility/math/convert/mat4f_to_rpy.h>
7 #include <SimoxUtility/math/convert/mat4f_to_xyyaw.h>
8 #include <VirtualRobot/Robot.h>
12 #include <ArmarXCore/interface/serialization/Eigen/Eigen_fdi.h>
20 #include <armarx/navigation/trajectory_control/global/aron/TrajectoryFollowingControllerParams.aron.generated.h>
37 arondto::TrajectoryFollowingControllerParams dto;
48 arondto::TrajectoryFollowingControllerParams dto;
61 pidPos(params.pidPos.Kp,
64 std::numeric_limits<double>::
max(),
65 std::numeric_limits<double>::
max(),
67 std::vector<bool>{
false,
false,
false}),
68 pidPosTarget(params.pidPos.Kp,
74 std::vector<bool>{
false,
false,
false}),
75 pidOri(params.pidOri.Kp,
81 std::vector<bool>{
true,
true,
true}),
82 pidOriTarget(params.pidOri.Kp,
88 std::vector<bool>{
true,
true,
true})
91 <<
VAROUT(params.limits.linear) <<
", " <<
VAROUT(params.limits.angular);
107 const float scalePos = twist.
linear.norm() / limits.linear.norm();
108 const auto scaleOri = twist.
angular.cwiseAbs().cwiseQuotient(limits.angular.cwiseAbs());
113 const float scaleMax =
std::max(scalePos, scaleOri.maxCoeff());
143 using simox::math::mat4f_to_pos;
144 using simox::math::mat4f_to_rpy;
147 const float currentOrientation = mat4f_to_rpy(currentPose.matrix()).z();
149 if (trajectory.
points().empty())
155 .isFinalSegment =
true,
156 .currentOrientation = currentOrientation,
157 .desiredOrientation = currentOrientation,
158 .orientationError = 0,
167 pidPos.
update(mat4f_to_pos(currentPose.matrix()),
168 mat4f_to_pos(projectedPose.projection.waypoint.pose.matrix()));
169 pidOri.
update(mat4f_to_rpy(currentPose.matrix()),
170 mat4f_to_rpy(projectedPose.projection.waypoint.pose.matrix()));
172 const float desiredOrientation =
173 mat4f_to_rpy(projectedPose.projection.waypoint.pose.matrix()).z();
186 pidPosTarget.
update(currentPose.translation(),
187 trajectory.
points().back().waypoint.pose.translation());
190 mat4f_to_rpy(currentPose.matrix()),
191 mat4f_to_rpy(trajectory.
points().back().waypoint.pose.matrix()));
199 pidPosTarget.
reset();
202 const Eigen::Vector3f desiredMovementDirection =
203 (projectedPose.wayPointAfter.waypoint.pose.translation() -
204 projectedPose.wayPointBefore.waypoint.pose.translation())
207 const float ffVel = projectedPose.projection.velocity;
211 const auto feedforwardVelocity = desiredMovementDirection * ffVel;
214 << feedforwardVelocity.normalized();
227 const auto& twistGlobal = twistLimited;
230 twistLocal.
linear = global_T_robot.linear().inverse() * twistGlobal.linear;
232 twistLocal.
angular = twistGlobal.angular;
239 .dropPoint = projectedPose.projection,
240 .isFinalSegment = isFinalSegment,
241 .currentOrientation = currentOrientation,
242 .desiredOrientation = desiredOrientation,
243 .orientationError =
std::abs(currentOrientation - desiredOrientation),
244 .positionError = (global_T_robot.translation() -
245 trajectory.
points().back().waypoint.pose.translation())