moveit2
The MoveIt Motion Planning Framework for ROS 2.
time_optimal_trajectory_generation.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Georgia Tech Research Corporation
3  * All rights reserved.
4  *
5  * Author: Tobias Kunz <tobias@gatech.edu>
6  * Date: 05/2012
7  *
8  * Humanoid Robotics Lab Georgia Institute of Technology
9  * Director: Mike Stilman http://www.golems.org
10  *
11  * Algorithm details and publications:
12  * http://www.golems.org/node/1570
13  *
14  * This file is provided under the following "BSD-style" License:
15  * Redistribution and use in source and binary forms, with or
16  * without modification, are permitted provided that the following
17  * conditions are met:
18  * * Redistributions of source code must retain the above copyright
19  * notice, this list of conditions and the following disclaimer.
20  * * Redistributions in binary form must reproduce the above
21  * copyright notice, this list of conditions and the following
22  * disclaimer in the documentation and/or other materials provided
23  * with the distribution.
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
25  * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
26  * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
27  * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
28  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
29  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
30  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
31  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
32  * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
33  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
34  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
35  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
36  * POSSIBILITY OF SUCH DAMAGE.
37  */
38 
39 #include <rclcpp/logger.hpp>
40 #include <rclcpp/logging.hpp>
41 #include <limits>
42 #include <Eigen/Geometry>
43 #include <algorithm>
44 #include <cmath>
46 #include <vector>
47 
48 namespace trajectory_processing
49 {
50 namespace
51 {
52 static const rclcpp::Logger LOGGER =
53  rclcpp::get_logger("moveit_trajectory_processing.time_optimal_trajectory_generation");
54 constexpr double DEFAULT_TIMESTEP = 1e-3;
55 constexpr double EPS = 1e-6;
56 } // namespace
57 
59 {
60 public:
61  LinearPathSegment(const Eigen::VectorXd& start, const Eigen::VectorXd& end)
62  : PathSegment((end - start).norm()), end_(end), start_(start)
63  {
64  }
65 
66  Eigen::VectorXd getConfig(double s) const override
67  {
68  s /= length_;
69  s = std::max(0.0, std::min(1.0, s));
70  return (1.0 - s) * start_ + s * end_;
71  }
72 
73  Eigen::VectorXd getTangent(double /* s */) const override
74  {
75  return (end_ - start_) / length_;
76  }
77 
78  Eigen::VectorXd getCurvature(double /* s */) const override
79  {
80  return Eigen::VectorXd::Zero(start_.size());
81  }
82 
83  std::list<double> getSwitchingPoints() const override
84  {
85  return std::list<double>();
86  }
87 
88  LinearPathSegment* clone() const override
89  {
90  return new LinearPathSegment(*this);
91  }
92 
93 private:
94  Eigen::VectorXd end_;
95  Eigen::VectorXd start_;
96 };
97 
99 {
100 public:
101  CircularPathSegment(const Eigen::VectorXd& start, const Eigen::VectorXd& intersection, const Eigen::VectorXd& end,
102  double max_deviation)
103  {
104  if ((intersection - start).norm() < 0.000001 || (end - intersection).norm() < 0.000001)
105  {
106  length_ = 0.0;
107  radius = 1.0;
108  center = intersection;
109  x = Eigen::VectorXd::Zero(start.size());
110  y = Eigen::VectorXd::Zero(start.size());
111  return;
112  }
113 
114  const Eigen::VectorXd start_direction = (intersection - start).normalized();
115  const Eigen::VectorXd end_direction = (end - intersection).normalized();
116  const double start_dot_end = start_direction.dot(end_direction);
117 
118  // catch division by 0 in computations below
119  if (start_dot_end > 0.999999 || start_dot_end < -0.999999)
120  {
121  length_ = 0.0;
122  radius = 1.0;
123  center = intersection;
124  x = Eigen::VectorXd::Zero(start.size());
125  y = Eigen::VectorXd::Zero(start.size());
126  return;
127  }
128 
129  const double angle = acos(start_dot_end);
130  const double start_distance = (start - intersection).norm();
131  const double end_distance = (end - intersection).norm();
132 
133  // enforce max deviation
134  double distance = std::min(start_distance, end_distance);
135  distance = std::min(distance, max_deviation * sin(0.5 * angle) / (1.0 - cos(0.5 * angle)));
136 
137  radius = distance / tan(0.5 * angle);
138  length_ = angle * radius;
139 
140  center = intersection + (end_direction - start_direction).normalized() * radius / cos(0.5 * angle);
141  x = (intersection - distance * start_direction - center).normalized();
142  y = start_direction;
143  }
144 
145  Eigen::VectorXd getConfig(double s) const override
146  {
147  const double angle = s / radius;
148  return center + radius * (x * cos(angle) + y * sin(angle));
149  }
150 
151  Eigen::VectorXd getTangent(double s) const override
152  {
153  const double angle = s / radius;
154  return -x * sin(angle) + y * cos(angle);
155  }
156 
157  Eigen::VectorXd getCurvature(double s) const override
158  {
159  const double angle = s / radius;
160  return -1.0 / radius * (x * cos(angle) + y * sin(angle));
161  }
162 
163  std::list<double> getSwitchingPoints() const override
164  {
165  std::list<double> switching_points;
166  const double dim = x.size();
167  for (unsigned int i = 0; i < dim; ++i)
168  {
169  double switching_angle = atan2(y[i], x[i]);
170  if (switching_angle < 0.0)
171  {
172  switching_angle += M_PI;
173  }
174  const double switching_point = switching_angle * radius;
175  if (switching_point < length_)
176  {
177  switching_points.push_back(switching_point);
178  }
179  }
180  switching_points.sort();
181  return switching_points;
182  }
183 
184  CircularPathSegment* clone() const override
185  {
186  return new CircularPathSegment(*this);
187  }
188 
189 private:
190  double radius;
191  Eigen::VectorXd center;
192  Eigen::VectorXd x;
193  Eigen::VectorXd y;
194 };
195 
196 Path::Path(const std::list<Eigen::VectorXd>& path, double max_deviation) : length_(0.0)
197 {
198  if (path.size() < 2)
199  return;
200  std::list<Eigen::VectorXd>::const_iterator path_iterator1 = path.begin();
201  std::list<Eigen::VectorXd>::const_iterator path_iterator2 = path_iterator1;
202  ++path_iterator2;
203  std::list<Eigen::VectorXd>::const_iterator path_iterator3;
204  Eigen::VectorXd start_config = *path_iterator1;
205  while (path_iterator2 != path.end())
206  {
207  path_iterator3 = path_iterator2;
208  ++path_iterator3;
209  if (max_deviation > 0.0 && path_iterator3 != path.end())
210  {
211  CircularPathSegment* blend_segment =
212  new CircularPathSegment(0.5 * (*path_iterator1 + *path_iterator2), *path_iterator2,
213  0.5 * (*path_iterator2 + *path_iterator3), max_deviation);
214  Eigen::VectorXd end_config = blend_segment->getConfig(0.0);
215  if ((end_config - start_config).norm() > 0.000001)
216  {
217  path_segments_.push_back(std::make_unique<LinearPathSegment>(start_config, end_config));
218  }
219  path_segments_.emplace_back(blend_segment);
220 
221  start_config = blend_segment->getConfig(blend_segment->getLength());
222  }
223  else
224  {
225  path_segments_.push_back(std::make_unique<LinearPathSegment>(start_config, *path_iterator2));
226  start_config = *path_iterator2;
227  }
228  path_iterator1 = path_iterator2;
229  ++path_iterator2;
230  }
231 
232  // Create list of switching point candidates, calculate total path length and
233  // absolute positions of path segments
234  for (std::unique_ptr<PathSegment>& path_segment : path_segments_)
235  {
236  path_segment->position_ = length_;
237  std::list<double> local_switching_points = path_segment->getSwitchingPoints();
238  for (std::list<double>::const_iterator point = local_switching_points.begin();
239  point != local_switching_points.end(); ++point)
240  {
241  switching_points_.push_back(std::make_pair(length_ + *point, false));
242  }
243  length_ += path_segment->getLength();
244  while (!switching_points_.empty() && switching_points_.back().first >= length_)
245  switching_points_.pop_back();
246  switching_points_.push_back(std::make_pair(length_, true));
247  }
248  switching_points_.pop_back();
249 }
250 
251 Path::Path(const Path& path) : length_(path.length_), switching_points_(path.switching_points_)
252 {
253  for (const std::unique_ptr<PathSegment>& path_segment : path.path_segments_)
254  {
255  path_segments_.emplace_back(path_segment->clone());
256  }
257 }
258 
259 double Path::getLength() const
260 {
261  return length_;
262 }
263 
264 PathSegment* Path::getPathSegment(double& s) const
265 {
266  std::list<std::unique_ptr<PathSegment>>::const_iterator it = path_segments_.begin();
267  std::list<std::unique_ptr<PathSegment>>::const_iterator next = it;
268  ++next;
269  while (next != path_segments_.end() && s >= (*next)->position_)
270  {
271  it = next;
272  ++next;
273  }
274  s -= (*it)->position_;
275  return (*it).get();
276 }
277 
278 Eigen::VectorXd Path::getConfig(double s) const
279 {
280  const PathSegment* path_segment = getPathSegment(s);
281  return path_segment->getConfig(s);
282 }
283 
284 Eigen::VectorXd Path::getTangent(double s) const
285 {
286  const PathSegment* path_segment = getPathSegment(s);
287  return path_segment->getTangent(s);
288 }
289 
290 Eigen::VectorXd Path::getCurvature(double s) const
291 {
292  const PathSegment* path_segment = getPathSegment(s);
293  return path_segment->getCurvature(s);
294 }
295 
296 double Path::getNextSwitchingPoint(double s, bool& discontinuity) const
297 {
298  std::list<std::pair<double, bool>>::const_iterator it = switching_points_.begin();
299  while (it != switching_points_.end() && it->first <= s)
300  {
301  ++it;
302  }
303  if (it == switching_points_.end())
304  {
305  discontinuity = true;
306  return length_;
307  }
308  discontinuity = it->second;
309  return it->first;
310 }
311 
312 std::list<std::pair<double, bool>> Path::getSwitchingPoints() const
313 {
314  return switching_points_;
315 }
316 
317 Trajectory::Trajectory(const Path& path, const Eigen::VectorXd& max_velocity, const Eigen::VectorXd& max_acceleration,
318  double time_step)
319  : path_(path)
320  , max_velocity_(max_velocity)
321  , max_acceleration_(max_acceleration)
322  , joint_num_(max_velocity.size())
323  , valid_(true)
324  , time_step_(time_step)
325  , cached_time_(std::numeric_limits<double>::max())
326 {
327  if (time_step_ == 0)
328  {
329  valid_ = false;
330  RCLCPP_ERROR(LOGGER, "The trajectory is invalid because the time step is 0.");
331  return;
332  }
333  trajectory_.push_back(TrajectoryStep(0.0, 0.0));
334  double after_acceleration = getMinMaxPathAcceleration(0.0, 0.0, true);
335  while (valid_ && !integrateForward(trajectory_, after_acceleration) && valid_)
336  {
337  double before_acceleration;
338  TrajectoryStep switching_point;
339  if (getNextSwitchingPoint(trajectory_.back().path_pos_, switching_point, before_acceleration, after_acceleration))
340  {
341  break;
342  }
343  integrateBackward(trajectory_, switching_point.path_pos_, switching_point.path_vel_, before_acceleration);
344  }
345 
346  if (valid_)
347  {
348  double before_acceleration = getMinMaxPathAcceleration(path_.getLength(), 0.0, false);
349  integrateBackward(trajectory_, path_.getLength(), 0.0, before_acceleration);
350  }
351 
352  if (valid_)
353  {
354  // Calculate timing
355  std::list<TrajectoryStep>::iterator previous = trajectory_.begin();
356  std::list<TrajectoryStep>::iterator it = previous;
357  it->time_ = 0.0;
358  ++it;
359  while (it != trajectory_.end())
360  {
361  it->time_ =
362  previous->time_ + (it->path_pos_ - previous->path_pos_) / ((it->path_vel_ + previous->path_vel_) / 2.0);
363  previous = it;
364  ++it;
365  }
366  }
367 }
368 
370 {
371 }
372 
373 // Returns true if end of path is reached.
374 bool Trajectory::getNextSwitchingPoint(double path_pos, TrajectoryStep& next_switching_point,
375  double& before_acceleration, double& after_acceleration)
376 {
377  TrajectoryStep acceleration_switching_point(path_pos, 0.0);
378  double acceleration_before_acceleration, acceleration_after_acceleration;
379  bool acceleration_reached_end;
380  do
381  {
382  acceleration_reached_end =
383  getNextAccelerationSwitchingPoint(acceleration_switching_point.path_pos_, acceleration_switching_point,
384  acceleration_before_acceleration, acceleration_after_acceleration);
385  } while (!acceleration_reached_end &&
386  acceleration_switching_point.path_vel_ > getVelocityMaxPathVelocity(acceleration_switching_point.path_pos_));
387 
388  TrajectoryStep velocity_switching_point(path_pos, 0.0);
389  double velocity_before_acceleration, velocity_after_acceleration;
390  bool velocity_reached_end;
391  do
392  {
393  velocity_reached_end = getNextVelocitySwitchingPoint(velocity_switching_point.path_pos_, velocity_switching_point,
394  velocity_before_acceleration, velocity_after_acceleration);
395  } while (
396  !velocity_reached_end && velocity_switching_point.path_pos_ <= acceleration_switching_point.path_pos_ &&
397  (velocity_switching_point.path_vel_ > getAccelerationMaxPathVelocity(velocity_switching_point.path_pos_ - EPS) ||
398  velocity_switching_point.path_vel_ > getAccelerationMaxPathVelocity(velocity_switching_point.path_pos_ + EPS)));
399 
400  if (acceleration_reached_end && velocity_reached_end)
401  {
402  return true;
403  }
404  else if (!acceleration_reached_end &&
405  (velocity_reached_end || acceleration_switching_point.path_pos_ <= velocity_switching_point.path_pos_))
406  {
407  next_switching_point = acceleration_switching_point;
408  before_acceleration = acceleration_before_acceleration;
409  after_acceleration = acceleration_after_acceleration;
410  return false;
411  }
412  else
413  {
414  next_switching_point = velocity_switching_point;
415  before_acceleration = velocity_before_acceleration;
416  after_acceleration = velocity_after_acceleration;
417  return false;
418  }
419 }
420 
421 bool Trajectory::getNextAccelerationSwitchingPoint(double path_pos, TrajectoryStep& next_switching_point,
422  double& before_acceleration, double& after_acceleration)
423 {
424  double switching_path_pos = path_pos;
425  double switching_path_vel;
426  while (true)
427  {
428  bool discontinuity;
429  switching_path_pos = path_.getNextSwitchingPoint(switching_path_pos, discontinuity);
430 
431  if (switching_path_pos > path_.getLength() - EPS)
432  {
433  return true;
434  }
435 
436  if (discontinuity)
437  {
438  const double before_path_vel = getAccelerationMaxPathVelocity(switching_path_pos - EPS);
439  const double after_path_vel = getAccelerationMaxPathVelocity(switching_path_pos + EPS);
440  switching_path_vel = std::min(before_path_vel, after_path_vel);
441  before_acceleration = getMinMaxPathAcceleration(switching_path_pos - EPS, switching_path_vel, false);
442  after_acceleration = getMinMaxPathAcceleration(switching_path_pos + EPS, switching_path_vel, true);
443 
444  if ((before_path_vel > after_path_vel ||
445  getMinMaxPhaseSlope(switching_path_pos - EPS, switching_path_vel, false) >
446  getAccelerationMaxPathVelocityDeriv(switching_path_pos - 2.0 * EPS)) &&
447  (before_path_vel < after_path_vel || getMinMaxPhaseSlope(switching_path_pos + EPS, switching_path_vel, true) <
448  getAccelerationMaxPathVelocityDeriv(switching_path_pos + 2.0 * EPS)))
449  {
450  break;
451  }
452  }
453  else
454  {
455  switching_path_vel = getAccelerationMaxPathVelocity(switching_path_pos);
456  before_acceleration = 0.0;
457  after_acceleration = 0.0;
458 
459  if (getAccelerationMaxPathVelocityDeriv(switching_path_pos - EPS) < 0.0 &&
460  getAccelerationMaxPathVelocityDeriv(switching_path_pos + EPS) > 0.0)
461  {
462  break;
463  }
464  }
465  }
466 
467  next_switching_point = TrajectoryStep(switching_path_pos, switching_path_vel);
468  return false;
469 }
470 
471 bool Trajectory::getNextVelocitySwitchingPoint(double path_pos, TrajectoryStep& next_switching_point,
472  double& before_acceleration, double& after_acceleration)
473 {
474  bool start = false;
475  path_pos -= DEFAULT_TIMESTEP;
476  do
477  {
478  path_pos += DEFAULT_TIMESTEP;
479 
480  if (getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos), false) >=
481  getVelocityMaxPathVelocityDeriv(path_pos))
482  {
483  start = true;
484  }
485  } while ((!start || getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos), false) >
486  getVelocityMaxPathVelocityDeriv(path_pos)) &&
487  path_pos < path_.getLength());
488 
489  if (path_pos >= path_.getLength())
490  {
491  return true; // end of trajectory reached
492  }
493 
494  double before_path_pos = path_pos - DEFAULT_TIMESTEP;
495  double after_path_pos = path_pos;
496  while (after_path_pos - before_path_pos > EPS)
497  {
498  path_pos = (before_path_pos + after_path_pos) / 2.0;
499  if (getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos), false) >
500  getVelocityMaxPathVelocityDeriv(path_pos))
501  {
502  before_path_pos = path_pos;
503  }
504  else
505  {
506  after_path_pos = path_pos;
507  }
508  }
509 
510  before_acceleration = getMinMaxPathAcceleration(before_path_pos, getVelocityMaxPathVelocity(before_path_pos), false);
511  after_acceleration = getMinMaxPathAcceleration(after_path_pos, getVelocityMaxPathVelocity(after_path_pos), true);
512  next_switching_point = TrajectoryStep(after_path_pos, getVelocityMaxPathVelocity(after_path_pos));
513  return false;
514 }
515 
516 // Returns true if end of path is reached
517 bool Trajectory::integrateForward(std::list<TrajectoryStep>& trajectory, double acceleration)
518 {
519  double path_pos = trajectory.back().path_pos_;
520  double path_vel = trajectory.back().path_vel_;
521 
522  std::list<std::pair<double, bool>> switching_points = path_.getSwitchingPoints();
523  std::list<std::pair<double, bool>>::iterator next_discontinuity = switching_points.begin();
524 
525  while (true)
526  {
527  while ((next_discontinuity != switching_points.end()) &&
528  (next_discontinuity->first <= path_pos || !next_discontinuity->second))
529  {
530  ++next_discontinuity;
531  }
532 
533  double old_path_pos = path_pos;
534  double old_path_vel = path_vel;
535 
536  path_vel += time_step_ * acceleration;
537  path_pos += time_step_ * 0.5 * (old_path_vel + path_vel);
538 
539  if (next_discontinuity != switching_points.end() && path_pos > next_discontinuity->first)
540  {
541  // Avoid having a TrajectoryStep with path_pos near a switching point which will cause an almost identical
542  // TrajectoryStep get added in the next run (https://github.com/ros-planning/moveit/issues/1665)
543  if (path_pos - next_discontinuity->first < EPS)
544  {
545  continue;
546  }
547  path_vel = old_path_vel +
548  (next_discontinuity->first - old_path_pos) * (path_vel - old_path_vel) / (path_pos - old_path_pos);
549  path_pos = next_discontinuity->first;
550  }
551 
552  if (path_pos > path_.getLength())
553  {
554  trajectory.push_back(TrajectoryStep(path_pos, path_vel));
555  return true;
556  }
557  else if (path_vel < 0.0)
558  {
559  valid_ = false;
560  RCLCPP_ERROR(LOGGER, "Error while integrating forward: Negative path velocity");
561  return true;
562  }
563 
564  if (path_vel > getVelocityMaxPathVelocity(path_pos) &&
565  getMinMaxPhaseSlope(old_path_pos, getVelocityMaxPathVelocity(old_path_pos), false) <=
566  getVelocityMaxPathVelocityDeriv(old_path_pos))
567  {
568  path_vel = getVelocityMaxPathVelocity(path_pos);
569  }
570 
571  trajectory.push_back(TrajectoryStep(path_pos, path_vel));
572  acceleration = getMinMaxPathAcceleration(path_pos, path_vel, true);
573 
574  if (path_vel == 0 && acceleration == 0)
575  {
576  // The position will never change if velocity and acceleration are zero.
577  // The loop will spin indefinitely as no exit condition is met.
578  valid_ = false;
579  RCLCPP_ERROR(LOGGER, "Error while integrating forward: zero acceleration and velocity. Are any relevant "
580  "acceleration components limited to zero?");
581  return true;
582  }
583 
584  if (path_vel > getAccelerationMaxPathVelocity(path_pos) || path_vel > getVelocityMaxPathVelocity(path_pos))
585  {
586  // Find more accurate intersection with max-velocity curve using bisection
587  TrajectoryStep overshoot = trajectory.back();
588  trajectory.pop_back();
589  double before = trajectory.back().path_pos_;
590  double before_path_vel = trajectory.back().path_vel_;
591  double after = overshoot.path_pos_;
592  double after_path_vel = overshoot.path_vel_;
593  while (after - before > EPS)
594  {
595  const double midpoint = 0.5 * (before + after);
596  double midpoint_path_vel = 0.5 * (before_path_vel + after_path_vel);
597 
598  if (midpoint_path_vel > getVelocityMaxPathVelocity(midpoint) &&
599  getMinMaxPhaseSlope(before, getVelocityMaxPathVelocity(before), false) <=
600  getVelocityMaxPathVelocityDeriv(before))
601  {
602  midpoint_path_vel = getVelocityMaxPathVelocity(midpoint);
603  }
604 
605  if (midpoint_path_vel > getAccelerationMaxPathVelocity(midpoint) ||
606  midpoint_path_vel > getVelocityMaxPathVelocity(midpoint))
607  {
608  after = midpoint;
609  after_path_vel = midpoint_path_vel;
610  }
611  else
612  {
613  before = midpoint;
614  before_path_vel = midpoint_path_vel;
615  }
616  }
617  trajectory.push_back(TrajectoryStep(before, before_path_vel));
618 
619  if (getAccelerationMaxPathVelocity(after) < getVelocityMaxPathVelocity(after))
620  {
621  if (after > next_discontinuity->first)
622  {
623  return false;
624  }
625  else if (getMinMaxPhaseSlope(trajectory.back().path_pos_, trajectory.back().path_vel_, true) >
626  getAccelerationMaxPathVelocityDeriv(trajectory.back().path_pos_))
627  {
628  return false;
629  }
630  }
631  else
632  {
633  if (getMinMaxPhaseSlope(trajectory.back().path_pos_, trajectory_.back().path_vel_, false) >
634  getVelocityMaxPathVelocityDeriv(trajectory_.back().path_pos_))
635  {
636  return false;
637  }
638  }
639  }
640  }
641 }
642 
643 void Trajectory::integrateBackward(std::list<TrajectoryStep>& start_trajectory, double path_pos, double path_vel,
644  double acceleration)
645 {
646  std::list<TrajectoryStep>::iterator start2 = start_trajectory.end();
647  --start2;
648  std::list<TrajectoryStep>::iterator start1 = start2;
649  --start1;
650  std::list<TrajectoryStep> trajectory;
651  double slope;
652  assert(start1->path_pos_ <= path_pos);
653 
654  while (start1 != start_trajectory.begin() || path_pos >= 0.0)
655  {
656  if (start1->path_pos_ <= path_pos)
657  {
658  trajectory.push_front(TrajectoryStep(path_pos, path_vel));
659  path_vel -= time_step_ * acceleration;
660  path_pos -= time_step_ * 0.5 * (path_vel + trajectory.front().path_vel_);
661  acceleration = getMinMaxPathAcceleration(path_pos, path_vel, false);
662  slope = (trajectory.front().path_vel_ - path_vel) / (trajectory.front().path_pos_ - path_pos);
663 
664  if (path_vel < 0.0)
665  {
666  valid_ = false;
667  RCLCPP_ERROR(LOGGER, "Error while integrating backward: Negative path velocity");
668  end_trajectory_ = trajectory;
669  return;
670  }
671  }
672  else
673  {
674  --start1;
675  --start2;
676  }
677 
678  // Check for intersection between current start trajectory and backward
679  // trajectory segments
680  const double start_slope = (start2->path_vel_ - start1->path_vel_) / (start2->path_pos_ - start1->path_pos_);
681  const double intersection_path_pos =
682  (start1->path_vel_ - path_vel + slope * path_pos - start_slope * start1->path_pos_) / (slope - start_slope);
683  if (std::max(start1->path_pos_, path_pos) - EPS <= intersection_path_pos &&
684  intersection_path_pos <= EPS + std::min(start2->path_pos_, trajectory.front().path_pos_))
685  {
686  const double intersection_path_vel =
687  start1->path_vel_ + start_slope * (intersection_path_pos - start1->path_pos_);
688  start_trajectory.erase(start2, start_trajectory.end());
689  start_trajectory.push_back(TrajectoryStep(intersection_path_pos, intersection_path_vel));
690  start_trajectory.splice(start_trajectory.end(), trajectory);
691  return;
692  }
693  }
694 
695  valid_ = false;
696  RCLCPP_ERROR(LOGGER, "Error while integrating backward: Did not hit start trajectory");
697  end_trajectory_ = trajectory;
698 }
699 
700 double Trajectory::getMinMaxPathAcceleration(double path_pos, double path_vel, bool max)
701 {
702  Eigen::VectorXd config_deriv = path_.getTangent(path_pos);
703  Eigen::VectorXd config_deriv2 = path_.getCurvature(path_pos);
704  double factor = max ? 1.0 : -1.0;
705  double max_path_acceleration = std::numeric_limits<double>::max();
706  for (unsigned int i = 0; i < joint_num_; ++i)
707  {
708  if (config_deriv[i] != 0.0)
709  {
710  max_path_acceleration =
711  std::min(max_path_acceleration, max_acceleration_[i] / std::abs(config_deriv[i]) -
712  factor * config_deriv2[i] * path_vel * path_vel / config_deriv[i]);
713  }
714  }
715  return factor * max_path_acceleration;
716 }
717 
718 double Trajectory::getMinMaxPhaseSlope(double path_pos, double path_vel, bool max)
719 {
720  return getMinMaxPathAcceleration(path_pos, path_vel, max) / path_vel;
721 }
722 
723 double Trajectory::getAccelerationMaxPathVelocity(double path_pos) const
724 {
725  double max_path_velocity = std::numeric_limits<double>::infinity();
726  const Eigen::VectorXd config_deriv = path_.getTangent(path_pos);
727  const Eigen::VectorXd config_deriv2 = path_.getCurvature(path_pos);
728  for (unsigned int i = 0; i < joint_num_; ++i)
729  {
730  if (config_deriv[i] != 0.0)
731  {
732  for (unsigned int j = i + 1; j < joint_num_; ++j)
733  {
734  if (config_deriv[j] != 0.0)
735  {
736  double a_ij = config_deriv2[i] / config_deriv[i] - config_deriv2[j] / config_deriv[j];
737  if (a_ij != 0.0)
738  {
739  max_path_velocity = std::min(max_path_velocity, sqrt((max_acceleration_[i] / std::abs(config_deriv[i]) +
740  max_acceleration_[j] / std::abs(config_deriv[j])) /
741  std::abs(a_ij)));
742  }
743  }
744  }
745  }
746  else if (config_deriv2[i] != 0.0)
747  {
748  max_path_velocity = std::min(max_path_velocity, sqrt(max_acceleration_[i] / std::abs(config_deriv2[i])));
749  }
750  }
751  return max_path_velocity;
752 }
753 
754 double Trajectory::getVelocityMaxPathVelocity(double path_pos) const
755 {
756  const Eigen::VectorXd tangent = path_.getTangent(path_pos);
757  double max_path_velocity = std::numeric_limits<double>::max();
758  for (unsigned int i = 0; i < joint_num_; ++i)
759  {
760  max_path_velocity = std::min(max_path_velocity, max_velocity_[i] / std::abs(tangent[i]));
761  }
762  return max_path_velocity;
763 }
764 
765 double Trajectory::getAccelerationMaxPathVelocityDeriv(double path_pos)
766 {
767  return (getAccelerationMaxPathVelocity(path_pos + EPS) - getAccelerationMaxPathVelocity(path_pos - EPS)) /
768  (2.0 * EPS);
769 }
770 
771 double Trajectory::getVelocityMaxPathVelocityDeriv(double path_pos)
772 {
773  const Eigen::VectorXd tangent = path_.getTangent(path_pos);
774  double max_path_velocity = std::numeric_limits<double>::max();
775  unsigned int active_constraint;
776  for (unsigned int i = 0; i < joint_num_; ++i)
777  {
778  const double this_max_path_velocity = max_velocity_[i] / std::abs(tangent[i]);
779  if (this_max_path_velocity < max_path_velocity)
780  {
781  max_path_velocity = this_max_path_velocity;
782  active_constraint = i;
783  }
784  }
785  return -(max_velocity_[active_constraint] * path_.getCurvature(path_pos)[active_constraint]) /
786  (tangent[active_constraint] * std::abs(tangent[active_constraint]));
787 }
788 
790 {
791  return valid_;
792 }
793 
795 {
796  return trajectory_.back().time_;
797 }
798 
799 std::list<Trajectory::TrajectoryStep>::const_iterator Trajectory::getTrajectorySegment(double time) const
800 {
801  if (time >= trajectory_.back().time_)
802  {
803  std::list<TrajectoryStep>::const_iterator last = trajectory_.end();
804  last--;
805  return last;
806  }
807  else
808  {
809  if (time < cached_time_)
810  {
811  cached_trajectory_segment_ = trajectory_.begin();
812  }
813  while (time >= cached_trajectory_segment_->time_)
814  {
815  ++cached_trajectory_segment_;
816  }
817  cached_time_ = time;
818  return cached_trajectory_segment_;
819  }
820 }
821 
822 Eigen::VectorXd Trajectory::getPosition(double time) const
823 {
824  std::list<TrajectoryStep>::const_iterator it = getTrajectorySegment(time);
825  std::list<TrajectoryStep>::const_iterator previous = it;
826  previous--;
827 
828  double time_step = it->time_ - previous->time_;
829  const double acceleration =
830  2.0 * (it->path_pos_ - previous->path_pos_ - time_step * previous->path_vel_) / (time_step * time_step);
831 
832  time_step = time - previous->time_;
833  const double path_pos =
834  previous->path_pos_ + time_step * previous->path_vel_ + 0.5 * time_step * time_step * acceleration;
835 
836  return path_.getConfig(path_pos);
837 }
838 
839 Eigen::VectorXd Trajectory::getVelocity(double time) const
840 {
841  std::list<TrajectoryStep>::const_iterator it = getTrajectorySegment(time);
842  std::list<TrajectoryStep>::const_iterator previous = it;
843  previous--;
844 
845  double time_step = it->time_ - previous->time_;
846  const double acceleration =
847  2.0 * (it->path_pos_ - previous->path_pos_ - time_step * previous->path_vel_) / (time_step * time_step);
848 
849  time_step = time - previous->time_;
850  const double path_pos =
851  previous->path_pos_ + time_step * previous->path_vel_ + 0.5 * time_step * time_step * acceleration;
852  const double path_vel = previous->path_vel_ + time_step * acceleration;
853 
854  return path_.getTangent(path_pos) * path_vel;
855 }
856 
857 Eigen::VectorXd Trajectory::getAcceleration(double time) const
858 {
859  std::list<TrajectoryStep>::const_iterator it = getTrajectorySegment(time);
860  std::list<TrajectoryStep>::const_iterator previous = it;
861  previous--;
862 
863  double time_step = it->time_ - previous->time_;
864  const double acceleration =
865  2.0 * (it->path_pos_ - previous->path_pos_ - time_step * previous->path_vel_) / (time_step * time_step);
866 
867  time_step = time - previous->time_;
868  const double path_pos =
869  previous->path_pos_ + time_step * previous->path_vel_ + 0.5 * time_step * time_step * acceleration;
870  const double path_vel = previous->path_vel_ + time_step * acceleration;
871  Eigen::VectorXd path_acc =
872  (path_.getTangent(path_pos) * path_vel - path_.getTangent(previous->path_pos_) * previous->path_vel_);
873  if (time_step > 0.0)
874  path_acc /= time_step;
875  return path_acc;
876 }
877 
878 TimeOptimalTrajectoryGeneration::TimeOptimalTrajectoryGeneration(const double path_tolerance, const double resample_dt,
879  const double min_angle_change)
880  : path_tolerance_(path_tolerance), resample_dt_(resample_dt), min_angle_change_(min_angle_change)
881 {
882 }
883 
885  const double max_velocity_scaling_factor,
886  const double max_acceleration_scaling_factor) const
887 {
888  if (trajectory.empty())
889  return true;
890 
891  const moveit::core::JointModelGroup* group = trajectory.getGroup();
892  if (!group)
893  {
894  RCLCPP_ERROR(LOGGER, "It looks like the planner did not set the group the plan was computed for");
895  return false;
896  }
897 
898  // Validate scaling
899  double velocity_scaling_factor = 1.0;
900  if (max_velocity_scaling_factor > 0.0 && max_velocity_scaling_factor <= 1.0)
901  {
902  velocity_scaling_factor = max_velocity_scaling_factor;
903  }
904  else if (max_velocity_scaling_factor == 0.0)
905  {
906  RCLCPP_DEBUG(LOGGER, "A max_velocity_scaling_factor of 0.0 was specified, defaulting to %f instead.",
907  velocity_scaling_factor);
908  }
909  else
910  {
911  RCLCPP_WARN(LOGGER, "Invalid max_velocity_scaling_factor %f specified, defaulting to %f instead.",
912  max_velocity_scaling_factor, velocity_scaling_factor);
913  }
914 
915  double acceleration_scaling_factor = 1.0;
916  if (max_acceleration_scaling_factor > 0.0 && max_acceleration_scaling_factor <= 1.0)
917  {
918  acceleration_scaling_factor = max_acceleration_scaling_factor;
919  }
920  else if (max_acceleration_scaling_factor == 0.0)
921  {
922  RCLCPP_DEBUG(LOGGER, "A max_acceleration_scaling_factor of 0.0 was specified, defaulting to %f instead.",
923  acceleration_scaling_factor);
924  }
925  else
926  {
927  RCLCPP_WARN(LOGGER, "Invalid max_acceleration_scaling_factor %f specified, defaulting to %f instead.",
928  max_acceleration_scaling_factor, acceleration_scaling_factor);
929  }
930 
931  const std::vector<std::string>& vars = group->getVariableNames();
932  const moveit::core::RobotModel& rmodel = group->getParentModel();
933  const unsigned num_joints = group->getVariableCount();
934 
935  // Get the vel/accel limits
936  Eigen::VectorXd max_velocity(num_joints);
937  Eigen::VectorXd max_acceleration(num_joints);
938  for (size_t j = 0; j < num_joints; ++j)
939  {
940  const moveit::core::VariableBounds& bounds = rmodel.getVariableBounds(vars[j]);
941 
942  // Limits need to be non-zero, otherwise we never exit
943  max_velocity[j] = 1.0;
944  if (bounds.velocity_bounded_)
945  {
946  if (bounds.max_velocity_ <= 0.0)
947  {
948  RCLCPP_ERROR(LOGGER, "Invalid max_velocity %f specified for '%s', must be greater than 0.0",
949  bounds.max_velocity_, vars[j].c_str());
950  return false;
951  }
952  max_velocity[j] =
953  std::min(std::fabs(bounds.max_velocity_), std::fabs(bounds.min_velocity_)) * velocity_scaling_factor;
954  }
955  else
956  {
957  RCLCPP_WARN_STREAM_ONCE(
958  LOGGER, "Joint velocity limits are not defined. Using the default "
959  << max_velocity[j] << " rad/s. You can define velocity limits in the URDF or joint_limits.yaml.");
960  }
961 
962  max_acceleration[j] = 1.0;
963  if (bounds.acceleration_bounded_)
964  {
965  if (bounds.max_acceleration_ < 0.0)
966  {
967  RCLCPP_ERROR(LOGGER, "Invalid max_acceleration %f specified for '%s', must be greater than 0.0",
968  bounds.max_acceleration_, vars[j].c_str());
969  return false;
970  }
971  max_acceleration[j] = std::min(std::fabs(bounds.max_acceleration_), std::fabs(bounds.min_acceleration_)) *
972  acceleration_scaling_factor;
973  }
974  else
975  {
976  RCLCPP_WARN_STREAM_ONCE(LOGGER,
977  "Joint acceleration limits are not defined. Using the default "
978  << max_acceleration[j]
979  << " rad/s^2. You can define acceleration limits in the URDF or joint_limits.yaml.");
980  }
981  }
982 
983  return doTimeParameterizationCalculations(trajectory, max_velocity, max_acceleration);
984 }
985 
987  robot_trajectory::RobotTrajectory& trajectory, const std::unordered_map<std::string, double>& velocity_limits,
988  const std::unordered_map<std::string, double>& acceleration_limits) const
989 {
990  if (trajectory.empty())
991  return true;
992 
993  // Get the default joint limits from the robot model, then overwrite any that are provided as arguments
994  const moveit::core::JointModelGroup* group = trajectory.getGroup();
995  if (!group)
996  {
997  RCLCPP_ERROR(LOGGER, "It looks like the planner did not set the group the plan was computed for");
998  return false;
999  }
1000  const unsigned num_joints = group->getVariableCount();
1001  const std::vector<std::string>& vars = group->getVariableNames();
1002  const moveit::core::RobotModel& rmodel = group->getParentModel();
1003 
1004  Eigen::VectorXd max_velocity(num_joints);
1005  Eigen::VectorXd max_acceleration(num_joints);
1006  for (size_t j = 0; j < num_joints; ++j)
1007  {
1008  const moveit::core::VariableBounds& bounds = rmodel.getVariableBounds(vars[j]);
1009 
1010  // VELOCITY LIMIT
1011  // Check if a custom limit was specified as an argument
1012  bool set_velocity_limit = false;
1013  auto it = velocity_limits.find(vars[j]);
1014  if (it != velocity_limits.end())
1015  {
1016  max_velocity[j] = it->second;
1017  set_velocity_limit = true;
1018  }
1019 
1020  if (bounds.velocity_bounded_ && !set_velocity_limit)
1021  {
1022  // Set the default velocity limit, from robot model
1023  if (bounds.max_velocity_ < 0.0)
1024  {
1025  RCLCPP_ERROR(LOGGER, "Invalid max_velocity %f specified for '%s', must be greater than 0.0",
1026  bounds.max_velocity_, vars[j].c_str());
1027  return false;
1028  }
1029  max_velocity[j] = std::min(std::fabs(bounds.max_velocity_), std::fabs(bounds.min_velocity_));
1030  set_velocity_limit = true;
1031  }
1032 
1033  if (!set_velocity_limit)
1034  {
1035  max_velocity[j] = 1.0;
1036  RCLCPP_WARN_STREAM_ONCE(
1037  LOGGER, "Joint velocity limits are not defined. Using the default "
1038  << max_velocity[j] << " rad/s. You can define velocity limits in the URDF or joint_limits.yaml.");
1039  }
1040 
1041  // ACCELERATION LIMIT
1042  // Check if a custom limit was specified as an argument
1043  bool set_acceleration_limit = false;
1044  it = acceleration_limits.find(vars[j]);
1045  if (it != acceleration_limits.end())
1046  {
1047  max_acceleration[j] = it->second;
1048  set_acceleration_limit = true;
1049  }
1050 
1051  if (bounds.acceleration_bounded_ && !set_acceleration_limit)
1052  {
1053  // Set the default acceleration limit, from robot model
1054  if (bounds.max_acceleration_ < 0.0)
1055  {
1056  RCLCPP_ERROR(LOGGER, "Invalid max_acceleration %f specified for '%s', must be greater than 0.0",
1057  bounds.max_acceleration_, vars[j].c_str());
1058  return false;
1059  }
1060  max_acceleration[j] = std::min(std::fabs(bounds.max_acceleration_), std::fabs(bounds.min_acceleration_));
1061  set_acceleration_limit = true;
1062  }
1063  if (!set_acceleration_limit)
1064  {
1065  max_acceleration[j] = 1.0;
1066  RCLCPP_WARN_STREAM_ONCE(LOGGER,
1067  "Joint acceleration limits are not defined. Using the default "
1068  << max_acceleration[j]
1069  << " rad/s^2. You can define acceleration limits in the URDF or joint_limits.yaml.");
1070  }
1071  }
1072 
1073  return doTimeParameterizationCalculations(trajectory, max_velocity, max_acceleration);
1074 }
1075 
1076 bool TimeOptimalTrajectoryGeneration::doTimeParameterizationCalculations(robot_trajectory::RobotTrajectory& trajectory,
1077  const Eigen::VectorXd& max_velocity,
1078  const Eigen::VectorXd& max_acceleration) const
1079 {
1080  // This lib does not actually work properly when angles wrap around, so we need to unwind the path first
1081  trajectory.unwind();
1082 
1083  const moveit::core::JointModelGroup* group = trajectory.getGroup();
1084  if (!group)
1085  {
1086  RCLCPP_ERROR(LOGGER, "It looks like the planner did not set the group the plan was computed for");
1087  return false;
1088  }
1089 
1090  const unsigned num_points = trajectory.getWayPointCount();
1091  const std::vector<int>& idx = group->getVariableIndexList();
1092  const unsigned num_joints = group->getVariableCount();
1093 
1094  // Have to convert into Eigen data structs and remove repeated points
1095  // (https://github.com/tobiaskunz/trajectories/issues/3)
1096  std::list<Eigen::VectorXd> points;
1097  for (size_t p = 0; p < num_points; ++p)
1098  {
1099  moveit::core::RobotStatePtr waypoint = trajectory.getWayPointPtr(p);
1100  Eigen::VectorXd new_point(num_joints);
1101  // The first point should always be kept
1102  bool diverse_point = (p == 0);
1103 
1104  for (size_t j = 0; j < num_joints; ++j)
1105  {
1106  new_point[j] = waypoint->getVariablePosition(idx[j]);
1107  // If any joint angle is different, it's a unique waypoint
1108  if (p > 0 && std::fabs(new_point[j] - points.back()[j]) > min_angle_change_)
1109  {
1110  diverse_point = true;
1111  }
1112  }
1113 
1114  if (diverse_point)
1115  points.push_back(new_point);
1116  // If the last point is not a diverse_point we replace the last added point with it to make sure to always have the
1117  // input end point as the last point
1118  else if (p == num_points - 1)
1119  points.back() = new_point;
1120  }
1121 
1122  // Return trajectory with only the first waypoint if there are not multiple diverse points
1123  if (points.size() == 1)
1124  {
1126  waypoint.zeroVelocities();
1127  waypoint.zeroAccelerations();
1128  trajectory.clear();
1129  trajectory.addSuffixWayPoint(waypoint, 0.0);
1130  return true;
1131  }
1132 
1133  // Now actually call the algorithm
1134  Trajectory parameterized(Path(points, path_tolerance_), max_velocity, max_acceleration, DEFAULT_TIMESTEP);
1135  if (!parameterized.isValid())
1136  {
1137  RCLCPP_ERROR(LOGGER, "Unable to parameterize trajectory.");
1138  return false;
1139  }
1140 
1141  // Compute sample count
1142  size_t sample_count = std::ceil(parameterized.getDuration() / resample_dt_);
1143 
1144  // Resample and fill in trajectory
1146  trajectory.clear();
1147  double last_t = 0;
1148  for (size_t sample = 0; sample <= sample_count; ++sample)
1149  {
1150  // always sample the end of the trajectory as well
1151  double t = std::min(parameterized.getDuration(), sample * resample_dt_);
1152  Eigen::VectorXd position = parameterized.getPosition(t);
1153  Eigen::VectorXd velocity = parameterized.getVelocity(t);
1154  Eigen::VectorXd acceleration = parameterized.getAcceleration(t);
1155 
1156  for (size_t j = 0; j < num_joints; ++j)
1157  {
1158  waypoint.setVariablePosition(idx[j], position[j]);
1159  waypoint.setVariableVelocity(idx[j], velocity[j]);
1160  waypoint.setVariableAcceleration(idx[j], acceleration[j]);
1161  }
1162 
1163  trajectory.addSuffixWayPoint(waypoint, t - last_t);
1164  last_t = t;
1165  }
1166 
1167  return true;
1168 }
1169 } // 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
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void setVariableAcceleration(const std::string &variable, double value)
Set the acceleration of a variable. If an unknown variable name is specified, an exception is thrown.
Definition: robot_state.h:381
void zeroVelocities()
Set all velocities to 0.0.
void setVariableVelocity(const std::string &variable, double value)
Set the velocity of a variable. If an unknown variable name is specified, an exception is thrown.
Definition: robot_state.h:282
void setVariablePosition(const std::string &variable, double value)
Set the position of a single variable. An exception is thrown if the variable name is not known.
Definition: robot_state.h:188
void zeroAccelerations()
Set all accelerations to 0.0.
Maintain a sequence of waypoints and the time durations between these waypoints.
const moveit::core::JointModelGroup * getGroup() const
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
moveit::core::RobotStatePtr & getWayPointPtr(std::size_t index)
const moveit::core::RobotState & getWayPoint(std::size_t index) const
CircularPathSegment(const Eigen::VectorXd &start, const Eigen::VectorXd &intersection, const Eigen::VectorXd &end, double max_deviation)
Eigen::VectorXd getConfig(double s) const override
LinearPathSegment(const Eigen::VectorXd &start, const Eigen::VectorXd &end)
virtual Eigen::VectorXd getConfig(double s) const =0
virtual Eigen::VectorXd getCurvature(double s) const =0
virtual Eigen::VectorXd getTangent(double s) const =0
Eigen::VectorXd getTangent(double s) const
std::list< std::pair< double, bool > > getSwitchingPoints() const
Eigen::VectorXd getCurvature(double s) const
double getNextSwitchingPoint(double s, bool &discontinuity) const
Path(const std::list< Eigen::VectorXd > &path, double max_deviation=0.0)
TimeOptimalTrajectoryGeneration(const double path_tolerance=0.1, const double resample_dt=0.1, const double min_angle_change=0.001)
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
Eigen::VectorXd getAcceleration(double time) const
Return the acceleration vector for a given point in time.
bool isValid() const
Call this method after constructing the object to make sure the trajectory generation succeeded witho...
Eigen::VectorXd getPosition(double time) const
Return the position/configuration vector for a given point in time.
Trajectory(const Path &path, const Eigen::VectorXd &max_velocity, const Eigen::VectorXd &max_acceleration, double time_step=0.001)
Generates a time-optimal trajectory.
double getDuration() const
Returns the optimal duration of the trajectory.
Eigen::VectorXd getVelocity(double time) const
Return the velocity vector for a given point in time.
p
Definition: pick.py:62
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
const rclcpp::Logger LOGGER
Definition: async_test.h:31