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 <limits>
40 #include <Eigen/Geometry>
41 #include <algorithm>
42 #include <cmath>
44 #include <ros/console.h>
45 #include <vector>
46 
47 namespace trajectory_processing
48 {
49 const std::string LOGNAME = "trajectory_processing.time_optimal_trajectory_generation";
50 constexpr double EPS = 0.000001;
51 constexpr double DEFAULT_VELOCITY_LIMIT = 1.0;
52 constexpr double DEFAULT_ACCELERATION_LIMIT = 1.0;
53 
55 {
56 public:
57  LinearPathSegment(const Eigen::VectorXd& start, const Eigen::VectorXd& end)
58  : PathSegment((end - start).norm()), end_(end), start_(start)
59  {
60  }
61 
62  Eigen::VectorXd getConfig(double s) const override
63  {
64  s /= length_;
65  s = std::max(0.0, std::min(1.0, s));
66  return (1.0 - s) * start_ + s * end_;
67  }
68 
69  Eigen::VectorXd getTangent(double /* s */) const override
70  {
71  return (end_ - start_) / length_;
72  }
73 
74  Eigen::VectorXd getCurvature(double /* s */) const override
75  {
76  return Eigen::VectorXd::Zero(start_.size());
77  }
78 
79  std::list<double> getSwitchingPoints() const override
80  {
81  return std::list<double>();
82  }
83 
84  LinearPathSegment* clone() const override
85  {
86  return new LinearPathSegment(*this);
87  }
88 
89 private:
90  Eigen::VectorXd end_;
91  Eigen::VectorXd start_;
92 };
93 
95 {
96 public:
97  CircularPathSegment(const Eigen::VectorXd& start, const Eigen::VectorXd& intersection, const Eigen::VectorXd& end,
98  double max_deviation)
99  {
100  if ((intersection - start).norm() < 0.000001 || (end - intersection).norm() < 0.000001)
101  {
102  length_ = 0.0;
103  radius = 1.0;
104  center = intersection;
105  x = Eigen::VectorXd::Zero(start.size());
106  y = Eigen::VectorXd::Zero(start.size());
107  return;
108  }
109 
110  const Eigen::VectorXd start_direction = (intersection - start).normalized();
111  const Eigen::VectorXd end_direction = (end - intersection).normalized();
112  const double start_dot_end = start_direction.dot(end_direction);
113 
114  // catch division by 0 in computations below
115  if (start_dot_end > 0.999999 || start_dot_end < -0.999999)
116  {
117  length_ = 0.0;
118  radius = 1.0;
119  center = intersection;
120  x = Eigen::VectorXd::Zero(start.size());
121  y = Eigen::VectorXd::Zero(start.size());
122  return;
123  }
124 
125  const double angle = acos(start_dot_end);
126  const double start_distance = (start - intersection).norm();
127  const double end_distance = (end - intersection).norm();
128 
129  // enforce max deviation
130  double distance = std::min(start_distance, end_distance);
131  distance = std::min(distance, max_deviation * sin(0.5 * angle) / (1.0 - cos(0.5 * angle)));
132 
133  radius = distance / tan(0.5 * angle);
134  length_ = angle * radius;
135 
136  center = intersection + (end_direction - start_direction).normalized() * radius / cos(0.5 * angle);
137  x = (intersection - distance * start_direction - center).normalized();
138  y = start_direction;
139  }
140 
141  Eigen::VectorXd getConfig(double s) const override
142  {
143  const double angle = s / radius;
144  return center + radius * (x * cos(angle) + y * sin(angle));
145  }
146 
147  Eigen::VectorXd getTangent(double s) const override
148  {
149  const double angle = s / radius;
150  return -x * sin(angle) + y * cos(angle);
151  }
152 
153  Eigen::VectorXd getCurvature(double s) const override
154  {
155  const double angle = s / radius;
156  return -1.0 / radius * (x * cos(angle) + y * sin(angle));
157  }
158 
159  std::list<double> getSwitchingPoints() const override
160  {
161  std::list<double> switching_points;
162  const double dim = x.size();
163  for (unsigned int i = 0; i < dim; ++i)
164  {
165  double switching_angle = atan2(y[i], x[i]);
166  if (switching_angle < 0.0)
167  {
168  switching_angle += M_PI;
169  }
170  const double switching_point = switching_angle * radius;
171  if (switching_point < length_)
172  {
173  switching_points.push_back(switching_point);
174  }
175  }
176  switching_points.sort();
177  return switching_points;
178  }
179 
180  CircularPathSegment* clone() const override
181  {
182  return new CircularPathSegment(*this);
183  }
184 
185 private:
186  double radius;
187  Eigen::VectorXd center;
188  Eigen::VectorXd x;
189  Eigen::VectorXd y;
190 };
191 
192 Path::Path(const std::list<Eigen::VectorXd>& path, double max_deviation) : length_(0.0)
193 {
194  if (path.size() < 2)
195  return;
196  std::list<Eigen::VectorXd>::const_iterator path_iterator1 = path.begin();
197  std::list<Eigen::VectorXd>::const_iterator path_iterator2 = path_iterator1;
198  ++path_iterator2;
199  std::list<Eigen::VectorXd>::const_iterator path_iterator3;
200  Eigen::VectorXd start_config = *path_iterator1;
201  while (path_iterator2 != path.end())
202  {
203  path_iterator3 = path_iterator2;
204  ++path_iterator3;
205  if (max_deviation > 0.0 && path_iterator3 != path.end())
206  {
207  CircularPathSegment* blend_segment =
208  new CircularPathSegment(0.5 * (*path_iterator1 + *path_iterator2), *path_iterator2,
209  0.5 * (*path_iterator2 + *path_iterator3), max_deviation);
210  Eigen::VectorXd end_config = blend_segment->getConfig(0.0);
211  if ((end_config - start_config).norm() > 0.000001)
212  {
213  path_segments_.push_back(std::make_unique<LinearPathSegment>(start_config, end_config));
214  }
215  path_segments_.emplace_back(blend_segment);
216 
217  start_config = blend_segment->getConfig(blend_segment->getLength());
218  }
219  else
220  {
221  path_segments_.push_back(std::make_unique<LinearPathSegment>(start_config, *path_iterator2));
222  start_config = *path_iterator2;
223  }
224  path_iterator1 = path_iterator2;
225  ++path_iterator2;
226  }
227 
228  // Create list of switching point candidates, calculate total path length and
229  // absolute positions of path segments
230  for (std::unique_ptr<PathSegment>& path_segment : path_segments_)
231  {
232  path_segment->position_ = length_;
233  std::list<double> local_switching_points = path_segment->getSwitchingPoints();
234  for (std::list<double>::const_iterator point = local_switching_points.begin();
235  point != local_switching_points.end(); ++point)
236  {
237  switching_points_.push_back(std::make_pair(length_ + *point, false));
238  }
239  length_ += path_segment->getLength();
240  while (!switching_points_.empty() && switching_points_.back().first >= length_)
241  switching_points_.pop_back();
242  switching_points_.push_back(std::make_pair(length_, true));
243  }
244  switching_points_.pop_back();
245 }
246 
247 Path::Path(const Path& path) : length_(path.length_), switching_points_(path.switching_points_)
248 {
249  for (const std::unique_ptr<PathSegment>& path_segment : path.path_segments_)
250  {
251  path_segments_.emplace_back(path_segment->clone());
252  }
253 }
254 
255 double Path::getLength() const
256 {
257  return length_;
258 }
259 
261 {
262  std::list<std::unique_ptr<PathSegment>>::const_iterator it = path_segments_.begin();
263  std::list<std::unique_ptr<PathSegment>>::const_iterator next = it;
264  ++next;
265  while (next != path_segments_.end() && s >= (*next)->position_)
266  {
267  it = next;
268  ++next;
269  }
270  s -= (*it)->position_;
271  return (*it).get();
272 }
273 
274 Eigen::VectorXd Path::getConfig(double s) const
275 {
276  const PathSegment* path_segment = getPathSegment(s);
277  return path_segment->getConfig(s);
278 }
279 
280 Eigen::VectorXd Path::getTangent(double s) const
281 {
282  const PathSegment* path_segment = getPathSegment(s);
283  return path_segment->getTangent(s);
284 }
285 
286 Eigen::VectorXd Path::getCurvature(double s) const
287 {
288  const PathSegment* path_segment = getPathSegment(s);
289  return path_segment->getCurvature(s);
290 }
291 
292 double Path::getNextSwitchingPoint(double s, bool& discontinuity) const
293 {
294  std::list<std::pair<double, bool>>::const_iterator it = switching_points_.begin();
295  while (it != switching_points_.end() && it->first <= s)
296  {
297  ++it;
298  }
299  if (it == switching_points_.end())
300  {
301  discontinuity = true;
302  return length_;
303  }
304  discontinuity = it->second;
305  return it->first;
306 }
307 
308 std::list<std::pair<double, bool>> Path::getSwitchingPoints() const
309 {
310  return switching_points_;
311 }
312 
313 Trajectory::Trajectory(const Path& path, const Eigen::VectorXd& max_velocity, const Eigen::VectorXd& max_acceleration,
314  double time_step)
315  : path_(path)
316  , max_velocity_(max_velocity)
317  , max_acceleration_(max_acceleration)
318  , joint_num_(max_velocity.size())
319  , valid_(true)
320  , time_step_(time_step)
321  , cached_time_(std::numeric_limits<double>::max())
322 {
323  trajectory_.push_back(TrajectoryStep(0.0, 0.0));
324  double after_acceleration = getMinMaxPathAcceleration(0.0, 0.0, true);
325  while (valid_ && !integrateForward(trajectory_, after_acceleration) && valid_)
326  {
327  double before_acceleration;
328  TrajectoryStep switching_point;
329  if (getNextSwitchingPoint(trajectory_.back().path_pos_, switching_point, before_acceleration, after_acceleration))
330  {
331  break;
332  }
333  integrateBackward(trajectory_, switching_point.path_pos_, switching_point.path_vel_, before_acceleration);
334  }
335 
336  if (valid_)
337  {
338  double before_acceleration = getMinMaxPathAcceleration(path_.getLength(), 0.0, false);
339  integrateBackward(trajectory_, path_.getLength(), 0.0, before_acceleration);
340  }
341 
342  if (valid_)
343  {
344  // Calculate timing
345  std::list<TrajectoryStep>::iterator previous = trajectory_.begin();
346  std::list<TrajectoryStep>::iterator it = previous;
347  it->time_ = 0.0;
348  ++it;
349  while (it != trajectory_.end())
350  {
351  it->time_ =
352  previous->time_ + (it->path_pos_ - previous->path_pos_) / ((it->path_vel_ + previous->path_vel_) / 2.0);
353  previous = it;
354  ++it;
355  }
356  }
357 }
358 
360 {
361 }
362 
363 // Returns true if end of path is reached.
364 bool Trajectory::getNextSwitchingPoint(double path_pos, TrajectoryStep& next_switching_point,
365  double& before_acceleration, double& after_acceleration)
366 {
367  TrajectoryStep acceleration_switching_point(path_pos, 0.0);
368  double acceleration_before_acceleration, acceleration_after_acceleration;
369  bool acceleration_reached_end;
370  do
371  {
372  acceleration_reached_end =
373  getNextAccelerationSwitchingPoint(acceleration_switching_point.path_pos_, acceleration_switching_point,
374  acceleration_before_acceleration, acceleration_after_acceleration);
375  } while (!acceleration_reached_end &&
376  acceleration_switching_point.path_vel_ > getVelocityMaxPathVelocity(acceleration_switching_point.path_pos_));
377 
378  TrajectoryStep velocity_switching_point(path_pos, 0.0);
379  double velocity_before_acceleration, velocity_after_acceleration;
380  bool velocity_reached_end;
381  do
382  {
383  velocity_reached_end = getNextVelocitySwitchingPoint(velocity_switching_point.path_pos_, velocity_switching_point,
384  velocity_before_acceleration, velocity_after_acceleration);
385  } while (
386  !velocity_reached_end && velocity_switching_point.path_pos_ <= acceleration_switching_point.path_pos_ &&
387  (velocity_switching_point.path_vel_ > getAccelerationMaxPathVelocity(velocity_switching_point.path_pos_ - EPS) ||
388  velocity_switching_point.path_vel_ > getAccelerationMaxPathVelocity(velocity_switching_point.path_pos_ + EPS)));
389 
390  if (acceleration_reached_end && velocity_reached_end)
391  {
392  return true;
393  }
394  else if (!acceleration_reached_end &&
395  (velocity_reached_end || acceleration_switching_point.path_pos_ <= velocity_switching_point.path_pos_))
396  {
397  next_switching_point = acceleration_switching_point;
398  before_acceleration = acceleration_before_acceleration;
399  after_acceleration = acceleration_after_acceleration;
400  return false;
401  }
402  else
403  {
404  next_switching_point = velocity_switching_point;
405  before_acceleration = velocity_before_acceleration;
406  after_acceleration = velocity_after_acceleration;
407  return false;
408  }
409 }
410 
411 bool Trajectory::getNextAccelerationSwitchingPoint(double path_pos, TrajectoryStep& next_switching_point,
412  double& before_acceleration, double& after_acceleration)
413 {
414  double switching_path_pos = path_pos;
415  double switching_path_vel;
416  while (true)
417  {
418  bool discontinuity;
419  switching_path_pos = path_.getNextSwitchingPoint(switching_path_pos, discontinuity);
420 
421  if (switching_path_pos > path_.getLength() - EPS)
422  {
423  return true;
424  }
425 
426  if (discontinuity)
427  {
428  const double before_path_vel = getAccelerationMaxPathVelocity(switching_path_pos - EPS);
429  const double after_path_vel = getAccelerationMaxPathVelocity(switching_path_pos + EPS);
430  switching_path_vel = std::min(before_path_vel, after_path_vel);
431  before_acceleration = getMinMaxPathAcceleration(switching_path_pos - EPS, switching_path_vel, false);
432  after_acceleration = getMinMaxPathAcceleration(switching_path_pos + EPS, switching_path_vel, true);
433 
434  if ((before_path_vel > after_path_vel ||
435  getMinMaxPhaseSlope(switching_path_pos - EPS, switching_path_vel, false) >
436  getAccelerationMaxPathVelocityDeriv(switching_path_pos - 2.0 * EPS)) &&
437  (before_path_vel < after_path_vel || getMinMaxPhaseSlope(switching_path_pos + EPS, switching_path_vel, true) <
438  getAccelerationMaxPathVelocityDeriv(switching_path_pos + 2.0 * EPS)))
439  {
440  break;
441  }
442  }
443  else
444  {
445  switching_path_vel = getAccelerationMaxPathVelocity(switching_path_pos);
446  before_acceleration = 0.0;
447  after_acceleration = 0.0;
448 
449  if (getAccelerationMaxPathVelocityDeriv(switching_path_pos - EPS) < 0.0 &&
450  getAccelerationMaxPathVelocityDeriv(switching_path_pos + EPS) > 0.0)
451  {
452  break;
453  }
454  }
455  }
456 
457  next_switching_point = TrajectoryStep(switching_path_pos, switching_path_vel);
458  return false;
459 }
460 
461 bool Trajectory::getNextVelocitySwitchingPoint(double path_pos, TrajectoryStep& next_switching_point,
462  double& before_acceleration, double& after_acceleration)
463 {
464  const double step_size = 0.001;
465  const double accuracy = 0.000001;
466 
467  bool start = false;
468  path_pos -= step_size;
469  do
470  {
471  path_pos += step_size;
472 
473  if (getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos), false) >=
475  {
476  start = true;
477  }
478  } while ((!start || getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos), false) >
479  getVelocityMaxPathVelocityDeriv(path_pos)) &&
480  path_pos < path_.getLength());
481 
482  if (path_pos >= path_.getLength())
483  {
484  return true; // end of trajectory reached
485  }
486 
487  double before_path_pos = path_pos - step_size;
488  double after_path_pos = path_pos;
489  while (after_path_pos - before_path_pos > accuracy)
490  {
491  path_pos = (before_path_pos + after_path_pos) / 2.0;
492  if (getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos), false) >
494  {
495  before_path_pos = path_pos;
496  }
497  else
498  {
499  after_path_pos = path_pos;
500  }
501  }
502 
503  before_acceleration = getMinMaxPathAcceleration(before_path_pos, getVelocityMaxPathVelocity(before_path_pos), false);
504  after_acceleration = getMinMaxPathAcceleration(after_path_pos, getVelocityMaxPathVelocity(after_path_pos), true);
505  next_switching_point = TrajectoryStep(after_path_pos, getVelocityMaxPathVelocity(after_path_pos));
506  return false;
507 }
508 
509 // Returns true if end of path is reached
510 bool Trajectory::integrateForward(std::list<TrajectoryStep>& trajectory, double acceleration)
511 {
512  double path_pos = trajectory.back().path_pos_;
513  double path_vel = trajectory.back().path_vel_;
514 
515  std::list<std::pair<double, bool>> switching_points = path_.getSwitchingPoints();
516  std::list<std::pair<double, bool>>::iterator next_discontinuity = switching_points.begin();
517 
518  while (true)
519  {
520  while ((next_discontinuity != switching_points.end()) &&
521  (next_discontinuity->first <= path_pos || !next_discontinuity->second))
522  {
523  ++next_discontinuity;
524  }
525 
526  double old_path_pos = path_pos;
527  double old_path_vel = path_vel;
528 
529  path_vel += time_step_ * acceleration;
530  path_pos += time_step_ * 0.5 * (old_path_vel + path_vel);
531 
532  if (next_discontinuity != switching_points.end() && path_pos > next_discontinuity->first)
533  {
534  // Avoid having a TrajectoryStep with path_pos near a switching point which will cause an almost identical
535  // TrajectoryStep get added in the next run (https://github.com/ros-planning/moveit/issues/1665)
536  if (path_pos - next_discontinuity->first < EPS)
537  {
538  continue;
539  }
540  path_vel = old_path_vel +
541  (next_discontinuity->first - old_path_pos) * (path_vel - old_path_vel) / (path_pos - old_path_pos);
542  path_pos = next_discontinuity->first;
543  }
544 
545  if (path_pos > path_.getLength())
546  {
547  trajectory.push_back(TrajectoryStep(path_pos, path_vel));
548  return true;
549  }
550  else if (path_vel < 0.0)
551  {
552  valid_ = false;
553  ROS_ERROR_NAMED(LOGNAME, "Error while integrating forward: Negative path velocity");
554  return true;
555  }
556 
557  if (path_vel > getVelocityMaxPathVelocity(path_pos) &&
558  getMinMaxPhaseSlope(old_path_pos, getVelocityMaxPathVelocity(old_path_pos), false) <=
559  getVelocityMaxPathVelocityDeriv(old_path_pos))
560  {
561  path_vel = getVelocityMaxPathVelocity(path_pos);
562  }
563 
564  trajectory.push_back(TrajectoryStep(path_pos, path_vel));
565  acceleration = getMinMaxPathAcceleration(path_pos, path_vel, true);
566 
567  if (path_vel > getAccelerationMaxPathVelocity(path_pos) || path_vel > getVelocityMaxPathVelocity(path_pos))
568  {
569  // Find more accurate intersection with max-velocity curve using bisection
570  TrajectoryStep overshoot = trajectory.back();
571  trajectory.pop_back();
572  double before = trajectory.back().path_pos_;
573  double before_path_vel = trajectory.back().path_vel_;
574  double after = overshoot.path_pos_;
575  double after_path_vel = overshoot.path_vel_;
576  while (after - before > EPS)
577  {
578  const double midpoint = 0.5 * (before + after);
579  double midpoint_path_vel = 0.5 * (before_path_vel + after_path_vel);
580 
581  if (midpoint_path_vel > getVelocityMaxPathVelocity(midpoint) &&
582  getMinMaxPhaseSlope(before, getVelocityMaxPathVelocity(before), false) <=
584  {
585  midpoint_path_vel = getVelocityMaxPathVelocity(midpoint);
586  }
587 
588  if (midpoint_path_vel > getAccelerationMaxPathVelocity(midpoint) ||
589  midpoint_path_vel > getVelocityMaxPathVelocity(midpoint))
590  {
591  after = midpoint;
592  after_path_vel = midpoint_path_vel;
593  }
594  else
595  {
596  before = midpoint;
597  before_path_vel = midpoint_path_vel;
598  }
599  }
600  trajectory.push_back(TrajectoryStep(before, before_path_vel));
601 
603  {
604  if (after > next_discontinuity->first)
605  {
606  return false;
607  }
608  else if (getMinMaxPhaseSlope(trajectory.back().path_pos_, trajectory.back().path_vel_, true) >
609  getAccelerationMaxPathVelocityDeriv(trajectory.back().path_pos_))
610  {
611  return false;
612  }
613  }
614  else
615  {
616  if (getMinMaxPhaseSlope(trajectory.back().path_pos_, trajectory_.back().path_vel_, false) >
618  {
619  return false;
620  }
621  }
622  }
623  }
624 }
625 
626 void Trajectory::integrateBackward(std::list<TrajectoryStep>& start_trajectory, double path_pos, double path_vel,
627  double acceleration)
628 {
629  std::list<TrajectoryStep>::iterator start2 = start_trajectory.end();
630  --start2;
631  std::list<TrajectoryStep>::iterator start1 = start2;
632  --start1;
633  std::list<TrajectoryStep> trajectory;
634  double slope;
635  assert(start1->path_pos_ <= path_pos);
636 
637  while (start1 != start_trajectory.begin() || path_pos >= 0.0)
638  {
639  if (start1->path_pos_ <= path_pos)
640  {
641  trajectory.push_front(TrajectoryStep(path_pos, path_vel));
642  path_vel -= time_step_ * acceleration;
643  path_pos -= time_step_ * 0.5 * (path_vel + trajectory.front().path_vel_);
644  acceleration = getMinMaxPathAcceleration(path_pos, path_vel, false);
645  slope = (trajectory.front().path_vel_ - path_vel) / (trajectory.front().path_pos_ - path_pos);
646 
647  if (path_vel < 0.0)
648  {
649  valid_ = false;
650  ROS_ERROR_NAMED(LOGNAME, "Error while integrating backward: Negative path velocity");
651  end_trajectory_ = trajectory;
652  return;
653  }
654  }
655  else
656  {
657  --start1;
658  --start2;
659  }
660 
661  // Check for intersection between current start trajectory and backward
662  // trajectory segments
663  const double start_slope = (start2->path_vel_ - start1->path_vel_) / (start2->path_pos_ - start1->path_pos_);
664  const double intersection_path_pos =
665  (start1->path_vel_ - path_vel + slope * path_pos - start_slope * start1->path_pos_) / (slope - start_slope);
666  if (std::max(start1->path_pos_, path_pos) - EPS <= intersection_path_pos &&
667  intersection_path_pos <= EPS + std::min(start2->path_pos_, trajectory.front().path_pos_))
668  {
669  const double intersection_path_vel =
670  start1->path_vel_ + start_slope * (intersection_path_pos - start1->path_pos_);
671  start_trajectory.erase(start2, start_trajectory.end());
672  start_trajectory.push_back(TrajectoryStep(intersection_path_pos, intersection_path_vel));
673  start_trajectory.splice(start_trajectory.end(), trajectory);
674  return;
675  }
676  }
677 
678  valid_ = false;
679  ROS_ERROR_NAMED(LOGNAME, "Error while integrating backward: Did not hit start trajectory");
680  end_trajectory_ = trajectory;
681 }
682 
683 double Trajectory::getMinMaxPathAcceleration(double path_pos, double path_vel, bool max)
684 {
685  Eigen::VectorXd config_deriv = path_.getTangent(path_pos);
686  Eigen::VectorXd config_deriv2 = path_.getCurvature(path_pos);
687  double factor = max ? 1.0 : -1.0;
688  double max_path_acceleration = std::numeric_limits<double>::max();
689  for (unsigned int i = 0; i < joint_num_; ++i)
690  {
691  if (config_deriv[i] != 0.0)
692  {
693  max_path_acceleration =
694  std::min(max_path_acceleration, max_acceleration_[i] / std::abs(config_deriv[i]) -
695  factor * config_deriv2[i] * path_vel * path_vel / config_deriv[i]);
696  }
697  }
698  return factor * max_path_acceleration;
699 }
700 
701 double Trajectory::getMinMaxPhaseSlope(double path_pos, double path_vel, bool max)
702 {
703  return getMinMaxPathAcceleration(path_pos, path_vel, max) / path_vel;
704 }
705 
706 double Trajectory::getAccelerationMaxPathVelocity(double path_pos) const
707 {
708  double max_path_velocity = std::numeric_limits<double>::infinity();
709  const Eigen::VectorXd config_deriv = path_.getTangent(path_pos);
710  const Eigen::VectorXd config_deriv2 = path_.getCurvature(path_pos);
711  for (unsigned int i = 0; i < joint_num_; ++i)
712  {
713  if (config_deriv[i] != 0.0)
714  {
715  for (unsigned int j = i + 1; j < joint_num_; ++j)
716  {
717  if (config_deriv[j] != 0.0)
718  {
719  double a_ij = config_deriv2[i] / config_deriv[i] - config_deriv2[j] / config_deriv[j];
720  if (a_ij != 0.0)
721  {
722  max_path_velocity = std::min(max_path_velocity, sqrt((max_acceleration_[i] / std::abs(config_deriv[i]) +
723  max_acceleration_[j] / std::abs(config_deriv[j])) /
724  std::abs(a_ij)));
725  }
726  }
727  }
728  }
729  else if (config_deriv2[i] != 0.0)
730  {
731  max_path_velocity = std::min(max_path_velocity, sqrt(max_acceleration_[i] / std::abs(config_deriv2[i])));
732  }
733  }
734  return max_path_velocity;
735 }
736 
737 double Trajectory::getVelocityMaxPathVelocity(double path_pos) const
738 {
739  const Eigen::VectorXd tangent = path_.getTangent(path_pos);
740  double max_path_velocity = std::numeric_limits<double>::max();
741  for (unsigned int i = 0; i < joint_num_; ++i)
742  {
743  max_path_velocity = std::min(max_path_velocity, max_velocity_[i] / std::abs(tangent[i]));
744  }
745  return max_path_velocity;
746 }
747 
749 {
750  return (getAccelerationMaxPathVelocity(path_pos + EPS) - getAccelerationMaxPathVelocity(path_pos - EPS)) /
751  (2.0 * EPS);
752 }
753 
755 {
756  const Eigen::VectorXd tangent = path_.getTangent(path_pos);
757  double max_path_velocity = std::numeric_limits<double>::max();
758  unsigned int active_constraint;
759  for (unsigned int i = 0; i < joint_num_; ++i)
760  {
761  const double this_max_path_velocity = max_velocity_[i] / std::abs(tangent[i]);
762  if (this_max_path_velocity < max_path_velocity)
763  {
764  max_path_velocity = this_max_path_velocity;
765  active_constraint = i;
766  }
767  }
768  return -(max_velocity_[active_constraint] * path_.getCurvature(path_pos)[active_constraint]) /
769  (tangent[active_constraint] * std::abs(tangent[active_constraint]));
770 }
771 
773 {
774  return valid_;
775 }
776 
778 {
779  return trajectory_.back().time_;
780 }
781 
782 std::list<Trajectory::TrajectoryStep>::const_iterator Trajectory::getTrajectorySegment(double time) const
783 {
784  if (time >= trajectory_.back().time_)
785  {
786  std::list<TrajectoryStep>::const_iterator last = trajectory_.end();
787  last--;
788  return last;
789  }
790  else
791  {
792  if (time < cached_time_)
793  {
795  }
796  while (time >= cached_trajectory_segment_->time_)
797  {
799  }
800  cached_time_ = time;
802  }
803 }
804 
805 Eigen::VectorXd Trajectory::getPosition(double time) const
806 {
807  std::list<TrajectoryStep>::const_iterator it = getTrajectorySegment(time);
808  std::list<TrajectoryStep>::const_iterator previous = it;
809  previous--;
810 
811  double time_step = it->time_ - previous->time_;
812  const double acceleration =
813  2.0 * (it->path_pos_ - previous->path_pos_ - time_step * previous->path_vel_) / (time_step * time_step);
814 
815  time_step = time - previous->time_;
816  const double path_pos =
817  previous->path_pos_ + time_step * previous->path_vel_ + 0.5 * time_step * time_step * acceleration;
818 
819  return path_.getConfig(path_pos);
820 }
821 
822 Eigen::VectorXd Trajectory::getVelocity(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  const double path_pos =
833  previous->path_pos_ + time_step * previous->path_vel_ + 0.5 * time_step * time_step * acceleration;
834  const double path_vel = previous->path_vel_ + time_step * acceleration;
835 
836  return path_.getTangent(path_pos) * path_vel;
837 }
838 
839 Eigen::VectorXd Trajectory::getAcceleration(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  const double path_pos =
850  previous->path_pos_ + time_step * previous->path_vel_ + 0.5 * time_step * time_step * acceleration;
851  const double path_vel = previous->path_vel_ + time_step * acceleration;
852  Eigen::VectorXd path_acc =
853  (path_.getTangent(path_pos) * path_vel - path_.getTangent(previous->path_pos_) * previous->path_vel_);
854  if (time_step > 0.0)
855  path_acc /= time_step;
856  return path_acc;
857 }
858 
859 TimeOptimalTrajectoryGeneration::TimeOptimalTrajectoryGeneration(const double path_tolerance, const double resample_dt,
860  const double min_angle_change)
861  : path_tolerance_(path_tolerance), resample_dt_(resample_dt), min_angle_change_(min_angle_change)
862 {
863 }
864 
866  robot_trajectory::RobotTrajectory& trajectory, const std::unordered_map<std::string, double>& velocity_limits,
867  const std::unordered_map<std::string, double>& acceleration_limits, const double max_velocity_scaling_factor,
868  const double max_acceleration_scaling_factor) const
869 {
870  if (trajectory.empty())
871  return true;
872 
873  const moveit::core::JointModelGroup* group = trajectory.getGroup();
874  if (!group)
875  {
876  ROS_ERROR_NAMED(LOGNAME, "It looks like the planner did not set the group the plan was computed for");
877  return false;
878  }
879 
880  // Validate scaling
881  double velocity_scaling_factor = verifyScalingFactor(max_velocity_scaling_factor);
882  double acceleration_scaling_factor = verifyScalingFactor(max_acceleration_scaling_factor);
883 
884  // limits need to be positive, otherwise we never exit
885  auto validate_limit = [](const char* type, double value, const std::string& name) {
886  if (value <= std::numeric_limits<double>::epsilon())
887  {
888  ROS_ERROR_NAMED(LOGNAME, "Invalid %s limit %f for joint '%s'. Must be greater than zero!", type, value,
889  name.c_str());
890  return false;
891  }
892  return true;
893  };
894 
895  // Get the velocity and acceleration limits for all joint variables
896  const moveit::core::RobotModel& rmodel = group->getParentModel();
897  const std::vector<std::string>& vars = group->getVariableNames();
898  const auto num_joints = group->getVariableCount();
899  Eigen::VectorXd max_velocity(num_joints);
900  Eigen::VectorXd max_acceleration(num_joints);
901  for (size_t j = 0; j < num_joints; ++j)
902  {
903  const auto& name = vars[j];
904  const moveit::core::VariableBounds& bounds = rmodel.getVariableBounds(name);
905 
906  // VELOCITY LIMIT
907  auto it = velocity_limits.find(name); // check for a custom limit
908  if (it != velocity_limits.end())
909  {
910  if (!validate_limit("velocity", it->second, name))
911  return false;
912  max_velocity[j] = it->second * velocity_scaling_factor;
913  }
914  else if (bounds.velocity_bounded_) // resort to the limit from the robot model
915  {
916  if (!validate_limit("velocity", bounds.max_velocity_, name))
917  return false;
918  max_velocity[j] =
919  std::min(std::fabs(bounds.max_velocity_), std::fabs(bounds.min_velocity_)) * velocity_scaling_factor;
920  }
921  else // default limit
922  {
923  max_velocity[j] = DEFAULT_VELOCITY_LIMIT;
924  ROS_WARN_ONCE_NAMED(LOGNAME, "No velocity limits defined for '%s'! Define them in URDF or joint_limits.yaml",
925  name.c_str());
926  }
927 
928  // ACCELERATION LIMIT
929  it = acceleration_limits.find(name); // check for a custom limit
930  if (it != acceleration_limits.end())
931  {
932  if (!validate_limit("acceleration", it->second, name))
933  return false;
934  max_acceleration[j] = it->second * acceleration_scaling_factor;
935  }
936 
937  else if (bounds.acceleration_bounded_) // resort to the limit from the robot model
938  {
939  if (!validate_limit("acceleration", bounds.max_acceleration_, name))
940  return false;
941  max_acceleration[j] = std::min(std::fabs(bounds.max_acceleration_), std::fabs(bounds.min_acceleration_)) *
942  acceleration_scaling_factor;
943  }
944  else // default limit
945  {
946  max_acceleration[j] = DEFAULT_ACCELERATION_LIMIT;
947  ROS_WARN_ONCE_NAMED(LOGNAME, "No acceleration limits defined for '%s'! Define them in joint_limits.yaml",
948  name.c_str());
949  }
950  }
951 
952  // This lib does not actually work properly when angles wrap around, so we need to unwind the path first
953  trajectory.unwind();
954 
955  if (hasMixedJointTypes(group))
956  {
958  "There is a combination of revolute and prismatic joints in the robot model. "
959  "TOTG's `path_tolerance` parameter is applied to both types ignoring their different units.");
960  }
961 
962  const unsigned num_points = trajectory.getWayPointCount();
963  const std::vector<int>& idx = group->getVariableIndexList();
964 
965  // Have to convert into Eigen data structs and remove repeated points
966  // (https://github.com/tobiaskunz/trajectories/issues/3)
967  std::list<Eigen::VectorXd> points;
968  for (size_t p = 0; p < num_points; ++p)
969  {
970  moveit::core::RobotStatePtr waypoint = trajectory.getWayPointPtr(p);
971  Eigen::VectorXd new_point(num_joints);
972  // The first point should always be kept
973  bool diverse_point = (p == 0);
974 
975  for (size_t j = 0; j < num_joints; ++j)
976  {
977  new_point[j] = waypoint->getVariablePosition(idx[j]);
978  // If any joint angle is different, it's a unique waypoint
979  if (p > 0 && std::fabs(new_point[j] - points.back()[j]) > min_angle_change_)
980  {
981  diverse_point = true;
982  }
983  }
984 
985  if (diverse_point)
986  {
987  points.push_back(new_point);
988  // If the last point is not a diverse_point we replace the last added point with it to make sure to always have
989  // the input end point as the last point
990  }
991  else if (p == num_points - 1)
992  {
993  points.back() = new_point;
994  }
995  }
996 
997  // Return trajectory with only the first waypoint if there are not multiple diverse points
998  if (points.size() == 1)
999  {
1001  waypoint.zeroVelocities();
1002  waypoint.zeroAccelerations();
1003  trajectory.clear();
1004  trajectory.addSuffixWayPoint(waypoint, 0.0);
1005  return true;
1006  }
1007 
1008  // Now actually call the algorithm
1009  // We use a smaller timestep for better accuracy
1010  Trajectory parameterized(Path(points, path_tolerance_), max_velocity, max_acceleration, 0.1 * resample_dt_);
1011  if (!parameterized.isValid())
1012  {
1013  ROS_ERROR_NAMED(LOGNAME, "Unable to parameterize trajectory.");
1014  return false;
1015  }
1016 
1017  // Compute sample count
1018  size_t sample_count = std::ceil(parameterized.getDuration() / resample_dt_);
1019 
1020  // Resample and fill in trajectory
1022  trajectory.clear();
1023  double last_t = 0;
1024  for (size_t sample = 0; sample <= sample_count; ++sample)
1025  {
1026  // always sample the end of the trajectory as well
1027  double t = std::min(parameterized.getDuration(), sample * resample_dt_);
1028  Eigen::VectorXd position = parameterized.getPosition(t);
1029  Eigen::VectorXd velocity = parameterized.getVelocity(t);
1030  Eigen::VectorXd acceleration = parameterized.getAcceleration(t);
1031 
1032  for (size_t j = 0; j < num_joints; ++j)
1033  {
1034  waypoint.setVariablePosition(idx[j], position[j]);
1035  waypoint.setVariableVelocity(idx[j], velocity[j]);
1036  waypoint.setVariableAcceleration(idx[j], acceleration[j]);
1037  }
1038 
1039  trajectory.addSuffixWayPoint(waypoint, t - last_t);
1040  last_t = t;
1041  }
1042 
1043  return true;
1044 }
1045 
1047 {
1048  const std::vector<const moveit::core::JointModel*>& joint_models = group->getActiveJointModels();
1049 
1050  bool have_prismatic =
1051  std::any_of(joint_models.cbegin(), joint_models.cend(), [](const moveit::core::JointModel* joint_model) {
1052  return joint_model->getType() == moveit::core::JointModel::JointType::PRISMATIC;
1053  });
1054 
1055  bool have_revolute =
1056  std::any_of(joint_models.cbegin(), joint_models.cend(), [](const moveit::core::JointModel* joint_model) {
1057  return joint_model->getType() == moveit::core::JointModel::JointType::REVOLUTE;
1058  });
1059 
1060  return have_prismatic && have_revolute;
1061 }
1062 
1063 double TimeOptimalTrajectoryGeneration::verifyScalingFactor(const double requested_scaling_factor) const
1064 {
1065  double scaling_factor = std::clamp(requested_scaling_factor, 1e-7, 1.0);
1066  if (requested_scaling_factor != scaling_factor)
1067  {
1068  ROS_WARN_NAMED(LOGNAME, "Invalid max_scaling_factor specified: %f, reverting to %f instead.",
1069  requested_scaling_factor, scaling_factor);
1070  }
1071  return scaling_factor;
1072 }
1073 } // namespace trajectory_processing
moveit::core::JointModelGroup::getActiveJointModels
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
Definition: joint_model_group.h:222
trajectory_processing::Trajectory::TrajectoryStep::path_pos_
double path_pos_
Definition: time_optimal_trajectory_generation.h:135
trajectory_processing::Path::getPathSegment
PathSegment * getPathSegment(double &s) const
Definition: time_optimal_trajectory_generation.cpp:260
robot_trajectory::RobotTrajectory::getWayPointCount
std::size_t getWayPointCount() const
Definition: robot_trajectory.h:131
robot_trajectory::RobotTrajectory::getGroup
const moveit::core::JointModelGroup * getGroup() const
Definition: robot_trajectory.h:118
trajectory_processing::Trajectory::getVelocityMaxPathVelocity
double getVelocityMaxPathVelocity(double path_pos) const
Definition: time_optimal_trajectory_generation.cpp:737
trajectory_processing::Trajectory::getVelocity
Eigen::VectorXd getVelocity(double time) const
Return the velocity vector for a given point in time.
Definition: time_optimal_trajectory_generation.cpp:822
moveit::core::JointModelGroup::getVariableIndexList
const std::vector< int > & getVariableIndexList() const
Get the index locations in the complete robot state for all the variables in this group.
Definition: joint_model_group.h:351
trajectory_processing::CircularPathSegment::getSwitchingPoints
std::list< double > getSwitchingPoints() const override
Definition: time_optimal_trajectory_generation.cpp:159
moveit::core::JointModelGroup
Definition: joint_model_group.h:134
moveit::core::VariableBounds
Definition: joint_model.h:118
trajectory_processing::Trajectory::cached_trajectory_segment_
std::list< TrajectoryStep >::const_iterator cached_trajectory_segment_
Definition: time_optimal_trajectory_generation.h:169
trajectory_processing::CircularPathSegment::getCurvature
Eigen::VectorXd getCurvature(double s) const override
Definition: time_optimal_trajectory_generation.cpp:153
trajectory_processing::Trajectory::TrajectoryStep
Definition: time_optimal_trajectory_generation.h:127
trajectory_processing::CircularPathSegment::CircularPathSegment
CircularPathSegment(const Eigen::VectorXd &start, const Eigen::VectorXd &intersection, const Eigen::VectorXd &end, double max_deviation)
Definition: time_optimal_trajectory_generation.cpp:97
trajectory_processing::Path::getLength
double getLength() const
Definition: time_optimal_trajectory_generation.cpp:255
s
XmlRpcServer s
trajectory_processing::LinearPathSegment::clone
LinearPathSegment * clone() const override
Definition: time_optimal_trajectory_generation.cpp:84
trajectory_processing::PathSegment::getTangent
virtual Eigen::VectorXd getTangent(double s) const =0
trajectory_processing::Trajectory::getTrajectorySegment
std::list< TrajectoryStep >::const_iterator getTrajectorySegment(double time) const
Definition: time_optimal_trajectory_generation.cpp:782
moveit::core::RobotState::zeroAccelerations
void zeroAccelerations()
Set all accelerations to 0.0.
Definition: robot_state.cpp:319
trajectory_processing::DEFAULT_ACCELERATION_LIMIT
constexpr double DEFAULT_ACCELERATION_LIMIT
Definition: time_optimal_trajectory_generation.cpp:52
trajectory_processing::LinearPathSegment::end_
Eigen::VectorXd end_
Definition: time_optimal_trajectory_generation.cpp:90
trajectory_processing::Path::length_
double length_
Definition: time_optimal_trajectory_generation.h:96
moveit::core::RobotModel
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:143
moveit::core::RobotModel::getVariableBounds
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:512
trajectory_processing::Trajectory::~Trajectory
~Trajectory()
Definition: time_optimal_trajectory_generation.cpp:359
trajectory_processing::TimeOptimalTrajectoryGeneration::TimeOptimalTrajectoryGeneration
TimeOptimalTrajectoryGeneration(const double path_tolerance=0.1, const double resample_dt=0.1, const double min_angle_change=0.001)
Definition: time_optimal_trajectory_generation.cpp:859
robot_trajectory::RobotTrajectory::addSuffixWayPoint
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
Definition: robot_trajectory.h:205
moveit::core::JointModelGroup::getParentModel
const RobotModel & getParentModel() const
Get the kinematic model this group is part of.
Definition: joint_model_group.h:179
trajectory_processing::CircularPathSegment
Definition: time_optimal_trajectory_generation.cpp:94
ROS_WARN_ONCE_NAMED
#define ROS_WARN_ONCE_NAMED(name,...)
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit::core::RobotState
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:155
moveit::core::RobotState::setVariableVelocity
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:348
trajectory_processing::LinearPathSegment::LinearPathSegment
LinearPathSegment(const Eigen::VectorXd &start, const Eigen::VectorXd &end)
Definition: time_optimal_trajectory_generation.cpp:57
robot_trajectory::RobotTrajectory
Maintain a sequence of waypoints and the time durations between these waypoints.
Definition: robot_trajectory.h:84
trajectory_processing::Path::switching_points_
std::list< std::pair< double, bool > > switching_points_
Definition: time_optimal_trajectory_generation.h:97
trajectory_processing::Trajectory::max_velocity_
Eigen::VectorXd max_velocity_
Definition: time_optimal_trajectory_generation.h:159
trajectory_processing::PathSegment::getCurvature
virtual Eigen::VectorXd getCurvature(double s) const =0
trajectory_processing::Path::getNextSwitchingPoint
double getNextSwitchingPoint(double s, bool &discontinuity) const
Get the next switching point.
Definition: time_optimal_trajectory_generation.cpp:292
trajectory_processing::Trajectory::cached_time_
double cached_time_
Definition: time_optimal_trajectory_generation.h:168
trajectory_processing::CircularPathSegment::x
Eigen::VectorXd x
Definition: time_optimal_trajectory_generation.cpp:188
trajectory_processing::LinearPathSegment::getConfig
Eigen::VectorXd getConfig(double s) const override
Definition: time_optimal_trajectory_generation.cpp:62
moveit::core::JointModelGroup::getVariableNames
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...
Definition: joint_model_group.h:254
trajectory_processing::CircularPathSegment::getConfig
Eigen::VectorXd getConfig(double s) const override
Definition: time_optimal_trajectory_generation.cpp:141
console.h
trajectory_processing::Trajectory::integrateBackward
void integrateBackward(std::list< TrajectoryStep > &start_trajectory, double path_pos, double path_vel, double acceleration)
Definition: time_optimal_trajectory_generation.cpp:626
moveit::core::VariableBounds::max_velocity_
double max_velocity_
Definition: joint_model.h:171
trajectory_processing::Trajectory::valid_
bool valid_
Definition: time_optimal_trajectory_generation.h:162
trajectory_processing::TimeOptimalTrajectoryGeneration::path_tolerance_
const double path_tolerance_
Definition: time_optimal_trajectory_generation.h:233
trajectory_processing::Trajectory::getAccelerationMaxPathVelocityDeriv
double getAccelerationMaxPathVelocityDeriv(double path_pos)
Definition: time_optimal_trajectory_generation.cpp:748
name
std::string name
trajectory_processing::Trajectory::getDuration
double getDuration() const
Returns the optimal duration of the trajectory.
Definition: time_optimal_trajectory_generation.cpp:777
moveit::core::RobotState::setVariablePosition
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:254
trajectory_processing::DEFAULT_VELOCITY_LIMIT
constexpr double DEFAULT_VELOCITY_LIMIT
Definition: time_optimal_trajectory_generation.cpp:51
trajectory_processing::CircularPathSegment::clone
CircularPathSegment * clone() const override
Definition: time_optimal_trajectory_generation.cpp:180
trajectory_processing::Trajectory::TrajectoryStep::path_vel_
double path_vel_
Definition: time_optimal_trajectory_generation.h:136
trajectory_processing::Trajectory::max_acceleration_
Eigen::VectorXd max_acceleration_
Definition: time_optimal_trajectory_generation.h:160
trajectory_processing::Trajectory::time_step_
const double time_step_
Definition: time_optimal_trajectory_generation.h:166
trajectory_processing::Trajectory::getNextSwitchingPoint
bool getNextSwitchingPoint(double path_pos, TrajectoryStep &next_switching_point, double &before_acceleration, double &after_acceleration)
Definition: time_optimal_trajectory_generation.cpp:364
trajectory_processing::CircularPathSegment::center
Eigen::VectorXd center
Definition: time_optimal_trajectory_generation.cpp:187
trajectory_processing::Trajectory::getNextAccelerationSwitchingPoint
bool getNextAccelerationSwitchingPoint(double path_pos, TrajectoryStep &next_switching_point, double &before_acceleration, double &after_acceleration)
Definition: time_optimal_trajectory_generation.cpp:411
robot_trajectory::RobotTrajectory::clear
RobotTrajectory & clear()
Definition: robot_trajectory.h:264
robot_trajectory::RobotTrajectory::empty
bool empty() const
Definition: robot_trajectory.h:195
trajectory_processing::Trajectory::getMinMaxPathAcceleration
double getMinMaxPathAcceleration(double path_position, double path_velocity, bool max)
Definition: time_optimal_trajectory_generation.cpp:683
time_optimal_trajectory_generation.h
trajectory_processing
Definition: iterative_spline_parameterization.h:43
moveit::core::VariableBounds::min_velocity_
double min_velocity_
Definition: joint_model.h:170
trajectory_processing::LinearPathSegment::getTangent
Eigen::VectorXd getTangent(double) const override
Definition: time_optimal_trajectory_generation.cpp:69
trajectory_processing::Path::Path
Path(const std::list< Eigen::VectorXd > &path, double max_deviation=0.0)
Definition: time_optimal_trajectory_generation.cpp:192
next
EndPoint * next[3]
trajectory_processing::CircularPathSegment::getTangent
Eigen::VectorXd getTangent(double s) const override
Definition: time_optimal_trajectory_generation.cpp:147
trajectory_processing::Trajectory::trajectory_
std::list< TrajectoryStep > trajectory_
Definition: time_optimal_trajectory_generation.h:163
trajectory_processing::Path::getConfig
Eigen::VectorXd getConfig(double s) const
Definition: time_optimal_trajectory_generation.cpp:274
trajectory_processing::TimeOptimalTrajectoryGeneration::hasMixedJointTypes
bool hasMixedJointTypes(const moveit::core::JointModelGroup *group) const
Check if a combination of revolute and prismatic joints is used. path_tolerance_ is not valid,...
Definition: time_optimal_trajectory_generation.cpp:1046
trajectory_processing::Trajectory::Trajectory
Trajectory(const Path &path, const Eigen::VectorXd &max_velocity, const Eigen::VectorXd &max_acceleration, double time_step=0.001)
Generates a time-optimal trajectory.
Definition: time_optimal_trajectory_generation.cpp:313
trajectory_processing::CircularPathSegment::radius
double radius
Definition: time_optimal_trajectory_generation.cpp:186
trajectory_processing::Trajectory::getVelocityMaxPathVelocityDeriv
double getVelocityMaxPathVelocityDeriv(double path_pos)
Definition: time_optimal_trajectory_generation.cpp:754
trajectory_processing::EPS
constexpr double EPS
Definition: time_optimal_trajectory_generation.cpp:50
point
std::chrono::system_clock::time_point point
trajectory_processing::Trajectory::getAcceleration
Eigen::VectorXd getAcceleration(double time) const
Return the acceleration vector for a given point in time.
Definition: time_optimal_trajectory_generation.cpp:839
start
ROSCPP_DECL void start()
trajectory_processing::Trajectory::end_trajectory_
std::list< TrajectoryStep > end_trajectory_
Definition: time_optimal_trajectory_generation.h:164
trajectory_processing::Trajectory
Definition: time_optimal_trajectory_generation.h:101
moveit::core::RobotState::zeroVelocities
void zeroVelocities()
Set all velocities to 0.0.
Definition: robot_state.cpp:313
trajectory_processing::TimeOptimalTrajectoryGeneration::resample_dt_
const double resample_dt_
Definition: time_optimal_trajectory_generation.h:234
trajectory_processing::LinearPathSegment::getSwitchingPoints
std::list< double > getSwitchingPoints() const override
Definition: time_optimal_trajectory_generation.cpp:79
trajectory_processing::LinearPathSegment
Definition: time_optimal_trajectory_generation.cpp:54
trajectory_processing::LinearPathSegment::getCurvature
Eigen::VectorXd getCurvature(double) const override
Definition: time_optimal_trajectory_generation.cpp:74
trajectory_processing::Trajectory::getMinMaxPhaseSlope
double getMinMaxPhaseSlope(double path_position, double path_velocity, bool max)
Definition: time_optimal_trajectory_generation.cpp:701
std
trajectory_processing::Path
Definition: time_optimal_trajectory_generation.h:74
trajectory_processing::CircularPathSegment::y
Eigen::VectorXd y
Definition: time_optimal_trajectory_generation.cpp:189
trajectory_processing::Path::getSwitchingPoints
std::list< std::pair< double, bool > > getSwitchingPoints() const
Return a list of all switching points as a pair (arc length to switching point, discontinuity)
Definition: time_optimal_trajectory_generation.cpp:308
moveit::core::VariableBounds::acceleration_bounded_
bool acceleration_bounded_
Definition: joint_model.h:176
M_PI
#define M_PI
trajectory_processing::Trajectory::getAccelerationMaxPathVelocity
double getAccelerationMaxPathVelocity(double path_pos) const
Definition: time_optimal_trajectory_generation.cpp:706
trajectory_processing::TimeOptimalTrajectoryGeneration::computeTimeStamps
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_)....
Definition: time_optimal_trajectory_generation.h:191
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
angle
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
moveit::core::VariableBounds::velocity_bounded_
bool velocity_bounded_
Definition: joint_model.h:172
trajectory_processing::Trajectory::getNextVelocitySwitchingPoint
bool getNextVelocitySwitchingPoint(double path_pos, TrajectoryStep &next_switching_point, double &before_acceleration, double &after_acceleration)
Definition: time_optimal_trajectory_generation.cpp:461
trajectory_processing::Path::path_segments_
std::list< std::unique_ptr< PathSegment > > path_segments_
Definition: time_optimal_trajectory_generation.h:98
robot_trajectory::RobotTrajectory::getWayPointPtr
moveit::core::RobotStatePtr & getWayPointPtr(std::size_t index)
Definition: robot_trajectory.h:151
trajectory_processing::Path::getTangent
Eigen::VectorXd getTangent(double s) const
Definition: time_optimal_trajectory_generation.cpp:280
moveit::core::JointModelGroup::getVariableCount
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
Definition: joint_model_group.h:475
trajectory_processing::Trajectory::joint_num_
unsigned int joint_num_
Definition: time_optimal_trajectory_generation.h:161
trajectory_processing::TimeOptimalTrajectoryGeneration::min_angle_change_
const double min_angle_change_
Definition: time_optimal_trajectory_generation.h:235
trajectory_processing::Trajectory::integrateForward
bool integrateForward(std::list< TrajectoryStep > &trajectory, double acceleration)
Definition: time_optimal_trajectory_generation.cpp:510
trajectory_processing::Trajectory::path_
Path path_
Definition: time_optimal_trajectory_generation.h:158
robot_trajectory::RobotTrajectory::unwind
RobotTrajectory & unwind()
Definition: robot_trajectory.cpp:170
moveit::core::RobotState::setVariableAcceleration
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:447
pr2_arm_kinematics::distance
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:86
trajectory_processing::PathSegment::length_
double length_
Definition: time_optimal_trajectory_generation.h:71
moveit::core::VariableBounds::max_acceleration_
double max_acceleration_
Definition: joint_model.h:175
trajectory_processing::PathSegment::getLength
double getLength() const
Definition: time_optimal_trajectory_generation.h:58
trajectory_processing::Path::getCurvature
Eigen::VectorXd getCurvature(double s) const
Definition: time_optimal_trajectory_generation.cpp:286
trajectory_processing::TimeOptimalTrajectoryGeneration::verifyScalingFactor
double verifyScalingFactor(const double requested_scaling_factor) const
Check if the requested scaling factor is valid and if not, return 1.0.
Definition: time_optimal_trajectory_generation.cpp:1063
t
geometry_msgs::TransformStamped t
trajectory_processing::Trajectory::getPosition
Eigen::VectorXd getPosition(double time) const
Return the position/configuration vector for a given point in time.
Definition: time_optimal_trajectory_generation.cpp:805
moveit::core::VariableBounds::min_acceleration_
double min_acceleration_
Definition: joint_model.h:174
moveit::core::JointModel
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:173
trajectory_processing::Trajectory::isValid
bool isValid() const
Call this method after constructing the object to make sure the trajectory generation succeeded witho...
Definition: time_optimal_trajectory_generation.cpp:772
trajectory_processing::LinearPathSegment::start_
Eigen::VectorXd start_
Definition: time_optimal_trajectory_generation.cpp:91
trajectory_processing::PathSegment
Definition: time_optimal_trajectory_generation.h:49
trajectory_processing::PathSegment::getConfig
virtual Eigen::VectorXd getConfig(double s) const =0
trajectory_processing::LOGNAME
const std::string LOGNAME
Definition: time_optimal_trajectory_generation.cpp:49
robot_trajectory::RobotTrajectory::getWayPoint
const moveit::core::RobotState & getWayPoint(std::size_t index) const
Definition: robot_trajectory.h:136


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Mar 3 2024 03:23:36