moveit2
The MoveIt Motion Planning Framework for ROS 2.
command_list_manager.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 Pilz GmbH & Co. KG
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Pilz GmbH & Co. KG nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #pragma once
36 
37 #include <string>
38 
39 #include <memory>
40 #include <functional>
41 
44 #include <moveit_msgs/msg/motion_plan_response.hpp>
45 #include <moveit_msgs/msg/motion_sequence_request.hpp>
46 
50 
52 {
53 using RobotTrajCont = std::vector<robot_trajectory::RobotTrajectoryPtr>;
54 
55 // List of exceptions which can be thrown by the CommandListManager class.
56 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NegativeBlendRadiusException,
57  moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
58 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(LastBlendRadiusNotZeroException,
59  moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
60 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(StartStateSetException, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
61 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(OverlappingBlendRadiiException,
62  moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
63 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(PlanningPipelineException, moveit_msgs::msg::MoveItErrorCodes::FAILURE);
64 
70 {
71 public:
72  CommandListManager(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModelConstPtr& model);
73 
105  RobotTrajCont solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
106  const planning_pipeline::PlanningPipelinePtr& planning_pipeline,
107  const moveit_msgs::msg::MotionSequenceRequest& req_list);
108 
109 private:
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>;
114 
115 private:
123  void checkForOverlappingRadii(const MotionResponseCont& resp_cont, const RadiiCont& radii) const;
124 
134  MotionResponseCont solveSequenceItems(const planning_scene::PlanningSceneConstPtr& planning_scene,
135  const planning_pipeline::PlanningPipelinePtr& planning_pipeline,
136  const moveit_msgs::msg::MotionSequenceRequest& req_list) const;
137 
143  bool checkRadiiForOverlap(const robot_trajectory::RobotTrajectory& traj_A, const double radii_A,
144  const robot_trajectory::RobotTrajectory& traj_B, const double radii_B) const;
145 
146 private:
151  static RobotState_OptRef getPreviousEndState(const MotionResponseCont& motion_plan_responses,
152  const std::string& group_name);
153 
158  static void setStartState(const MotionResponseCont& motion_plan_responses, const std::string& group_name,
159  moveit_msgs::msg::RobotState& start_state);
160 
169  static RadiiCont extractBlendRadii(const moveit::core::RobotModel& model,
170  const moveit_msgs::msg::MotionSequenceRequest& req_list);
171 
178  static bool isInvalidBlendRadii(const moveit::core::RobotModel& model,
179  const moveit_msgs::msg::MotionSequenceItem& item_A,
180  const moveit_msgs::msg::MotionSequenceItem& item_B);
181 
185  static void checkForNegativeRadii(const moveit_msgs::msg::MotionSequenceRequest& req_list);
186 
190  static void checkLastBlendRadiusZero(const moveit_msgs::msg::MotionSequenceRequest& req_list);
191 
196  static void checkStartStatesOfGroup(const moveit_msgs::msg::MotionSequenceRequest& req_list,
197  const std::string& group_name);
198 
203  static void checkStartStates(const moveit_msgs::msg::MotionSequenceRequest& req_list);
204 
209  static GroupNamesCont getGroupNames(const moveit_msgs::msg::MotionSequenceRequest& req_list);
210 
211 private:
213  const rclcpp::Node::SharedPtr node_;
214 
216  moveit::core::RobotModelConstPtr model_;
217 
220  PlanComponentsBuilder plan_comp_builder_;
221 };
222 
223 inline void CommandListManager::checkLastBlendRadiusZero(const moveit_msgs::msg::MotionSequenceRequest& req_list)
224 {
225  if (req_list.items.back().blend_radius != 0.0)
226  {
227  throw LastBlendRadiusNotZeroException("The last blending radius must be zero");
228  }
229 }
230 
231 } // namespace pilz_industrial_motion_planner
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Definition: robot_model.h:76
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
Planning pipeline.
This namespace includes the central class for representing planning contexts.