moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
43#include <rclcpp/node.hpp>
44#include <string>
45#include <map>
46#include <rclcpp/rclcpp.hpp>
47
50{
57{
59 std::string group;
60
61 /* \brief Name of the configuration.
62
63 For a group's default configuration, this should be the same as the group name.
64 Otherwise, the form "group_name[config_name]" is expected for the name. */
65 std::string name;
66
68 std::map<std::string, std::string> config;
69};
70
72typedef std::map<std::string, PlannerConfigurationSettings> PlannerConfigurationMap;
73
74MOVEIT_CLASS_FORWARD(PlanningContext); // Defines PlanningContextPtr, ConstPtr, WeakPtr... etc
75
79{
80public:
82 PlanningContext(const std::string& name, const std::string& group);
83
84 virtual ~PlanningContext();
85
87 const std::string& getGroupName() const
88 {
89 return group_;
90 }
91
93 const std::string& getName() const
94 {
95 return name_;
96 }
97
99 const planning_scene::PlanningSceneConstPtr& getPlanningScene() const
100 {
101 return planning_scene_;
102 }
103
106 {
107 return request_;
108 }
109
111 void setPlanningScene(const planning_scene::PlanningSceneConstPtr& planning_scene);
112
114 void setMotionPlanRequest(const MotionPlanRequest& request);
115
118 virtual void solve(MotionPlanResponse& res) = 0;
119
122 virtual void solve(MotionPlanDetailedResponse& res) = 0;
123
126 virtual bool terminate() = 0;
127
129 virtual void clear() = 0;
130
131protected:
133 std::string name_;
134
136 std::string group_;
137
139 planning_scene::PlanningSceneConstPtr planning_scene_;
140
143};
144
145MOVEIT_CLASS_FORWARD(PlannerManager); // Defines PlannerManagerPtr, ConstPtr, WeakPtr... etc
146
149{
150public:
152 {
153 }
154
156 {
157 }
158
164 virtual bool initialize(const moveit::core::RobotModelConstPtr& model, const rclcpp::Node::SharedPtr& node,
165 const std::string& parameter_namespace);
166
168 virtual std::string getDescription() const = 0;
169
172 virtual void getPlanningAlgorithms(std::vector<std::string>& algs) const;
173
181 virtual PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
182 const MotionPlanRequest& req,
183 moveit_msgs::msg::MoveItErrorCodes& error_code) const = 0;
184
186 PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
187 const MotionPlanRequest& req) const;
188
190 virtual bool canServiceRequest(const MotionPlanRequest& req) const = 0;
191
193 virtual void setPlannerConfigurations(const PlannerConfigurationMap& pcs);
194
200
202 void terminate() const;
203
204protected:
211};
212
213} // namespace planning_interface
#define MOVEIT_CLASS_FORWARD(C)
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 std::string getDescription() const =0
Get a short string that identifies the planning interface.
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 void setPlannerConfigurations(const PlannerConfigurationMap &pcs)
Specify the settings to be used for specific algorithms.
const PlannerConfigurationMap & getPlannerConfigurations() const
Get the settings for a specific algorithm.
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...
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.
virtual void solve(MotionPlanDetailedResponse &res)=0
Solve the motion planning problem and store the detailed result in res. This function should not clea...
std::string name_
The name of this planning context.
MotionPlanRequest request_
The planning request for this context.
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.
virtual void solve(MotionPlanResponse &res)=0
Solve the motion planning problem and store the result in res. This function should not clear data st...
std::string group_
The group (as in the SRDF) this planning context is for.
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 std::string & getGroupName() const
Get the name of the group this planning context is for.
void setMotionPlanRequest(const MotionPlanRequest &request)
Set the planning request for this context.
const std::string & getName() const
Get the name of this planning context.
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
This namespace includes the central class for representing planning contexts.
Response to a planning query.
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.