75 virtual Eigen::VectorXd
getConfig(
double s)
const = 0;
92 static std::optional<Path>
create(
const std::vector<Eigen::VectorXd>& waypoint,
99 Eigen::VectorXd
getConfig(
double s)
const;
119 double length_ = 0.0;
120 std::list<std::pair<double, bool>> switching_points_;
121 std::list<std::unique_ptr<PathSegment>> path_segments_;
129 static std::optional<Trajectory>
create(
const Path& path,
const Eigen::VectorXd& max_velocity,
130 const Eigen::VectorXd& max_acceleration,
double time_step = 0.001);
144 Trajectory(
const Path& path,
const Eigen::VectorXd& max_velocity,
const Eigen::VectorXd& max_acceleration,
147 struct TrajectoryStep
152 TrajectoryStep(
double path_pos,
double path_vel) : path_pos_(path_pos), path_vel_(path_vel)
160 bool getNextSwitchingPoint(
double path_pos, TrajectoryStep& next_switching_point,
double& before_acceleration,
161 double& after_acceleration)
const;
162 bool getNextAccelerationSwitchingPoint(
double path_pos, TrajectoryStep& next_switching_point,
163 double& before_acceleration,
double& after_acceleration)
const;
164 bool getNextVelocitySwitchingPoint(
double path_pos, TrajectoryStep& next_switching_point,
double& before_acceleration,
165 double& after_acceleration)
const;
166 bool integrateForward(std::list<TrajectoryStep>& trajectory,
double acceleration);
167 void integrateBackward(std::list<TrajectoryStep>& start_trajectory,
double path_pos,
double path_vel,
168 double acceleration);
169 double getMinMaxPathAcceleration(
double path_position,
double path_velocity,
bool max)
const;
170 double getMinMaxPhaseSlope(
double path_position,
double path_velocity,
bool max)
const;
171 double getAccelerationMaxPathVelocity(
double path_pos)
const;
172 double getVelocityMaxPathVelocity(
double path_pos)
const;
173 double getAccelerationMaxPathVelocityDeriv(
double path_pos)
const;
174 double getVelocityMaxPathVelocityDeriv(
double path_pos)
const;
176 std::list<TrajectoryStep>::const_iterator getTrajectorySegment(
double time)
const;
179 Eigen::VectorXd max_velocity_;
180 Eigen::VectorXd max_acceleration_;
181 unsigned int joint_num_ = 0.0;
183 std::list<TrajectoryStep> trajectory_;
184 std::list<TrajectoryStep> end_trajectory_;
186 double time_step_ = 0.0;
188 mutable double cached_time_ = std::numeric_limits<double>::max();
189 mutable std::list<TrajectoryStep>::const_iterator cached_trajectory_segment_;
197 const double min_angle_change = 0.001);
214 const double max_acceleration_scaling_factor = 1.0)
const override;
233 const std::unordered_map<std::string, double>& velocity_limits,
234 const std::unordered_map<std::string, double>& acceleration_limits,
235 const double max_velocity_scaling_factor = 1.0,
236 const double max_acceleration_scaling_factor = 1.0)
const override;
254 const std::vector<moveit_msgs::msg::JointLimits>&
joint_limits,
255 const double max_velocity_scaling_factor = 1.0,
256 const double max_acceleration_scaling_factor = 1.0)
const override;
260 const Eigen::VectorXd& max_velocity,
261 const Eigen::VectorXd& max_acceleration)
const;
276 double verifyScalingFactor(
const double requested_scaling_factor,
const LimitType limit_type)
const;
278 const double path_tolerance_;
279 const double resample_dt_;
280 const double min_angle_change_;
300 const double max_velocity_scaling_factor = 1.0,
301 const double max_acceleration_scaling_factor = 1.0);
Maintain a sequence of waypoints and the time durations between these waypoints.
virtual Eigen::VectorXd getConfig(double s) const =0
virtual std::list< double > getSwitchingPoints() const =0
virtual PathSegment * clone() const =0
virtual Eigen::VectorXd getCurvature(double s) const =0
virtual Eigen::VectorXd getTangent(double s) const =0
PathSegment(double length=0.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.
const std::unordered_map< LimitType, std::string > LIMIT_TYPES
constexpr double DEFAULT_PATH_TOLERANCE
MOVEIT_CLASS_FORWARD(TimeOptimalTrajectoryGeneration)
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...