moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Classes | |
class | CircularPathSegment |
class | LinearPathSegment |
class | Path |
class | PathSegment |
class | RuckigSmoothing |
class | TimeOptimalTrajectoryGeneration |
class | TimeParameterization |
class | Trajectory |
Enumerations | |
enum | LimitType { VELOCITY , ACCELERATION } |
Functions | |
MOVEIT_CLASS_FORWARD (TimeOptimalTrajectoryGeneration) | |
bool | totgComputeTimeStamps (const size_t num_waypoints, robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) |
Compute a trajectory with the desired number of waypoints. 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. This is a free function because it needs to modify the const resample_dt_ member of TimeOptimalTrajectoryGeneration class. | |
MOVEIT_CLASS_FORWARD (TimeParameterization) | |
Base class for trajectory parameterization algorithms. | |
bool | isTrajectoryEmpty (const moveit_msgs::msg::RobotTrajectory &trajectory) |
Checks if a robot trajectory is empty. | |
std::size_t | trajectoryWaypointCount (const moveit_msgs::msg::RobotTrajectory &trajectory) |
Returns the number of waypoints in a robot trajectory. | |
bool | applyTOTGTimeParameterization (robot_trajectory::RobotTrajectory &trajectory, double velocity_scaling_factor, double acceleration_scaling_factor, double path_tolerance=0.1, double resample_dt=0.1, double min_angle_change=0.001) |
Applies time parameterization to a robot trajectory using the Time-Optimal Trajectory Generation (TOTG) algorithm. | |
bool | applyRuckigSmoothing (robot_trajectory::RobotTrajectory &trajectory, double velocity_scaling_factor, double acceleration_scaling_factor, bool mitigate_overshoot=false, double overshoot_threshold=0.01) |
Applies Ruckig smoothing to a robot trajectory. | |
trajectory_msgs::msg::JointTrajectory | createTrajectoryMessage (const std::vector< std::string > &joint_names, const trajectory_processing::Trajectory &trajectory, const int sampling_rate) |
Converts a trajectory_processing::Trajectory into a JointTrajectory message with a given sampling rate. | |
Variables | |
constexpr double | DEFAULT_PATH_TOLERANCE = 0.1 |
const std::unordered_map< LimitType, std::string > | LIMIT_TYPES |
Enumerator | |
---|---|
VELOCITY | |
ACCELERATION |
Definition at line 54 of file time_optimal_trajectory_generation.h.
bool trajectory_processing::applyRuckigSmoothing | ( | robot_trajectory::RobotTrajectory & | trajectory, |
double | velocity_scaling_factor, | ||
double | acceleration_scaling_factor, | ||
bool | mitigate_overshoot = false , |
||
double | overshoot_threshold = 0.01 |
||
) |
Applies Ruckig smoothing to a robot trajectory.
[in,out] | trajectory | The robot trajectory to be smoothed. |
[in] | velocity_scaling_factor | The factor by which to scale the maximum velocity of the trajectory. |
[in] | acceleration_scaling_factor | The factor by which to scale the maximum acceleration of the trajectory. |
[in] | mitigate_overshoot | Whether to mitigate overshoot during smoothing (default: false). |
[in] | overshoot_threshold | The maximum allowed overshoot during smoothing (default: 0.01). |
Definition at line 70 of file trajectory_tools.cpp.
bool trajectory_processing::applyTOTGTimeParameterization | ( | robot_trajectory::RobotTrajectory & | trajectory, |
double | velocity_scaling_factor, | ||
double | acceleration_scaling_factor, | ||
double | path_tolerance = 0.1 , |
||
double | resample_dt = 0.1 , |
||
double | min_angle_change = 0.001 |
||
) |
Applies time parameterization to a robot trajectory using the Time-Optimal Trajectory Generation (TOTG) algorithm.
[in,out] | trajectory | The robot trajectory to be time parameterized. |
[in] | velocity_scaling_factor | The factor by which to scale the maximum velocity of the trajectory. |
[in] | acceleration_scaling_factor | The factor by which to scale the maximum acceleration of the trajectory. |
[in] | path_tolerance | The path tolerance to use for time parameterization (default: 0.1). |
[in] | resample_dt | The time step to use for time parameterization (default: 0.1). |
[in] | min_angle_change | The minimum angle change to use for time parameterization (default: 0.001). |
Definition at line 63 of file trajectory_tools.cpp.
trajectory_msgs::msg::JointTrajectory trajectory_processing::createTrajectoryMessage | ( | const std::vector< std::string > & | joint_names, |
const trajectory_processing::Trajectory & | trajectory, | ||
const int | sampling_rate | ||
) |
Converts a trajectory_processing::Trajectory
into a JointTrajectory
message with a given sampling rate.
Definition at line 78 of file trajectory_tools.cpp.
bool trajectory_processing::isTrajectoryEmpty | ( | const moveit_msgs::msg::RobotTrajectory & | trajectory | ) |
Checks if a robot trajectory is empty.
[in] | trajectory | The robot trajectory to check. |
Definition at line 54 of file trajectory_tools.cpp.
trajectory_processing::MOVEIT_CLASS_FORWARD | ( | TimeOptimalTrajectoryGeneration | ) |
trajectory_processing::MOVEIT_CLASS_FORWARD | ( | TimeParameterization | ) |
Base class for trajectory parameterization algorithms.
bool trajectory_processing::totgComputeTimeStamps | ( | const size_t | num_waypoints, |
robot_trajectory::RobotTrajectory & | trajectory, | ||
const double | max_velocity_scaling_factor = 1.0 , |
||
const double | max_acceleration_scaling_factor = 1.0 |
||
) |
Compute a trajectory with the desired number of waypoints. 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. This is a free function because it needs to modify the const resample_dt_ member of TimeOptimalTrajectoryGeneration class.
num_waypoints | The desired number of waypoints (plus or minus one due to numerical rounding). | |
[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. |
Definition at line 1137 of file time_optimal_trajectory_generation.cpp.
std::size_t trajectory_processing::trajectoryWaypointCount | ( | const moveit_msgs::msg::RobotTrajectory & | trajectory | ) |
Returns the number of waypoints in a robot trajectory.
[in] | trajectory | The robot trajectory to count waypoints in. |
Definition at line 59 of file trajectory_tools.cpp.
|
constexpr |
Definition at line 52 of file time_optimal_trajectory_generation.h.
const std::unordered_map<LimitType, std::string> trajectory_processing::LIMIT_TYPES |
Definition at line 60 of file time_optimal_trajectory_generation.h.