Go to the documentation of this file.
61 virtual Eigen::VectorXd
getConfig(
double s)
const = 0;
62 virtual Eigen::VectorXd
getTangent(
double s)
const = 0;
63 virtual Eigen::VectorXd
getCurvature(
double s)
const = 0;
76 Path(
const std::list<Eigen::VectorXd>& path,
double max_deviation = 0.0);
96 Trajectory(
const Path& path,
const Eigen::VectorXd& max_velocity,
const Eigen::VectorXd& max_acceleration,
97 double time_step = 0.001);
132 double& after_acceleration);
134 double& before_acceleration,
double& after_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);
168 const double min_angle_change = 0.001);
171 const double max_acceleration_scaling_factor = 1.0)
const override;
virtual std::list< double > getSwitchingPoints() const =0
PathSegment * getPathSegment(double &s) const
double getVelocityMaxPathVelocity(double path_pos) const
Eigen::VectorXd getVelocity(double time) const
Return the velocity vector for a given point in time.
std::list< TrajectoryStep >::const_iterator cached_trajectory_segment_
TrajectoryStep(double path_pos, double path_vel)
virtual Eigen::VectorXd getTangent(double s) const =0
std::list< TrajectoryStep >::const_iterator getTrajectorySegment(double time) const
PathSegment(double length=0.0)
TimeOptimalTrajectoryGeneration(const double path_tolerance=0.1, const double resample_dt=0.1, const double min_angle_change=0.001)
Maintain a sequence of waypoints and the time durations between these waypoints.
std::list< std::pair< double, bool > > switching_points_
Eigen::VectorXd max_velocity_
virtual Eigen::VectorXd getCurvature(double s) const =0
double getNextSwitchingPoint(double s, bool &discontinuity) const
void integrateBackward(std::list< TrajectoryStep > &start_trajectory, double path_pos, double path_vel, double acceleration)
const double path_tolerance_
double getAccelerationMaxPathVelocityDeriv(double path_pos)
double getDuration() const
Returns the optimal duration of the trajectory.
Eigen::VectorXd max_acceleration_
bool getNextSwitchingPoint(double path_pos, TrajectoryStep &next_switching_point, double &before_acceleration, double &after_acceleration)
bool getNextAccelerationSwitchingPoint(double path_pos, TrajectoryStep &next_switching_point, double &before_acceleration, double &after_acceleration)
double getMinMaxPathAcceleration(double path_position, double path_velocity, bool max)
Path(const std::list< Eigen::VectorXd > &path, double max_deviation=0.0)
std::list< TrajectoryStep > trajectory_
Eigen::VectorXd getConfig(double s) const
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 getVelocityMaxPathVelocityDeriv(double path_pos)
Eigen::VectorXd getAcceleration(double time) const
Return the acceleration vector for a given point in time.
std::list< TrajectoryStep > end_trajectory_
const double resample_dt_
double getMinMaxPhaseSlope(double path_position, double path_velocity, bool max)
std::list< std::pair< double, bool > > getSwitchingPoints() const
double getAccelerationMaxPathVelocity(double path_pos) const
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
bool getNextVelocitySwitchingPoint(double path_pos, TrajectoryStep &next_switching_point, double &before_acceleration, double &after_acceleration)
TF2SIMD_FORCE_INLINE tf2Scalar length(const Quaternion &q)
std::list< std::unique_ptr< PathSegment > > path_segments_
Eigen::VectorXd getTangent(double s) const
const double min_angle_change_
bool integrateForward(std::list< TrajectoryStep > &trajectory, double acceleration)
MOVEIT_CLASS_FORWARD(IterativeParabolicTimeParameterization)
This class modifies the timestamps of a trajectory to respect velocity and acceleration constraints.
Eigen::VectorXd getCurvature(double s) const
Eigen::VectorXd getPosition(double time) const
Return the position/configuration vector for a given point in time.
virtual PathSegment * clone() const =0
bool isValid() const
Call this method after constructing the object to make sure the trajectory generation succeeded witho...
virtual Eigen::VectorXd getConfig(double s) const =0
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Wed May 18 2022 02:23:53