TrajectoryFollowingController.cpp
Go to the documentation of this file.
2
3#include <algorithm>
4#include <cmath>
5#include <limits>
6#include <vector>
7
8#include <SimoxUtility/math/convert/mat4f_to_pos.h>
9#include <SimoxUtility/math/convert/mat4f_to_rpy.h>
10
14#include <ArmarXCore/interface/serialization/Eigen/Eigen_fdi.h>
15
18
23#include <armarx/navigation/trajectory_control/global/aron/TrajectoryFollowingControllerParams.aron.generated.h>
26
28{
29 // TrajectoryFollowingControllerParams
30
36
39 {
40 arondto::TrajectoryFollowingControllerParams dto;
41
44
45 return dto.toAron();
46 }
47
50 {
51 arondto::TrajectoryFollowingControllerParams dto;
52 dto.fromAron(dict);
53
56
57 return bo;
58 }
59
60 // TrajectoryFollowingController
61
63 params(params),
64 pidPos(params.pidPos.Kp,
65 params.pidPos.Ki,
66 params.pidPos.Kd,
67 std::numeric_limits<double>::max(),
68 std::numeric_limits<double>::max(),
69 false,
70 std::vector<bool>{false, false, false}),
71 pidPosTarget(params.pidPos.Kp,
72 params.pidPos.Ki,
73 params.pidPos.Kd,
74 std::numeric_limits<double>::max(),
75 std::numeric_limits<double>::max(),
76 false,
77 std::vector<bool>{false, false, false}),
78 pidOri(params.pidOri.Kp,
79 params.pidOri.Ki,
80 params.pidOri.Kd,
81 std::numeric_limits<double>::max(),
82 std::numeric_limits<double>::max(),
83 false,
84 std::vector<bool>{true, true, true}),
85 pidOriTarget(params.pidOri.Kp,
86 params.pidOri.Ki,
87 params.pidOri.Kd,
88 std::numeric_limits<double>::max(),
89 std::numeric_limits<double>::max(),
90 false,
91 std::vector<bool>{true, true, true})
92 {
93 ARMARX_IMPORTANT << "Trajectory following controller params: "
94 << VAROUT(params.limits.linear) << ", " << VAROUT(params.limits.angular);
95 }
96
99 {
100 if (params.limits.linear == 0 or params.limits.angular == 0)
101 {
102 return core::Twist{.linear = Eigen::Vector3f::Zero(),
103 .angular = Eigen::Vector3f::Zero()};
104 }
105
106 ARMARX_CHECK_POSITIVE(params.limits.linear);
107 ARMARX_CHECK_POSITIVE(params.limits.angular);
108
109 core::AngularVelocity angularLimit = Eigen::Vector3f::Ones() * params.limits.angular;
110
111 ARMARX_CHECK(std::isfinite(params.limits.linear));
112 ARMARX_CHECK(angularLimit.allFinite());
113
114 // for all entries, scale should be less than 1
115 // velocity limit is for total cartesian velocity, not a limit for each coordinate direction
116 const float scalePos = twist.linear.norm() / params.limits.linear;
117 const auto scaleOri = twist.angular.cwiseAbs().cwiseQuotient(angularLimit.cwiseAbs());
118
119 // ARMARX_CHECK(scalePos.allFinite());
120 ARMARX_CHECK(scaleOri.allFinite());
121
122 const float scaleMax = std::max(scalePos, scaleOri.maxCoeff());
123
124 if (scaleMax < 1.0F) // both linear and angular velocity in bounds?
125 {
126 return twist;
127 }
128
129 ARMARX_CHECK(not std::isnan(scaleMax));
130
131 // scale such that no limit is violated
132 twist.linear /= scaleMax;
133 twist.angular /= scaleMax;
134
135 // constexpr float eps = 0.001;
136
137 // pedantic checks
138 // ARMARX_CHECK_LESS_EQUAL(std::abs(twist.linear.x()), params.limits.linear + eps);
139 //ARMARX_CHECK_LESS_EQUAL(std::abs(twist.linear.y()), params.limits.linear + eps);
140 //ARMARX_CHECK_LESS_EQUAL(std::abs(twist.linear.z()), params.limits.linear + eps);
141 //ARMARX_CHECK_LESS_EQUAL(std::abs(twist.angular.x()), params.limits.angular + eps);
142 //ARMARX_CHECK_LESS_EQUAL(std::abs(twist.angular.y()), params.limits.angular + eps);
143 //ARMARX_CHECK_LESS_EQUAL(std::abs(twist.angular.z()), params.limits.angular + eps);
144
145 return twist;
146 }
147
150 {
151 twist.linear *= params.velocityFactor;
152 twist.angular *= params.velocityFactor;
153
154 return twist;
155 }
156
157 void
159 {
161 << "Scaling factor for velocity may not be negative, but is " << p.velocityFactor;
163 << "Scaling factor for velocity may not be > 1, but is " << p.velocityFactor;
164
165 // only changes to these to parameters are actually relevant for this class
166 params.velocityFactor = p.velocityFactor;
167 params.limits = p.limits;
168 }
169
172 const core::Pose& global_T_robot)
173 {
174 using simox::math::mat4f_to_pos;
175 using simox::math::mat4f_to_rpy;
176
177 const core::Pose currentPose(global_T_robot);
178 const float currentOrientation = mat4f_to_rpy(currentPose.matrix()).z();
179
180 if (trajectory.points().empty())
181 {
182 ARMARX_INFO << "Trajectory is empty.";
184 .twist = core::Twist::Zero(),
185 .dropPoint = {.waypoint = {.pose = core::Pose::Identity()}, .velocity = 0},
186 .isFinalSegment = true,
187 .currentOrientation = currentOrientation,
188 .desiredOrientation = currentOrientation,
189 .orientationError = 0,
190 .positionError = 0};
191 }
192
193
194 const auto projectedPose = trajectory.getProjection(
195 currentPose.translation(), core::VelocityInterpolation::LinearInterpolation);
196
197
198 pidPos.update(mat4f_to_pos(currentPose.matrix()),
199 mat4f_to_pos(projectedPose.projection.waypoint.pose.matrix()));
200 pidOri.update(mat4f_to_rpy(currentPose.matrix()),
201 mat4f_to_rpy(projectedPose.projection.waypoint.pose.matrix()));
202
203 const float desiredOrientation =
204 mat4f_to_rpy(projectedPose.projection.waypoint.pose.matrix()).z();
205
206 const core::Twist twist = [&]() -> core::Twist
207 {
208 // on the final segment, bahavior differs
209 if (projectedPose.segment == core::Projection::Segment::FINAL)
210 {
211
212 ARMARX_VERBOSE << deactivateSpam(1) << "final segment";
213 // TODO fairly inefficient to do this every time
214 pidPos.reset();
215 pidOri.reset();
216
217 pidPosTarget.update(currentPose.translation(),
218 trajectory.points().back().waypoint.pose.translation());
219
220 pidOriTarget.update(
221 mat4f_to_rpy(currentPose.matrix()),
222 mat4f_to_rpy(trajectory.points().back().waypoint.pose.matrix()));
223
224 return core::Twist{.linear = pidPosTarget.getControlValue(),
225 .angular = pidOriTarget.getControlValue()};
226 }
227
228 // pidPosTarget not used yet
229 // TODO fairly inefficient to do this every time
230 pidPosTarget.reset();
231
232 // the "standard" case following the trajectory
233 const Eigen::Vector3f desiredMovementDirection =
234 (projectedPose.wayPointAfter.waypoint.pose.translation() -
235 projectedPose.wayPointBefore.waypoint.pose.translation())
236 .normalized();
237
238 const float ffVel = projectedPose.projection.velocity;
239 ARMARX_CHECK_FINITE(ffVel);
240 ARMARX_CHECK_LESS(ffVel, 3000); // 3 m/s should be sufficient, right?
241
242 const auto feedforwardVelocity = desiredMovementDirection * ffVel;
243
244 ARMARX_VERBOSE << deactivateSpam(1) << "Feed forward direction "
245 << feedforwardVelocity.normalized();
246 ARMARX_VERBOSE << deactivateSpam(1) << "Feed forward velocity " << feedforwardVelocity;
247 ARMARX_VERBOSE << deactivateSpam(1) << "Control value " << pidPos.getControlValue();
248
249 return core::Twist{.linear = pidPos.getControlValue() + feedforwardVelocity,
250 .angular = pidOri.getControlValue()};
251 }();
252
253 const auto twistLimited = applyTwistLimits(twist);
254 ARMARX_VERBOSE << deactivateSpam(1) << "Twist limited linear "
255 << twistLimited.linear.transpose();
256 ARMARX_VERBOSE << deactivateSpam(1) << "Twist limited angular "
257 << twistLimited.angular.transpose();
258
259 const auto twistScaled = applyVelocityFactor(twistLimited);
260 ARMARX_VERBOSE << deactivateSpam(1) << "Twist scaled linear "
261 << twistScaled.linear.transpose();
262 ARMARX_VERBOSE << deactivateSpam(1) << "Twist scaled angular "
263 << twistScaled.angular.transpose();
264
265 // convert to the robot's base frame
266 const auto& twistGlobal = twistScaled;
267
268 core::Twist twistLocal;
269 twistLocal.linear = global_T_robot.linear().inverse() * twistGlobal.linear;
270 // TODO if not in 2D, then this must be changed!
271 twistLocal.angular = twistGlobal.angular;
272
273
274 const bool isFinalSegment = projectedPose.segment == core::Projection::Segment::FINAL;
275
277 .twist = twistLocal,
278 .dropPoint = projectedPose.projection,
279 .isFinalSegment = isFinalSegment,
280 .currentOrientation = currentOrientation,
281 .desiredOrientation = desiredOrientation,
282 .orientationError = std::abs(currentOrientation - desiredOrientation),
283 .positionError = (global_T_robot.translation() -
284 trajectory.points().back().waypoint.pose.translation())
285 .head<2>()
286 .norm()};
287 }
288
289} // namespace armarx::navigation::traj_ctrl::global
SpamFilterDataPtr deactivateSpam(SpamFilterDataPtr const &spamFilter, float deactivationDurationSec, const std::string &identifier, bool deactivate)
Definition Logging.cpp:75
#define VAROUT(x)
TrajectoryControllerResult control(const core::GlobalTrajectory &trajectory, const core::Pose &global_T_robot) override
#define ARMARX_CHECK_FINITE(number)
This macro evaluates whether number is finite (not nan or inf) and if it turns out to be false it wil...
#define ARMARX_CHECK(expression)
Shortcut for ARMARX_CHECK_EXPRESSION.
#define ARMARX_CHECK_POSITIVE(number)
This macro evaluates whether number is positive (> 0) and if it turns out to be false it will throw a...
#define ARMARX_CHECK_LESS(lhs, rhs)
This macro evaluates whether lhs is less (<) than rhs and if it turns out to be false it will throw a...
#define ARMARX_INFO
The normal logging level.
Definition Logging.h:181
#define ARMARX_IMPORTANT
The logging level for always important information, but expected behaviour (in contrast to ARMARX_WAR...
Definition Logging.h:190
#define ARMARX_VERBOSE
The logging level for verbose information.
Definition Logging.h:187
std::shared_ptr< Dict > DictPtr
Definition Dict.h:42
Eigen::Isometry3f Pose
Definition basic_types.h:31
Eigen::Vector3f AngularVelocity
Definition basic_types.h:44
void fromAron(const arondto::TrajectoryControllerParams &dto, TrajectoryControllerParams &bo)
void toAron(arondto::TrajectoryControllerParams &dto, const TrajectoryControllerParams &bo)
std::vector< T > max(const std::vector< T > &v1, const std::vector< T > &v2)
bool isfinite(const std::vector< T, Ts... > &v)
Definition algorithm.h:366
double norm(const Point &a)
Definition point.hpp:102
static TrajectoryFollowingControllerParams FromAron(const aron::data::DictPtr &dict)