moveit2
The MoveIt Motion Planning Framework for ROS 2.
iterative_time_parameterization.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
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
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ken Anderson */
36 
38 #include <moveit_msgs/msg/joint_limits.hpp>
40 #include <rclcpp/logger.hpp>
41 #include <rclcpp/logging.hpp>
42 
43 namespace trajectory_processing
44 {
45 static const double DEFAULT_VEL_MAX = 1.0;
46 static const double DEFAULT_ACCEL_MAX = 1.0;
47 static const double ROUNDING_THRESHOLD = 0.01;
48 
49 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_trajectory_processing.iterative_time_parameterization");
50 
52  double max_time_change_per_it)
53  : max_iterations_(max_iterations), max_time_change_per_it_(max_time_change_per_it)
54 {
55 }
56 
57 #if 0 // unused functions
58 namespace
59 {
60 void printPoint(const trajectory_msgs::msg::JointTrajectoryPoint& point, std::size_t i)
61 {
62  RCLCPP_DEBUG(LOGGER, " time [%zu]= %f", i, point.time_from_start.sec + point.time_from_start.nanosec / 1e9);
63  if (point.positions.size() >= 7)
64  {
65  RCLCPP_DEBUG(LOGGER, " pos_ [%zu]= %f %f %f %f %f %f %f", i, point.positions[0], point.positions[1],
66  point.positions[2], point.positions[3], point.positions[4], point.positions[5], point.positions[6]);
67  }
68  if (point.velocities.size() >= 7)
69  {
70  RCLCPP_DEBUG(LOGGER, " vel_ [%zu]= %f %f %f %f %f %f %f", i, point.velocities[0], point.velocities[1],
71  point.velocities[2], point.velocities[3], point.velocities[4], point.velocities[5],
72  point.velocities[6]);
73  }
74  if (point.accelerations.size() >= 7)
75  {
76  RCLCPP_DEBUG(LOGGER, " acc_ [%zu]= %f %f %f %f %f %f %f", i, point.accelerations[0], point.accelerations[1],
77  point.accelerations[2], point.accelerations[3], point.accelerations[4], point.accelerations[5],
78  point.accelerations[6]);
79  }
80 }
81 
82 void printStats(const trajectory_msgs::msg::JointTrajectory& trajectory,
83  const std::vector<moveit_msgs::msg::JointLimits>& limits)
84 {
85  RCLCPP_DEBUG(LOGGER, "jointNames= %s %s %s %s %s %s %s", limits[0].joint_name.c_str(), limits[1].joint_name.c_str(),
86  limits[2].joint_name.c_str(), limits[3].joint_name.c_str(), limits[4].joint_name.c_str(),
87  limits[5].joint_name.c_str(), limits[6].joint_name.c_str());
88  RCLCPP_DEBUG(LOGGER, "maxVelocities= %f %f %f %f %f %f %f", limits[0].max_velocity, limits[1].max_velocity,
89  limits[2].max_velocity, limits[3].max_velocity, limits[4].max_velocity, limits[5].max_velocity,
90  limits[6].max_velocity);
91  RCLCPP_DEBUG(LOGGER, "maxAccelerations= %f %f %f %f %f %f %f", limits[0].max_acceleration, limits[1].max_acceleration,
92  limits[2].max_acceleration, limits[3].max_acceleration, limits[4].max_acceleration,
93  limits[5].max_acceleration, limits[6].max_acceleration);
94  // for every point in time:
95  for (std::size_t i = 0; i < trajectory.points.size(); ++i)
96  printPoint(trajectory.points[i], i);
97 }
98 } // namespace
99 #endif
100 
101 // Applies velocity
102 void IterativeParabolicTimeParameterization::applyVelocityConstraints(robot_trajectory::RobotTrajectory& rob_trajectory,
103  std::vector<double>& time_diff,
104  const double max_velocity_scaling_factor) const
105 {
106  const moveit::core::JointModelGroup* group = rob_trajectory.getGroup();
107  const std::vector<std::string>& vars = group->getVariableNames();
108  const std::vector<int>& idx = group->getVariableIndexList();
109  const moveit::core::RobotModel& rmodel = group->getParentModel();
110  const int num_points = rob_trajectory.getWayPointCount();
111 
112  double velocity_scaling_factor = 1.0;
113 
114  if (max_velocity_scaling_factor > 0.0 && max_velocity_scaling_factor <= 1.0)
115  velocity_scaling_factor = max_velocity_scaling_factor;
116  else if (max_velocity_scaling_factor == 0.0)
117  {
118  RCLCPP_DEBUG(LOGGER, "A max_velocity_scaling_factor of 0.0 was specified, defaulting to %f instead.",
119  velocity_scaling_factor);
120  }
121  else
122  {
123  RCLCPP_WARN(LOGGER, "Invalid max_velocity_scaling_factor %f specified, defaulting to %f instead.",
124  max_velocity_scaling_factor, velocity_scaling_factor);
125  }
126  for (int i = 0; i < num_points - 1; ++i)
127  {
128  const moveit::core::RobotStatePtr& curr_waypoint = rob_trajectory.getWayPointPtr(i);
129  const moveit::core::RobotStatePtr& next_waypoint = rob_trajectory.getWayPointPtr(i + 1);
130 
131  for (std::size_t j = 0; j < vars.size(); ++j)
132  {
133  double v_max = DEFAULT_VEL_MAX;
134  const moveit::core::VariableBounds& b = rmodel.getVariableBounds(vars[j]);
135  if (b.velocity_bounded_)
136  v_max =
137  std::min(fabs(b.max_velocity_ * velocity_scaling_factor), fabs(b.min_velocity_ * velocity_scaling_factor));
138  const double dq1 = curr_waypoint->getVariablePosition(idx[j]);
139  const double dq2 = next_waypoint->getVariablePosition(idx[j]);
140  const double t_min = std::abs(dq2 - dq1) / v_max;
141  if (t_min > time_diff[i])
142  time_diff[i] = t_min;
143  }
144  }
145 }
146 
147 // Iteratively expand dt1 interval by a constant factor until within acceleration constraint
148 // In the future we may want to solve to quadratic equation to get the exact timing interval.
149 // To do this, use the CubicTrajectory::quadSolve() function in cubic_trajectory.h
150 double IterativeParabolicTimeParameterization::findT1(const double dq1, const double dq2, double dt1, const double dt2,
151  const double a_max) const
152 {
153  const double mult_factor = 1.01;
154  double v1 = (dq1) / dt1;
155  double v2 = (dq2) / dt2;
156  double a = 2.0 * (v2 - v1) / (dt1 + dt2);
157 
158  while (std::abs(a) > a_max)
159  {
160  v1 = (dq1) / dt1;
161  v2 = (dq2) / dt2;
162  a = 2.0 * (v2 - v1) / (dt1 + dt2);
163  dt1 *= mult_factor;
164  }
165 
166  return dt1;
167 }
168 
169 double IterativeParabolicTimeParameterization::findT2(const double dq1, const double dq2, const double dt1, double dt2,
170  const double a_max) const
171 {
172  const double mult_factor = 1.01;
173  double v1 = (dq1) / dt1;
174  double v2 = (dq2) / dt2;
175  double a = 2.0 * (v2 - v1) / (dt1 + dt2);
176 
177  while (std::abs(a) > a_max)
178  {
179  v1 = (dq1) / dt1;
180  v2 = (dq2) / dt2;
181  a = 2.0 * (v2 - v1) / (dt1 + dt2);
182  dt2 *= mult_factor;
183  }
184 
185  return dt2;
186 }
187 
188 namespace
189 {
190 // Takes the time differences, and updates the timestamps, velocities and accelerations
191 // in the trajectory.
192 void updateTrajectory(robot_trajectory::RobotTrajectory& rob_trajectory, const std::vector<double>& time_diff)
193 {
194  // Error check
195  if (time_diff.empty())
196  return;
197 
198  double time_sum = 0.0;
199 
200  moveit::core::RobotStatePtr prev_waypoint;
201  moveit::core::RobotStatePtr curr_waypoint;
202  moveit::core::RobotStatePtr next_waypoint;
203 
204  const moveit::core::JointModelGroup* group = rob_trajectory.getGroup();
205  const std::vector<std::string>& vars = group->getVariableNames();
206  const std::vector<int>& idx = group->getVariableIndexList();
207 
208  int num_points = rob_trajectory.getWayPointCount();
209 
210  rob_trajectory.setWayPointDurationFromPrevious(0, time_sum);
211 
212  // Times
213  for (int i = 1; i < num_points; ++i)
214  // Update the time between the waypoints in the robot_trajectory.
215  rob_trajectory.setWayPointDurationFromPrevious(i, time_diff[i - 1]);
216 
217  // Return if there is only one point in the trajectory!
218  if (num_points <= 1)
219  return;
220 
221  // Accelerations
222  for (int i = 0; i < num_points; ++i)
223  {
224  curr_waypoint = rob_trajectory.getWayPointPtr(i);
225 
226  if (i > 0)
227  prev_waypoint = rob_trajectory.getWayPointPtr(i - 1);
228 
229  if (i < num_points - 1)
230  next_waypoint = rob_trajectory.getWayPointPtr(i + 1);
231 
232  for (std::size_t j = 0; j < vars.size(); ++j)
233  {
234  double q1;
235  double q2;
236  double q3;
237  double dt1;
238  double dt2;
239 
240  if (i == 0)
241  {
242  // First point
243  q1 = next_waypoint->getVariablePosition(idx[j]);
244  q2 = curr_waypoint->getVariablePosition(idx[j]);
245  q3 = q1;
246 
247  dt1 = dt2 = time_diff[i];
248  }
249  else if (i < num_points - 1)
250  {
251  // middle points
252  q1 = prev_waypoint->getVariablePosition(idx[j]);
253  q2 = curr_waypoint->getVariablePosition(idx[j]);
254  q3 = next_waypoint->getVariablePosition(idx[j]);
255 
256  dt1 = time_diff[i - 1];
257  dt2 = time_diff[i];
258  }
259  else
260  {
261  // last point
262  q1 = prev_waypoint->getVariablePosition(idx[j]);
263  q2 = curr_waypoint->getVariablePosition(idx[j]);
264  q3 = q1;
265 
266  dt1 = dt2 = time_diff[i - 1];
267  }
268 
269  double v1, v2, a;
270 
271  bool start_velocity = false;
272  if (dt1 == 0.0 || dt2 == 0.0)
273  {
274  v1 = 0.0;
275  v2 = 0.0;
276  a = 0.0;
277  }
278  else
279  {
280  if (i == 0)
281  {
282  if (curr_waypoint->hasVelocities())
283  {
284  start_velocity = true;
285  v1 = curr_waypoint->getVariableVelocity(idx[j]);
286  }
287  }
288  v1 = start_velocity ? v1 : (q2 - q1) / dt1;
289  // v2 = (q3-q2)/dt2;
290  v2 = start_velocity ? v1 : (q3 - q2) / dt2; // Needed to ensure continuous velocity for first point
291  a = 2.0 * (v2 - v1) / (dt1 + dt2);
292  }
293 
294  curr_waypoint->setVariableVelocity(idx[j], (v2 + v1) / 2.0);
295  curr_waypoint->setVariableAcceleration(idx[j], a);
296  }
297  }
298 }
299 } // namespace
300 
301 // Applies Acceleration constraints
302 void IterativeParabolicTimeParameterization::applyAccelerationConstraints(
303  robot_trajectory::RobotTrajectory& rob_trajectory, std::vector<double>& time_diff,
304  const double max_acceleration_scaling_factor) const
305 {
306  moveit::core::RobotStatePtr prev_waypoint;
307  moveit::core::RobotStatePtr curr_waypoint;
308  moveit::core::RobotStatePtr next_waypoint;
309 
310  const moveit::core::JointModelGroup* group = rob_trajectory.getGroup();
311  const std::vector<std::string>& vars = group->getVariableNames();
312  const std::vector<int>& idx = group->getVariableIndexList();
313  const moveit::core::RobotModel& rmodel = group->getParentModel();
314 
315  const int num_points = rob_trajectory.getWayPointCount();
316  const unsigned int num_joints = group->getVariableCount();
317  int num_updates = 0;
318  int iteration = 0;
319  bool backwards = false;
320  double q1;
321  double q2;
322  double q3;
323  double dt1;
324  double dt2;
325  double v1;
326  double v2;
327  double a;
328 
329  double acceleration_scaling_factor = 1.0;
330 
331  if (max_acceleration_scaling_factor > 0.0 && max_acceleration_scaling_factor <= 1.0)
332  acceleration_scaling_factor = max_acceleration_scaling_factor;
333  else if (max_acceleration_scaling_factor == 0.0)
334  {
335  RCLCPP_DEBUG(LOGGER, "A max_acceleration_scaling_factor of 0.0 was specified, defaulting to %f instead.",
336  acceleration_scaling_factor);
337  }
338  else
339  {
340  RCLCPP_WARN(LOGGER, "Invalid max_acceleration_scaling_factor %f specified, defaulting to %f instead.",
341  max_acceleration_scaling_factor, acceleration_scaling_factor);
342  }
343  do
344  {
345  num_updates = 0;
346  iteration++;
347 
348  // In this case we iterate through the joints on the outer loop.
349  // This is so that any time interval increases have a chance to get propagated through the trajectory
350  for (unsigned int j = 0; j < num_joints; ++j)
351  {
352  // Loop forwards, then backwards
353  for (int count = 0; count < 2; ++count)
354  {
355  for (int i = 0; i < num_points - 1; ++i)
356  {
357  int index = backwards ? (num_points - 1) - i : i;
358 
359  curr_waypoint = rob_trajectory.getWayPointPtr(index);
360 
361  if (index > 0)
362  prev_waypoint = rob_trajectory.getWayPointPtr(index - 1);
363 
364  if (index < num_points - 1)
365  next_waypoint = rob_trajectory.getWayPointPtr(index + 1);
366 
367  // Get acceleration limits
368  double a_max = DEFAULT_ACCEL_MAX;
369  const moveit::core::VariableBounds& b = rmodel.getVariableBounds(vars[j]);
370  if (b.acceleration_bounded_)
371  a_max = std::min(fabs(b.max_acceleration_ * acceleration_scaling_factor),
372  fabs(b.min_acceleration_ * acceleration_scaling_factor));
373 
374  if (index == 0)
375  {
376  // First point
377  q1 = next_waypoint->getVariablePosition(idx[j]);
378  q2 = curr_waypoint->getVariablePosition(idx[j]);
379  q3 = next_waypoint->getVariablePosition(idx[j]);
380 
381  dt1 = dt2 = time_diff[index];
382  assert(!backwards);
383  }
384  else if (index < num_points - 1)
385  {
386  // middle points
387  q1 = prev_waypoint->getVariablePosition(idx[j]);
388  q2 = curr_waypoint->getVariablePosition(idx[j]);
389  q3 = next_waypoint->getVariablePosition(idx[j]);
390 
391  dt1 = time_diff[index - 1];
392  dt2 = time_diff[index];
393  }
394  else
395  {
396  // last point - careful, there are only numpoints-1 time intervals
397  q1 = prev_waypoint->getVariablePosition(idx[j]);
398  q2 = curr_waypoint->getVariablePosition(idx[j]);
399  q3 = prev_waypoint->getVariablePosition(idx[j]);
400 
401  dt1 = dt2 = time_diff[index - 1];
402  assert(backwards);
403  }
404 
405  if (dt1 == 0.0 || dt2 == 0.0)
406  {
407  v1 = 0.0;
408  v2 = 0.0;
409  a = 0.0;
410  }
411  else
412  {
413  bool start_velocity = false;
414  if (index == 0)
415  {
416  if (curr_waypoint->hasVelocities())
417  {
418  start_velocity = true;
419  v1 = curr_waypoint->getVariableVelocity(idx[j]);
420  }
421  }
422  v1 = start_velocity ? v1 : (q2 - q1) / dt1;
423  v2 = (q3 - q2) / dt2;
424  a = 2.0 * (v2 - v1) / (dt1 + dt2);
425  }
426 
427  if (fabs(a) > a_max + ROUNDING_THRESHOLD)
428  {
429  if (!backwards)
430  {
431  dt2 = std::min(dt2 + max_time_change_per_it_, findT2(q2 - q1, q3 - q2, dt1, dt2, a_max));
432  time_diff[index] = dt2;
433  }
434  else
435  {
436  dt1 = std::min(dt1 + max_time_change_per_it_, findT1(q2 - q1, q3 - q2, dt1, dt2, a_max));
437  time_diff[index - 1] = dt1;
438  }
439  num_updates++;
440 
441  if (dt1 == 0.0 || dt2 == 0.0)
442  {
443  v1 = 0.0;
444  v2 = 0.0;
445  a = 0.0;
446  }
447  else
448  {
449  v1 = (q2 - q1) / dt1;
450  v2 = (q3 - q2) / dt2;
451  a = 2 * (v2 - v1) / (dt1 + dt2);
452  }
453  }
454  }
455  backwards = !backwards;
456  }
457  }
458  // RCLCPP_DEBUG(LOGGER, "applyAcceleration: num_updates=%i",
459  // num_updates);
460  } while (num_updates > 0 && iteration < static_cast<int>(max_iterations_));
461 }
462 
464  const double max_velocity_scaling_factor,
465  const double max_acceleration_scaling_factor) const
466 {
467  if (trajectory.empty())
468  return true;
469 
470  const moveit::core::JointModelGroup* group = trajectory.getGroup();
471  if (!group)
472  {
473  RCLCPP_ERROR(LOGGER, "It looks like the planner did not set "
474  "the group the plan was computed for");
475  return false;
476  }
477 
478  // this lib does not actually work properly when angles wrap around, so we need to unwind the path first
479  trajectory.unwind();
480 
481  const int num_points = trajectory.getWayPointCount();
482  std::vector<double> time_diff(num_points - 1, 0.0); // the time difference between adjacent points
483 
484  applyVelocityConstraints(trajectory, time_diff, max_velocity_scaling_factor);
485  applyAccelerationConstraints(trajectory, time_diff, max_acceleration_scaling_factor);
486 
487  updateTrajectory(trajectory, time_diff);
488  return true;
489 }
490 
492  robot_trajectory::RobotTrajectory& /*trajectory*/,
493  const std::unordered_map<std::string, double>& /*velocity_limits*/,
494  const std::unordered_map<std::string, double>& /*acceleration_limits*/) const
495 {
496  RCLCPP_ERROR(LOGGER, "IPTP does not support this version of computeTimeStamps. Try TOTG instead?");
497  return false;
498 }
499 } // namespace trajectory_processing
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.
Definition: robot_model.h:433
Maintain a sequence of waypoints and the time durations between these waypoints.
RobotTrajectory & setWayPointDurationFromPrevious(std::size_t index, double value)
const moveit::core::JointModelGroup * getGroup() const
moveit::core::RobotStatePtr & getWayPointPtr(std::size_t index)
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
IterativeParabolicTimeParameterization(unsigned int max_iterations=100, double max_time_change_per_it=.01)
a
Definition: plan.py:54