Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
trajectory_processing::Trajectory Class Reference

#include <time_optimal_trajectory_generation.h>

Classes

struct  TrajectoryStep
 

Public Member Functions

Eigen::VectorXd getAcceleration (double time) const
 Return the acceleration vector for a given point in time. More...
 
double getDuration () const
 Returns the optimal duration of the trajectory. More...
 
Eigen::VectorXd getPosition (double time) const
 Return the position/configuration vector for a given point in time. More...
 
Eigen::VectorXd getVelocity (double time) const
 Return the velocity vector for a given point in time. More...
 
bool isValid () const
 Call this method after constructing the object to make sure the trajectory generation succeeded without errors. If this method returns false, all other methods have undefined behavior. More...
 
 Trajectory (const Path &path, const Eigen::VectorXd &max_velocity, const Eigen::VectorXd &max_acceleration, double time_step=0.001)
 Generates a time-optimal trajectory. More...
 
 ~Trajectory ()
 

Private Member Functions

double getAccelerationMaxPathVelocity (double path_pos) const
 
double getAccelerationMaxPathVelocityDeriv (double path_pos)
 
double getMinMaxPathAcceleration (double path_position, double path_velocity, bool max)
 
double getMinMaxPhaseSlope (double path_position, double path_velocity, bool max)
 
bool getNextAccelerationSwitchingPoint (double path_pos, TrajectoryStep &next_switching_point, double &before_acceleration, double &after_acceleration)
 
bool getNextSwitchingPoint (double path_pos, TrajectoryStep &next_switching_point, double &before_acceleration, double &after_acceleration)
 
bool getNextVelocitySwitchingPoint (double path_pos, TrajectoryStep &next_switching_point, double &before_acceleration, double &after_acceleration)
 
std::list< TrajectoryStep >::const_iterator getTrajectorySegment (double time) const
 
double getVelocityMaxPathVelocity (double path_pos) const
 
double getVelocityMaxPathVelocityDeriv (double path_pos)
 
void integrateBackward (std::list< TrajectoryStep > &start_trajectory, double path_pos, double path_vel, double acceleration)
 
bool integrateForward (std::list< TrajectoryStep > &trajectory, double acceleration)
 

Private Attributes

double cached_time_
 
std::list< TrajectoryStep >::const_iterator cached_trajectory_segment_
 
std::list< TrajectoryStepend_trajectory_
 
unsigned int joint_num_
 
Eigen::VectorXd max_acceleration_
 
Eigen::VectorXd max_velocity_
 
Path path_
 
const double time_step_
 
std::list< TrajectorySteptrajectory_
 
bool valid_
 

Detailed Description

Definition at line 101 of file time_optimal_trajectory_generation.h.

Constructor & Destructor Documentation

◆ Trajectory()

trajectory_processing::Trajectory::Trajectory ( const Path path,
const Eigen::VectorXd max_velocity,
const Eigen::VectorXd max_acceleration,
double  time_step = 0.001 
)

Generates a time-optimal trajectory.

Definition at line 313 of file time_optimal_trajectory_generation.cpp.

◆ ~Trajectory()

trajectory_processing::Trajectory::~Trajectory ( )

Definition at line 359 of file time_optimal_trajectory_generation.cpp.

Member Function Documentation

◆ getAcceleration()

Eigen::VectorXd trajectory_processing::Trajectory::getAcceleration ( double  time) const

Return the acceleration vector for a given point in time.

Definition at line 839 of file time_optimal_trajectory_generation.cpp.

◆ getAccelerationMaxPathVelocity()

double trajectory_processing::Trajectory::getAccelerationMaxPathVelocity ( double  path_pos) const
private

Definition at line 706 of file time_optimal_trajectory_generation.cpp.

◆ getAccelerationMaxPathVelocityDeriv()

double trajectory_processing::Trajectory::getAccelerationMaxPathVelocityDeriv ( double  path_pos)
private

Definition at line 748 of file time_optimal_trajectory_generation.cpp.

◆ getDuration()

double trajectory_processing::Trajectory::getDuration ( ) const

Returns the optimal duration of the trajectory.

Definition at line 777 of file time_optimal_trajectory_generation.cpp.

◆ getMinMaxPathAcceleration()

double trajectory_processing::Trajectory::getMinMaxPathAcceleration ( double  path_position,
double  path_velocity,
bool  max 
)
private

Definition at line 683 of file time_optimal_trajectory_generation.cpp.

◆ getMinMaxPhaseSlope()

double trajectory_processing::Trajectory::getMinMaxPhaseSlope ( double  path_position,
double  path_velocity,
bool  max 
)
private

Definition at line 701 of file time_optimal_trajectory_generation.cpp.

◆ getNextAccelerationSwitchingPoint()

bool trajectory_processing::Trajectory::getNextAccelerationSwitchingPoint ( double  path_pos,
TrajectoryStep next_switching_point,
double &  before_acceleration,
double &  after_acceleration 
)
private

Definition at line 411 of file time_optimal_trajectory_generation.cpp.

◆ getNextSwitchingPoint()

bool trajectory_processing::Trajectory::getNextSwitchingPoint ( double  path_pos,
TrajectoryStep next_switching_point,
double &  before_acceleration,
double &  after_acceleration 
)
private

Definition at line 364 of file time_optimal_trajectory_generation.cpp.

◆ getNextVelocitySwitchingPoint()

bool trajectory_processing::Trajectory::getNextVelocitySwitchingPoint ( double  path_pos,
TrajectoryStep next_switching_point,
double &  before_acceleration,
double &  after_acceleration 
)
private

Definition at line 461 of file time_optimal_trajectory_generation.cpp.

◆ getPosition()

Eigen::VectorXd trajectory_processing::Trajectory::getPosition ( double  time) const

Return the position/configuration vector for a given point in time.

Definition at line 805 of file time_optimal_trajectory_generation.cpp.

◆ getTrajectorySegment()

std::list< Trajectory::TrajectoryStep >::const_iterator trajectory_processing::Trajectory::getTrajectorySegment ( double  time) const
private

Definition at line 782 of file time_optimal_trajectory_generation.cpp.

◆ getVelocity()

Eigen::VectorXd trajectory_processing::Trajectory::getVelocity ( double  time) const

Return the velocity vector for a given point in time.

Definition at line 822 of file time_optimal_trajectory_generation.cpp.

◆ getVelocityMaxPathVelocity()

double trajectory_processing::Trajectory::getVelocityMaxPathVelocity ( double  path_pos) const
private

Definition at line 737 of file time_optimal_trajectory_generation.cpp.

◆ getVelocityMaxPathVelocityDeriv()

double trajectory_processing::Trajectory::getVelocityMaxPathVelocityDeriv ( double  path_pos)
private

Definition at line 754 of file time_optimal_trajectory_generation.cpp.

◆ integrateBackward()

void trajectory_processing::Trajectory::integrateBackward ( std::list< TrajectoryStep > &  start_trajectory,
double  path_pos,
double  path_vel,
double  acceleration 
)
private

Definition at line 626 of file time_optimal_trajectory_generation.cpp.

◆ integrateForward()

bool trajectory_processing::Trajectory::integrateForward ( std::list< TrajectoryStep > &  trajectory,
double  acceleration 
)
private

Definition at line 510 of file time_optimal_trajectory_generation.cpp.

◆ isValid()

bool trajectory_processing::Trajectory::isValid ( ) const

Call this method after constructing the object to make sure the trajectory generation succeeded without errors. If this method returns false, all other methods have undefined behavior.

Definition at line 772 of file time_optimal_trajectory_generation.cpp.

Member Data Documentation

◆ cached_time_

double trajectory_processing::Trajectory::cached_time_
mutableprivate

Definition at line 168 of file time_optimal_trajectory_generation.h.

◆ cached_trajectory_segment_

std::list<TrajectoryStep>::const_iterator trajectory_processing::Trajectory::cached_trajectory_segment_
mutableprivate

Definition at line 169 of file time_optimal_trajectory_generation.h.

◆ end_trajectory_

std::list<TrajectoryStep> trajectory_processing::Trajectory::end_trajectory_
private

Definition at line 164 of file time_optimal_trajectory_generation.h.

◆ joint_num_

unsigned int trajectory_processing::Trajectory::joint_num_
private

Definition at line 161 of file time_optimal_trajectory_generation.h.

◆ max_acceleration_

Eigen::VectorXd trajectory_processing::Trajectory::max_acceleration_
private

Definition at line 160 of file time_optimal_trajectory_generation.h.

◆ max_velocity_

Eigen::VectorXd trajectory_processing::Trajectory::max_velocity_
private

Definition at line 159 of file time_optimal_trajectory_generation.h.

◆ path_

Path trajectory_processing::Trajectory::path_
private

Definition at line 158 of file time_optimal_trajectory_generation.h.

◆ time_step_

const double trajectory_processing::Trajectory::time_step_
private

Definition at line 166 of file time_optimal_trajectory_generation.h.

◆ trajectory_

std::list<TrajectoryStep> trajectory_processing::Trajectory::trajectory_
private

Definition at line 163 of file time_optimal_trajectory_generation.h.

◆ valid_

bool trajectory_processing::Trajectory::valid_
private

Definition at line 162 of file time_optimal_trajectory_generation.h.


The documentation for this class was generated from the following files:


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:42