moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
trajectory_processing::IterativeSplineParameterization Class Reference

This class sets the timestamps of a trajectory to enforce velocity, acceleration constraints. Initial/final velocities and accelerations may be specified in the trajectory. Velocity and acceleration limits are specified in the model. More...

#include <iterative_spline_parameterization.h>

Inheritance diagram for trajectory_processing::IterativeSplineParameterization:
Inheritance graph
[legend]
Collaboration diagram for trajectory_processing::IterativeSplineParameterization:
Collaboration graph
[legend]

Public Member Functions

 IterativeSplineParameterization (bool add_points=true)
 
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 computeTimeStamps (robot_trajectory::RobotTrajectory &trajectory, const std::unordered_map< std::string, double > &velocity_limits, const std::unordered_map< std::string, double > &acceleration_limits) const override
 
- Public Member Functions inherited from trajectory_processing::TimeParameterization
 TimeParameterization ()=default
 
 TimeParameterization (const TimeParameterization &)=default
 
 TimeParameterization (TimeParameterization &&)=default
 
TimeParameterizationoperator= (const TimeParameterization &)=default
 
TimeParameterizationoperator= (TimeParameterization &&)=default
 
virtual ~TimeParameterization ()=default
 

Detailed Description

This class sets the timestamps of a trajectory to enforce velocity, acceleration constraints. Initial/final velocities and accelerations may be specified in the trajectory. Velocity and acceleration limits are specified in the model.

This algorithm repeatedly fits a cubic spline, adjusts the timing intervals, and repeats until all constraints are satisfied. When finished, each trajectory waypoint will have the time set, as well as the velocities and accelerations for each joint. Since we fit to a cubic spline, the position, velocity, and acceleration will be continuous and within bounds. The jerk will be discontinuous.

To match the velocity and acceleration at the endpoints, the second and second-last point locations need to move. By default, two extra points are added to leave the original trajectory unaffected. If points are not added, the trajectory could potentially be faster, but the 2nd and 2nd-last points should be re-checked for collisions.

Migration notes: If migrating from Iterative Parabolic Time Parameterization, be aware that the velocity and acceleration limits are more strictly enforced using this technique. This means that time-parameterizing the same trajectory with the same velocity and acceleration limits, will result in a longer trajectory. If this is a problem, try retuning (increasing) the limits.

Definition at line 72 of file iterative_spline_parameterization.h.

Constructor & Destructor Documentation

◆ IterativeSplineParameterization()

trajectory_processing::IterativeSplineParameterization::IterativeSplineParameterization ( bool  add_points = true)

Definition at line 76 of file iterative_spline_parameterization.cpp.

Member Function Documentation

◆ computeTimeStamps() [1/2]

bool trajectory_processing::IterativeSplineParameterization::computeTimeStamps ( robot_trajectory::RobotTrajectory trajectory,
const double  max_velocity_scaling_factor = 1.0,
const double  max_acceleration_scaling_factor = 1.0 
) const
overridevirtual

Implements trajectory_processing::TimeParameterization.

Definition at line 80 of file iterative_spline_parameterization.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ computeTimeStamps() [2/2]

bool trajectory_processing::IterativeSplineParameterization::computeTimeStamps ( robot_trajectory::RobotTrajectory trajectory,
const std::unordered_map< std::string, double > &  velocity_limits,
const std::unordered_map< std::string, double > &  acceleration_limits 
) const
overridevirtual

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