44 #include <moveit_msgs/msg/motion_plan_response.hpp>
45 #include <moveit_msgs/msg/motion_sequence_request.hpp>
53 using RobotTrajCont = std::vector<robot_trajectory::RobotTrajectoryPtr>;
57 moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
59 moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
62 moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
72 CommandListManager(
const rclcpp::Node::SharedPtr& node,
const moveit::core::RobotModelConstPtr& model);
107 const moveit_msgs::msg::MotionSequenceRequest& req_list);
110 using MotionResponseCont = std::vector<planning_interface::MotionPlanResponse>;
111 using RobotState_OptRef =
const std::optional<std::reference_wrapper<const moveit::core::RobotState>>;
112 using RadiiCont = std::vector<double>;
113 using GroupNamesCont = std::vector<std::string>;
123 void checkForOverlappingRadii(
const MotionResponseCont& resp_cont,
const RadiiCont& radii)
const;
134 MotionResponseCont solveSequenceItems(
const planning_scene::PlanningSceneConstPtr&
planning_scene,
136 const moveit_msgs::msg::MotionSequenceRequest& req_list)
const;
151 static RobotState_OptRef getPreviousEndState(
const MotionResponseCont& motion_plan_responses,
152 const std::string& group_name);
158 static void setStartState(
const MotionResponseCont& motion_plan_responses,
const std::string& group_name,
159 moveit_msgs::msg::RobotState& start_state);
170 const moveit_msgs::msg::MotionSequenceRequest& req_list);
179 const moveit_msgs::msg::MotionSequenceItem& item_A,
180 const moveit_msgs::msg::MotionSequenceItem& item_B);
185 static void checkForNegativeRadii(
const moveit_msgs::msg::MotionSequenceRequest& req_list);
190 static void checkLastBlendRadiusZero(
const moveit_msgs::msg::MotionSequenceRequest& req_list);
196 static void checkStartStatesOfGroup(
const moveit_msgs::msg::MotionSequenceRequest& req_list,
197 const std::string& group_name);
203 static void checkStartStates(
const moveit_msgs::msg::MotionSequenceRequest& req_list);
209 static GroupNamesCont getGroupNames(
const moveit_msgs::msg::MotionSequenceRequest& req_list);
213 const rclcpp::Node::SharedPtr node_;
216 moveit::core::RobotModelConstPtr model_;
223 inline void CommandListManager::checkLastBlendRadiusZero(
const moveit_msgs::msg::MotionSequenceRequest& req_list)
225 if (req_list.items.back().blend_radius != 0.0)
227 throw LastBlendRadiusNotZeroException(
"The last blending radius must be zero");
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
This class orchestrates the planning of single commands and command lists.
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.
Helper class to encapsulate the merge and blend process of trajectories.
Maintain a sequence of waypoints and the time durations between these waypoints.
CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NegativeBlendRadiusException, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
std::vector< robot_trajectory::RobotTrajectoryPtr > RobotTrajCont
This namespace includes the central class for representing planning contexts.