Class CommandListManager

Class Documentation

class CommandListManager

This class orchestrates the planning of single commands and command lists.

Public Functions

CommandListManager(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModelConstPtr &model)
RobotTrajCont solve(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_pipeline::PlanningPipelinePtr &planning_pipeline, const moveit_msgs::msg::MotionSequenceRequest &req_list)

Generates trajectories for the specified list of motion commands.

The following rules apply:

  • If two consecutive trajectories are from the same group, they are simply attached to each other, given that the blend_radius is zero.

  • If two consecutive trajectories are from the same group, they are blended together, given that the blend_radius is GREATER than zero.

  • If two consecutive trajectories are from different groups, then the second trajectory is added as new element to the result container. All following trajectories are then attached to the new trajectory element (until all requests are processed or until the next group change).

Please note: Starts states do not need to state the joints of all groups. It is sufficient if a start state states only the joints of the group which it belongs to. Starts states can even be incomplete. In this case default values are set for the unset joints.

Parameters:
  • planning_scene – The planning scene to be used for trajectory generation.

  • req_list – List of motion requests containing: PTP, LIN, CIRC and/or gripper commands. Please note: A request is only valid if:

    • All blending radii are non negative.

    • The blending radius of the last request is 0.

    • Only the first request of each group has a start state.

    • None of the blending radii overlap with each other.

Returns:

Contains the calculated/generated trajectories.