moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
ruckig_traj_smoothing.cpp
Go to the documentation of this file.
1/*******************************************************************************
2 * BSD 3-Clause License
3 *
4 * Copyright (c) 2021, PickNik Robotics
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions are met:
9 *
10 * * Redistributions of source code must retain the above copyright notice, this
11 * list of conditions and the following disclaimer.
12 *
13 * * Redistributions in binary form must reproduce the above copyright notice,
14 * this list of conditions and the following disclaimer in the documentation
15 * and/or other materials provided with the distribution.
16 *
17 * * Neither the name of the copyright holder nor the names of its
18 * contributors may be used to endorse or promote products derived from
19 * this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24 * ARE
25 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32 *******************************************************************************/
33
34/* Author: Jack Center, Wyatt Rees, Andy Zelenak, Stephanie Eng */
35
36#include <rclcpp/logger.hpp>
37#include <rclcpp/logging.hpp>
38#include <algorithm>
39#include <cmath>
40#include <Eigen/Geometry>
41#include <limits>
43#include <vector>
45
47{
48namespace
49{
50constexpr double DEFAULT_MAX_VELOCITY = 5; // rad/s
51constexpr double DEFAULT_MAX_ACCELERATION = 10; // rad/s^2
52constexpr double DEFAULT_MAX_JERK = 1000; // rad/s^3
53constexpr double MAX_DURATION_EXTENSION_FACTOR = 50.0;
54constexpr double DURATION_EXTENSION_FRACTION = 1.1;
55// If "mitigate_overshoot" is enabled, overshoot is checked with this timestep
56constexpr double OVERSHOOT_CHECK_PERIOD = 0.01; // sec
57
58rclcpp::Logger getLogger()
59{
60 return moveit::getLogger("moveit.core.ruckig_traj_smoothing");
61}
62} // namespace
63
65 const double max_velocity_scaling_factor,
66 const double max_acceleration_scaling_factor, const bool mitigate_overshoot,
67 const double overshoot_threshold)
68{
69 if (!validateGroup(trajectory))
70 {
71 return false;
72 }
73
74 const size_t num_waypoints = trajectory.getWayPointCount();
75 if (num_waypoints < 2)
76 {
77 RCLCPP_WARN(getLogger(),
78 "Trajectory does not have enough points to smooth with Ruckig. Returning an unmodified trajectory.");
79 return true;
80 }
81
82 // Kinematic limits (vels/accels/jerks) from RobotModel
83 const moveit::core::JointModelGroup* const group = trajectory.getGroup();
84 const size_t num_dof = group->getVariableCount();
85 ruckig::InputParameter<ruckig::DynamicDOFs> ruckig_input{ num_dof };
86 if (!getRobotModelBounds(max_velocity_scaling_factor, max_acceleration_scaling_factor, group, ruckig_input))
87 {
88 RCLCPP_ERROR(getLogger(), "Error while retrieving kinematic limits (vel/accel/jerk) from RobotModel.");
89 return false;
90 }
91
92 return runRuckig(trajectory, ruckig_input, mitigate_overshoot, overshoot_threshold);
93}
94
96 const std::unordered_map<std::string, double>& velocity_limits,
97 const std::unordered_map<std::string, double>& acceleration_limits,
98 const std::unordered_map<std::string, double>& jerk_limits,
99 const double max_velocity_scaling_factor,
100 const double max_acceleration_scaling_factor, const bool mitigate_overshoot,
101 const double overshoot_threshold)
102{
103 if (!validateGroup(trajectory))
104 {
105 return false;
106 }
107
108 const size_t num_waypoints = trajectory.getWayPointCount();
109 if (num_waypoints < 2)
110 {
111 RCLCPP_WARN(getLogger(),
112 "Trajectory does not have enough points to smooth with Ruckig. Returning an unmodified trajectory.");
113 return true;
114 }
115
116 // Set default kinematic limits (vels/accels/jerks)
117 const moveit::core::JointModelGroup* const group = trajectory.getGroup();
118 const size_t num_dof = group->getVariableCount();
119 ruckig::InputParameter<ruckig::DynamicDOFs> ruckig_input{ num_dof };
120 if (!getRobotModelBounds(max_velocity_scaling_factor, max_acceleration_scaling_factor, group, ruckig_input))
121 {
122 RCLCPP_ERROR(getLogger(), "Error while retrieving kinematic limits (vel/accel/jerk) from RobotModel.");
123 return false;
124 }
125
126 // Check if custom limits were supplied as arguments to overwrite the defaults
127 const std::vector<std::string>& vars = group->getVariableNames();
128 const unsigned num_joints = group->getVariableCount();
129 for (size_t j = 0; j < num_joints; ++j)
130 {
131 // Velocity
132 auto it = velocity_limits.find(vars[j]);
133 if (it != velocity_limits.end())
134 {
135 ruckig_input.max_velocity.at(j) = it->second * max_velocity_scaling_factor;
136 }
137 // Acceleration
138 it = acceleration_limits.find(vars[j]);
139 if (it != acceleration_limits.end())
140 {
141 ruckig_input.max_acceleration.at(j) = it->second * max_acceleration_scaling_factor;
142 }
143 // Jerk
144 it = jerk_limits.find(vars[j]);
145 if (it != jerk_limits.end())
146 {
147 ruckig_input.max_jerk.at(j) = it->second;
148 }
149 }
150
151 return runRuckig(trajectory, ruckig_input, mitigate_overshoot, overshoot_threshold);
152}
153
155 const std::vector<moveit_msgs::msg::JointLimits>& joint_limits,
156 const double max_velocity_scaling_factor,
157 const double max_acceleration_scaling_factor)
158{
159 std::unordered_map<std::string, double> velocity_limits;
160 std::unordered_map<std::string, double> acceleration_limits;
161 std::unordered_map<std::string, double> jerk_limits;
162 for (const auto& limit : joint_limits)
163 {
164 // If custom limits are not defined here, they will be supplied from getRobotModelBounds() later
165 if (limit.has_velocity_limits)
166 {
167 velocity_limits[limit.joint_name] = limit.max_velocity;
168 }
169 if (limit.has_acceleration_limits)
170 {
171 acceleration_limits[limit.joint_name] = limit.max_acceleration;
172 }
173 if (limit.has_jerk_limits)
174 {
175 jerk_limits[limit.joint_name] = limit.max_jerk;
176 }
177 }
178 return applySmoothing(trajectory, velocity_limits, acceleration_limits, jerk_limits, max_velocity_scaling_factor,
179 max_acceleration_scaling_factor);
180}
181
182bool RuckigSmoothing::validateGroup(const robot_trajectory::RobotTrajectory& trajectory)
183{
184 const moveit::core::JointModelGroup* const group = trajectory.getGroup();
185 if (!group)
186 {
187 RCLCPP_ERROR(getLogger(), "The planner did not set the group the plan was computed for");
188 return false;
189 }
190 return true;
191}
192
193bool RuckigSmoothing::getRobotModelBounds(const double max_velocity_scaling_factor,
194 const double max_acceleration_scaling_factor,
195 const moveit::core::JointModelGroup* const group,
196 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input)
197{
198 const size_t num_dof = group->getVariableCount();
199 const std::vector<std::string>& vars = group->getVariableNames();
200 const moveit::core::RobotModel& rmodel = group->getParentModel();
201 for (size_t i = 0; i < num_dof; ++i)
202 {
203 const moveit::core::VariableBounds& bounds = rmodel.getVariableBounds(vars.at(i));
204
205 // This assumes min/max bounds are symmetric
206 if (bounds.velocity_bounded_)
207 {
208 ruckig_input.max_velocity.at(i) = max_velocity_scaling_factor * bounds.max_velocity_;
209 }
210 else
211 {
212 RCLCPP_WARN_STREAM_ONCE(getLogger(),
213 "Joint velocity limits are not defined. Using the default "
214 << DEFAULT_MAX_VELOCITY
215 << " rad/s. You can define velocity limits in the URDF or joint_limits.yaml.");
216 ruckig_input.max_velocity.at(i) = max_velocity_scaling_factor * DEFAULT_MAX_VELOCITY;
217 }
218 if (bounds.acceleration_bounded_)
219 {
220 ruckig_input.max_acceleration.at(i) = max_acceleration_scaling_factor * bounds.max_acceleration_;
221 }
222 else
223 {
224 RCLCPP_WARN_STREAM_ONCE(getLogger(),
225 "Joint acceleration limits are not defined. Using the default "
226 << DEFAULT_MAX_ACCELERATION
227 << " rad/s^2. You can define acceleration limits in the URDF or joint_limits.yaml.");
228 ruckig_input.max_acceleration.at(i) = max_acceleration_scaling_factor * DEFAULT_MAX_ACCELERATION;
229 }
230 ruckig_input.max_jerk.at(i) = bounds.jerk_bounded_ ? bounds.max_jerk_ : DEFAULT_MAX_JERK;
231 if (bounds.jerk_bounded_)
232 {
233 ruckig_input.max_jerk.at(i) = bounds.max_jerk_;
234 }
235 else
236 {
237 RCLCPP_WARN_STREAM_ONCE(getLogger(), "Joint jerk limits are not defined. Using the default "
238 << DEFAULT_MAX_JERK
239 << " rad/s^3. You can define jerk limits in joint_limits.yaml.");
240 ruckig_input.max_jerk.at(i) = DEFAULT_MAX_JERK;
241 }
242 }
243
244 return true;
245}
246
247bool RuckigSmoothing::runRuckig(robot_trajectory::RobotTrajectory& trajectory,
248 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input,
249 const bool mitigate_overshoot, const double overshoot_threshold)
250{
251 const size_t num_waypoints = trajectory.getWayPointCount();
252 const moveit::core::JointModelGroup* const group = trajectory.getGroup();
253 const size_t num_dof = group->getVariableCount();
254 ruckig::Trajectory<ruckig::DynamicDOFs, ruckig::StandardVector> ruckig_output(num_dof);
255
256 // This lib does not work properly when angles wrap, so we need to unwind the path first
257 trajectory.unwind();
258
259 // Initialize the smoother
260 ruckig::Ruckig<ruckig::DynamicDOFs> ruckig(num_dof, trajectory.getAverageSegmentDuration());
261 initializeRuckigState(*trajectory.getFirstWayPointPtr(), group, ruckig_input);
262
263 // Cache the trajectory in case we need to reset it
264 robot_trajectory::RobotTrajectory original_trajectory =
265 robot_trajectory::RobotTrajectory(trajectory, true /* deep copy */);
266
267 ruckig::Result ruckig_result;
268 double duration_extension_factor = 1;
269 bool smoothing_complete = false;
270 size_t waypoint_idx = 0;
271 while ((duration_extension_factor <= MAX_DURATION_EXTENSION_FACTOR) && !smoothing_complete)
272 {
273 while (waypoint_idx < num_waypoints - 1)
274 {
275 moveit::core::RobotStatePtr curr_waypoint = trajectory.getWayPointPtr(waypoint_idx);
276 moveit::core::RobotStatePtr next_waypoint = trajectory.getWayPointPtr(waypoint_idx + 1);
277
278 getNextRuckigInput(curr_waypoint, next_waypoint, group, ruckig_input);
279
280 // Run Ruckig
281 ruckig_result = ruckig.calculate(ruckig_input, ruckig_output);
282
283 // Step through the trajectory at the given OVERSHOOT_CHECK_PERIOD and check for overshoot.
284 // We will extend the duration to mitigate it.
285 bool overshoots = false;
286 if (mitigate_overshoot)
287 {
288 overshoots = checkOvershoot(ruckig_output, num_dof, ruckig_input, overshoot_threshold);
289 }
290
291 // The difference between Result::Working and Result::Finished is that Finished can be reached in one
292 // Ruckig timestep (constructor parameter). Both are acceptable for trajectories.
293 // (The difference is only relevant for streaming mode.)
294
295 // If successful and at the last trajectory segment
296 if (!overshoots && (waypoint_idx == num_waypoints - 2) &&
297 (ruckig_result == ruckig::Result::Working || ruckig_result == ruckig::Result::Finished))
298 {
299 trajectory.setWayPointDurationFromPrevious(waypoint_idx + 1, ruckig_output.get_duration());
300 smoothing_complete = true;
301 break;
302 }
303
304 // Extend the trajectory duration if Ruckig could not reach the waypoint successfully
305 if (overshoots || (ruckig_result != ruckig::Result::Working && ruckig_result != ruckig::Result::Finished))
306 {
307 duration_extension_factor *= DURATION_EXTENSION_FRACTION;
308 // Reset the trajectory
309 trajectory = robot_trajectory::RobotTrajectory(original_trajectory, true /* deep copy */);
310
311 const std::vector<int>& move_group_idx = group->getVariableIndexList();
312 extendTrajectoryDuration(duration_extension_factor, waypoint_idx, num_dof, move_group_idx, original_trajectory,
313 trajectory);
314
315 initializeRuckigState(*trajectory.getFirstWayPointPtr(), group, ruckig_input);
316 // Begin the for() loop again
317 break;
318 }
319 ++waypoint_idx;
320 }
321 }
322
323 if (duration_extension_factor > MAX_DURATION_EXTENSION_FACTOR)
324 {
325 RCLCPP_ERROR_STREAM(getLogger(),
326 "Ruckig extended the trajectory duration to its maximum and still did not find a solution");
327 }
328
329 if (ruckig_result != ruckig::Result::Working && ruckig_result != ruckig::Result::Finished)
330 {
331 RCLCPP_ERROR_STREAM(getLogger(), "Ruckig trajectory smoothing failed. Ruckig error: " << ruckig_result);
332 return false;
333 }
334
335 return true;
336}
337
338void RuckigSmoothing::extendTrajectoryDuration(const double duration_extension_factor, size_t waypoint_idx,
339 const size_t num_dof, const std::vector<int>& move_group_idx,
340 const robot_trajectory::RobotTrajectory& original_trajectory,
342{
343 trajectory.setWayPointDurationFromPrevious(waypoint_idx + 1,
344 duration_extension_factor *
345 original_trajectory.getWayPointDurationFromPrevious(waypoint_idx + 1));
346 // re-calculate waypoint velocity and acceleration
347 auto target_state = trajectory.getWayPointPtr(waypoint_idx + 1);
348 const auto prev_state = trajectory.getWayPointPtr(waypoint_idx);
349
350 double timestep = trajectory.getWayPointDurationFromPrevious(waypoint_idx + 1);
351
352 for (size_t joint = 0; joint < num_dof; ++joint)
353 {
354 target_state->setVariableVelocity(move_group_idx.at(joint),
355 (1 / duration_extension_factor) *
356 target_state->getVariableVelocity(move_group_idx.at(joint)));
357 double prev_velocity = prev_state->getVariableVelocity(move_group_idx.at(joint));
358 double curr_velocity = target_state->getVariableVelocity(move_group_idx.at(joint));
359 target_state->setVariableAcceleration(move_group_idx.at(joint), (curr_velocity - prev_velocity) / timestep);
360 }
361}
362
363void RuckigSmoothing::initializeRuckigState(const moveit::core::RobotState& first_waypoint,
364 const moveit::core::JointModelGroup* joint_group,
365 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input)
366{
367 const size_t num_dof = joint_group->getVariableCount();
368 const std::vector<int>& idx = joint_group->getVariableIndexList();
369
370 std::vector<double> current_positions_vector(num_dof);
371 std::vector<double> current_velocities_vector(num_dof);
372 std::vector<double> current_accelerations_vector(num_dof);
373
374 for (size_t i = 0; i < num_dof; ++i)
375 {
376 current_positions_vector.at(i) = first_waypoint.getVariablePosition(idx.at(i));
377 current_velocities_vector.at(i) = first_waypoint.getVariableVelocity(idx.at(i));
378 current_accelerations_vector.at(i) = first_waypoint.getVariableAcceleration(idx.at(i));
379 // Clamp velocities/accelerations in case they exceed the limit due to small numerical errors
380 current_velocities_vector.at(i) =
381 std::clamp(current_velocities_vector.at(i), -ruckig_input.max_velocity.at(i), ruckig_input.max_velocity.at(i));
382 current_accelerations_vector.at(i) = std::clamp(
383 current_accelerations_vector.at(i), -ruckig_input.max_acceleration.at(i), ruckig_input.max_acceleration.at(i));
384 }
385 std::copy_n(current_positions_vector.begin(), num_dof, ruckig_input.current_position.begin());
386 std::copy_n(current_velocities_vector.begin(), num_dof, ruckig_input.current_velocity.begin());
387 std::copy_n(current_accelerations_vector.begin(), num_dof, ruckig_input.current_acceleration.begin());
388}
389
390void RuckigSmoothing::getNextRuckigInput(const moveit::core::RobotStateConstPtr& current_waypoint,
391 const moveit::core::RobotStateConstPtr& next_waypoint,
392 const moveit::core::JointModelGroup* joint_group,
393 ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input)
394{
395 const size_t num_dof = joint_group->getVariableCount();
396 const std::vector<int>& idx = joint_group->getVariableIndexList();
397
398 for (size_t joint = 0; joint < num_dof; ++joint)
399 {
400 ruckig_input.current_position.at(joint) = current_waypoint->getVariablePosition(idx.at(joint));
401 ruckig_input.current_velocity.at(joint) = current_waypoint->getVariableVelocity(idx.at(joint));
402 ruckig_input.current_acceleration.at(joint) = current_waypoint->getVariableAcceleration(idx.at(joint));
403
404 // Target state is the next waypoint
405 ruckig_input.target_position.at(joint) = next_waypoint->getVariablePosition(idx.at(joint));
406 ruckig_input.target_velocity.at(joint) = next_waypoint->getVariableVelocity(idx.at(joint));
407 ruckig_input.target_acceleration.at(joint) = next_waypoint->getVariableAcceleration(idx.at(joint));
408
409 // Clamp velocities/accelerations in case they exceed the limit due to small numerical errors
410 ruckig_input.current_velocity.at(joint) =
411 std::clamp(ruckig_input.current_velocity.at(joint), -ruckig_input.max_velocity.at(joint),
412 ruckig_input.max_velocity.at(joint));
413 ruckig_input.current_acceleration.at(joint) =
414 std::clamp(ruckig_input.current_acceleration.at(joint), -ruckig_input.max_acceleration.at(joint),
415 ruckig_input.max_acceleration.at(joint));
416 ruckig_input.target_velocity.at(joint) =
417 std::clamp(ruckig_input.target_velocity.at(joint), -ruckig_input.max_velocity.at(joint),
418 ruckig_input.max_velocity.at(joint));
419 ruckig_input.target_acceleration.at(joint) =
420 std::clamp(ruckig_input.target_acceleration.at(joint), -ruckig_input.max_acceleration.at(joint),
421 ruckig_input.max_acceleration.at(joint));
422 }
423}
424
425bool RuckigSmoothing::checkOvershoot(ruckig::Trajectory<ruckig::DynamicDOFs, ruckig::StandardVector>& ruckig_trajectory,
426 const size_t num_dof, ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input,
427 const double overshoot_threshold)
428{
429 // For every timestep
430 for (double time_from_start = OVERSHOOT_CHECK_PERIOD; time_from_start < ruckig_trajectory.get_duration();
431 time_from_start += OVERSHOOT_CHECK_PERIOD)
432 {
433 std::vector<double> new_position(num_dof);
434 std::vector<double> new_velocity(num_dof);
435 std::vector<double> new_acceleration(num_dof);
436 ruckig_trajectory.at_time(time_from_start, new_position, new_velocity, new_acceleration);
437 // For every joint
438 for (size_t joint = 0; joint < num_dof; ++joint)
439 {
440 // If the sign of the error changed and the threshold difference was exceeded
441 double error = new_position[joint] - ruckig_input.target_position.at(joint);
442 if (((error / (ruckig_input.current_position.at(joint) - ruckig_input.target_position.at(joint))) < 0.0) &&
443 std::fabs(error) > overshoot_threshold)
444 {
445 return true;
446 }
447 }
448 }
449 return false;
450}
451} // namespace trajectory_processing
const RobotModel & getParentModel() const
Get the kinematic model this group is part of.
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up the joints included in this group. The number of returned...
const std::vector< int > & getVariableIndexList() const
Get the index locations in the complete robot state for all the variables in this group.
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition robot_model.h:76
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a specific variable. Throw an exception of variable is not found.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
double getVariableAcceleration(const std::string &variable) const
Get the acceleration of a particular variable. An exception is thrown if the variable is not known.
double getVariableVelocity(const std::string &variable) const
Get the velocity of a particular variable. An exception is thrown if the variable is not known.
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known.
Maintain a sequence of waypoints and the time durations between these waypoints.
moveit::core::RobotStatePtr & getWayPointPtr(std::size_t index)
RobotTrajectory & setWayPointDurationFromPrevious(std::size_t index, double value)
const moveit::core::JointModelGroup * getGroup() const
moveit::core::RobotStatePtr & getFirstWayPointPtr()
double getWayPointDurationFromPrevious(std::size_t index) const
static bool applySmoothing(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0, const bool mitigate_overshoot=false, const double overshoot_threshold=0.01)
Apply smoothing to a time-parameterized trajectory so that jerk limits are not violated.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79