39#include <rclcpp/logger.hpp>
40#include <rclcpp/logging.hpp>
42#include <Eigen/Geometry>
53constexpr double DEFAULT_TIMESTEP = 1e-3;
54constexpr double EPS = 1e-6;
55constexpr double DEFAULT_SCALING_FACTOR = 1.0;
67 :
PathSegment((end - start).norm()), end_(end), start_(start)
74 s = std::max(0.0, std::min(1.0, s));
75 return (1.0 - s) * start_ + s * end_;
80 return (end_ - start_) /
length_;
85 return Eigen::VectorXd::Zero(start_.size());
90 return std::list<double>();
100 Eigen::VectorXd start_;
106 CircularPathSegment(
const Eigen::VectorXd& start,
const Eigen::VectorXd& intersection,
const Eigen::VectorXd& end,
107 double max_deviation)
109 if ((intersection - start).norm() < 0.000001 || (end - intersection).norm() < 0.000001)
113 center_ = intersection;
114 x_ = Eigen::VectorXd::Zero(start.size());
115 y_ = Eigen::VectorXd::Zero(start.size());
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);
124 if (start_dot_end > 0.999999 || start_dot_end < -0.999999)
128 center_ = intersection;
129 x_ = Eigen::VectorXd::Zero(start.size());
130 y_ = Eigen::VectorXd::Zero(start.size());
134 const double angle = acos(start_dot_end);
135 const double start_distance = (start - intersection).norm();
136 const double end_distance = (end - intersection).norm();
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)));
142 radius_ = distance / tan(0.5 * angle);
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;
152 const double angle = s / radius_;
153 return center_ + radius_ * (x_ * cos(angle) + y_ * sin(angle));
158 const double angle = s / radius_;
159 return -x_ * sin(angle) + y_ * cos(angle);
164 const double angle = s / radius_;
165 return -1.0 / radius_ * (x_ * cos(angle) + y_ * sin(angle));
170 std::list<double> switching_points;
171 const double dim = x_.size();
172 for (
unsigned int i = 0; i < dim; ++i)
174 double switching_angle = atan2(y_[i], x_[i]);
175 if (switching_angle < 0.0)
177 switching_angle += M_PI;
179 const double switching_point = switching_angle * radius_;
182 switching_points.push_back(switching_point);
185 switching_points.sort();
186 return switching_points;
196 Eigen::VectorXd center_;
201std::optional<Path>
Path::create(
const std::vector<Eigen::VectorXd>& waypoints,
double max_deviation)
203 if (waypoints.size() < 2)
205 RCLCPP_ERROR(getLogger(),
"A path needs at least 2 waypoints.");
208 if (max_deviation <= 0.0)
210 RCLCPP_ERROR(getLogger(),
"Path max_deviation must be greater than 0.0.");
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())
227 waypoints_iterator3 = waypoints_iterator2;
228 ++waypoints_iterator3;
229 if (waypoints_iterator3 != waypoints.end())
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())
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)
243 RCLCPP_ERROR(getLogger(),
244 "The path requires a 180 deg. turn, which is not supported by the current implementation.");
249 if (max_deviation > 0.0 && waypoints_iterator3 != waypoints.end())
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)
257 path.path_segments_.push_back(std::make_unique<LinearPathSegment>(start_config, end_config));
259 path.path_segments_.emplace_back(blend_segment);
265 path.path_segments_.push_back(std::make_unique<LinearPathSegment>(start_config, *waypoints_iterator2));
266 start_config = *waypoints_iterator2;
268 waypoints_iterator1 = waypoints_iterator2;
269 ++waypoints_iterator2;
274 for (std::unique_ptr<PathSegment>& path_segment : path.path_segments_)
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)
281 path.switching_points_.push_back(std::make_pair(path.length_ + *point,
false));
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));
288 path.switching_points_.pop_back();
292Path::Path(
const Path& path) : length_(path.length_), switching_points_(path.switching_points_)
294 for (
const std::unique_ptr<PathSegment>& path_segment : path.path_segments_)
296 path_segments_.emplace_back(path_segment->clone());
307 std::list<std::unique_ptr<PathSegment>>::const_iterator it = path_segments_.begin();
308 std::list<std::unique_ptr<PathSegment>>::const_iterator next = it;
310 while (next != path_segments_.end() && s >= (*next)->position_)
315 s -= (*it)->position_;
321 const PathSegment* path_segment = getPathSegment(s);
327 const PathSegment* path_segment = getPathSegment(s);
333 const PathSegment* path_segment = getPathSegment(s);
339 std::list<std::pair<double, bool>>::const_iterator it = switching_points_.begin();
340 while (it != switching_points_.end() && it->first <= s)
344 if (it == switching_points_.end())
346 discontinuity =
true;
349 discontinuity = it->second;
355 return switching_points_;
359 const Eigen::VectorXd& max_acceleration,
double time_step)
363 RCLCPP_ERROR(getLogger(),
"The trajectory is invalid because the time step is <= 0.0.");
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_)
372 double before_acceleration;
373 TrajectoryStep switching_point;
374 if (output.getNextSwitchingPoint(output.trajectory_.back().path_pos_, switching_point, before_acceleration,
379 output.integrateBackward(output.trajectory_, switching_point.path_pos_, switching_point.path_vel_,
380 before_acceleration);
385 RCLCPP_ERROR(getLogger(),
"Trajectory not valid after integrateForward and integrateBackward.");
389 double before_acceleration = output.getMinMaxPathAcceleration(output.path_.
getLength(), 0.0,
false);
390 output.integrateBackward(output.trajectory_, output.path_.
getLength(), 0.0, before_acceleration);
394 RCLCPP_ERROR(getLogger(),
"Trajectory not valid after the second integrateBackward pass.");
399 std::list<TrajectoryStep>::iterator previous = output.trajectory_.begin();
400 std::list<TrajectoryStep>::iterator it = previous;
403 while (it != output.trajectory_.end())
405 it->time_ = previous->time_ + (it->path_pos_ - previous->path_pos_) / ((it->path_vel_ + previous->path_vel_) / 2.0);
413Trajectory::Trajectory(
const Path& path,
const Eigen::VectorXd& max_velocity,
const Eigen::VectorXd& max_acceleration,
415 : path_(path), max_velocity_(max_velocity), max_acceleration_(max_acceleration), time_step_(time_step)
417 joint_num_ = max_velocity.size();
421bool Trajectory::getNextSwitchingPoint(
double path_pos, TrajectoryStep& next_switching_point,
422 double& before_acceleration,
double& after_acceleration)
424 TrajectoryStep acceleration_switching_point(path_pos, 0.0);
425 double acceleration_before_acceleration, acceleration_after_acceleration;
426 bool acceleration_reached_end;
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_));
435 TrajectoryStep velocity_switching_point(path_pos, 0.0);
436 double velocity_before_acceleration, velocity_after_acceleration;
437 bool velocity_reached_end;
440 velocity_reached_end = getNextVelocitySwitchingPoint(velocity_switching_point.path_pos_, velocity_switching_point,
441 velocity_before_acceleration, velocity_after_acceleration);
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)));
447 if (acceleration_reached_end && velocity_reached_end)
451 else if (!acceleration_reached_end &&
452 (velocity_reached_end || acceleration_switching_point.path_pos_ <= velocity_switching_point.path_pos_))
454 next_switching_point = acceleration_switching_point;
455 before_acceleration = acceleration_before_acceleration;
456 after_acceleration = acceleration_after_acceleration;
461 next_switching_point = velocity_switching_point;
462 before_acceleration = velocity_before_acceleration;
463 after_acceleration = velocity_after_acceleration;
468bool Trajectory::getNextAccelerationSwitchingPoint(
double path_pos, TrajectoryStep& next_switching_point,
469 double& before_acceleration,
double& after_acceleration)
471 double switching_path_pos = path_pos;
472 double switching_path_vel;
478 if (switching_path_pos > path_.
getLength() - EPS)
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);
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)))
502 switching_path_vel = getAccelerationMaxPathVelocity(switching_path_pos);
503 before_acceleration = 0.0;
504 after_acceleration = 0.0;
506 if (getAccelerationMaxPathVelocityDeriv(switching_path_pos - EPS) < 0.0 &&
507 getAccelerationMaxPathVelocityDeriv(switching_path_pos + EPS) > 0.0)
514 next_switching_point = TrajectoryStep(switching_path_pos, switching_path_vel);
518bool Trajectory::getNextVelocitySwitchingPoint(
double path_pos, TrajectoryStep& next_switching_point,
519 double& before_acceleration,
double& after_acceleration)
522 path_pos -= DEFAULT_TIMESTEP;
525 path_pos += DEFAULT_TIMESTEP;
527 if (getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos),
false) >=
528 getVelocityMaxPathVelocityDeriv(path_pos))
532 }
while ((!start || getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos),
false) >
533 getVelocityMaxPathVelocityDeriv(path_pos)) &&
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)
545 path_pos = (before_path_pos + after_path_pos) / 2.0;
546 if (getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos),
false) >
547 getVelocityMaxPathVelocityDeriv(path_pos))
549 before_path_pos = path_pos;
553 after_path_pos = path_pos;
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));
564bool Trajectory::integrateForward(std::list<TrajectoryStep>& trajectory,
double acceleration)
566 double path_pos = trajectory.back().path_pos_;
567 double path_vel = trajectory.back().path_vel_;
570 std::list<std::pair<double, bool>>::iterator next_discontinuity = switching_points.begin();
574 while ((next_discontinuity != switching_points.end()) &&
575 (next_discontinuity->first <= path_pos || !next_discontinuity->second))
577 ++next_discontinuity;
580 double old_path_pos = path_pos;
581 double old_path_vel = path_vel;
583 path_vel += time_step_ * acceleration;
584 path_pos += time_step_ * 0.5 * (old_path_vel + path_vel);
586 if (next_discontinuity != switching_points.end() && path_pos > next_discontinuity->first)
590 if (path_pos - next_discontinuity->first < EPS)
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;
601 trajectory.push_back(TrajectoryStep(path_pos, path_vel));
604 else if (path_vel < 0.0)
607 RCLCPP_ERROR(
getLogger(),
"Error while integrating forward: Negative path velocity");
611 if (path_vel > getVelocityMaxPathVelocity(path_pos) &&
612 getMinMaxPhaseSlope(old_path_pos, getVelocityMaxPathVelocity(old_path_pos),
false) <=
613 getVelocityMaxPathVelocityDeriv(old_path_pos))
615 path_vel = getVelocityMaxPathVelocity(path_pos);
618 trajectory.push_back(TrajectoryStep(path_pos, path_vel));
619 acceleration = getMinMaxPathAcceleration(path_pos, path_vel,
true);
621 if (path_vel == 0 && acceleration == 0)
626 RCLCPP_ERROR(
getLogger(),
"Error while integrating forward: zero acceleration and velocity. Are any relevant "
627 "acceleration components limited to zero?");
631 if (path_vel > getAccelerationMaxPathVelocity(path_pos) || path_vel > getVelocityMaxPathVelocity(path_pos))
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)
642 const double midpoint = 0.5 * (before + after);
643 double midpoint_path_vel = 0.5 * (before_path_vel + after_path_vel);
645 if (midpoint_path_vel > getVelocityMaxPathVelocity(midpoint) &&
646 getMinMaxPhaseSlope(before, getVelocityMaxPathVelocity(before),
false) <=
647 getVelocityMaxPathVelocityDeriv(before))
649 midpoint_path_vel = getVelocityMaxPathVelocity(midpoint);
652 if (midpoint_path_vel > getAccelerationMaxPathVelocity(midpoint) ||
653 midpoint_path_vel > getVelocityMaxPathVelocity(midpoint))
656 after_path_vel = midpoint_path_vel;
661 before_path_vel = midpoint_path_vel;
664 trajectory.push_back(TrajectoryStep(before, before_path_vel));
666 if (getAccelerationMaxPathVelocity(after) < getVelocityMaxPathVelocity(after))
668 if (after > next_discontinuity->first)
672 else if (getMinMaxPhaseSlope(trajectory.back().path_pos_, trajectory.back().path_vel_,
true) >
673 getAccelerationMaxPathVelocityDeriv(trajectory.back().path_pos_))
680 if (getMinMaxPhaseSlope(trajectory.back().path_pos_, trajectory_.back().path_vel_,
false) >
681 getVelocityMaxPathVelocityDeriv(trajectory_.back().path_pos_))
690void Trajectory::integrateBackward(std::list<TrajectoryStep>& start_trajectory,
double path_pos,
double path_vel,
693 std::list<TrajectoryStep>::iterator start2 = start_trajectory.end();
695 std::list<TrajectoryStep>::iterator start1 = start2;
697 std::list<TrajectoryStep> trajectory;
699 assert(start1->path_pos_ <= path_pos);
701 while (start1 != start_trajectory.begin() || path_pos >= 0.0)
703 if (start1->path_pos_ <= path_pos)
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);
714 RCLCPP_ERROR(
getLogger(),
"Error while integrating backward: Negative path velocity");
715 end_trajectory_ = trajectory;
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_))
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);
743 RCLCPP_ERROR(
getLogger(),
"Error while integrating backward: Did not hit start trajectory");
744 end_trajectory_ = trajectory;
747double Trajectory::getMinMaxPathAcceleration(
double path_pos,
double path_vel,
bool max)
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)
755 if (config_deriv[i] != 0.0)
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]);
762 return factor * max_path_acceleration;
765double Trajectory::getMinMaxPhaseSlope(
double path_pos,
double path_vel,
bool max)
767 return getMinMaxPathAcceleration(path_pos, path_vel, max) / path_vel;
770double Trajectory::getAccelerationMaxPathVelocity(
double path_pos)
const
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)
777 if (config_deriv[i] != 0.0)
779 for (
unsigned int j = i + 1; j < joint_num_; ++j)
781 if (config_deriv[j] != 0.0)
783 double a_ij = config_deriv2[i] / config_deriv[i] - config_deriv2[j] / config_deriv[j];
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])) /
793 else if (config_deriv2[i] != 0.0)
795 max_path_velocity = std::min(max_path_velocity, sqrt(max_acceleration_[i] / std::abs(config_deriv2[i])));
798 return max_path_velocity;
801double Trajectory::getVelocityMaxPathVelocity(
double path_pos)
const
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)
807 max_path_velocity = std::min(max_path_velocity, max_velocity_[i] / std::abs(tangent[i]));
809 return max_path_velocity;
812double Trajectory::getAccelerationMaxPathVelocityDeriv(
double path_pos)
814 return (getAccelerationMaxPathVelocity(path_pos + EPS) - getAccelerationMaxPathVelocity(path_pos - EPS)) /
818double Trajectory::getVelocityMaxPathVelocityDeriv(
double path_pos)
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)
825 const double this_max_path_velocity = max_velocity_[i] / std::abs(tangent[i]);
826 if (this_max_path_velocity < max_path_velocity)
828 max_path_velocity = this_max_path_velocity;
829 active_constraint = i;
832 return -(max_velocity_[active_constraint] * path_.
getCurvature(path_pos)[active_constraint]) /
833 (tangent[active_constraint] * std::abs(tangent[active_constraint]));
838 return trajectory_.back().time_;
841std::list<Trajectory::TrajectoryStep>::const_iterator Trajectory::getTrajectorySegment(
double time)
const
843 if (time >= trajectory_.back().time_)
845 std::list<TrajectoryStep>::const_iterator last = trajectory_.end();
851 if (time < cached_time_)
853 cached_trajectory_segment_ = trajectory_.begin();
855 while (time >= cached_trajectory_segment_->time_)
857 ++cached_trajectory_segment_;
860 return cached_trajectory_segment_;
866 std::list<TrajectoryStep>::const_iterator it = getTrajectorySegment(time);
867 std::list<TrajectoryStep>::const_iterator previous = it;
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);
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;
883 std::list<TrajectoryStep>::const_iterator it = getTrajectorySegment(time);
884 std::list<TrajectoryStep>::const_iterator previous = it;
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);
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;
900 std::list<TrajectoryStep>::const_iterator it = getTrajectorySegment(time);
901 std::list<TrajectoryStep>::const_iterator previous = it;
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);
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_);
914 path_acc /= time_step;
919 const double min_angle_change)
920 : path_tolerance_(path_tolerance), resample_dt_(resample_dt), min_angle_change_(min_angle_change)
925 const double max_velocity_scaling_factor,
926 const double max_acceleration_scaling_factor)
const
928 if (trajectory.
empty())
934 RCLCPP_ERROR(getLogger(),
"It looks like the planner did not set the group the plan was computed for");
939 double velocity_scaling_factor = verifyScalingFactor(max_velocity_scaling_factor,
VELOCITY);
940 double acceleration_scaling_factor = verifyScalingFactor(max_acceleration_scaling_factor,
ACCELERATION);
945 std::vector<size_t> active_joint_indices;
948 RCLCPP_ERROR(getLogger(),
"Failed to get active variable indices.");
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)
964 RCLCPP_ERROR(getLogger(),
"Invalid max_velocity %f specified for '%s', must be greater than 0.0",
973 RCLCPP_ERROR_STREAM(getLogger(),
"No velocity limit was defined for joint " << vars[idx].c_str()
974 <<
"! You have to define velocity "
977 "joint_limits.yaml");
985 RCLCPP_ERROR(getLogger(),
"Invalid max_acceleration %f specified for '%s', must be greater than 0.0",
990 acceleration_scaling_factor;
994 RCLCPP_ERROR_STREAM(getLogger(),
"No acceleration limit was defined for joint " << vars[idx].c_str()
995 <<
"! You have to define "
997 "limits in the URDF or "
998 "joint_limits.yaml");
1003 return doTimeParameterizationCalculations(trajectory, max_velocity, max_acceleration);
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
1011 std::unordered_map<std::string, double> velocity_limits;
1012 std::unordered_map<std::string, double> acceleration_limits;
1016 if (limit.has_velocity_limits)
1018 velocity_limits[limit.joint_name] = limit.max_velocity;
1020 if (limit.has_acceleration_limits)
1022 acceleration_limits[limit.joint_name] = limit.max_acceleration;
1025 return computeTimeStamps(trajectory, velocity_limits, acceleration_limits, max_velocity_scaling_factor,
1026 max_acceleration_scaling_factor);
1031 const std::unordered_map<std::string, double>& acceleration_limits,
const double max_velocity_scaling_factor,
1032 const double max_acceleration_scaling_factor)
const
1034 if (trajectory.
empty())
1041 RCLCPP_ERROR(getLogger(),
"It looks like the planner did not set the group the plan was computed for");
1046 double velocity_scaling_factor = verifyScalingFactor(max_velocity_scaling_factor,
VELOCITY);
1047 double acceleration_scaling_factor = verifyScalingFactor(max_acceleration_scaling_factor,
ACCELERATION);
1052 std::vector<size_t> indices;
1055 RCLCPP_ERROR(getLogger(),
"Failed to get active variable indices.");
1058 const size_t num_joints = indices.size();
1060 Eigen::VectorXd max_velocity(num_joints);
1061 Eigen::VectorXd max_acceleration(num_joints);
1062 for (
const auto idx : indices)
1068 bool set_velocity_limit =
false;
1069 auto it = velocity_limits.find(vars[idx]);
1070 if (it != velocity_limits.end())
1072 max_velocity[idx] = it->second * velocity_scaling_factor;
1073 set_velocity_limit =
true;
1081 RCLCPP_ERROR(getLogger(),
"Invalid max_velocity %f specified for '%s', must be greater than 0.0",
1087 set_velocity_limit =
true;
1090 if (!set_velocity_limit)
1092 RCLCPP_ERROR_STREAM(getLogger(),
"No velocity limit was defined for joint " << vars[idx].c_str()
1093 <<
"! You have to define velocity "
1096 "joint_limits.yaml");
1102 bool set_acceleration_limit =
false;
1103 it = acceleration_limits.find(vars[idx]);
1104 if (it != acceleration_limits.end())
1106 max_acceleration[idx] = it->second * acceleration_scaling_factor;
1107 set_acceleration_limit =
true;
1115 RCLCPP_ERROR(getLogger(),
"Invalid max_acceleration %f specified for '%s', must be greater than 0.0",
1120 acceleration_scaling_factor;
1121 set_acceleration_limit =
true;
1123 if (!set_acceleration_limit)
1125 RCLCPP_ERROR_STREAM(getLogger(),
"No acceleration limit was defined for joint " << vars[idx].c_str()
1126 <<
"! You have to define "
1128 "limits in the URDF or "
1129 "joint_limits.yaml");
1134 return doTimeParameterizationCalculations(trajectory, max_velocity, max_acceleration);
1138 const double max_velocity_scaling_factor,
const double max_acceleration_scaling_factor)
1147 if (num_waypoints < 2)
1149 RCLCPP_ERROR(getLogger(),
"computeTimeStamps() requires num_waypoints > 1");
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);
1158 resample_totg.
computeTimeStamps(trajectory, max_velocity_scaling_factor, max_acceleration_scaling_factor);
1163 const Eigen::VectorXd& max_velocity,
1164 const Eigen::VectorXd& max_acceleration)
const
1172 RCLCPP_ERROR(getLogger(),
"It looks like the planner did not set the group the plan was computed for");
1176 if (hasMixedJointTypes(group))
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.");
1188 std::vector<Eigen::VectorXd> points;
1189 for (
size_t p = 0; p < num_points; ++p)
1191 moveit::core::RobotStatePtr waypoint = trajectory.
getWayPointPtr(p);
1192 Eigen::VectorXd new_point(num_joints);
1194 bool diverse_point = (p == 0);
1196 for (
size_t j = 0; j < num_joints; ++j)
1198 new_point[j] = waypoint->getVariablePosition(idx[j]);
1200 if (p > 0 && std::fabs(new_point[j] - points.back()[j]) > min_angle_change_)
1202 diverse_point =
true;
1208 points.push_back(new_point);
1212 else if (p == num_points - 1)
1214 points.back() = new_point;
1219 if (points.size() == 1)
1230 std::optional<Path> path =
Path::create(points, path_tolerance_);
1233 RCLCPP_ERROR(
getLogger(),
"Invalid path.");
1237 std::optional<Trajectory> parameterized =
Trajectory::create(*path, max_velocity, max_acceleration, DEFAULT_TIMESTEP);
1240 RCLCPP_ERROR(
getLogger(),
"Couldn't create trajectory");
1245 const size_t sample_count = std::ceil(parameterized->getDuration() / resample_dt_);
1251 for (
size_t sample = 0; sample <= sample_count; ++sample)
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);
1259 for (
size_t j = 0; j < num_joints; ++j)
1275 const std::vector<const moveit::core::JointModel*>& joint_models = group->
getActiveJointModels();
1277 bool have_prismatic =
1279 return joint_model->getType() == moveit::core::JointModel::JointType::PRISMATIC;
1282 bool have_revolute =
1284 return joint_model->getType() == moveit::core::JointModel::JointType::REVOLUTE;
1287 return have_prismatic && have_revolute;
1290double TimeOptimalTrajectoryGeneration::verifyScalingFactor(
const double requested_scaling_factor,
1293 std::string limit_type_str;
1294 double scaling_factor = DEFAULT_SCALING_FACTOR;
1296 const auto limit_type_it =
LIMIT_TYPES.find(limit_type);
1299 limit_type_str = limit_type_it->second +
"_";
1302 if (requested_scaling_factor > 0.0 && requested_scaling_factor <= 1.0)
1304 scaling_factor = requested_scaling_factor;
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);
1311 return scaling_factor;
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...
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.
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)
RobotTrajectory & unwind()
RobotTrajectory & clear()
const moveit::core::JointModelGroup * getGroup() const
std::size_t getWayPointCount() const
const moveit::core::RobotState & getWayPoint(std::size_t index) const
double getDuration() const
Eigen::VectorXd getConfig(double s) const override
std::list< double > getSwitchingPoints() const override
CircularPathSegment(const Eigen::VectorXd &start, const Eigen::VectorXd &intersection, const Eigen::VectorXd &end, double max_deviation)
Eigen::VectorXd getTangent(double s) const override
Eigen::VectorXd getCurvature(double s) const override
CircularPathSegment * clone() const override
Eigen::VectorXd getTangent(double) const override
LinearPathSegment * clone() const override
std::list< double > getSwitchingPoints() const override
Eigen::VectorXd getCurvature(double) const override
Eigen::VectorXd getConfig(double s) const override
LinearPathSegment(const Eigen::VectorXd &start, const Eigen::VectorXd &end)
virtual Eigen::VectorXd getConfig(double s) const =0
virtual Eigen::VectorXd getCurvature(double s) const =0
virtual Eigen::VectorXd getTangent(double s) const =0
Eigen::VectorXd getTangent(double s) const
std::list< std::pair< double, bool > > getSwitchingPoints() const
Return a list of all switching points as a pair (arc length to switching point, discontinuity)
Eigen::VectorXd getConfig(double s) const
static std::optional< Path > create(const std::vector< Eigen::VectorXd > &waypoint, double max_deviation=DEFAULT_PATH_TOLERANCE)
Eigen::VectorXd getCurvature(double s) const
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()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
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...
bool acceleration_bounded_