moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
42
43namespace move_group
44{
45namespace
46{
47rclcpp::Logger getLogger()
48{
49 return moveit::getLogger("moveit.ros.move_group.query_planners_service_capability");
50}
51} // namespace
55
57{
58 query_service_ = context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::QueryPlannerInterfaces>(
59 QUERY_PLANNERS_SERVICE_NAME,
60 [this](const std::shared_ptr<moveit_msgs::srv::QueryPlannerInterfaces::Request>& req,
61 const std::shared_ptr<moveit_msgs::srv::QueryPlannerInterfaces::Response>& res) {
62 queryInterface(req, res);
63 });
64
65 get_service_ = context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::GetPlannerParams>(
66 GET_PLANNER_PARAMS_SERVICE_NAME,
67 [this](const std::shared_ptr<moveit_msgs::srv::GetPlannerParams::Request>& req,
68 const std::shared_ptr<moveit_msgs::srv::GetPlannerParams::Response>& res) { getParams(req, res); });
69
70 set_service_ = context_->moveit_cpp_->getNode()->create_service<moveit_msgs::srv::SetPlannerParams>(
71 SET_PLANNER_PARAMS_SERVICE_NAME,
72 [this](const std::shared_ptr<moveit_msgs::srv::SetPlannerParams::Request>& req,
73 const std::shared_ptr<moveit_msgs::srv::SetPlannerParams::Response>& res) { setParams(req, res); });
74}
75
76void MoveGroupQueryPlannersService::queryInterface(
77 const std::shared_ptr<moveit_msgs::srv::QueryPlannerInterfaces::Request>& /* unused */,
78 const std::shared_ptr<moveit_msgs::srv::QueryPlannerInterfaces::Response>& res)
79{
80 for (const auto& planning_pipelines : context_->moveit_cpp_->getPlanningPipelines())
81 {
82 const auto& planning_pipeline = planning_pipelines.second;
83
84 // TODO(sjahr): Update for multiple planner plugins
85 const auto& planner_plugin_names = planning_pipeline->getPlannerPluginNames();
86 if (planner_plugin_names.empty())
87 {
88 RCLCPP_ERROR(getLogger(), "Pipeline '%s' does not have any planner plugins.", planning_pipelines.first.c_str());
89 return;
90 }
91 const auto planner_interface = planning_pipeline->getPlannerManager(planner_plugin_names.at(0));
92 if (!planner_interface)
93 {
94 RCLCPP_ERROR(getLogger(), "Requesting planner '%s' from '%s' returned a null pointer.",
95 planner_plugin_names.at(0).c_str(), planning_pipelines.first.c_str());
96 }
97 std::vector<std::string> algs;
98 planner_interface->getPlanningAlgorithms(algs);
99 moveit_msgs::msg::PlannerInterfaceDescription pi_desc;
100 pi_desc.name = planner_interface->getDescription();
101 pi_desc.pipeline_id = planning_pipelines.first;
102 planner_interface->getPlanningAlgorithms(pi_desc.planner_ids);
103 res->planner_interfaces.push_back(pi_desc);
104 }
105}
106
107void MoveGroupQueryPlannersService::getParams(const std::shared_ptr<moveit_msgs::srv::GetPlannerParams::Request>& req,
108 const std::shared_ptr<moveit_msgs::srv::GetPlannerParams::Response>& res)
109{
110 const planning_pipeline::PlanningPipelinePtr planning_pipeline = resolvePlanningPipeline(req->pipeline_id);
112 {
113 RCLCPP_ERROR(getLogger(), "Pipeline '%s' does not exist.", req->pipeline_id.c_str());
114 return;
115 }
116
117 // TODO(sjahr): Update for multiple planner plugins
118 const auto& planner_plugin_names = planning_pipeline->getPlannerPluginNames();
119 if (planner_plugin_names.empty())
120 {
121 RCLCPP_ERROR(getLogger(), "Pipeline '%s' does not have any planner plugins.", req->pipeline_id.c_str());
122 return;
123 }
124 const auto planner_interface = planning_pipeline->getPlannerManager(planner_plugin_names.at(0));
125 if (!planner_interface)
126 {
127 RCLCPP_ERROR(getLogger(), "Requesting planner '%s' from '%s' returned a null pointer.",
128 planner_plugin_names.at(0).c_str(), req->pipeline_id.c_str());
129 }
130 std::map<std::string, std::string> config;
131
132 const planning_interface::PlannerConfigurationMap& configs = planner_interface->getPlannerConfigurations();
133
134 planning_interface::PlannerConfigurationMap::const_iterator it =
135 configs.find(req->planner_config); // fetch default params first
136 if (it != configs.end())
137 {
138 config.insert(it->second.config.begin(), it->second.config.end());
139 }
140
141 if (!req->group.empty())
142 { // merge in group-specific params
143 it = configs.find(req->group + "[" + req->planner_config + "]");
144 if (it != configs.end())
145 {
146 config.insert(it->second.config.begin(), it->second.config.end());
147 }
148 }
149
150 for (const auto& key_value_pair : config)
151 {
152 res->params.keys.push_back(key_value_pair.first);
153 res->params.values.push_back(key_value_pair.second);
154 }
155}
156
157void MoveGroupQueryPlannersService::setParams(
158 const std::shared_ptr<moveit_msgs::srv::SetPlannerParams::Request>& req,
159 const std::shared_ptr<moveit_msgs::srv::SetPlannerParams::Response>& /*res*/)
160{
161 if (req->params.keys.size() != req->params.values.size())
162 {
163 RCLCPP_ERROR(getLogger(), "Number of parameter names does not match the number of parameters");
164 return;
165 }
166
167 const planning_pipeline::PlanningPipelinePtr planning_pipeline = resolvePlanningPipeline(req->pipeline_id);
169 {
170 RCLCPP_ERROR(getLogger(), "Pipeline '%s' does not exist.", req->pipeline_id.c_str());
171 return;
172 }
173
174 // TODO(sjahr): Update for multiple planner plugins
175 const auto& planner_plugin_names = planning_pipeline->getPlannerPluginNames();
176 if (planner_plugin_names.empty())
177 {
178 RCLCPP_ERROR(getLogger(), "Pipeline '%s' does not have any planner plugins.", req->pipeline_id.c_str());
179 return;
180 }
181 auto planner_interface = planning_pipeline->getPlannerManager(planner_plugin_names.at(0));
182 if (!planner_interface)
183 {
184 RCLCPP_ERROR(getLogger(), "Requesting planner '%s' from '%s' returned a null pointer.",
185 planner_plugin_names.at(0).c_str(), req->pipeline_id.c_str());
186 return;
187 }
188
189 planning_interface::PlannerConfigurationMap configs = planner_interface->getPlannerConfigurations();
190 const std::string config_name =
191 req->group.empty() ? req->planner_config : req->group + "[" + req->planner_config + "]";
192
193 planning_interface::PlannerConfigurationSettings& config = configs[config_name];
194 config.group = req->group;
195 config.name = config_name;
196 if (req->replace)
197 {
198 config.config.clear();
199 }
200 for (unsigned int i = 0, end = req->params.keys.size(); i < end; ++i)
201 {
202 config.config[req->params.keys.at(i)] = req->params.values.at(i);
203 }
204
205 planner_interface->setPlannerConfigurations(configs);
206}
207} // namespace move_group
208
209#include <pluginlib/class_list_macros.hpp>
210
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline(const std::string &pipeline_id) const
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
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.