moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <time_optimal_trajectory_generation.h>
Public Member Functions | |
TimeOptimalTrajectoryGeneration (const double path_tolerance=DEFAULT_PATH_TOLERANCE, 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 |
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_). Resampling the trajectory doesn't change the start and goal point, and all re-sampled waypoints will be on the path of the original trajectory (within path_tolerance_). However, controller execution is separate from MoveIt and may deviate from the intended path between waypoints. path_tolerance_ is defined in configuration space, so the unit is rad for revolute joints, meters for prismatic joints. | |
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 double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override |
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_). Resampling the trajectory doesn't change the start and goal point, and all re-sampled waypoints will be on the path of the original trajectory (within path_tolerance_). However, controller execution is separate from MoveIt and may deviate from the intended path between waypoints. path_tolerance_ is defined in configuration space, so the unit is rad for revolute joints, meters for prismatic joints. | |
bool | computeTimeStamps (robot_trajectory::RobotTrajectory &trajectory, const std::vector< moveit_msgs::msg::JointLimits > &joint_limits, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override |
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_). Resampling the trajectory doesn't change the start and goal point, and all re-sampled waypoints will be on the path of the original trajectory (within path_tolerance_). However, controller execution is separate from MoveIt and may deviate from the intended path between waypoints. path_tolerance_ is defined in configuration space, so the unit is rad for revolute joints, meters for prismatic joints. | |
Public Member Functions inherited from trajectory_processing::TimeParameterization | |
TimeParameterization ()=default | |
TimeParameterization (const TimeParameterization &)=default | |
TimeParameterization (TimeParameterization &&)=default | |
TimeParameterization & | operator= (const TimeParameterization &)=default |
TimeParameterization & | operator= (TimeParameterization &&)=default |
virtual | ~TimeParameterization ()=default |
Definition at line 193 of file time_optimal_trajectory_generation.h.
trajectory_processing::TimeOptimalTrajectoryGeneration::TimeOptimalTrajectoryGeneration | ( | const double | path_tolerance = DEFAULT_PATH_TOLERANCE , |
const double | resample_dt = 0.1 , |
||
const double | min_angle_change = 0.001 |
||
) |
Definition at line 918 of file time_optimal_trajectory_generation.cpp.
|
overridevirtual |
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_). Resampling the trajectory doesn't change the start and goal point, and all re-sampled waypoints will be on the path of the original trajectory (within path_tolerance_). However, controller execution is separate from MoveIt and may deviate from the intended path between waypoints. path_tolerance_ is defined in configuration space, so the unit is rad for revolute joints, meters for prismatic joints.
[in,out] | trajectory | A path which needs time-parameterization. It's OK if this path has already been time-parameterized; this function will re-time-parameterize it. |
max_velocity_scaling_factor | A factor in the range [0,1] which can slow down the trajectory. | |
max_acceleration_scaling_factor | A factor in the range [0,1] which can slow down the trajectory. |
Implements trajectory_processing::TimeParameterization.
Definition at line 924 of file time_optimal_trajectory_generation.cpp.
|
overridevirtual |
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_). Resampling the trajectory doesn't change the start and goal point, and all re-sampled waypoints will be on the path of the original trajectory (within path_tolerance_). However, controller execution is separate from MoveIt and may deviate from the intended path between waypoints. path_tolerance_ is defined in configuration space, so the unit is rad for revolute joints, meters for prismatic joints.
[in,out] | trajectory | A path which needs time-parameterization. It's OK if this path has already been time-parameterized; this function will re-time-parameterize it. |
velocity_limits | Joint names and velocity limits in rad/s | |
acceleration_limits | Joint names and acceleration limits in rad/s^2 | |
max_velocity_scaling_factor | A factor in the range [0,1] which can slow down the trajectory. | |
max_acceleration_scaling_factor | A factor in the range [0,1] which can slow down the trajectory. |
Implements trajectory_processing::TimeParameterization.
Definition at line 1029 of file time_optimal_trajectory_generation.cpp.
|
overridevirtual |
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_). Resampling the trajectory doesn't change the start and goal point, and all re-sampled waypoints will be on the path of the original trajectory (within path_tolerance_). However, controller execution is separate from MoveIt and may deviate from the intended path between waypoints. path_tolerance_ is defined in configuration space, so the unit is rad for revolute joints, meters for prismatic joints.
[in,out] | trajectory | A path which needs time-parameterization. It's OK if this path has already been time-parameterized; this function will re-time-parameterize it. |
joint_limits | Joint names and corresponding velocity limits in rad/s and acceleration limits in rad/s^2 | |
max_velocity_scaling_factor | A factor in the range [0,1] which can slow down the trajectory. | |
max_acceleration_scaling_factor | A factor in the range [0,1] which can slow down the trajectory. |
Implements trajectory_processing::TimeParameterization.
Definition at line 1006 of file time_optimal_trajectory_generation.cpp.