#include <time_optimal_trajectory_generation.h>
|
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. More...
|
|
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 |
| 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. More...
|
|
| TimeOptimalTrajectoryGeneration (const double path_tolerance=0.1, const double resample_dt=0.1, const double min_angle_change=0.001) |
|
virtual | ~TimeParameterization ()=default |
|
◆ TimeOptimalTrajectoryGeneration()
trajectory_processing::TimeOptimalTrajectoryGeneration::TimeOptimalTrajectoryGeneration |
( |
const double |
path_tolerance = 0.1 , |
|
|
const double |
resample_dt = 0.1 , |
|
|
const double |
min_angle_change = 0.001 |
|
) |
| |
◆ computeTimeStamps() [1/2]
bool trajectory_processing::TimeOptimalTrajectoryGeneration::computeTimeStamps |
( |
robot_trajectory::RobotTrajectory & |
trajectory, |
|
|
const double |
max_velocity_scaling_factor = 1.0 , |
|
|
const double |
max_acceleration_scaling_factor = 1.0 |
|
) |
| const |
|
inlineoverridevirtual |
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.
- Parameters
-
[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 191 of file time_optimal_trajectory_generation.h.
◆ computeTimeStamps() [2/2]
bool trajectory_processing::TimeOptimalTrajectoryGeneration::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 |
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.
- Parameters
-
[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. |
Definition at line 865 of file time_optimal_trajectory_generation.cpp.
◆ hasMixedJointTypes()
Check if a combination of revolute and prismatic joints is used. path_tolerance_ is not valid, if so.
- Parameters
-
group | The JointModelGroup to check. |
- Returns
- true if there are mixed joints.
Definition at line 1046 of file time_optimal_trajectory_generation.cpp.
◆ verifyScalingFactor()
double trajectory_processing::TimeOptimalTrajectoryGeneration::verifyScalingFactor |
( |
const double |
requested_scaling_factor | ) |
const |
|
private |
Check if the requested scaling factor is valid and if not, return 1.0.
- Parameters
-
requested_scaling_factor | The desired maximum scaling factor to apply to the velocity or acceleration limits |
- Returns
- The user requested scaling factor, if it is valid. Otherwise, return 1.0.
Definition at line 1063 of file time_optimal_trajectory_generation.cpp.
◆ min_angle_change_
const double trajectory_processing::TimeOptimalTrajectoryGeneration::min_angle_change_ |
|
private |
◆ path_tolerance_
const double trajectory_processing::TimeOptimalTrajectoryGeneration::path_tolerance_ |
|
private |
◆ resample_dt_
const double trajectory_processing::TimeOptimalTrajectoryGeneration::resample_dt_ |
|
private |
The documentation for this class was generated from the following files: