#include <time_optimal_trajectory_generation.h>
|
| 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) |
| |
◆ Trajectory()
| trajectory_processing::Trajectory::Trajectory |
( |
const Path & |
path, |
|
|
const Eigen::VectorXd & |
max_velocity, |
|
|
const Eigen::VectorXd & |
max_acceleration, |
|
|
double |
time_step = 0.001 |
|
) |
| |
◆ ~Trajectory()
| trajectory_processing::Trajectory::~Trajectory |
( |
| ) |
|
◆ getAcceleration()
| Eigen::VectorXd trajectory_processing::Trajectory::getAcceleration |
( |
double |
time | ) |
const |
◆ getAccelerationMaxPathVelocity()
| double trajectory_processing::Trajectory::getAccelerationMaxPathVelocity |
( |
double |
path_pos | ) |
const |
|
private |
◆ getAccelerationMaxPathVelocityDeriv()
| double trajectory_processing::Trajectory::getAccelerationMaxPathVelocityDeriv |
( |
double |
path_pos | ) |
|
|
private |
◆ getDuration()
| double trajectory_processing::Trajectory::getDuration |
( |
| ) |
const |
◆ getMinMaxPathAcceleration()
| double trajectory_processing::Trajectory::getMinMaxPathAcceleration |
( |
double |
path_position, |
|
|
double |
path_velocity, |
|
|
bool |
max |
|
) |
| |
|
private |
◆ getMinMaxPhaseSlope()
| double trajectory_processing::Trajectory::getMinMaxPhaseSlope |
( |
double |
path_position, |
|
|
double |
path_velocity, |
|
|
bool |
max |
|
) |
| |
|
private |
◆ getNextAccelerationSwitchingPoint()
| bool trajectory_processing::Trajectory::getNextAccelerationSwitchingPoint |
( |
double |
path_pos, |
|
|
TrajectoryStep & |
next_switching_point, |
|
|
double & |
before_acceleration, |
|
|
double & |
after_acceleration |
|
) |
| |
|
private |
◆ getNextSwitchingPoint()
| bool trajectory_processing::Trajectory::getNextSwitchingPoint |
( |
double |
path_pos, |
|
|
TrajectoryStep & |
next_switching_point, |
|
|
double & |
before_acceleration, |
|
|
double & |
after_acceleration |
|
) |
| |
|
private |
◆ getNextVelocitySwitchingPoint()
| bool trajectory_processing::Trajectory::getNextVelocitySwitchingPoint |
( |
double |
path_pos, |
|
|
TrajectoryStep & |
next_switching_point, |
|
|
double & |
before_acceleration, |
|
|
double & |
after_acceleration |
|
) |
| |
|
private |
◆ getPosition()
| Eigen::VectorXd trajectory_processing::Trajectory::getPosition |
( |
double |
time | ) |
const |
◆ getTrajectorySegment()
| std::list< Trajectory::TrajectoryStep >::const_iterator trajectory_processing::Trajectory::getTrajectorySegment |
( |
double |
time | ) |
const |
|
private |
◆ getVelocity()
| Eigen::VectorXd trajectory_processing::Trajectory::getVelocity |
( |
double |
time | ) |
const |
◆ getVelocityMaxPathVelocity()
| double trajectory_processing::Trajectory::getVelocityMaxPathVelocity |
( |
double |
path_pos | ) |
const |
|
private |
◆ getVelocityMaxPathVelocityDeriv()
| double trajectory_processing::Trajectory::getVelocityMaxPathVelocityDeriv |
( |
double |
path_pos | ) |
|
|
private |
◆ integrateBackward()
| void trajectory_processing::Trajectory::integrateBackward |
( |
std::list< TrajectoryStep > & |
start_trajectory, |
|
|
double |
path_pos, |
|
|
double |
path_vel, |
|
|
double |
acceleration |
|
) |
| |
|
private |
◆ integrateForward()
| bool trajectory_processing::Trajectory::integrateForward |
( |
std::list< TrajectoryStep > & |
trajectory, |
|
|
double |
acceleration |
|
) |
| |
|
private |
◆ 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.
◆ cached_time_
| double trajectory_processing::Trajectory::cached_time_ |
|
mutableprivate |
◆ cached_trajectory_segment_
| std::list<TrajectoryStep>::const_iterator trajectory_processing::Trajectory::cached_trajectory_segment_ |
|
mutableprivate |
◆ end_trajectory_
| std::list<TrajectoryStep> trajectory_processing::Trajectory::end_trajectory_ |
|
private |
◆ joint_num_
| unsigned int trajectory_processing::Trajectory::joint_num_ |
|
private |
◆ max_acceleration_
◆ max_velocity_
◆ path_
| Path trajectory_processing::Trajectory::path_ |
|
private |
◆ time_step_
| const double trajectory_processing::Trajectory::time_step_ |
|
private |
◆ trajectory_
| std::list<TrajectoryStep> trajectory_processing::Trajectory::trajectory_ |
|
private |
◆ valid_
| bool trajectory_processing::Trajectory::valid_ |
|
private |
The documentation for this class was generated from the following files: