49 return moveit::getLogger(
"moveit.ros.move_group.query_planners_service_capability");
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);
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); });
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); });
76void MoveGroupQueryPlannersService::queryInterface(
77 const std::shared_ptr<moveit_msgs::srv::QueryPlannerInterfaces::Request>& ,
78 const std::shared_ptr<moveit_msgs::srv::QueryPlannerInterfaces::Response>& res)
80 for (
const auto& planning_pipelines :
context_->moveit_cpp_->getPlanningPipelines())
86 if (planner_plugin_names.empty())
88 RCLCPP_ERROR(getLogger(),
"Pipeline '%s' does not have any planner plugins.", planning_pipelines.first.c_str());
91 const auto planner_interface =
planning_pipeline->getPlannerManager(planner_plugin_names.at(0));
92 if (!planner_interface)
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());
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);
107void MoveGroupQueryPlannersService::getParams(
const std::shared_ptr<moveit_msgs::srv::GetPlannerParams::Request>& req,
108 const std::shared_ptr<moveit_msgs::srv::GetPlannerParams::Response>& res)
113 RCLCPP_ERROR(
getLogger(),
"Pipeline '%s' does not exist.", req->pipeline_id.c_str());
119 if (planner_plugin_names.empty())
121 RCLCPP_ERROR(
getLogger(),
"Pipeline '%s' does not have any planner plugins.", req->pipeline_id.c_str());
124 const auto planner_interface =
planning_pipeline->getPlannerManager(planner_plugin_names.at(0));
125 if (!planner_interface)
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());
130 std::map<std::string, std::string> config;
134 planning_interface::PlannerConfigurationMap::const_iterator it =
135 configs.find(req->planner_config);
136 if (it != configs.end())
138 config.insert(it->second.config.begin(), it->second.config.end());
141 if (!req->group.empty())
143 it = configs.find(req->group +
"[" + req->planner_config +
"]");
144 if (it != configs.end())
146 config.insert(it->second.config.begin(), it->second.config.end());
150 for (
const auto& key_value_pair : config)
152 res->params.keys.push_back(key_value_pair.first);
153 res->params.values.push_back(key_value_pair.second);
157void MoveGroupQueryPlannersService::setParams(
158 const std::shared_ptr<moveit_msgs::srv::SetPlannerParams::Request>& req,
159 const std::shared_ptr<moveit_msgs::srv::SetPlannerParams::Response>& )
161 if (req->params.keys.size() != req->params.values.size())
163 RCLCPP_ERROR(
getLogger(),
"Number of parameter names does not match the number of parameters");
170 RCLCPP_ERROR(
getLogger(),
"Pipeline '%s' does not exist.", req->pipeline_id.c_str());
176 if (planner_plugin_names.empty())
178 RCLCPP_ERROR(
getLogger(),
"Pipeline '%s' does not have any planner plugins.", req->pipeline_id.c_str());
181 auto planner_interface =
planning_pipeline->getPlannerManager(planner_plugin_names.at(0));
182 if (!planner_interface)
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());
190 const std::string config_name =
191 req->group.empty() ? req->planner_config : req->group +
"[" + req->planner_config +
"]";
194 config.
group = req->group;
195 config.
name = config_name;
200 for (
unsigned int i = 0, end = req->params.keys.size(); i < end; ++i)
202 config.
config[req->params.keys.at(i)] = req->params.values.at(i);
205 planner_interface->setPlannerConfigurations(configs);
209#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
MoveGroupContextPtr context_
planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline(const std::string &pipeline_id) const
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
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.