moveit2
The MoveIt Motion Planning Framework for ROS 2.
query_planners_service_capability.cpp
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, Robert Haschke */
36 
41 
42 namespace move_group
43 {
45 {
46 }
47 
49 {
50  query_service_ = context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::QueryPlannerInterfaces>(
51  QUERY_PLANNERS_SERVICE_NAME,
52  [this](const std::shared_ptr<rmw_request_id_t>& request_header,
53  const std::shared_ptr<moveit_msgs::srv::QueryPlannerInterfaces::Request>& req,
54  const std::shared_ptr<moveit_msgs::srv::QueryPlannerInterfaces::Response>& res) {
55  return queryInterface(request_header, req, res);
56  });
57 
58  get_service_ = context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetPlannerParams>(
59  GET_PLANNER_PARAMS_SERVICE_NAME, [this](const std::shared_ptr<rmw_request_id_t>& request_header,
60  const std::shared_ptr<moveit_msgs::srv::GetPlannerParams::Request>& req,
61  const std::shared_ptr<moveit_msgs::srv::GetPlannerParams::Response>& res) {
62  return getParams(request_header, req, res);
63  });
64 
65  set_service_ = context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::SetPlannerParams>(
66  SET_PLANNER_PARAMS_SERVICE_NAME, [this](const std::shared_ptr<rmw_request_id_t>& request_header,
67  const std::shared_ptr<moveit_msgs::srv::SetPlannerParams::Request>& req,
68  const std::shared_ptr<moveit_msgs::srv::SetPlannerParams::Response>& res) {
69  return setParams(request_header, req, res);
70  });
71 }
72 
73 bool MoveGroupQueryPlannersService::queryInterface(
74  const std::shared_ptr<rmw_request_id_t>& /* unused */,
75  const std::shared_ptr<moveit_msgs::srv::QueryPlannerInterfaces::Request>& /*req*/,
76  const std::shared_ptr<moveit_msgs::srv::QueryPlannerInterfaces::Response>& res)
77 {
78  for (const auto& planning_pipelines : context_->moveit_cpp_->getPlanningPipelines())
79  {
80  const auto& pipeline_id = planning_pipelines.first;
81  const auto& planning_pipeline = planning_pipelines.second;
82  const planning_interface::PlannerManagerPtr& planner_interface = planning_pipeline->getPlannerManager();
83  if (planner_interface)
84  {
85  std::vector<std::string> algs;
86  planner_interface->getPlanningAlgorithms(algs);
87  moveit_msgs::msg::PlannerInterfaceDescription pi_desc;
88  pi_desc.name = planner_interface->getDescription();
89  pi_desc.pipeline_id = pipeline_id;
90  planner_interface->getPlanningAlgorithms(pi_desc.planner_ids);
91  res->planner_interfaces.push_back(pi_desc);
92  }
93  }
94  return true;
95 }
96 
97 bool MoveGroupQueryPlannersService::getParams(const std::shared_ptr<rmw_request_id_t>& /* unused */,
98  const std::shared_ptr<moveit_msgs::srv::GetPlannerParams::Request>& req,
99  const std::shared_ptr<moveit_msgs::srv::GetPlannerParams::Response>& res)
100 {
101  const planning_pipeline::PlanningPipelinePtr planning_pipeline = resolvePlanningPipeline(req->pipeline_id);
102  if (!planning_pipeline)
103  return false;
104 
105  const planning_interface::PlannerManagerPtr& planner_interface = planning_pipeline->getPlannerManager();
106  if (planner_interface)
107  {
108  std::map<std::string, std::string> config;
109 
110  const planning_interface::PlannerConfigurationMap& configs = planner_interface->getPlannerConfigurations();
111 
112  planning_interface::PlannerConfigurationMap::const_iterator it =
113  configs.find(req->planner_config); // fetch default params first
114  if (it != configs.end())
115  config.insert(it->second.config.begin(), it->second.config.end());
116 
117  if (!req->group.empty())
118  { // merge in group-specific params
119  it = configs.find(req->group + "[" + req->planner_config + "]");
120  if (it != configs.end())
121  config.insert(it->second.config.begin(), it->second.config.end());
122  }
123 
124  for (const auto& key_value_pair : config)
125  {
126  res->params.keys.push_back(key_value_pair.first);
127  res->params.values.push_back(key_value_pair.second);
128  }
129  }
130  return true;
131 }
132 
133 bool MoveGroupQueryPlannersService::setParams(
134  const std::shared_ptr<rmw_request_id_t>& /* unused */,
135  const std::shared_ptr<moveit_msgs::srv::SetPlannerParams::Request>& req,
136  const std::shared_ptr<moveit_msgs::srv::SetPlannerParams::Response>& /*res*/)
137 {
138  if (req->params.keys.size() != req->params.values.size())
139  return false;
140 
141  const planning_pipeline::PlanningPipelinePtr planning_pipeline = resolvePlanningPipeline(req->pipeline_id);
142  if (!planning_pipeline)
143  return false;
144 
145  const planning_interface::PlannerManagerPtr& planner_interface = planning_pipeline->getPlannerManager();
146 
147  if (planner_interface)
148  {
149  planning_interface::PlannerConfigurationMap configs = planner_interface->getPlannerConfigurations();
150  const std::string config_name =
151  req->group.empty() ? req->planner_config : req->group + "[" + req->planner_config + "]";
152 
153  planning_interface::PlannerConfigurationSettings& config = configs[config_name];
154  config.group = req->group;
155  config.name = config_name;
156  if (req->replace)
157  config.config.clear();
158  for (unsigned int i = 0, end = req->params.keys.size(); i < end; ++i)
159  config.config[req->params.keys[i]] = req->params.values[i];
160 
161  planner_interface->setPlannerConfigurations(configs);
162  }
163  return true;
164 }
165 } // namespace move_group
166 
167 #include <pluginlib/class_list_macros.hpp>
168 
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline(const std::string &pipeline_id) const
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
Planning pipeline.
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.