moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_request_adapter.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 <functional>
43 #include <rclcpp/logging.hpp>
44 #include <rclcpp/node.hpp>
45 
48 {
49 MOVEIT_CLASS_FORWARD(PlanningRequestAdapter); // Defines PlanningRequestAdapterPtr, ConstPtr, WeakPtr... etc
50 
52 {
53 public:
54  using PlannerFn =
55  std::function<bool(const planning_scene::PlanningSceneConstPtr&, const planning_interface::MotionPlanRequest&,
57 
59  {
60  }
61 
63  {
64  }
65 
68  virtual void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) = 0;
69 
71  virtual std::string getDescription() const
72  {
73  return "";
74  }
75 
76  bool adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
77  const planning_scene::PlanningSceneConstPtr& planning_scene,
80 
81  bool adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
82  const planning_scene::PlanningSceneConstPtr& planning_scene,
84  std::vector<std::size_t>& added_path_index) const;
85 
91  virtual bool adaptAndPlan(const PlannerFn& planner, const planning_scene::PlanningSceneConstPtr& planning_scene,
94  std::vector<std::size_t>& added_path_index) const = 0;
95 
96 protected:
98  template <typename T>
99  T getParam(const rclcpp::Node::SharedPtr& node, const rclcpp::Logger& logger, const std::string& parameter_namespace,
100  const std::string& parameter_name, T default_value = {}) const
101  {
102  std::string full_name = parameter_namespace.empty() ? parameter_name : parameter_namespace + "." + parameter_name;
103  T value;
104  if (!node->get_parameter(full_name, value))
105  {
106  RCLCPP_INFO(logger, "Param '%s' was not set. Using default value: %s", full_name.c_str(),
107  std::to_string(default_value).c_str());
108  return default_value;
109  }
110  else
111  {
112  RCLCPP_INFO(logger, "Param '%s' was set to %s", full_name.c_str(), std::to_string(value).c_str());
113  return value;
114  }
115  }
116 };
117 
120 {
121 public:
123  {
124  }
125 
126  void addAdapter(const PlanningRequestAdapterConstPtr& adapter)
127  {
128  adapters_.push_back(adapter);
129  }
130 
131  bool adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
132  const planning_scene::PlanningSceneConstPtr& planning_scene,
135 
136  bool adaptAndPlan(const planning_interface::PlannerManagerPtr& planner,
137  const planning_scene::PlanningSceneConstPtr& planning_scene,
139  std::vector<std::size_t>& added_path_index) const;
140 
141 private:
142  std::vector<PlanningRequestAdapterConstPtr> adapters_;
143 };
144 } // namespace planning_request_adapter
Apply a sequence of adapters to a motion plan.
bool adaptAndPlan(const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const
void addAdapter(const PlanningRequestAdapterConstPtr &adapter)
virtual bool adaptAndPlan(const PlannerFn &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, std::vector< std::size_t > &added_path_index) const =0
Adapt the planning request if needed, call the planner function planner and update the planning respo...
T getParam(const rclcpp::Node::SharedPtr &node, const rclcpp::Logger &logger, const std::string &parameter_namespace, const std::string &parameter_name, T default_value={}) const
Helper param for getting a parameter using a namespace.
virtual std::string getDescription() const
Get a short string that identifies the planning request adapter.
bool adaptAndPlan(const planning_interface::PlannerManagerPtr &planner, const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const
virtual void initialize(const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace)=0
Initialize parameters using the passed Node and parameter namespace. If no initialization is needed,...
std::function< bool(const planning_scene::PlanningSceneConstPtr &, const planning_interface::MotionPlanRequest &, planning_interface::MotionPlanResponse &)> PlannerFn
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
Generic interface to adapting motion planning requests.
MOVEIT_CLASS_FORWARD(PlanningRequestAdapter)
This namespace includes the central class for representing planning contexts.