moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_interface.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage 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 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
42 #include <rclcpp/node.hpp>
43 #include <string>
44 #include <map>
45 #include <rclcpp/rclcpp.hpp>
46 
47 namespace planning_scene
48 {
49 MOVEIT_CLASS_FORWARD(PlanningScene); // Defines PlanningScenePtr, ConstPtr, WeakPtr... etc
50 }
51 
54 {
61 {
63  std::string group;
64 
65  /* \brief Name of the configuration.
66 
67  For a group's default configuration, this should be the same as the group name.
68  Otherwise, the form "group_name[config_name]" is expected for the name. */
69  std::string name;
70 
72  std::map<std::string, std::string> config;
73 };
74 
76 typedef std::map<std::string, PlannerConfigurationSettings> PlannerConfigurationMap;
77 
78 MOVEIT_CLASS_FORWARD(PlanningContext); // Defines PlanningContextPtr, ConstPtr, WeakPtr... etc
79 
83 {
84 public:
86  PlanningContext(const std::string& name, const std::string& group);
87 
88  virtual ~PlanningContext();
89 
91  const std::string& getGroupName() const
92  {
93  return group_;
94  }
95 
97  const std::string& getName() const
98  {
99  return name_;
100  }
101 
103  const planning_scene::PlanningSceneConstPtr& getPlanningScene() const
104  {
105  return planning_scene_;
106  }
107 
110  {
111  return request_;
112  }
113 
115  void setPlanningScene(const planning_scene::PlanningSceneConstPtr& planning_scene);
116 
118  void setMotionPlanRequest(const MotionPlanRequest& request);
119 
122  virtual bool solve(MotionPlanResponse& res) = 0;
123 
126  virtual bool solve(MotionPlanDetailedResponse& res) = 0;
127 
130  virtual bool terminate() = 0;
131 
133  virtual void clear() = 0;
134 
135 protected:
137  std::string name_;
138 
140  std::string group_;
141 
143  planning_scene::PlanningSceneConstPtr planning_scene_;
144 
147 };
148 
149 MOVEIT_CLASS_FORWARD(PlannerManager); // Defines PlannerManagerPtr, ConstPtr, WeakPtr... etc
150 
153 {
154 public:
156  {
157  }
158 
159  virtual ~PlannerManager()
160  {
161  }
162 
168  virtual bool initialize(const moveit::core::RobotModelConstPtr& model, const rclcpp::Node::SharedPtr& node,
169  const std::string& parameter_namespace);
170 
172  virtual std::string getDescription() const;
173 
176  virtual void getPlanningAlgorithms(std::vector<std::string>& algs) const;
177 
185  virtual PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
186  const MotionPlanRequest& req,
187  moveit_msgs::msg::MoveItErrorCodes& error_code) const = 0;
188 
190  PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
191  const MotionPlanRequest& req) const;
192 
194  virtual bool canServiceRequest(const MotionPlanRequest& req) const = 0;
195 
197  virtual void setPlannerConfigurations(const PlannerConfigurationMap& pcs) = 0;
198 
201  {
202  return config_settings_;
203  }
204 
206  void terminate() const;
207 
208 protected:
215 };
216 
217 } // namespace planning_interface
Base class for a MoveIt planner.
virtual bool canServiceRequest(const MotionPlanRequest &req) const =0
Determine whether this plugin instance is able to represent this planning request.
void terminate() const
Request termination, if a solve() function is currently computing plans.
virtual void getPlanningAlgorithms(std::vector< std::string > &algs) const
Get the names of the known planning algorithms (values that can be filled as planner_id in the planni...
virtual std::string getDescription() const
Get.
virtual void setPlannerConfigurations(const PlannerConfigurationMap &pcs)=0
Specify the settings to be used for specific algorithms.
virtual bool initialize(const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace)
virtual PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const =0
Construct a planning context given the current scene and a planning request. If a problem is encounte...
const PlannerConfigurationMap & getPlannerConfigurations() const
Get the settings for a specific algorithm.
PlannerConfigurationMap config_settings_
All the existing planning configurations. The name of the configuration is the key of the map....
Representation of a particular planning context – the planning scene and the request are known,...
void setPlanningScene(const planning_scene::PlanningSceneConstPtr &planning_scene)
Set the planning scene for this context.
planning_scene::PlanningSceneConstPtr planning_scene_
The planning scene for this context.
std::string name_
The name of this planning context.
MotionPlanRequest request_
The planning request for this context.
const std::string & getName() const
Get the name of this planning context.
const std::string & getGroupName() const
Get the name of the group this planning context is for.
std::string group_
The group (as in the SRDF) this planning context is for.
virtual bool solve(MotionPlanDetailedResponse &res)=0
Solve the motion planning problem and store the detailed result in res. This function should not clea...
virtual bool terminate()=0
If solve() is running, terminate the computation. Return false if termination not possible....
virtual void clear()=0
Clear the data structures used by the planner.
const MotionPlanRequest & getMotionPlanRequest() const
Get the motion plan request associated to this planning context.
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
void setMotionPlanRequest(const MotionPlanRequest &request)
Set the planning request for this context.
virtual bool solve(MotionPlanResponse &res)=0
Solve the motion planning problem and store the result in res. This function should not clear data st...
PlanningContext(const std::string &name, const std::string &group)
Construct a planning context named name for the group group.
This class maintains the representation of the environment as seen by a planning instance....
This namespace includes the base class for MoveIt planners.
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
MOVEIT_CLASS_FORWARD(PlanningContext)
This namespace includes the central class for representing planning contexts.
MOVEIT_CLASS_FORWARD(PlanningScene)
name
Definition: setup.py:7
Specify the settings for a particular planning algorithm, for a particular group. The Planner plugin ...
std::map< std::string, std::string > config
Key-value pairs of settings that get passed to the planning algorithm.
std::string group
The group (as defined in the SRDF) this configuration is meant for.