moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
51#include <cartesian_limits_parameters.hpp>
52
54{
55using RobotTrajCont = std::vector<robot_trajectory::RobotTrajectoryPtr>;
56
57// List of exceptions which can be thrown by the CommandListManager class.
58CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NegativeBlendRadiusException,
59 moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
60CREATE_MOVEIT_ERROR_CODE_EXCEPTION(LastBlendRadiusNotZeroException,
61 moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
62CREATE_MOVEIT_ERROR_CODE_EXCEPTION(StartStateSetException, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
63CREATE_MOVEIT_ERROR_CODE_EXCEPTION(OverlappingBlendRadiiException,
64 moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
65CREATE_MOVEIT_ERROR_CODE_EXCEPTION(PlanningPipelineException, moveit_msgs::msg::MoveItErrorCodes::FAILURE);
66
72{
73public:
74 CommandListManager(const rclcpp::Node::SharedPtr& node, const moveit::core::RobotModelConstPtr& model);
75
107 RobotTrajCont solve(const planning_scene::PlanningSceneConstPtr& planning_scene,
108 const planning_pipeline::PlanningPipelinePtr& planning_pipeline,
109 const moveit_msgs::msg::MotionSequenceRequest& req_list);
110
111private:
112 using MotionResponseCont = std::vector<planning_interface::MotionPlanResponse>;
113 using RobotState_OptRef = const std::optional<std::reference_wrapper<const moveit::core::RobotState>>;
114 using RadiiCont = std::vector<double>;
115 using GroupNamesCont = std::vector<std::string>;
116
117private:
125 void checkForOverlappingRadii(const MotionResponseCont& resp_cont, const RadiiCont& radii) const;
126
136 MotionResponseCont solveSequenceItems(const planning_scene::PlanningSceneConstPtr& planning_scene,
137 const planning_pipeline::PlanningPipelinePtr& planning_pipeline,
138 const moveit_msgs::msg::MotionSequenceRequest& req_list) const;
139
145 bool checkRadiiForOverlap(const robot_trajectory::RobotTrajectory& traj_A, const double radii_A,
146 const robot_trajectory::RobotTrajectory& traj_B, const double radii_B) const;
147
148private:
153 static RobotState_OptRef getPreviousEndState(const MotionResponseCont& motion_plan_responses,
154 const std::string& group_name);
155
160 static void setStartState(const MotionResponseCont& motion_plan_responses, const std::string& group_name,
161 moveit_msgs::msg::RobotState& start_state);
162
171 static RadiiCont extractBlendRadii(const moveit::core::RobotModel& model,
172 const moveit_msgs::msg::MotionSequenceRequest& req_list);
173
180 static bool isInvalidBlendRadii(const moveit::core::RobotModel& model,
181 const moveit_msgs::msg::MotionSequenceItem& item_A,
182 const moveit_msgs::msg::MotionSequenceItem& item_B);
183
187 static void checkForNegativeRadii(const moveit_msgs::msg::MotionSequenceRequest& req_list);
188
192 static void checkLastBlendRadiusZero(const moveit_msgs::msg::MotionSequenceRequest& req_list);
193
198 static void checkStartStatesOfGroup(const moveit_msgs::msg::MotionSequenceRequest& req_list,
199 const std::string& group_name);
200
205 static void checkStartStates(const moveit_msgs::msg::MotionSequenceRequest& req_list);
206
211 static GroupNamesCont getGroupNames(const moveit_msgs::msg::MotionSequenceRequest& req_list);
212
213private:
215 const rclcpp::Node::SharedPtr node_;
216
218 moveit::core::RobotModelConstPtr model_;
219
222 PlanComponentsBuilder plan_comp_builder_;
223
224 std::shared_ptr<cartesian_limits::ParamListener> param_listener_;
225 cartesian_limits::Params params_;
226};
227
228inline void CommandListManager::checkLastBlendRadiusZero(const moveit_msgs::msg::MotionSequenceRequest& req_list)
229{
230 if (req_list.items.back().blend_radius != 0.0)
231 {
232 throw LastBlendRadiusNotZeroException("The last blending radius must be zero");
233 }
234}
235
236} // 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.
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.
std::vector< robot_trajectory::RobotTrajectoryPtr > RobotTrajCont
This namespace includes the central class for representing planning contexts.
#define CREATE_MOVEIT_ERROR_CODE_EXCEPTION(EXCEPTION_CLASS_NAME, ERROR_CODE)