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);
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);
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);
73 bool MoveGroupQueryPlannersService::queryInterface(
74 const std::shared_ptr<rmw_request_id_t>& ,
75 const std::shared_ptr<moveit_msgs::srv::QueryPlannerInterfaces::Request>& ,
76 const std::shared_ptr<moveit_msgs::srv::QueryPlannerInterfaces::Response>& res)
78 for (
const auto& planning_pipelines :
context_->moveit_cpp_->getPlanningPipelines())
80 const auto& pipeline_id = planning_pipelines.first;
82 const planning_interface::PlannerManagerPtr& planner_interface =
planning_pipeline->getPlannerManager();
83 if (planner_interface)
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);
97 bool MoveGroupQueryPlannersService::getParams(
const std::shared_ptr<rmw_request_id_t>& ,
98 const std::shared_ptr<moveit_msgs::srv::GetPlannerParams::Request>& req,
99 const std::shared_ptr<moveit_msgs::srv::GetPlannerParams::Response>& res)
105 const planning_interface::PlannerManagerPtr& planner_interface =
planning_pipeline->getPlannerManager();
106 if (planner_interface)
108 std::map<std::string, std::string> config;
112 planning_interface::PlannerConfigurationMap::const_iterator it =
113 configs.find(req->planner_config);
114 if (it != configs.end())
115 config.insert(it->second.config.begin(), it->second.config.end());
117 if (!req->group.empty())
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());
124 for (
const auto& key_value_pair : config)
126 res->params.keys.push_back(key_value_pair.first);
127 res->params.values.push_back(key_value_pair.second);
133 bool MoveGroupQueryPlannersService::setParams(
134 const std::shared_ptr<rmw_request_id_t>& ,
135 const std::shared_ptr<moveit_msgs::srv::SetPlannerParams::Request>& req,
136 const std::shared_ptr<moveit_msgs::srv::SetPlannerParams::Response>& )
138 if (req->params.keys.size() != req->params.values.size())
145 const planning_interface::PlannerManagerPtr& planner_interface =
planning_pipeline->getPlannerManager();
147 if (planner_interface)
150 const std::string config_name =
151 req->group.empty() ? req->planner_config : req->group +
"[" + req->planner_config +
"]";
154 config.
group = req->group;
155 config.
name = config_name;
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];
161 planner_interface->setPlannerConfigurations(configs);
167 #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
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.