moveit2
The MoveIt Motion Planning Framework for ROS 2.
ompl_interface.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, 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 
41 #include <fstream>
42 #include <moveit/utils/logger.hpp>
43 
44 namespace ompl_interface
45 {
46 namespace
47 {
48 rclcpp::Logger getLogger()
49 {
50  return moveit::getLogger("ompl_interface");
51 }
52 } // namespace
53 
54 OMPLInterface::OMPLInterface(const moveit::core::RobotModelConstPtr& robot_model, const rclcpp::Node::SharedPtr& node,
55  const std::string& parameter_namespace)
56  : node_(node)
57  , parameter_namespace_(parameter_namespace)
58  , robot_model_(robot_model)
59  , constraint_sampler_manager_(std::make_shared<constraint_samplers::ConstraintSamplerManager>())
60  , context_manager_(robot_model, constraint_sampler_manager_)
61  , use_constraints_approximations_(true)
62 {
63  RCLCPP_DEBUG(getLogger(), "Initializing OMPL interface using ROS parameters");
66 }
67 
68 OMPLInterface::OMPLInterface(const moveit::core::RobotModelConstPtr& robot_model,
70  const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace)
71  : node_(node)
72  , parameter_namespace_(parameter_namespace)
73  , robot_model_(robot_model)
74  , constraint_sampler_manager_(std::make_shared<constraint_samplers::ConstraintSamplerManager>())
75  , context_manager_(robot_model, constraint_sampler_manager_)
76  , use_constraints_approximations_(true)
77 {
78  RCLCPP_DEBUG(getLogger(), "Initializing OMPL interface using specified configuration");
79  setPlannerConfigurations(pconfig);
81 }
82 
84 
86 {
88 
89  // construct default configurations for planning groups that don't have configs already passed in
90  for (const moveit::core::JointModelGroup* group : robot_model_->getJointModelGroups())
91  {
92  if (pconfig.find(group->getName()) == pconfig.end())
93  {
95  empty.name = empty.group = group->getName();
96  pconfig2[empty.name] = empty;
97  }
98  }
99 
101 }
102 
103 ModelBasedPlanningContextPtr
104 OMPLInterface::getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
105  const planning_interface::MotionPlanRequest& req) const
106 {
107  moveit_msgs::msg::MoveItErrorCodes dummy;
108  return getPlanningContext(planning_scene, req, dummy);
109 }
110 
111 ModelBasedPlanningContextPtr
112 OMPLInterface::getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene,
114  moveit_msgs::msg::MoveItErrorCodes& error_code) const
115 {
116  ModelBasedPlanningContextPtr ctx =
118  return ctx;
119 }
120 
122 {
123  constraint_sampler_manager_loader_ =
124  std::make_shared<constraint_sampler_manager_loader::ConstraintSamplerManagerLoader>(node_,
126 }
127 
128 bool OMPLInterface::loadPlannerConfiguration(const std::string& group_name, const std::string& planner_id,
129  const std::map<std::string, std::string>& group_params,
131 {
132  rcl_interfaces::msg::ListParametersResult planner_params_result =
133  node_->list_parameters({ parameter_namespace_ + ".planner_configs." + planner_id }, 2);
134 
135  if (planner_params_result.names.empty())
136  {
137  RCLCPP_ERROR(getLogger(), "Could not find the planner configuration '%s' on the param server", planner_id.c_str());
138  return false;
139  }
140 
141  planner_config.name = group_name + "[" + planner_id + "]";
142  planner_config.group = group_name;
143 
144  // default to specified parameters of the group (overridden by configuration specific parameters)
145  planner_config.config = group_params;
146 
147  // read parameters specific for this configuration
148  for (const auto& planner_param : planner_params_result.names)
149  {
150  const rclcpp::Parameter param = node_->get_parameter(planner_param);
151  auto param_name = planner_param.substr(planner_param.find(planner_id) + planner_id.size() + 1);
152  planner_config.config[param_name] = param.value_to_string();
153  }
154 
155  return true;
156 }
157 
159 {
160  // read the planning configuration for each group
162  pconfig.clear();
163 
164  for (const std::string& group_name : robot_model_->getJointModelGroupNames())
165  {
166  // the set of planning parameters that can be specific for the group (inherited by configurations of that group)
167  // with their expected parameter type
168  static const std::pair<std::string, rclcpp::ParameterType> KNOWN_GROUP_PARAMS[] = {
169  { "projection_evaluator", rclcpp::ParameterType::PARAMETER_STRING },
170  { "longest_valid_segment_fraction", rclcpp::ParameterType::PARAMETER_DOUBLE },
171  { "enforce_joint_model_state_space", rclcpp::ParameterType::PARAMETER_BOOL },
172  { "enforce_constrained_state_space", rclcpp::ParameterType::PARAMETER_BOOL }
173  };
174 
175  const std::string group_name_param = parameter_namespace_ + "." + group_name;
176 
177  // get parameters specific for the robot planning group
178  std::map<std::string, std::string> specific_group_params;
179  for (const auto& [name, type] : KNOWN_GROUP_PARAMS)
180  {
181  std::string param_name{ group_name_param };
182  param_name += ".";
183  param_name += name;
184  if (node_->has_parameter(param_name))
185  {
186  const rclcpp::Parameter parameter = node_->get_parameter(param_name);
187  if (parameter.get_type() != type)
188  {
189  RCLCPP_ERROR_STREAM(getLogger(), "Invalid type for parameter '"
190  << name << "' expected [" << rclcpp::to_string(type) << "] got ["
191  << rclcpp::to_string(parameter.get_type()) << ']');
192  continue;
193  }
194  if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_STRING)
195  {
196  specific_group_params[name] = parameter.as_string();
197  }
198  else if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_DOUBLE)
199  {
200  specific_group_params[name] = moveit::core::toString(parameter.as_double());
201  }
202  else if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_INTEGER)
203  {
204  specific_group_params[name] = std::to_string(parameter.as_int());
205  }
206  else if (parameter.get_type() == rclcpp::ParameterType::PARAMETER_BOOL)
207  {
208  specific_group_params[name] = std::to_string(parameter.as_bool());
209  }
210  }
211  }
212 
213  // add default planner configuration
215  std::string default_planner_id;
216  if (node_->get_parameter(group_name_param + ".default_planner_config", default_planner_id))
217  {
218  if (!loadPlannerConfiguration(group_name, default_planner_id, specific_group_params, default_pc))
219  {
220  default_planner_id = "";
221  }
222  }
223 
224  if (default_planner_id.empty())
225  {
226  default_pc.group = group_name;
227  default_pc.config = specific_group_params;
228  default_pc.config["type"] = "geometric::RRTConnect";
229  }
230 
231  default_pc.name = group_name; // this is the name of the default config
232  pconfig[default_pc.name] = default_pc;
233 
234  // get parameters specific to each planner type
235  std::vector<std::string> config_names;
236  if (node_->get_parameter(group_name_param + ".planner_configs", config_names))
237  {
238  for (const auto& planner_id : config_names)
239  {
241  if (loadPlannerConfiguration(group_name, planner_id, specific_group_params, pc))
242  {
243  pconfig[pc.name] = pc;
244  }
245  }
246  }
247  }
248 
249  for (const auto& [name, config_settings] : pconfig)
250  {
251  RCLCPP_DEBUG(getLogger(), "Parameters for configuration '%s'", name.c_str());
252 
253  for (const auto& [param_name, param_value] : config_settings.config)
254  {
255  RCLCPP_DEBUG_STREAM(getLogger(), " - " << param_name << " = " << param_value);
256  }
257  }
258 
259  setPlannerConfigurations(pconfig);
260 }
261 
263 {
264  RCLCPP_INFO(getLogger(), "OMPL ROS interface is running.");
265 }
266 } // namespace ompl_interface
rclcpp::Node::SharedPtr node_
void printStatus()
Print the status of this node.
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
void loadConstraintSamplers()
Load the additional plugins for sampling constraints.
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
PlanningContextManager context_manager_
bool loadPlannerConfiguration(const std::string &group_name, const std::string &planner_id, const std::map< std::string, std::string > &group_params, planning_interface::PlannerConfigurationSettings &planner_config)
Load planner configurations for specified group into planner_config.
moveit::core::RobotModelConstPtr robot_model_
The kinematic model for which motion plans are computed.
const std::string parameter_namespace_
The ROS node.
ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req) const
void loadPlannerConfigurations()
Configure the planners.
OMPLInterface(const moveit::core::RobotModelConstPtr &robot_model, const rclcpp::Node::SharedPtr &node, const std::string &parameter_namespace)
Initialize OMPL-based planning for a particular robot model. ROS configuration is read from the speci...
ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code, const rclcpp::Node::SharedPtr &node, bool use_constraints_approximations) const
Returns a planning context to OMPLInterface, which in turn passes it to OMPLPlannerManager.
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
locale-agnostic conversion functions from floating point numbers to strings
The constraint samplers namespace contains a number of methods for generating samples based on a cons...
std::string toString(double d)
Convert a double to std::string using the classic C locale.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
The MoveIt interface to OMPL.
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.
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.