moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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 <[email protected]>
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>
48
50{
51namespace
52{
53constexpr double DEFAULT_TIMESTEP = 1e-3;
54constexpr double EPS = 1e-6;
55constexpr double DEFAULT_SCALING_FACTOR = 1.0;
56
57rclcpp::Logger getLogger()
58{
59 return moveit::getLogger("moveit.core.time_optimal_trajectory_generation");
60}
61} // namespace
62
64{
65public:
66 LinearPathSegment(const Eigen::VectorXd& start, const Eigen::VectorXd& end)
67 : PathSegment((end - start).norm()), end_(end), start_(start)
68 {
69 }
70
71 Eigen::VectorXd getConfig(double s) const override
72 {
73 s /= length_;
74 s = std::max(0.0, std::min(1.0, s));
75 return (1.0 - s) * start_ + s * end_;
76 }
77
78 Eigen::VectorXd getTangent(double /* s */) const override
79 {
80 return (end_ - start_) / length_;
81 }
82
83 Eigen::VectorXd getCurvature(double /* s */) const override
84 {
85 return Eigen::VectorXd::Zero(start_.size());
86 }
87
88 std::list<double> getSwitchingPoints() const override
89 {
90 return std::list<double>();
91 }
92
93 LinearPathSegment* clone() const override
94 {
95 return new LinearPathSegment(*this);
96 }
97
98private:
99 Eigen::VectorXd end_;
100 Eigen::VectorXd start_;
101};
102
104{
105public:
106 CircularPathSegment(const Eigen::VectorXd& start, const Eigen::VectorXd& intersection, const Eigen::VectorXd& end,
107 double max_deviation)
108 {
109 if ((intersection - start).norm() < 0.000001 || (end - intersection).norm() < 0.000001)
110 {
111 length_ = 0.0;
112 radius_ = 1.0;
113 center_ = intersection;
114 x_ = Eigen::VectorXd::Zero(start.size());
115 y_ = Eigen::VectorXd::Zero(start.size());
116 return;
117 }
118
119 const Eigen::VectorXd start_direction = (intersection - start).normalized();
120 const Eigen::VectorXd end_direction = (end - intersection).normalized();
121 const double start_dot_end = start_direction.dot(end_direction);
122
123 // catch division by 0 in computations below
124 if (start_dot_end > 0.999999 || start_dot_end < -0.999999)
125 {
126 length_ = 0.0;
127 radius_ = 1.0;
128 center_ = intersection;
129 x_ = Eigen::VectorXd::Zero(start.size());
130 y_ = Eigen::VectorXd::Zero(start.size());
131 return;
132 }
133
134 const double angle = acos(start_dot_end);
135 const double start_distance = (start - intersection).norm();
136 const double end_distance = (end - intersection).norm();
137
138 // enforce max deviation
139 double distance = std::min(start_distance, end_distance);
140 distance = std::min(distance, max_deviation * sin(0.5 * angle) / (1.0 - cos(0.5 * angle)));
141
142 radius_ = distance / tan(0.5 * angle);
143 length_ = angle * radius_;
144
145 center_ = intersection + (end_direction - start_direction).normalized() * radius_ / cos(0.5 * angle);
146 x_ = (intersection - distance * start_direction - center_).normalized();
147 y_ = start_direction;
148 }
149
150 Eigen::VectorXd getConfig(double s) const override
151 {
152 const double angle = s / radius_;
153 return center_ + radius_ * (x_ * cos(angle) + y_ * sin(angle));
154 }
155
156 Eigen::VectorXd getTangent(double s) const override
157 {
158 const double angle = s / radius_;
159 return -x_ * sin(angle) + y_ * cos(angle);
160 }
161
162 Eigen::VectorXd getCurvature(double s) const override
163 {
164 const double angle = s / radius_;
165 return -1.0 / radius_ * (x_ * cos(angle) + y_ * sin(angle));
166 }
167
168 std::list<double> getSwitchingPoints() const override
169 {
170 std::list<double> switching_points;
171 const double dim = x_.size();
172 for (unsigned int i = 0; i < dim; ++i)
173 {
174 double switching_angle = atan2(y_[i], x_[i]);
175 if (switching_angle < 0.0)
176 {
177 switching_angle += M_PI;
178 }
179 const double switching_point = switching_angle * radius_;
180 if (switching_point < length_)
181 {
182 switching_points.push_back(switching_point);
183 }
184 }
185 switching_points.sort();
186 return switching_points;
187 }
188
189 CircularPathSegment* clone() const override
190 {
191 return new CircularPathSegment(*this);
192 }
193
194private:
195 double radius_;
196 Eigen::VectorXd center_;
197 Eigen::VectorXd x_;
198 Eigen::VectorXd y_;
199};
200
201std::optional<Path> Path::create(const std::vector<Eigen::VectorXd>& waypoints, double max_deviation)
202{
203 if (waypoints.size() < 2)
204 {
205 RCLCPP_ERROR(getLogger(), "A path needs at least 2 waypoints.");
206 return std::nullopt;
207 }
208 if (max_deviation <= 0.0)
209 {
210 RCLCPP_ERROR(getLogger(), "Path max_deviation must be greater than 0.0.");
211 return std::nullopt;
212 }
213
214 // waypoints_iterator1, waypoints_iterator2 and waypoints_iterator3 point to three consecutive waypoints of the input
215 // path. The algorithm creates a LinearPathSegment starting at waypoints_iterator1, connected to CircularPathSegment
216 // at waypoints_iterator2, connected to another LinearPathSegment towards waypoints_iterator3.
217 // It does this iteratively for each three consecutive waypoints, therefore applying a blending of 'max_deviation' at
218 // the intermediate waypoints.
219 Path path;
220 std::vector<Eigen::VectorXd>::const_iterator waypoints_iterator1 = waypoints.begin();
221 std::vector<Eigen::VectorXd>::const_iterator waypoints_iterator2 = waypoints_iterator1;
222 ++waypoints_iterator2;
223 std::vector<Eigen::VectorXd>::const_iterator waypoints_iterator3;
224 Eigen::VectorXd start_config = *waypoints_iterator1;
225 while (waypoints_iterator2 != waypoints.end())
226 {
227 waypoints_iterator3 = waypoints_iterator2;
228 ++waypoints_iterator3;
229 if (waypoints_iterator3 != waypoints.end())
230 {
231 // Check that the path is not making a 180 deg. turn, which is not supported by the current implementation.
232 Eigen::VectorXd incoming_vector = *waypoints_iterator2 - *waypoints_iterator1;
233 Eigen::VectorXd outcoming_vector = *waypoints_iterator3 - *waypoints_iterator2;
234 double incoming_vector_norm = incoming_vector.norm();
235 double outcoming_vector_norm = outcoming_vector.norm();
236 if (incoming_vector_norm > std::numeric_limits<double>::epsilon() &&
237 outcoming_vector_norm > std::numeric_limits<double>::epsilon())
238 {
239 double cos_angle = incoming_vector.dot(outcoming_vector) / (incoming_vector_norm * outcoming_vector_norm);
240 constexpr double angle_tolerance = 1e-05;
241 if (cos_angle <= -1.0 + angle_tolerance)
242 {
243 RCLCPP_ERROR(getLogger(),
244 "The path requires a 180 deg. turn, which is not supported by the current implementation.");
245 return std::nullopt;
246 }
247 }
248 }
249 if (max_deviation > 0.0 && waypoints_iterator3 != waypoints.end())
250 {
251 CircularPathSegment* blend_segment =
252 new CircularPathSegment(0.5 * (*waypoints_iterator1 + *waypoints_iterator2), *waypoints_iterator2,
253 0.5 * (*waypoints_iterator2 + *waypoints_iterator3), max_deviation);
254 Eigen::VectorXd end_config = blend_segment->getConfig(0.0);
255 if ((end_config - start_config).norm() > 0.000001)
256 {
257 path.path_segments_.push_back(std::make_unique<LinearPathSegment>(start_config, end_config));
258 }
259 path.path_segments_.emplace_back(blend_segment);
260
261 start_config = blend_segment->getConfig(blend_segment->getLength());
262 }
263 else
264 {
265 path.path_segments_.push_back(std::make_unique<LinearPathSegment>(start_config, *waypoints_iterator2));
266 start_config = *waypoints_iterator2;
267 }
268 waypoints_iterator1 = waypoints_iterator2;
269 ++waypoints_iterator2;
270 }
271
272 // Create list of switching point candidates, calculate total path length and
273 // absolute positions of path segments
274 for (std::unique_ptr<PathSegment>& path_segment : path.path_segments_)
275 {
276 path_segment->position_ = path.length_;
277 std::list<double> local_switching_points = path_segment->getSwitchingPoints();
278 for (std::list<double>::const_iterator point = local_switching_points.begin();
279 point != local_switching_points.end(); ++point)
280 {
281 path.switching_points_.push_back(std::make_pair(path.length_ + *point, false));
282 }
283 path.length_ += path_segment->getLength();
284 while (!path.switching_points_.empty() && path.switching_points_.back().first >= path.length_)
285 path.switching_points_.pop_back();
286 path.switching_points_.push_back(std::make_pair(path.length_, true));
287 }
288 path.switching_points_.pop_back();
289 return path;
290}
291
292Path::Path(const Path& path) : length_(path.length_), switching_points_(path.switching_points_)
293{
294 for (const std::unique_ptr<PathSegment>& path_segment : path.path_segments_)
295 {
296 path_segments_.emplace_back(path_segment->clone());
297 }
298}
299
300double Path::getLength() const
301{
302 return length_;
303}
304
305PathSegment* Path::getPathSegment(double& s) const
306{
307 std::list<std::unique_ptr<PathSegment>>::const_iterator it = path_segments_.begin();
308 std::list<std::unique_ptr<PathSegment>>::const_iterator next = it;
309 ++next;
310 while (next != path_segments_.end() && s >= (*next)->position_)
311 {
312 it = next;
313 ++next;
314 }
315 s -= (*it)->position_;
316 return (*it).get();
317}
318
319Eigen::VectorXd Path::getConfig(double s) const
320{
321 const PathSegment* path_segment = getPathSegment(s);
322 return path_segment->getConfig(s);
323}
324
325Eigen::VectorXd Path::getTangent(double s) const
326{
327 const PathSegment* path_segment = getPathSegment(s);
328 return path_segment->getTangent(s);
329}
330
331Eigen::VectorXd Path::getCurvature(double s) const
332{
333 const PathSegment* path_segment = getPathSegment(s);
334 return path_segment->getCurvature(s);
335}
336
337double Path::getNextSwitchingPoint(double s, bool& discontinuity) const
338{
339 std::list<std::pair<double, bool>>::const_iterator it = switching_points_.begin();
340 while (it != switching_points_.end() && it->first <= s)
341 {
342 ++it;
343 }
344 if (it == switching_points_.end())
345 {
346 discontinuity = true;
347 return length_;
348 }
349 discontinuity = it->second;
350 return it->first;
351}
352
353std::list<std::pair<double, bool>> Path::getSwitchingPoints() const
354{
355 return switching_points_;
356}
357
358std::optional<Trajectory> Trajectory::create(const Path& path, const Eigen::VectorXd& max_velocity,
359 const Eigen::VectorXd& max_acceleration, double time_step)
360{
361 if (time_step <= 0)
362 {
363 RCLCPP_ERROR(getLogger(), "The trajectory is invalid because the time step is <= 0.0.");
364 return std::nullopt;
365 }
366
367 Trajectory output(path, max_velocity, max_acceleration, time_step);
368 output.trajectory_.push_back(TrajectoryStep(0.0, 0.0));
369 double after_acceleration = output.getMinMaxPathAcceleration(0.0, 0.0, true);
370 while (output.valid_ && !output.integrateForward(output.trajectory_, after_acceleration) && output.valid_)
371 {
372 double before_acceleration;
373 TrajectoryStep switching_point;
374 if (output.getNextSwitchingPoint(output.trajectory_.back().path_pos_, switching_point, before_acceleration,
375 after_acceleration))
376 {
377 break;
378 }
379 output.integrateBackward(output.trajectory_, switching_point.path_pos_, switching_point.path_vel_,
380 before_acceleration);
381 }
382
383 if (!output.valid_)
384 {
385 RCLCPP_ERROR(getLogger(), "Trajectory not valid after integrateForward and integrateBackward.");
386 return std::nullopt;
387 }
388
389 double before_acceleration = output.getMinMaxPathAcceleration(output.path_.getLength(), 0.0, false);
390 output.integrateBackward(output.trajectory_, output.path_.getLength(), 0.0, before_acceleration);
391
392 if (!output.valid_)
393 {
394 RCLCPP_ERROR(getLogger(), "Trajectory not valid after the second integrateBackward pass.");
395 return std::nullopt;
396 }
397
398 // Calculate timing.
399 std::list<TrajectoryStep>::iterator previous = output.trajectory_.begin();
400 std::list<TrajectoryStep>::iterator it = previous;
401 it->time_ = 0.0;
402 ++it;
403 while (it != output.trajectory_.end())
404 {
405 it->time_ = previous->time_ + (it->path_pos_ - previous->path_pos_) / ((it->path_vel_ + previous->path_vel_) / 2.0);
406 previous = it;
407 ++it;
408 }
409
410 return output;
411}
412
413Trajectory::Trajectory(const Path& path, const Eigen::VectorXd& max_velocity, const Eigen::VectorXd& max_acceleration,
414 double time_step)
415 : path_(path), max_velocity_(max_velocity), max_acceleration_(max_acceleration), time_step_(time_step)
416{
417 joint_num_ = max_velocity.size();
418}
419
420// Returns true if end of path is reached.
421bool Trajectory::getNextSwitchingPoint(double path_pos, TrajectoryStep& next_switching_point,
422 double& before_acceleration, double& after_acceleration)
423{
424 TrajectoryStep acceleration_switching_point(path_pos, 0.0);
425 double acceleration_before_acceleration, acceleration_after_acceleration;
426 bool acceleration_reached_end;
427 do
428 {
429 acceleration_reached_end =
430 getNextAccelerationSwitchingPoint(acceleration_switching_point.path_pos_, acceleration_switching_point,
431 acceleration_before_acceleration, acceleration_after_acceleration);
432 } while (!acceleration_reached_end &&
433 acceleration_switching_point.path_vel_ > getVelocityMaxPathVelocity(acceleration_switching_point.path_pos_));
434
435 TrajectoryStep velocity_switching_point(path_pos, 0.0);
436 double velocity_before_acceleration, velocity_after_acceleration;
437 bool velocity_reached_end;
438 do
439 {
440 velocity_reached_end = getNextVelocitySwitchingPoint(velocity_switching_point.path_pos_, velocity_switching_point,
441 velocity_before_acceleration, velocity_after_acceleration);
442 } while (
443 !velocity_reached_end && velocity_switching_point.path_pos_ <= acceleration_switching_point.path_pos_ &&
444 (velocity_switching_point.path_vel_ > getAccelerationMaxPathVelocity(velocity_switching_point.path_pos_ - EPS) ||
445 velocity_switching_point.path_vel_ > getAccelerationMaxPathVelocity(velocity_switching_point.path_pos_ + EPS)));
446
447 if (acceleration_reached_end && velocity_reached_end)
448 {
449 return true;
450 }
451 else if (!acceleration_reached_end &&
452 (velocity_reached_end || acceleration_switching_point.path_pos_ <= velocity_switching_point.path_pos_))
453 {
454 next_switching_point = acceleration_switching_point;
455 before_acceleration = acceleration_before_acceleration;
456 after_acceleration = acceleration_after_acceleration;
457 return false;
458 }
459 else
460 {
461 next_switching_point = velocity_switching_point;
462 before_acceleration = velocity_before_acceleration;
463 after_acceleration = velocity_after_acceleration;
464 return false;
465 }
466}
467
468bool Trajectory::getNextAccelerationSwitchingPoint(double path_pos, TrajectoryStep& next_switching_point,
469 double& before_acceleration, double& after_acceleration)
470{
471 double switching_path_pos = path_pos;
472 double switching_path_vel;
473 while (true)
474 {
475 bool discontinuity;
476 switching_path_pos = path_.getNextSwitchingPoint(switching_path_pos, discontinuity);
477
478 if (switching_path_pos > path_.getLength() - EPS)
479 {
480 return true;
481 }
482
483 if (discontinuity)
484 {
485 const double before_path_vel = getAccelerationMaxPathVelocity(switching_path_pos - EPS);
486 const double after_path_vel = getAccelerationMaxPathVelocity(switching_path_pos + EPS);
487 switching_path_vel = std::min(before_path_vel, after_path_vel);
488 before_acceleration = getMinMaxPathAcceleration(switching_path_pos - EPS, switching_path_vel, false);
489 after_acceleration = getMinMaxPathAcceleration(switching_path_pos + EPS, switching_path_vel, true);
490
491 if ((before_path_vel > after_path_vel ||
492 getMinMaxPhaseSlope(switching_path_pos - EPS, switching_path_vel, false) >
493 getAccelerationMaxPathVelocityDeriv(switching_path_pos - 2.0 * EPS)) &&
494 (before_path_vel < after_path_vel || getMinMaxPhaseSlope(switching_path_pos + EPS, switching_path_vel, true) <
495 getAccelerationMaxPathVelocityDeriv(switching_path_pos + 2.0 * EPS)))
496 {
497 break;
498 }
499 }
500 else
501 {
502 switching_path_vel = getAccelerationMaxPathVelocity(switching_path_pos);
503 before_acceleration = 0.0;
504 after_acceleration = 0.0;
505
506 if (getAccelerationMaxPathVelocityDeriv(switching_path_pos - EPS) < 0.0 &&
507 getAccelerationMaxPathVelocityDeriv(switching_path_pos + EPS) > 0.0)
508 {
509 break;
510 }
511 }
512 }
513
514 next_switching_point = TrajectoryStep(switching_path_pos, switching_path_vel);
515 return false;
516}
517
518bool Trajectory::getNextVelocitySwitchingPoint(double path_pos, TrajectoryStep& next_switching_point,
519 double& before_acceleration, double& after_acceleration)
520{
521 bool start = false;
522 path_pos -= DEFAULT_TIMESTEP;
523 do
524 {
525 path_pos += DEFAULT_TIMESTEP;
526
527 if (getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos), false) >=
528 getVelocityMaxPathVelocityDeriv(path_pos))
529 {
530 start = true;
531 }
532 } while ((!start || getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos), false) >
533 getVelocityMaxPathVelocityDeriv(path_pos)) &&
534 path_pos < path_.getLength());
535
536 if (path_pos >= path_.getLength())
537 {
538 return true; // end of trajectory reached
539 }
540
541 double before_path_pos = path_pos - DEFAULT_TIMESTEP;
542 double after_path_pos = path_pos;
543 while (after_path_pos - before_path_pos > EPS)
544 {
545 path_pos = (before_path_pos + after_path_pos) / 2.0;
546 if (getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos), false) >
547 getVelocityMaxPathVelocityDeriv(path_pos))
548 {
549 before_path_pos = path_pos;
550 }
551 else
552 {
553 after_path_pos = path_pos;
554 }
555 }
556
557 before_acceleration = getMinMaxPathAcceleration(before_path_pos, getVelocityMaxPathVelocity(before_path_pos), false);
558 after_acceleration = getMinMaxPathAcceleration(after_path_pos, getVelocityMaxPathVelocity(after_path_pos), true);
559 next_switching_point = TrajectoryStep(after_path_pos, getVelocityMaxPathVelocity(after_path_pos));
560 return false;
561}
562
563// Returns true if end of path is reached
564bool Trajectory::integrateForward(std::list<TrajectoryStep>& trajectory, double acceleration)
565{
566 double path_pos = trajectory.back().path_pos_;
567 double path_vel = trajectory.back().path_vel_;
568
569 std::list<std::pair<double, bool>> switching_points = path_.getSwitchingPoints();
570 std::list<std::pair<double, bool>>::iterator next_discontinuity = switching_points.begin();
571
572 while (true)
573 {
574 while ((next_discontinuity != switching_points.end()) &&
575 (next_discontinuity->first <= path_pos || !next_discontinuity->second))
576 {
577 ++next_discontinuity;
578 }
579
580 double old_path_pos = path_pos;
581 double old_path_vel = path_vel;
582
583 path_vel += time_step_ * acceleration;
584 path_pos += time_step_ * 0.5 * (old_path_vel + path_vel);
585
586 if (next_discontinuity != switching_points.end() && path_pos > next_discontinuity->first)
587 {
588 // Avoid having a TrajectoryStep with path_pos near a switching point which will cause an almost identical
589 // TrajectoryStep get added in the next run (https://github.com/moveit/moveit/issues/1665)
590 if (path_pos - next_discontinuity->first < EPS)
591 {
592 continue;
593 }
594 path_vel = old_path_vel +
595 (next_discontinuity->first - old_path_pos) * (path_vel - old_path_vel) / (path_pos - old_path_pos);
596 path_pos = next_discontinuity->first;
597 }
598
599 if (path_pos > path_.getLength())
600 {
601 trajectory.push_back(TrajectoryStep(path_pos, path_vel));
602 return true;
603 }
604 else if (path_vel < 0.0)
605 {
606 valid_ = false;
607 RCLCPP_ERROR(getLogger(), "Error while integrating forward: Negative path velocity");
608 return true;
609 }
610
611 if (path_vel > getVelocityMaxPathVelocity(path_pos) &&
612 getMinMaxPhaseSlope(old_path_pos, getVelocityMaxPathVelocity(old_path_pos), false) <=
613 getVelocityMaxPathVelocityDeriv(old_path_pos))
614 {
615 path_vel = getVelocityMaxPathVelocity(path_pos);
616 }
617
618 trajectory.push_back(TrajectoryStep(path_pos, path_vel));
619 acceleration = getMinMaxPathAcceleration(path_pos, path_vel, true);
620
621 if (path_vel == 0 && acceleration == 0)
622 {
623 // The position will never change if velocity and acceleration are zero.
624 // The loop will spin indefinitely as no exit condition is met.
625 valid_ = false;
626 RCLCPP_ERROR(getLogger(), "Error while integrating forward: zero acceleration and velocity. Are any relevant "
627 "acceleration components limited to zero?");
628 return true;
629 }
630
631 if (path_vel > getAccelerationMaxPathVelocity(path_pos) || path_vel > getVelocityMaxPathVelocity(path_pos))
632 {
633 // Find more accurate intersection with max-velocity curve using bisection
634 TrajectoryStep overshoot = trajectory.back();
635 trajectory.pop_back();
636 double before = trajectory.back().path_pos_;
637 double before_path_vel = trajectory.back().path_vel_;
638 double after = overshoot.path_pos_;
639 double after_path_vel = overshoot.path_vel_;
640 while (after - before > EPS)
641 {
642 const double midpoint = 0.5 * (before + after);
643 double midpoint_path_vel = 0.5 * (before_path_vel + after_path_vel);
644
645 if (midpoint_path_vel > getVelocityMaxPathVelocity(midpoint) &&
646 getMinMaxPhaseSlope(before, getVelocityMaxPathVelocity(before), false) <=
647 getVelocityMaxPathVelocityDeriv(before))
648 {
649 midpoint_path_vel = getVelocityMaxPathVelocity(midpoint);
650 }
651
652 if (midpoint_path_vel > getAccelerationMaxPathVelocity(midpoint) ||
653 midpoint_path_vel > getVelocityMaxPathVelocity(midpoint))
654 {
655 after = midpoint;
656 after_path_vel = midpoint_path_vel;
657 }
658 else
659 {
660 before = midpoint;
661 before_path_vel = midpoint_path_vel;
662 }
663 }
664 trajectory.push_back(TrajectoryStep(before, before_path_vel));
665
666 if (getAccelerationMaxPathVelocity(after) < getVelocityMaxPathVelocity(after))
667 {
668 if (after > next_discontinuity->first)
669 {
670 return false;
671 }
672 else if (getMinMaxPhaseSlope(trajectory.back().path_pos_, trajectory.back().path_vel_, true) >
673 getAccelerationMaxPathVelocityDeriv(trajectory.back().path_pos_))
674 {
675 return false;
676 }
677 }
678 else
679 {
680 if (getMinMaxPhaseSlope(trajectory.back().path_pos_, trajectory_.back().path_vel_, false) >
681 getVelocityMaxPathVelocityDeriv(trajectory_.back().path_pos_))
682 {
683 return false;
684 }
685 }
686 }
687 }
688}
689
690void Trajectory::integrateBackward(std::list<TrajectoryStep>& start_trajectory, double path_pos, double path_vel,
691 double acceleration)
692{
693 std::list<TrajectoryStep>::iterator start2 = start_trajectory.end();
694 --start2;
695 std::list<TrajectoryStep>::iterator start1 = start2;
696 --start1;
697 std::list<TrajectoryStep> trajectory;
698 double slope;
699 assert(start1->path_pos_ <= path_pos);
700
701 while (start1 != start_trajectory.begin() || path_pos >= 0.0)
702 {
703 if (start1->path_pos_ <= path_pos)
704 {
705 trajectory.push_front(TrajectoryStep(path_pos, path_vel));
706 path_vel -= time_step_ * acceleration;
707 path_pos -= time_step_ * 0.5 * (path_vel + trajectory.front().path_vel_);
708 acceleration = getMinMaxPathAcceleration(path_pos, path_vel, false);
709 slope = (trajectory.front().path_vel_ - path_vel) / (trajectory.front().path_pos_ - path_pos);
710
711 if (path_vel < 0.0)
712 {
713 valid_ = false;
714 RCLCPP_ERROR(getLogger(), "Error while integrating backward: Negative path velocity");
715 end_trajectory_ = trajectory;
716 return;
717 }
718 }
719 else
720 {
721 --start1;
722 --start2;
723 }
724
725 // Check for intersection between current start trajectory and backward
726 // trajectory segments
727 const double start_slope = (start2->path_vel_ - start1->path_vel_) / (start2->path_pos_ - start1->path_pos_);
728 const double intersection_path_pos =
729 (start1->path_vel_ - path_vel + slope * path_pos - start_slope * start1->path_pos_) / (slope - start_slope);
730 if (std::max(start1->path_pos_, path_pos) - EPS <= intersection_path_pos &&
731 intersection_path_pos <= EPS + std::min(start2->path_pos_, trajectory.front().path_pos_))
732 {
733 const double intersection_path_vel =
734 start1->path_vel_ + start_slope * (intersection_path_pos - start1->path_pos_);
735 start_trajectory.erase(start2, start_trajectory.end());
736 start_trajectory.push_back(TrajectoryStep(intersection_path_pos, intersection_path_vel));
737 start_trajectory.splice(start_trajectory.end(), trajectory);
738 return;
739 }
740 }
741
742 valid_ = false;
743 RCLCPP_ERROR(getLogger(), "Error while integrating backward: Did not hit start trajectory");
744 end_trajectory_ = trajectory;
745}
746
747double Trajectory::getMinMaxPathAcceleration(double path_pos, double path_vel, bool max)
748{
749 Eigen::VectorXd config_deriv = path_.getTangent(path_pos);
750 Eigen::VectorXd config_deriv2 = path_.getCurvature(path_pos);
751 double factor = max ? 1.0 : -1.0;
752 double max_path_acceleration = std::numeric_limits<double>::max();
753 for (unsigned int i = 0; i < joint_num_; ++i)
754 {
755 if (config_deriv[i] != 0.0)
756 {
757 max_path_acceleration =
758 std::min(max_path_acceleration, max_acceleration_[i] / std::abs(config_deriv[i]) -
759 factor * config_deriv2[i] * path_vel * path_vel / config_deriv[i]);
760 }
761 }
762 return factor * max_path_acceleration;
763}
764
765double Trajectory::getMinMaxPhaseSlope(double path_pos, double path_vel, bool max)
766{
767 return getMinMaxPathAcceleration(path_pos, path_vel, max) / path_vel;
768}
769
770double Trajectory::getAccelerationMaxPathVelocity(double path_pos) const
771{
772 double max_path_velocity = std::numeric_limits<double>::infinity();
773 const Eigen::VectorXd config_deriv = path_.getTangent(path_pos);
774 const Eigen::VectorXd config_deriv2 = path_.getCurvature(path_pos);
775 for (unsigned int i = 0; i < joint_num_; ++i)
776 {
777 if (config_deriv[i] != 0.0)
778 {
779 for (unsigned int j = i + 1; j < joint_num_; ++j)
780 {
781 if (config_deriv[j] != 0.0)
782 {
783 double a_ij = config_deriv2[i] / config_deriv[i] - config_deriv2[j] / config_deriv[j];
784 if (a_ij != 0.0)
785 {
786 max_path_velocity = std::min(max_path_velocity, sqrt((max_acceleration_[i] / std::abs(config_deriv[i]) +
787 max_acceleration_[j] / std::abs(config_deriv[j])) /
788 std::abs(a_ij)));
789 }
790 }
791 }
792 }
793 else if (config_deriv2[i] != 0.0)
794 {
795 max_path_velocity = std::min(max_path_velocity, sqrt(max_acceleration_[i] / std::abs(config_deriv2[i])));
796 }
797 }
798 return max_path_velocity;
799}
800
801double Trajectory::getVelocityMaxPathVelocity(double path_pos) const
802{
803 const Eigen::VectorXd tangent = path_.getTangent(path_pos);
804 double max_path_velocity = std::numeric_limits<double>::max();
805 for (unsigned int i = 0; i < joint_num_; ++i)
806 {
807 max_path_velocity = std::min(max_path_velocity, max_velocity_[i] / std::abs(tangent[i]));
808 }
809 return max_path_velocity;
810}
811
812double Trajectory::getAccelerationMaxPathVelocityDeriv(double path_pos)
813{
814 return (getAccelerationMaxPathVelocity(path_pos + EPS) - getAccelerationMaxPathVelocity(path_pos - EPS)) /
815 (2.0 * EPS);
816}
817
818double Trajectory::getVelocityMaxPathVelocityDeriv(double path_pos)
819{
820 const Eigen::VectorXd tangent = path_.getTangent(path_pos);
821 double max_path_velocity = std::numeric_limits<double>::max();
822 unsigned int active_constraint;
823 for (unsigned int i = 0; i < joint_num_; ++i)
824 {
825 const double this_max_path_velocity = max_velocity_[i] / std::abs(tangent[i]);
826 if (this_max_path_velocity < max_path_velocity)
827 {
828 max_path_velocity = this_max_path_velocity;
829 active_constraint = i;
830 }
831 }
832 return -(max_velocity_[active_constraint] * path_.getCurvature(path_pos)[active_constraint]) /
833 (tangent[active_constraint] * std::abs(tangent[active_constraint]));
834}
835
837{
838 return trajectory_.back().time_;
839}
840
841std::list<Trajectory::TrajectoryStep>::const_iterator Trajectory::getTrajectorySegment(double time) const
842{
843 if (time >= trajectory_.back().time_)
844 {
845 std::list<TrajectoryStep>::const_iterator last = trajectory_.end();
846 last--;
847 return last;
848 }
849 else
850 {
851 if (time < cached_time_)
852 {
853 cached_trajectory_segment_ = trajectory_.begin();
854 }
855 while (time >= cached_trajectory_segment_->time_)
856 {
857 ++cached_trajectory_segment_;
858 }
859 cached_time_ = time;
860 return cached_trajectory_segment_;
861 }
862}
863
864Eigen::VectorXd Trajectory::getPosition(double time) const
865{
866 std::list<TrajectoryStep>::const_iterator it = getTrajectorySegment(time);
867 std::list<TrajectoryStep>::const_iterator previous = it;
868 previous--;
869
870 double time_step = it->time_ - previous->time_;
871 const double acceleration =
872 2.0 * (it->path_pos_ - previous->path_pos_ - time_step * previous->path_vel_) / (time_step * time_step);
873
874 time_step = time - previous->time_;
875 const double path_pos =
876 previous->path_pos_ + time_step * previous->path_vel_ + 0.5 * time_step * time_step * acceleration;
877
878 return path_.getConfig(path_pos);
879}
880
881Eigen::VectorXd Trajectory::getVelocity(double time) const
882{
883 std::list<TrajectoryStep>::const_iterator it = getTrajectorySegment(time);
884 std::list<TrajectoryStep>::const_iterator previous = it;
885 previous--;
886
887 double time_step = it->time_ - previous->time_;
888 const double acceleration =
889 2.0 * (it->path_pos_ - previous->path_pos_ - time_step * previous->path_vel_) / (time_step * time_step);
890
891 const double path_pos =
892 previous->path_pos_ + time_step * previous->path_vel_ + 0.5 * time_step * time_step * acceleration;
893 const double path_vel = previous->path_vel_ + time_step * acceleration;
894
895 return path_.getTangent(path_pos) * path_vel;
896}
897
898Eigen::VectorXd Trajectory::getAcceleration(double time) const
899{
900 std::list<TrajectoryStep>::const_iterator it = getTrajectorySegment(time);
901 std::list<TrajectoryStep>::const_iterator previous = it;
902 previous--;
903
904 double time_step = it->time_ - previous->time_;
905 const double acceleration =
906 2.0 * (it->path_pos_ - previous->path_pos_ - time_step * previous->path_vel_) / (time_step * time_step);
907
908 const double path_pos =
909 previous->path_pos_ + time_step * previous->path_vel_ + 0.5 * time_step * time_step * acceleration;
910 const double path_vel = previous->path_vel_ + time_step * acceleration;
911 Eigen::VectorXd path_acc =
912 (path_.getTangent(path_pos) * path_vel - path_.getTangent(previous->path_pos_) * previous->path_vel_);
913 if (time_step > 0.0)
914 path_acc /= time_step;
915 return path_acc;
916}
917
918TimeOptimalTrajectoryGeneration::TimeOptimalTrajectoryGeneration(const double path_tolerance, const double resample_dt,
919 const double min_angle_change)
920 : path_tolerance_(path_tolerance), resample_dt_(resample_dt), min_angle_change_(min_angle_change)
921{
922}
923
925 const double max_velocity_scaling_factor,
926 const double max_acceleration_scaling_factor) const
927{
928 if (trajectory.empty())
929 return true;
930
931 const moveit::core::JointModelGroup* group = trajectory.getGroup();
932 if (!group)
933 {
934 RCLCPP_ERROR(getLogger(), "It looks like the planner did not set the group the plan was computed for");
935 return false;
936 }
937
938 // Validate scaling
939 double velocity_scaling_factor = verifyScalingFactor(max_velocity_scaling_factor, VELOCITY);
940 double acceleration_scaling_factor = verifyScalingFactor(max_acceleration_scaling_factor, ACCELERATION);
941
942 // Get the velocity and acceleration limits for all active joints
943 const moveit::core::RobotModel& rmodel = group->getParentModel();
944 const std::vector<std::string>& vars = group->getVariableNames();
945 std::vector<size_t> active_joint_indices;
946 if (!group->computeJointVariableIndices(group->getActiveJointModelNames(), active_joint_indices))
947 {
948 RCLCPP_ERROR(getLogger(), "Failed to get active variable indices.");
949 }
950
951 const size_t num_active_joints = active_joint_indices.size();
952 Eigen::VectorXd max_velocity(num_active_joints);
953 Eigen::VectorXd max_acceleration(num_active_joints);
954 for (size_t idx = 0; idx < num_active_joints; ++idx)
955 {
956 // For active joints only (skip mimic joints and other types)
957 const moveit::core::VariableBounds& bounds = rmodel.getVariableBounds(vars[active_joint_indices[idx]]);
958
959 // Limits need to be non-zero, otherwise we never exit
960 if (bounds.velocity_bounded_)
961 {
962 if (bounds.max_velocity_ <= 0.0)
963 {
964 RCLCPP_ERROR(getLogger(), "Invalid max_velocity %f specified for '%s', must be greater than 0.0",
965 bounds.max_velocity_, vars[idx].c_str());
966 return false;
967 }
968 max_velocity[idx] =
969 std::min(std::fabs(bounds.max_velocity_), std::fabs(bounds.min_velocity_)) * velocity_scaling_factor;
970 }
971 else
972 {
973 RCLCPP_ERROR_STREAM(getLogger(), "No velocity limit was defined for joint " << vars[idx].c_str()
974 << "! You have to define velocity "
975 "limits "
976 "in the URDF or "
977 "joint_limits.yaml");
978 return false;
979 }
980
981 if (bounds.acceleration_bounded_)
982 {
983 if (bounds.max_acceleration_ < 0.0)
984 {
985 RCLCPP_ERROR(getLogger(), "Invalid max_acceleration %f specified for '%s', must be greater than 0.0",
986 bounds.max_acceleration_, vars[idx].c_str());
987 return false;
988 }
989 max_acceleration[idx] = std::min(std::fabs(bounds.max_acceleration_), std::fabs(bounds.min_acceleration_)) *
990 acceleration_scaling_factor;
991 }
992 else
993 {
994 RCLCPP_ERROR_STREAM(getLogger(), "No acceleration limit was defined for joint " << vars[idx].c_str()
995 << "! You have to define "
996 "acceleration "
997 "limits in the URDF or "
998 "joint_limits.yaml");
999 return false;
1000 }
1001 }
1002
1003 return doTimeParameterizationCalculations(trajectory, max_velocity, max_acceleration);
1004}
1005
1007 const std::vector<moveit_msgs::msg::JointLimits>& joint_limits,
1008 const double max_velocity_scaling_factor,
1009 const double max_acceleration_scaling_factor) const
1010{
1011 std::unordered_map<std::string, double> velocity_limits;
1012 std::unordered_map<std::string, double> acceleration_limits;
1013 for (const auto& limit : joint_limits)
1014 {
1015 // If custom limits are not defined here, they will be supplied from getRobotModelBounds() later
1016 if (limit.has_velocity_limits)
1017 {
1018 velocity_limits[limit.joint_name] = limit.max_velocity;
1019 }
1020 if (limit.has_acceleration_limits)
1021 {
1022 acceleration_limits[limit.joint_name] = limit.max_acceleration;
1023 }
1024 }
1025 return computeTimeStamps(trajectory, velocity_limits, acceleration_limits, max_velocity_scaling_factor,
1026 max_acceleration_scaling_factor);
1027}
1028
1030 robot_trajectory::RobotTrajectory& trajectory, const std::unordered_map<std::string, double>& velocity_limits,
1031 const std::unordered_map<std::string, double>& acceleration_limits, const double max_velocity_scaling_factor,
1032 const double max_acceleration_scaling_factor) const
1033{
1034 if (trajectory.empty())
1035 return true;
1036
1037 // Get the default joint limits from the robot model, then overwrite any that are provided as arguments
1038 const moveit::core::JointModelGroup* group = trajectory.getGroup();
1039 if (!group)
1040 {
1041 RCLCPP_ERROR(getLogger(), "It looks like the planner did not set the group the plan was computed for");
1042 return false;
1043 }
1044
1045 // Validate scaling
1046 double velocity_scaling_factor = verifyScalingFactor(max_velocity_scaling_factor, VELOCITY);
1047 double acceleration_scaling_factor = verifyScalingFactor(max_acceleration_scaling_factor, ACCELERATION);
1048
1049 // Get the velocity and acceleration limits for specified joints
1050 const moveit::core::RobotModel& rmodel = group->getParentModel();
1051 const std::vector<std::string>& vars = group->getVariableNames();
1052 std::vector<size_t> indices;
1053 if (!group->computeJointVariableIndices(group->getActiveJointModelNames(), indices))
1054 {
1055 RCLCPP_ERROR(getLogger(), "Failed to get active variable indices.");
1056 }
1057
1058 const size_t num_joints = indices.size();
1059
1060 Eigen::VectorXd max_velocity(num_joints);
1061 Eigen::VectorXd max_acceleration(num_joints);
1062 for (const auto idx : indices)
1063 {
1064 const moveit::core::VariableBounds& bounds = rmodel.getVariableBounds(vars[idx]);
1065
1066 // VELOCITY LIMIT
1067 // Check if a custom limit was specified as an argument
1068 bool set_velocity_limit = false;
1069 auto it = velocity_limits.find(vars[idx]);
1070 if (it != velocity_limits.end())
1071 {
1072 max_velocity[idx] = it->second * velocity_scaling_factor;
1073 set_velocity_limit = true;
1074 }
1075
1076 if (bounds.velocity_bounded_ && !set_velocity_limit)
1077 {
1078 // Set the default velocity limit, from robot model
1079 if (bounds.max_velocity_ < 0.0)
1080 {
1081 RCLCPP_ERROR(getLogger(), "Invalid max_velocity %f specified for '%s', must be greater than 0.0",
1082 bounds.max_velocity_, vars[idx].c_str());
1083 return false;
1084 }
1085 max_velocity[idx] =
1086 std::min(std::fabs(bounds.max_velocity_), std::fabs(bounds.min_velocity_)) * velocity_scaling_factor;
1087 set_velocity_limit = true;
1088 }
1089
1090 if (!set_velocity_limit)
1091 {
1092 RCLCPP_ERROR_STREAM(getLogger(), "No velocity limit was defined for joint " << vars[idx].c_str()
1093 << "! You have to define velocity "
1094 "limits "
1095 "in the URDF or "
1096 "joint_limits.yaml");
1097 return false;
1098 }
1099
1100 // ACCELERATION LIMIT
1101 // Check if a custom limit was specified as an argument
1102 bool set_acceleration_limit = false;
1103 it = acceleration_limits.find(vars[idx]);
1104 if (it != acceleration_limits.end())
1105 {
1106 max_acceleration[idx] = it->second * acceleration_scaling_factor;
1107 set_acceleration_limit = true;
1108 }
1109
1110 if (bounds.acceleration_bounded_ && !set_acceleration_limit)
1111 {
1112 // Set the default acceleration limit, from robot model
1113 if (bounds.max_acceleration_ < 0.0)
1114 {
1115 RCLCPP_ERROR(getLogger(), "Invalid max_acceleration %f specified for '%s', must be greater than 0.0",
1116 bounds.max_acceleration_, vars[idx].c_str());
1117 return false;
1118 }
1119 max_acceleration[idx] = std::min(std::fabs(bounds.max_acceleration_), std::fabs(bounds.min_acceleration_)) *
1120 acceleration_scaling_factor;
1121 set_acceleration_limit = true;
1122 }
1123 if (!set_acceleration_limit)
1124 {
1125 RCLCPP_ERROR_STREAM(getLogger(), "No acceleration limit was defined for joint " << vars[idx].c_str()
1126 << "! You have to define "
1127 "acceleration "
1128 "limits in the URDF or "
1129 "joint_limits.yaml");
1130 return false;
1131 }
1132 }
1133
1134 return doTimeParameterizationCalculations(trajectory, max_velocity, max_acceleration);
1135}
1136
1137bool totgComputeTimeStamps(const size_t num_waypoints, robot_trajectory::RobotTrajectory& trajectory,
1138 const double max_velocity_scaling_factor, const double max_acceleration_scaling_factor)
1139{
1140 // The algorithm is:
1141 // 1. Run TOTG with default settings once to find the optimal trajectory duration
1142 // 2. Calculate the timestep to get the desired num_waypoints:
1143 // new_delta_t = duration/(n-1) // subtract one for the initial waypoint
1144 // 3. Run TOTG again with the new timestep. This gives the exact num_waypoints you want (plus or minus one due to
1145 // numerical rounding)
1146
1147 if (num_waypoints < 2)
1148 {
1149 RCLCPP_ERROR(getLogger(), "computeTimeStamps() requires num_waypoints > 1");
1150 return false;
1151 }
1152
1153 TimeOptimalTrajectoryGeneration default_totg(0.1 /* default path tolerance */, 0.1 /* default resample_dt */);
1154 default_totg.computeTimeStamps(trajectory, max_velocity_scaling_factor, max_acceleration_scaling_factor);
1155 double optimal_duration = trajectory.getDuration();
1156 double new_resample_dt = optimal_duration / (num_waypoints - 1);
1157 TimeOptimalTrajectoryGeneration resample_totg(0.1 /* path tolerance */, new_resample_dt);
1158 resample_totg.computeTimeStamps(trajectory, max_velocity_scaling_factor, max_acceleration_scaling_factor);
1159 return true;
1160}
1161
1162bool TimeOptimalTrajectoryGeneration::doTimeParameterizationCalculations(robot_trajectory::RobotTrajectory& trajectory,
1163 const Eigen::VectorXd& max_velocity,
1164 const Eigen::VectorXd& max_acceleration) const
1165{
1166 // This lib does not actually work properly when angles wrap around, so we need to unwind the path first
1167 trajectory.unwind();
1168
1169 const moveit::core::JointModelGroup* group = trajectory.getGroup();
1170 if (!group)
1171 {
1172 RCLCPP_ERROR(getLogger(), "It looks like the planner did not set the group the plan was computed for");
1173 return false;
1174 }
1175
1176 if (hasMixedJointTypes(group))
1177 {
1178 RCLCPP_WARN(getLogger(), "There is a combination of revolute and prismatic joints in the robot model. TOTG's "
1179 "`path_tolerance` will not function correctly.");
1180 }
1181
1182 const unsigned num_points = trajectory.getWayPointCount();
1183 const std::vector<int>& idx = group->getVariableIndexList();
1184 const unsigned num_joints = group->getVariableCount();
1185
1186 // Have to convert into Eigen data structs and remove repeated points
1187 // (https://github.com/tobiaskunz/trajectories/issues/3)
1188 std::vector<Eigen::VectorXd> points;
1189 for (size_t p = 0; p < num_points; ++p)
1190 {
1191 moveit::core::RobotStatePtr waypoint = trajectory.getWayPointPtr(p);
1192 Eigen::VectorXd new_point(num_joints);
1193 // The first point should always be kept
1194 bool diverse_point = (p == 0);
1195
1196 for (size_t j = 0; j < num_joints; ++j)
1197 {
1198 new_point[j] = waypoint->getVariablePosition(idx[j]);
1199 // If any joint angle is different, it's a unique waypoint
1200 if (p > 0 && std::fabs(new_point[j] - points.back()[j]) > min_angle_change_)
1201 {
1202 diverse_point = true;
1203 }
1204 }
1205
1206 if (diverse_point)
1207 {
1208 points.push_back(new_point);
1209 // If the last point is not a diverse_point we replace the last added point with it to make sure to always have
1210 // the input end point as the last point
1211 }
1212 else if (p == num_points - 1)
1213 {
1214 points.back() = new_point;
1215 }
1216 }
1217
1218 // Return trajectory with only the first waypoint if there are not multiple diverse points
1219 if (points.size() == 1)
1220 {
1222 waypoint.zeroVelocities();
1223 waypoint.zeroAccelerations();
1224 trajectory.clear();
1225 trajectory.addSuffixWayPoint(waypoint, 0.0);
1226 return true;
1227 }
1228
1229 // Now actually call the algorithm
1230 std::optional<Path> path = Path::create(points, path_tolerance_);
1231 if (!path)
1232 {
1233 RCLCPP_ERROR(getLogger(), "Invalid path.");
1234 return false;
1235 }
1236
1237 std::optional<Trajectory> parameterized = Trajectory::create(*path, max_velocity, max_acceleration, DEFAULT_TIMESTEP);
1238 if (!parameterized)
1239 {
1240 RCLCPP_ERROR(getLogger(), "Couldn't create trajectory");
1241 return false;
1242 }
1243
1244 // Compute sample count
1245 const size_t sample_count = std::ceil(parameterized->getDuration() / resample_dt_);
1246
1247 // Resample and fill in trajectory
1249 trajectory.clear();
1250 double last_t = 0;
1251 for (size_t sample = 0; sample <= sample_count; ++sample)
1252 {
1253 // always sample the end of the trajectory as well
1254 double t = std::min(parameterized->getDuration(), sample * resample_dt_);
1255 Eigen::VectorXd position = parameterized->getPosition(t);
1256 Eigen::VectorXd velocity = parameterized->getVelocity(t);
1257 Eigen::VectorXd acceleration = parameterized->getAcceleration(t);
1258
1259 for (size_t j = 0; j < num_joints; ++j)
1260 {
1261 waypoint.setVariablePosition(idx[j], position[j]);
1262 waypoint.setVariableVelocity(idx[j], velocity[j]);
1263 waypoint.setVariableAcceleration(idx[j], acceleration[j]);
1264 }
1265
1266 trajectory.addSuffixWayPoint(waypoint, t - last_t);
1267 last_t = t;
1268 }
1269
1270 return true;
1271}
1272
1273bool TimeOptimalTrajectoryGeneration::hasMixedJointTypes(const moveit::core::JointModelGroup* group) const
1274{
1275 const std::vector<const moveit::core::JointModel*>& joint_models = group->getActiveJointModels();
1276
1277 bool have_prismatic =
1278 std::any_of(joint_models.cbegin(), joint_models.cend(), [](const moveit::core::JointModel* joint_model) {
1279 return joint_model->getType() == moveit::core::JointModel::JointType::PRISMATIC;
1280 });
1281
1282 bool have_revolute =
1283 std::any_of(joint_models.cbegin(), joint_models.cend(), [](const moveit::core::JointModel* joint_model) {
1284 return joint_model->getType() == moveit::core::JointModel::JointType::REVOLUTE;
1285 });
1286
1287 return have_prismatic && have_revolute;
1288}
1289
1290double TimeOptimalTrajectoryGeneration::verifyScalingFactor(const double requested_scaling_factor,
1291 const LimitType limit_type) const
1292{
1293 std::string limit_type_str;
1294 double scaling_factor = DEFAULT_SCALING_FACTOR;
1295
1296 const auto limit_type_it = LIMIT_TYPES.find(limit_type);
1297 if (limit_type_it != LIMIT_TYPES.end())
1298 {
1299 limit_type_str = limit_type_it->second + "_";
1300 }
1301
1302 if (requested_scaling_factor > 0.0 && requested_scaling_factor <= 1.0)
1303 {
1304 scaling_factor = requested_scaling_factor;
1305 }
1306 else
1307 {
1308 RCLCPP_WARN(getLogger(), "Invalid max_%sscaling_factor %f specified, defaulting to %f instead.",
1309 limit_type_str.c_str(), requested_scaling_factor, scaling_factor);
1310 }
1311 return scaling_factor;
1312}
1313} // namespace trajectory_processing
const RobotModel & getParentModel() const
Get the kinematic model this group is part of.
const std::vector< std::string > & getActiveJointModelNames() const
Get the names of the active joints in this group. These are the names of the joints returned by getJo...
bool computeJointVariableIndices(const std::vector< std::string > &joint_names, std::vector< size_t > &joint_bijection) const
Computes the indices of joint variables given a vector of joint names to look up.
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up the joints included in this group. The number of returned...
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
const std::vector< int > & getVariableIndexList() const
Get the index locations in the complete robot state for all the variables in this group.
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition robot_model.h:76
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a specific variable. Throw an exception of variable is not found.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
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.
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.
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.
void zeroAccelerations()
Set all accelerations to 0.0.
Maintain a sequence of waypoints and the time durations between these waypoints.
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::JointModelGroup * getGroup() const
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)
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
std::list< std::pair< double, bool > > getSwitchingPoints() const
Return a list of all switching points as a pair (arc length to switching point, discontinuity)
static std::optional< Path > create(const std::vector< Eigen::VectorXd > &waypoint, double max_deviation=DEFAULT_PATH_TOLERANCE)
double getNextSwitchingPoint(double s, bool &discontinuity) const
Get the next switching point.
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_)....
TimeOptimalTrajectoryGeneration(const double path_tolerance=DEFAULT_PATH_TOLERANCE, const double resample_dt=0.1, const double min_angle_change=0.001)
Eigen::VectorXd getAcceleration(double time) const
Return the acceleration vector for a given point in time.
Eigen::VectorXd getPosition(double time) const
Return the position/configuration vector for a given point in time.
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.
static std::optional< Trajectory > create(const Path &path, const Eigen::VectorXd &max_velocity, const Eigen::VectorXd &max_acceleration, double time_step=0.001)
Generates a time-optimal trajectory.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
const std::unordered_map< LimitType, std::string > LIMIT_TYPES
bool totgComputeTimeStamps(const size_t num_waypoints, robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0)
Compute a trajectory with the desired number of waypoints. Resampling the trajectory doesn't change t...