39 #include <rclcpp/logger.hpp>
40 #include <rclcpp/logging.hpp>
42 #include <Eigen/Geometry>
52 static const rclcpp::Logger
LOGGER =
53 rclcpp::get_logger(
"moveit_trajectory_processing.time_optimal_trajectory_generation");
54 constexpr
double DEFAULT_TIMESTEP = 1e-3;
55 constexpr
double EPS = 1e-6;
62 :
PathSegment((end - start).norm()), end_(end), start_(start)
69 s = std::max(0.0, std::min(1.0, s));
70 return (1.0 - s) * start_ + s * end_;
75 return (end_ - start_) /
length_;
80 return Eigen::VectorXd::Zero(start_.size());
85 return std::list<double>();
95 Eigen::VectorXd start_;
101 CircularPathSegment(
const Eigen::VectorXd& start,
const Eigen::VectorXd& intersection,
const Eigen::VectorXd& end,
102 double max_deviation)
104 if ((intersection - start).norm() < 0.000001 || (end - intersection).norm() < 0.000001)
108 center = intersection;
109 x = Eigen::VectorXd::Zero(start.size());
110 y = Eigen::VectorXd::Zero(start.size());
114 const Eigen::VectorXd start_direction = (intersection - start).normalized();
115 const Eigen::VectorXd end_direction = (end - intersection).normalized();
116 const double start_dot_end = start_direction.dot(end_direction);
119 if (start_dot_end > 0.999999 || start_dot_end < -0.999999)
123 center = intersection;
124 x = Eigen::VectorXd::Zero(start.size());
125 y = Eigen::VectorXd::Zero(start.size());
129 const double angle = acos(start_dot_end);
130 const double start_distance = (start - intersection).norm();
131 const double end_distance = (end - intersection).norm();
134 double distance = std::min(start_distance, end_distance);
135 distance = std::min(
distance, max_deviation * sin(0.5 * angle) / (1.0 - cos(0.5 * angle)));
137 radius =
distance / tan(0.5 * angle);
140 center = intersection + (end_direction - start_direction).normalized() * radius / cos(0.5 * angle);
141 x = (intersection -
distance * start_direction - center).normalized();
147 const double angle = s / radius;
148 return center + radius * (x * cos(angle) + y * sin(angle));
153 const double angle = s / radius;
154 return -x * sin(angle) + y * cos(angle);
159 const double angle = s / radius;
160 return -1.0 / radius * (x * cos(angle) + y * sin(angle));
165 std::list<double> switching_points;
166 const double dim = x.size();
167 for (
unsigned int i = 0; i < dim; ++i)
169 double switching_angle = atan2(y[i], x[i]);
170 if (switching_angle < 0.0)
172 switching_angle += M_PI;
174 const double switching_point = switching_angle * radius;
177 switching_points.push_back(switching_point);
180 switching_points.sort();
181 return switching_points;
191 Eigen::VectorXd center;
196 Path::Path(
const std::list<Eigen::VectorXd>& path,
double max_deviation) : length_(0.0)
200 std::list<Eigen::VectorXd>::const_iterator path_iterator1 = path.begin();
201 std::list<Eigen::VectorXd>::const_iterator path_iterator2 = path_iterator1;
203 std::list<Eigen::VectorXd>::const_iterator path_iterator3;
204 Eigen::VectorXd start_config = *path_iterator1;
205 while (path_iterator2 != path.end())
207 path_iterator3 = path_iterator2;
209 if (max_deviation > 0.0 && path_iterator3 != path.end())
213 0.5 * (*path_iterator2 + *path_iterator3), max_deviation);
214 Eigen::VectorXd end_config = blend_segment->
getConfig(0.0);
215 if ((end_config - start_config).norm() > 0.000001)
217 path_segments_.push_back(std::make_unique<LinearPathSegment>(start_config, end_config));
219 path_segments_.emplace_back(blend_segment);
225 path_segments_.push_back(std::make_unique<LinearPathSegment>(start_config, *path_iterator2));
226 start_config = *path_iterator2;
228 path_iterator1 = path_iterator2;
234 for (std::unique_ptr<PathSegment>& path_segment : path_segments_)
236 path_segment->position_ = length_;
237 std::list<double> local_switching_points = path_segment->getSwitchingPoints();
238 for (std::list<double>::const_iterator point = local_switching_points.begin();
239 point != local_switching_points.end(); ++point)
241 switching_points_.push_back(std::make_pair(length_ + *point,
false));
243 length_ += path_segment->getLength();
244 while (!switching_points_.empty() && switching_points_.back().first >= length_)
245 switching_points_.pop_back();
246 switching_points_.push_back(std::make_pair(length_,
true));
248 switching_points_.pop_back();
251 Path::Path(
const Path& path) : length_(path.length_), switching_points_(path.switching_points_)
253 for (
const std::unique_ptr<PathSegment>& path_segment : path.path_segments_)
255 path_segments_.emplace_back(path_segment->clone());
266 std::list<std::unique_ptr<PathSegment>>::const_iterator it = path_segments_.begin();
267 std::list<std::unique_ptr<PathSegment>>::const_iterator next = it;
269 while (next != path_segments_.end() && s >= (*next)->position_)
274 s -= (*it)->position_;
280 const PathSegment* path_segment = getPathSegment(s);
286 const PathSegment* path_segment = getPathSegment(s);
292 const PathSegment* path_segment = getPathSegment(s);
298 std::list<std::pair<double, bool>>::const_iterator it = switching_points_.begin();
299 while (it != switching_points_.end() && it->first <= s)
303 if (it == switching_points_.end())
305 discontinuity =
true;
308 discontinuity = it->second;
314 return switching_points_;
320 , max_velocity_(max_velocity)
321 , max_acceleration_(max_acceleration)
322 , joint_num_(max_velocity.size())
324 , time_step_(time_step)
325 , cached_time_(std::numeric_limits<double>::max())
330 RCLCPP_ERROR(LOGGER,
"The trajectory is invalid because the time step is 0.");
333 trajectory_.push_back(TrajectoryStep(0.0, 0.0));
334 double after_acceleration = getMinMaxPathAcceleration(0.0, 0.0,
true);
335 while (valid_ && !integrateForward(trajectory_, after_acceleration) && valid_)
337 double before_acceleration;
338 TrajectoryStep switching_point;
339 if (getNextSwitchingPoint(trajectory_.back().path_pos_, switching_point, before_acceleration, after_acceleration))
343 integrateBackward(trajectory_, switching_point.path_pos_, switching_point.path_vel_, before_acceleration);
348 double before_acceleration = getMinMaxPathAcceleration(path_.
getLength(), 0.0,
false);
349 integrateBackward(trajectory_, path_.
getLength(), 0.0, before_acceleration);
355 std::list<TrajectoryStep>::iterator previous = trajectory_.begin();
356 std::list<TrajectoryStep>::iterator it = previous;
359 while (it != trajectory_.end())
362 previous->time_ + (it->path_pos_ - previous->path_pos_) / ((it->path_vel_ + previous->path_vel_) / 2.0);
374 bool Trajectory::getNextSwitchingPoint(
double path_pos, TrajectoryStep& next_switching_point,
375 double& before_acceleration,
double& after_acceleration)
377 TrajectoryStep acceleration_switching_point(path_pos, 0.0);
378 double acceleration_before_acceleration, acceleration_after_acceleration;
379 bool acceleration_reached_end;
382 acceleration_reached_end =
383 getNextAccelerationSwitchingPoint(acceleration_switching_point.path_pos_, acceleration_switching_point,
384 acceleration_before_acceleration, acceleration_after_acceleration);
385 }
while (!acceleration_reached_end &&
386 acceleration_switching_point.path_vel_ > getVelocityMaxPathVelocity(acceleration_switching_point.path_pos_));
388 TrajectoryStep velocity_switching_point(path_pos, 0.0);
389 double velocity_before_acceleration, velocity_after_acceleration;
390 bool velocity_reached_end;
393 velocity_reached_end = getNextVelocitySwitchingPoint(velocity_switching_point.path_pos_, velocity_switching_point,
394 velocity_before_acceleration, velocity_after_acceleration);
396 !velocity_reached_end && velocity_switching_point.path_pos_ <= acceleration_switching_point.path_pos_ &&
397 (velocity_switching_point.path_vel_ > getAccelerationMaxPathVelocity(velocity_switching_point.path_pos_ - EPS) ||
398 velocity_switching_point.path_vel_ > getAccelerationMaxPathVelocity(velocity_switching_point.path_pos_ + EPS)));
400 if (acceleration_reached_end && velocity_reached_end)
404 else if (!acceleration_reached_end &&
405 (velocity_reached_end || acceleration_switching_point.path_pos_ <= velocity_switching_point.path_pos_))
407 next_switching_point = acceleration_switching_point;
408 before_acceleration = acceleration_before_acceleration;
409 after_acceleration = acceleration_after_acceleration;
414 next_switching_point = velocity_switching_point;
415 before_acceleration = velocity_before_acceleration;
416 after_acceleration = velocity_after_acceleration;
421 bool Trajectory::getNextAccelerationSwitchingPoint(
double path_pos, TrajectoryStep& next_switching_point,
422 double& before_acceleration,
double& after_acceleration)
424 double switching_path_pos = path_pos;
425 double switching_path_vel;
431 if (switching_path_pos > path_.
getLength() - EPS)
438 const double before_path_vel = getAccelerationMaxPathVelocity(switching_path_pos - EPS);
439 const double after_path_vel = getAccelerationMaxPathVelocity(switching_path_pos + EPS);
440 switching_path_vel = std::min(before_path_vel, after_path_vel);
441 before_acceleration = getMinMaxPathAcceleration(switching_path_pos - EPS, switching_path_vel,
false);
442 after_acceleration = getMinMaxPathAcceleration(switching_path_pos + EPS, switching_path_vel,
true);
444 if ((before_path_vel > after_path_vel ||
445 getMinMaxPhaseSlope(switching_path_pos - EPS, switching_path_vel,
false) >
446 getAccelerationMaxPathVelocityDeriv(switching_path_pos - 2.0 * EPS)) &&
447 (before_path_vel < after_path_vel || getMinMaxPhaseSlope(switching_path_pos + EPS, switching_path_vel,
true) <
448 getAccelerationMaxPathVelocityDeriv(switching_path_pos + 2.0 * EPS)))
455 switching_path_vel = getAccelerationMaxPathVelocity(switching_path_pos);
456 before_acceleration = 0.0;
457 after_acceleration = 0.0;
459 if (getAccelerationMaxPathVelocityDeriv(switching_path_pos - EPS) < 0.0 &&
460 getAccelerationMaxPathVelocityDeriv(switching_path_pos + EPS) > 0.0)
467 next_switching_point = TrajectoryStep(switching_path_pos, switching_path_vel);
471 bool Trajectory::getNextVelocitySwitchingPoint(
double path_pos, TrajectoryStep& next_switching_point,
472 double& before_acceleration,
double& after_acceleration)
475 path_pos -= DEFAULT_TIMESTEP;
478 path_pos += DEFAULT_TIMESTEP;
480 if (getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos),
false) >=
481 getVelocityMaxPathVelocityDeriv(path_pos))
485 }
while ((!start || getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos),
false) >
486 getVelocityMaxPathVelocityDeriv(path_pos)) &&
494 double before_path_pos = path_pos - DEFAULT_TIMESTEP;
495 double after_path_pos = path_pos;
496 while (after_path_pos - before_path_pos > EPS)
498 path_pos = (before_path_pos + after_path_pos) / 2.0;
499 if (getMinMaxPhaseSlope(path_pos, getVelocityMaxPathVelocity(path_pos),
false) >
500 getVelocityMaxPathVelocityDeriv(path_pos))
502 before_path_pos = path_pos;
506 after_path_pos = path_pos;
510 before_acceleration = getMinMaxPathAcceleration(before_path_pos, getVelocityMaxPathVelocity(before_path_pos),
false);
511 after_acceleration = getMinMaxPathAcceleration(after_path_pos, getVelocityMaxPathVelocity(after_path_pos),
true);
512 next_switching_point = TrajectoryStep(after_path_pos, getVelocityMaxPathVelocity(after_path_pos));
517 bool Trajectory::integrateForward(std::list<TrajectoryStep>& trajectory,
double acceleration)
519 double path_pos = trajectory.back().path_pos_;
520 double path_vel = trajectory.back().path_vel_;
523 std::list<std::pair<double, bool>>::iterator next_discontinuity = switching_points.begin();
527 while ((next_discontinuity != switching_points.end()) &&
528 (next_discontinuity->first <= path_pos || !next_discontinuity->second))
530 ++next_discontinuity;
533 double old_path_pos = path_pos;
534 double old_path_vel = path_vel;
536 path_vel += time_step_ * acceleration;
537 path_pos += time_step_ * 0.5 * (old_path_vel + path_vel);
539 if (next_discontinuity != switching_points.end() && path_pos > next_discontinuity->first)
543 if (path_pos - next_discontinuity->first < EPS)
547 path_vel = old_path_vel +
548 (next_discontinuity->first - old_path_pos) * (path_vel - old_path_vel) / (path_pos - old_path_pos);
549 path_pos = next_discontinuity->first;
554 trajectory.push_back(TrajectoryStep(path_pos, path_vel));
557 else if (path_vel < 0.0)
560 RCLCPP_ERROR(LOGGER,
"Error while integrating forward: Negative path velocity");
564 if (path_vel > getVelocityMaxPathVelocity(path_pos) &&
565 getMinMaxPhaseSlope(old_path_pos, getVelocityMaxPathVelocity(old_path_pos),
false) <=
566 getVelocityMaxPathVelocityDeriv(old_path_pos))
568 path_vel = getVelocityMaxPathVelocity(path_pos);
571 trajectory.push_back(TrajectoryStep(path_pos, path_vel));
572 acceleration = getMinMaxPathAcceleration(path_pos, path_vel,
true);
574 if (path_vel == 0 && acceleration == 0)
579 RCLCPP_ERROR(LOGGER,
"Error while integrating forward: zero acceleration and velocity. Are any relevant "
580 "acceleration components limited to zero?");
584 if (path_vel > getAccelerationMaxPathVelocity(path_pos) || path_vel > getVelocityMaxPathVelocity(path_pos))
587 TrajectoryStep overshoot = trajectory.back();
588 trajectory.pop_back();
589 double before = trajectory.back().path_pos_;
590 double before_path_vel = trajectory.back().path_vel_;
591 double after = overshoot.path_pos_;
592 double after_path_vel = overshoot.path_vel_;
593 while (after - before > EPS)
595 const double midpoint = 0.5 * (before + after);
596 double midpoint_path_vel = 0.5 * (before_path_vel + after_path_vel);
598 if (midpoint_path_vel > getVelocityMaxPathVelocity(midpoint) &&
599 getMinMaxPhaseSlope(before, getVelocityMaxPathVelocity(before),
false) <=
600 getVelocityMaxPathVelocityDeriv(before))
602 midpoint_path_vel = getVelocityMaxPathVelocity(midpoint);
605 if (midpoint_path_vel > getAccelerationMaxPathVelocity(midpoint) ||
606 midpoint_path_vel > getVelocityMaxPathVelocity(midpoint))
609 after_path_vel = midpoint_path_vel;
614 before_path_vel = midpoint_path_vel;
617 trajectory.push_back(TrajectoryStep(before, before_path_vel));
619 if (getAccelerationMaxPathVelocity(after) < getVelocityMaxPathVelocity(after))
621 if (after > next_discontinuity->first)
625 else if (getMinMaxPhaseSlope(trajectory.back().path_pos_, trajectory.back().path_vel_,
true) >
626 getAccelerationMaxPathVelocityDeriv(trajectory.back().path_pos_))
633 if (getMinMaxPhaseSlope(trajectory.back().path_pos_, trajectory_.back().path_vel_,
false) >
634 getVelocityMaxPathVelocityDeriv(trajectory_.back().path_pos_))
643 void Trajectory::integrateBackward(std::list<TrajectoryStep>& start_trajectory,
double path_pos,
double path_vel,
646 std::list<TrajectoryStep>::iterator start2 = start_trajectory.end();
648 std::list<TrajectoryStep>::iterator start1 = start2;
650 std::list<TrajectoryStep> trajectory;
652 assert(start1->path_pos_ <= path_pos);
654 while (start1 != start_trajectory.begin() || path_pos >= 0.0)
656 if (start1->path_pos_ <= path_pos)
658 trajectory.push_front(TrajectoryStep(path_pos, path_vel));
659 path_vel -= time_step_ * acceleration;
660 path_pos -= time_step_ * 0.5 * (path_vel + trajectory.front().path_vel_);
661 acceleration = getMinMaxPathAcceleration(path_pos, path_vel,
false);
662 slope = (trajectory.front().path_vel_ - path_vel) / (trajectory.front().path_pos_ - path_pos);
667 RCLCPP_ERROR(LOGGER,
"Error while integrating backward: Negative path velocity");
668 end_trajectory_ = trajectory;
680 const double start_slope = (start2->path_vel_ - start1->path_vel_) / (start2->path_pos_ - start1->path_pos_);
681 const double intersection_path_pos =
682 (start1->path_vel_ - path_vel + slope * path_pos - start_slope * start1->path_pos_) / (slope - start_slope);
683 if (std::max(start1->path_pos_, path_pos) - EPS <= intersection_path_pos &&
684 intersection_path_pos <= EPS + std::min(start2->path_pos_, trajectory.front().path_pos_))
686 const double intersection_path_vel =
687 start1->path_vel_ + start_slope * (intersection_path_pos - start1->path_pos_);
688 start_trajectory.erase(start2, start_trajectory.end());
689 start_trajectory.push_back(TrajectoryStep(intersection_path_pos, intersection_path_vel));
690 start_trajectory.splice(start_trajectory.end(), trajectory);
696 RCLCPP_ERROR(LOGGER,
"Error while integrating backward: Did not hit start trajectory");
697 end_trajectory_ = trajectory;
700 double Trajectory::getMinMaxPathAcceleration(
double path_pos,
double path_vel,
bool max)
702 Eigen::VectorXd config_deriv = path_.
getTangent(path_pos);
703 Eigen::VectorXd config_deriv2 = path_.
getCurvature(path_pos);
704 double factor = max ? 1.0 : -1.0;
705 double max_path_acceleration = std::numeric_limits<double>::max();
706 for (
unsigned int i = 0; i < joint_num_; ++i)
708 if (config_deriv[i] != 0.0)
710 max_path_acceleration =
711 std::min(max_path_acceleration, max_acceleration_[i] / std::abs(config_deriv[i]) -
712 factor * config_deriv2[i] * path_vel * path_vel / config_deriv[i]);
715 return factor * max_path_acceleration;
718 double Trajectory::getMinMaxPhaseSlope(
double path_pos,
double path_vel,
bool max)
720 return getMinMaxPathAcceleration(path_pos, path_vel, max) / path_vel;
723 double Trajectory::getAccelerationMaxPathVelocity(
double path_pos)
const
725 double max_path_velocity = std::numeric_limits<double>::infinity();
726 const Eigen::VectorXd config_deriv = path_.
getTangent(path_pos);
727 const Eigen::VectorXd config_deriv2 = path_.
getCurvature(path_pos);
728 for (
unsigned int i = 0; i < joint_num_; ++i)
730 if (config_deriv[i] != 0.0)
732 for (
unsigned int j = i + 1; j < joint_num_; ++j)
734 if (config_deriv[j] != 0.0)
736 double a_ij = config_deriv2[i] / config_deriv[i] - config_deriv2[j] / config_deriv[j];
739 max_path_velocity = std::min(max_path_velocity, sqrt((max_acceleration_[i] / std::abs(config_deriv[i]) +
740 max_acceleration_[j] / std::abs(config_deriv[j])) /
746 else if (config_deriv2[i] != 0.0)
748 max_path_velocity = std::min(max_path_velocity, sqrt(max_acceleration_[i] / std::abs(config_deriv2[i])));
751 return max_path_velocity;
754 double Trajectory::getVelocityMaxPathVelocity(
double path_pos)
const
756 const Eigen::VectorXd tangent = path_.
getTangent(path_pos);
757 double max_path_velocity = std::numeric_limits<double>::max();
758 for (
unsigned int i = 0; i < joint_num_; ++i)
760 max_path_velocity = std::min(max_path_velocity, max_velocity_[i] / std::abs(tangent[i]));
762 return max_path_velocity;
765 double Trajectory::getAccelerationMaxPathVelocityDeriv(
double path_pos)
767 return (getAccelerationMaxPathVelocity(path_pos + EPS) - getAccelerationMaxPathVelocity(path_pos - EPS)) /
771 double Trajectory::getVelocityMaxPathVelocityDeriv(
double path_pos)
773 const Eigen::VectorXd tangent = path_.
getTangent(path_pos);
774 double max_path_velocity = std::numeric_limits<double>::max();
775 unsigned int active_constraint;
776 for (
unsigned int i = 0; i < joint_num_; ++i)
778 const double this_max_path_velocity = max_velocity_[i] / std::abs(tangent[i]);
779 if (this_max_path_velocity < max_path_velocity)
781 max_path_velocity = this_max_path_velocity;
782 active_constraint = i;
785 return -(max_velocity_[active_constraint] * path_.
getCurvature(path_pos)[active_constraint]) /
786 (tangent[active_constraint] * std::abs(tangent[active_constraint]));
796 return trajectory_.back().time_;
799 std::list<Trajectory::TrajectoryStep>::const_iterator Trajectory::getTrajectorySegment(
double time)
const
801 if (time >= trajectory_.back().time_)
803 std::list<TrajectoryStep>::const_iterator last = trajectory_.end();
809 if (time < cached_time_)
811 cached_trajectory_segment_ = trajectory_.begin();
813 while (time >= cached_trajectory_segment_->time_)
815 ++cached_trajectory_segment_;
818 return cached_trajectory_segment_;
824 std::list<TrajectoryStep>::const_iterator it = getTrajectorySegment(time);
825 std::list<TrajectoryStep>::const_iterator previous = it;
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);
832 time_step = time - previous->time_;
833 const double path_pos =
834 previous->path_pos_ + time_step * previous->path_vel_ + 0.5 * time_step * time_step * acceleration;
841 std::list<TrajectoryStep>::const_iterator it = getTrajectorySegment(time);
842 std::list<TrajectoryStep>::const_iterator previous = it;
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);
849 time_step = time - previous->time_;
850 const double path_pos =
851 previous->path_pos_ + time_step * previous->path_vel_ + 0.5 * time_step * time_step * acceleration;
852 const double path_vel = previous->path_vel_ + time_step * acceleration;
859 std::list<TrajectoryStep>::const_iterator it = getTrajectorySegment(time);
860 std::list<TrajectoryStep>::const_iterator previous = it;
863 double time_step = it->time_ - previous->time_;
864 const double acceleration =
865 2.0 * (it->path_pos_ - previous->path_pos_ - time_step * previous->path_vel_) / (time_step * time_step);
867 time_step = time - previous->time_;
868 const double path_pos =
869 previous->path_pos_ + time_step * previous->path_vel_ + 0.5 * time_step * time_step * acceleration;
870 const double path_vel = previous->path_vel_ + time_step * acceleration;
871 Eigen::VectorXd path_acc =
872 (path_.
getTangent(path_pos) * path_vel - path_.
getTangent(previous->path_pos_) * previous->path_vel_);
874 path_acc /= time_step;
879 const double min_angle_change)
880 : path_tolerance_(path_tolerance), resample_dt_(resample_dt), min_angle_change_(min_angle_change)
885 const double max_velocity_scaling_factor,
886 const double max_acceleration_scaling_factor)
const
888 if (trajectory.
empty())
894 RCLCPP_ERROR(LOGGER,
"It looks like the planner did not set the group the plan was computed for");
899 double velocity_scaling_factor = 1.0;
900 if (max_velocity_scaling_factor > 0.0 && max_velocity_scaling_factor <= 1.0)
902 velocity_scaling_factor = max_velocity_scaling_factor;
904 else if (max_velocity_scaling_factor == 0.0)
906 RCLCPP_DEBUG(LOGGER,
"A max_velocity_scaling_factor of 0.0 was specified, defaulting to %f instead.",
907 velocity_scaling_factor);
911 RCLCPP_WARN(LOGGER,
"Invalid max_velocity_scaling_factor %f specified, defaulting to %f instead.",
912 max_velocity_scaling_factor, velocity_scaling_factor);
915 double acceleration_scaling_factor = 1.0;
916 if (max_acceleration_scaling_factor > 0.0 && max_acceleration_scaling_factor <= 1.0)
918 acceleration_scaling_factor = max_acceleration_scaling_factor;
920 else if (max_acceleration_scaling_factor == 0.0)
922 RCLCPP_DEBUG(LOGGER,
"A max_acceleration_scaling_factor of 0.0 was specified, defaulting to %f instead.",
923 acceleration_scaling_factor);
927 RCLCPP_WARN(LOGGER,
"Invalid max_acceleration_scaling_factor %f specified, defaulting to %f instead.",
928 max_acceleration_scaling_factor, acceleration_scaling_factor);
931 const std::vector<std::string>& vars =
group->getVariableNames();
933 const unsigned num_joints =
group->getVariableCount();
936 Eigen::VectorXd max_velocity(num_joints);
937 Eigen::VectorXd max_acceleration(num_joints);
938 for (
size_t j = 0; j < num_joints; ++j)
943 max_velocity[j] = 1.0;
948 RCLCPP_ERROR(LOGGER,
"Invalid max_velocity %f specified for '%s', must be greater than 0.0",
957 RCLCPP_WARN_STREAM_ONCE(
958 LOGGER,
"Joint velocity limits are not defined. Using the default "
959 << max_velocity[j] <<
" rad/s. You can define velocity limits in the URDF or joint_limits.yaml.");
962 max_acceleration[j] = 1.0;
967 RCLCPP_ERROR(LOGGER,
"Invalid max_acceleration %f specified for '%s', must be greater than 0.0",
972 acceleration_scaling_factor;
976 RCLCPP_WARN_STREAM_ONCE(LOGGER,
977 "Joint acceleration limits are not defined. Using the default "
978 << max_acceleration[j]
979 <<
" rad/s^2. You can define acceleration limits in the URDF or joint_limits.yaml.");
983 return doTimeParameterizationCalculations(trajectory, max_velocity, max_acceleration);
988 const std::unordered_map<std::string, double>& acceleration_limits)
const
990 if (trajectory.
empty())
997 RCLCPP_ERROR(LOGGER,
"It looks like the planner did not set the group the plan was computed for");
1000 const unsigned num_joints =
group->getVariableCount();
1001 const std::vector<std::string>& vars =
group->getVariableNames();
1004 Eigen::VectorXd max_velocity(num_joints);
1005 Eigen::VectorXd max_acceleration(num_joints);
1006 for (
size_t j = 0; j < num_joints; ++j)
1012 bool set_velocity_limit =
false;
1013 auto it = velocity_limits.find(vars[j]);
1014 if (it != velocity_limits.end())
1016 max_velocity[j] = it->second;
1017 set_velocity_limit =
true;
1025 RCLCPP_ERROR(LOGGER,
"Invalid max_velocity %f specified for '%s', must be greater than 0.0",
1030 set_velocity_limit =
true;
1033 if (!set_velocity_limit)
1035 max_velocity[j] = 1.0;
1036 RCLCPP_WARN_STREAM_ONCE(
1037 LOGGER,
"Joint velocity limits are not defined. Using the default "
1038 << max_velocity[j] <<
" rad/s. You can define velocity limits in the URDF or joint_limits.yaml.");
1043 bool set_acceleration_limit =
false;
1044 it = acceleration_limits.find(vars[j]);
1045 if (it != acceleration_limits.end())
1047 max_acceleration[j] = it->second;
1048 set_acceleration_limit =
true;
1056 RCLCPP_ERROR(LOGGER,
"Invalid max_acceleration %f specified for '%s', must be greater than 0.0",
1061 set_acceleration_limit =
true;
1063 if (!set_acceleration_limit)
1065 max_acceleration[j] = 1.0;
1066 RCLCPP_WARN_STREAM_ONCE(LOGGER,
1067 "Joint acceleration limits are not defined. Using the default "
1068 << max_acceleration[j]
1069 <<
" rad/s^2. You can define acceleration limits in the URDF or joint_limits.yaml.");
1073 return doTimeParameterizationCalculations(trajectory, max_velocity, max_acceleration);
1077 const Eigen::VectorXd& max_velocity,
1078 const Eigen::VectorXd& max_acceleration)
const
1086 RCLCPP_ERROR(LOGGER,
"It looks like the planner did not set the group the plan was computed for");
1091 const std::vector<int>& idx =
group->getVariableIndexList();
1092 const unsigned num_joints =
group->getVariableCount();
1096 std::list<Eigen::VectorXd> points;
1097 for (
size_t p = 0;
p < num_points; ++
p)
1100 Eigen::VectorXd new_point(num_joints);
1102 bool diverse_point = (
p == 0);
1104 for (
size_t j = 0; j < num_joints; ++j)
1106 new_point[j] = waypoint->getVariablePosition(idx[j]);
1108 if (
p > 0 && std::fabs(new_point[j] - points.back()[j]) > min_angle_change_)
1110 diverse_point =
true;
1115 points.push_back(new_point);
1118 else if (
p == num_points - 1)
1119 points.back() = new_point;
1123 if (points.size() == 1)
1134 Trajectory parameterized(Path(points, path_tolerance_), max_velocity, max_acceleration, DEFAULT_TIMESTEP);
1135 if (!parameterized.isValid())
1137 RCLCPP_ERROR(LOGGER,
"Unable to parameterize trajectory.");
1142 size_t sample_count = std::ceil(parameterized.getDuration() / resample_dt_);
1148 for (
size_t sample = 0; sample <= sample_count; ++sample)
1151 double t = std::min(parameterized.getDuration(), sample * resample_dt_);
1152 Eigen::VectorXd position = parameterized.getPosition(t);
1153 Eigen::VectorXd velocity = parameterized.getVelocity(t);
1154 Eigen::VectorXd acceleration = parameterized.getAcceleration(t);
1156 for (
size_t j = 0; j < num_joints; ++j)
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.
const moveit::core::JointModelGroup * getGroup() const
RobotTrajectory & unwind()
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
moveit::core::RobotStatePtr & getWayPointPtr(std::size_t index)
std::size_t getWayPointCount() const
RobotTrajectory & clear()
const moveit::core::RobotState & getWayPoint(std::size_t index) const
CircularPathSegment * clone() const override
Eigen::VectorXd getConfig(double s) 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
std::list< double > getSwitchingPoints() const override
Eigen::VectorXd getCurvature(double s) const override
LinearPathSegment * clone() const override
Eigen::VectorXd getTangent(double) const override
Eigen::VectorXd getCurvature(double) const override
Eigen::VectorXd getConfig(double s) const override
LinearPathSegment(const Eigen::VectorXd &start, const Eigen::VectorXd &end)
std::list< double > getSwitchingPoints() const override
virtual Eigen::VectorXd getConfig(double s) const =0
virtual Eigen::VectorXd getCurvature(double s) const =0
virtual Eigen::VectorXd getTangent(double s) const =0
Eigen::VectorXd getTangent(double s) const
std::list< std::pair< double, bool > > getSwitchingPoints() const
Eigen::VectorXd getConfig(double s) const
Eigen::VectorXd getCurvature(double s) const
double getNextSwitchingPoint(double s, bool &discontinuity) const
Path(const std::list< Eigen::VectorXd > &path, double max_deviation=0.0)
TimeOptimalTrajectoryGeneration(const double path_tolerance=0.1, const double resample_dt=0.1, const double min_angle_change=0.001)
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
Eigen::VectorXd getAcceleration(double time) const
Return the acceleration vector for a given point in time.
bool isValid() const
Call this method after constructing the object to make sure the trajectory generation succeeded witho...
Eigen::VectorXd getPosition(double time) const
Return the position/configuration vector for a given point in time.
Trajectory(const Path &path, const Eigen::VectorXd &max_velocity, const Eigen::VectorXd &max_acceleration, double time_step=0.001)
Generates a time-optimal trajectory.
double getDuration() const
Returns the optimal duration of the trajectory.
Eigen::VectorXd getVelocity(double time) const
Return the velocity vector for a given point in time.
double distance(const urdf::Pose &transform)
const rclcpp::Logger LOGGER
bool acceleration_bounded_