57 moveit_msgs::QueryPlannerInterfaces::Response& res)
59 const planning_interface::PlannerManagerPtr& planner_interface =
context_->planning_pipeline_->getPlannerManager();
60 if (planner_interface)
62 std::vector<std::string> algs;
63 planner_interface->getPlanningAlgorithms(algs);
64 moveit_msgs::PlannerInterfaceDescription pi_desc;
65 pi_desc.name = planner_interface->getDescription();
66 planner_interface->getPlanningAlgorithms(pi_desc.planner_ids);
67 res.planner_interfaces.push_back(pi_desc);
73 moveit_msgs::GetPlannerParams::Response& res)
75 const planning_interface::PlannerManagerPtr& planner_interface =
context_->planning_pipeline_->getPlannerManager();
76 if (planner_interface)
78 std::map<std::string, std::string> config;
82 planning_interface::PlannerConfigurationMap::const_iterator it =
83 configs.find(req.planner_config);
84 if (it != configs.end())
85 config.insert(it->second.config.begin(), it->second.config.end());
87 if (!req.group.empty())
89 it = configs.find(req.group +
"[" + req.planner_config +
"]");
90 if (it != configs.end())
91 config.insert(it->second.config.begin(), it->second.config.end());
94 for (std::map<std::string, std::string>::const_iterator it = config.begin(), end = config.end(); it != end; ++it)
96 res.params.keys.push_back(it->first);
97 res.params.values.push_back(it->second);
104 moveit_msgs::SetPlannerParams::Response& res)
106 const planning_interface::PlannerManagerPtr& planner_interface =
context_->planning_pipeline_->getPlannerManager();
107 if (req.params.keys.size() != req.params.values.size())
110 if (planner_interface)
113 std::string config_name = req.group.empty() ? req.planner_config : req.group +
"[" + req.planner_config +
"]";
116 config.
group = req.group;
117 config.
name = config_name;
120 for (
unsigned int i = 0, end = req.params.keys.size(); i < end; ++i)
121 config.
config[req.params.keys[i]] = req.params.values[i];
123 planner_interface->setPlannerConfigurations(configs);
static const std::string SET_PLANNER_PARAMS_SERVICE_NAME
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
std::map< std::string, std::string > config
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
MoveGroupContextPtr context_
static const std::string QUERY_PLANNERS_SERVICE_NAME
static const std::string GET_PLANNER_PARAMS_SERVICE_NAME
ros::NodeHandle root_node_handle_
CLASS_LOADER_REGISTER_CLASS(Dog, Base)