61 virtual Eigen::VectorXd
getConfig(
double s)
const = 0;
76 Path(
const std::list<Eigen::VectorXd>& path,
double max_deviation = 0.0);
79 Eigen::VectorXd
getConfig(
double s)
const;
88 std::list<std::pair<double, bool>> switching_points_;
89 std::list<std::unique_ptr<PathSegment>> path_segments_;
96 Trajectory(
const Path& path,
const Eigen::VectorXd& max_velocity,
const Eigen::VectorXd& max_acceleration,
97 double time_step = 0.001);
118 struct TrajectoryStep
123 TrajectoryStep(
double path_pos,
double path_vel) : path_pos_(path_pos), path_vel_(path_vel)
131 bool getNextSwitchingPoint(
double path_pos, TrajectoryStep& next_switching_point,
double& before_acceleration,
132 double& after_acceleration);
133 bool getNextAccelerationSwitchingPoint(
double path_pos, TrajectoryStep& next_switching_point,
134 double& before_acceleration,
double& after_acceleration);
135 bool getNextVelocitySwitchingPoint(
double path_pos, TrajectoryStep& next_switching_point,
double& before_acceleration,
136 double& after_acceleration);
137 bool integrateForward(std::list<TrajectoryStep>& trajectory,
double acceleration);
138 void integrateBackward(std::list<TrajectoryStep>& start_trajectory,
double path_pos,
double path_vel,
139 double acceleration);
140 double getMinMaxPathAcceleration(
double path_position,
double path_velocity,
bool max);
141 double getMinMaxPhaseSlope(
double path_position,
double path_velocity,
bool max);
142 double getAccelerationMaxPathVelocity(
double path_pos)
const;
143 double getVelocityMaxPathVelocity(
double path_pos)
const;
144 double getAccelerationMaxPathVelocityDeriv(
double path_pos);
145 double getVelocityMaxPathVelocityDeriv(
double path_pos);
147 std::list<TrajectoryStep>::const_iterator getTrajectorySegment(
double time)
const;
150 Eigen::VectorXd max_velocity_;
151 Eigen::VectorXd max_acceleration_;
152 unsigned int joint_num_;
154 std::list<TrajectoryStep> trajectory_;
155 std::list<TrajectoryStep> end_trajectory_;
157 const double time_step_;
159 mutable double cached_time_;
160 mutable std::list<TrajectoryStep>::const_iterator cached_trajectory_segment_;
168 const double min_angle_change = 0.001);
171 const double max_acceleration_scaling_factor = 1.0)
const override;
174 const std::unordered_map<std::string, double>& velocity_limits,
175 const std::unordered_map<std::string, double>& acceleration_limits)
const override;
179 const Eigen::VectorXd& max_velocity,
180 const Eigen::VectorXd& max_acceleration)
const;
182 const double path_tolerance_;
183 const double resample_dt_;
184 const double min_angle_change_;
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
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.
MOVEIT_CLASS_FORWARD(IterativeParabolicTimeParameterization)
This class modifies the timestamps of a trajectory to respect velocity and acceleration constraints.