moveit.core.robot_trajectory
Classes
Maintains a sequence of waypoints and the durations between these waypoints. |
- class moveit.core.robot_trajectory.RobotTrajectory
Maintains a sequence of waypoints and the durations between these waypoints.
- apply_ruckig_smoothing()
Applies Ruckig smoothing to the trajectory.
- Parameters:
velocity_scaling_factor (float) – The velocity scaling factor.
acceleration_scaling_factor (float) – The acceleration scaling factor.
mitigate_overshoot (bool) – Whether to mitigate overshoot during smoothing (default: false).
overshoot_threshold (float) – The maximum allowed overshoot during smoothing (default: 0.01).
- Returns:
bool – True if the trajectory was successfully retimed, false otherwise.
- apply_totg_time_parameterization()
Adds time parameterization to the trajectory using the Time-Optimal Trajectory Generation (TOTG) algorithm.
- Parameters:
velocity_scaling_factor (float) – The velocity scaling factor.
acceleration_scaling_factor (float) – The acceleration scaling factor.
path_tolerance (float) – The path tolerance to use for time parameterization (default: 0.1).
resample_dt (float) – The time step to use for time parameterization (default: 0.1).
min_angle_change (float) – The minimum angle change to use for time parameterization (default: 0.001).
- Returns:
bool – True if the trajectory was successfully retimed, false otherwise.
- property average_segment_duration
The average duration of the segments in the trajectory.
- Type:
float
- property duration
The duration of the trajectory.
- Type:
float
- get_robot_trajectory_msg()
Get the trajectory as a moveit_msgs.msg.RobotTrajectory message.
- Parameters:
joint_filter (list[string]) – List of joints to consider in creating the message. If empty, uses all joints.
- Returns:
moveit_msgs.msg.RobotTrajectory – A ROS robot trajectory message.
- get_waypoint_durations()
Get the durations from the previous waypoint in the trajectory.
- Returns:
list of float – The duration from previous of each waypoint in the trajectory.
- property joint_model_group_name
The name of the joint model group that this trajectory is for.
- Type:
str
- property robot_model
The robot model that this trajectory is for.
- Type:
moveit_py.core.RobotModel
- set_robot_trajectory_msg()
Set the trajectory from a moveit_msgs.msg.RobotTrajectory message.
- Parameters:
robot_state (
moveit_py.core.RobotState
) – The reference robot starting state.msg (moveit_msgs.msg.RobotTrajectory) – A ROS robot trajectory message.
- unwind()
Unwind the trajectory.