97 bool allow_trajectory_execution;
98 moveit_cpp->getNode()->get_parameter_or(
"allow_trajectory_execution", allow_trajectory_execution,
true);
101 std::make_shared<MoveGroupContext>(
moveit_cpp, default_planning_pipeline, allow_trajectory_execution, debug);
104 configureCapabilities();
109 capabilities_.clear();
111 capability_plugin_loader_.reset();
118 if (context_->status())
120 if (capabilities_.empty())
133 RCLCPP_ERROR(getLogger(),
"No MoveGroup context created. Nothing will work.");
142 void configureCapabilities()
146 capability_plugin_loader_ = std::make_shared<pluginlib::ClassLoader<MoveGroupCapability>>(
147 "moveit_ros_move_group",
"move_group::MoveGroupCapability");
149 catch (pluginlib::PluginlibException& ex)
151 RCLCPP_FATAL_STREAM(getLogger(),
152 "Exception while creating plugin loader for move_group capabilities: " << ex.what());
156 std::set<std::string> capabilities;
159 for (
const char* capability : DEFAULT_CAPABILITIES)
160 capabilities.insert(capability);
163 std::string capability_plugins;
164 if (context_->moveit_cpp_->getNode()->get_parameter(
"capabilities", capability_plugins))
166 boost::char_separator<char> sep(
" ");
167 boost::tokenizer<boost::char_separator<char>> tok(capability_plugins, sep);
168 capabilities.insert(tok.begin(), tok.end());
172 for (
const auto& pipeline_entry : context_->moveit_cpp_->getPlanningPipelines())
174 const auto& pipeline_name = pipeline_entry.first;
175 std::string pipeline_capabilities;
176 if (context_->moveit_cpp_->getNode()->get_parameter(pipeline_name +
".capabilities", pipeline_capabilities))
178 boost::char_separator<char> sep(
" ");
179 boost::tokenizer<boost::char_separator<char>> tok(pipeline_capabilities, sep);
180 capabilities.insert(tok.begin(), tok.end());
185 if (context_->moveit_cpp_->getNode()->get_parameter(
"disable_capabilities", capability_plugins))
187 boost::char_separator<char> sep(
" ");
188 boost::tokenizer<boost::char_separator<char>> tok(capability_plugins, sep);
189 for (boost::tokenizer<boost::char_separator<char>>::iterator cap_name = tok.begin(); cap_name != tok.end();
191 capabilities.erase(*cap_name);
194 for (
const std::string& capability : capabilities)
199 MoveGroupCapabilityPtr cap = capability_plugin_loader_->createUniqueInstance(capability);
200 cap->setContext(context_);
202 capabilities_.push_back(cap);
204 catch (pluginlib::PluginlibException& ex)
207 "Exception while loading move_group capability '" << capability <<
"': " << ex.what());
211 std::stringstream ss;
214 ss <<
"********************************************************" <<
'\n';
215 ss <<
"* MoveGroup using: " <<
'\n';
216 for (
const MoveGroupCapabilityPtr& cap : capabilities_)
217 ss <<
"* - " << cap->getName() <<
'\n';
218 ss <<
"********************************************************" <<
'\n';
219 RCLCPP_INFO(
getLogger(),
"%s", ss.str().c_str());
222 MoveGroupContextPtr context_;
223 std::shared_ptr<pluginlib::ClassLoader<MoveGroupCapability>> capability_plugin_loader_;
224 std::vector<MoveGroupCapabilityPtr> capabilities_;
230 rclcpp::init(argc, argv);
232 rclcpp::NodeOptions opt;
233 opt.allow_undeclared_parameters(
true);
234 opt.automatically_declare_parameters_from_overrides(
true);
235 rclcpp::Node::SharedPtr nh = rclcpp::Node::make_shared(
"move_group", opt);
241 std::vector<std::string> planning_pipeline_configs;
242 if (nh->get_parameter(
"planning_pipelines", planning_pipeline_configs))
244 if (planning_pipeline_configs.empty())
246 RCLCPP_ERROR(nh->get_logger(),
"Failed to read parameter 'move_group.planning_pipelines'");
250 for (
const auto& config : planning_pipeline_configs)
259 std::string default_planning_pipeline;
260 if (nh->get_parameter(
"default_planning_pipeline", default_planning_pipeline))
263 if (std::find(pipeline_names.begin(), pipeline_names.end(), default_planning_pipeline) == pipeline_names.end())
265 RCLCPP_WARN(nh->get_logger(),
266 "MoveGroup launched with ~default_planning_pipeline '%s' not configured in ~planning_pipelines",
267 default_planning_pipeline.c_str());
268 default_planning_pipeline =
"";
271 else if (pipeline_names.size() > 1)
274 RCLCPP_WARN(nh->get_logger(),
275 "MoveGroup launched without ~default_planning_pipeline specifying the namespace for the default "
276 "planning pipeline configuration");
280 if (default_planning_pipeline.empty())
282 if (!pipeline_names.empty())
284 RCLCPP_WARN(nh->get_logger(),
"Using default pipeline '%s'", pipeline_names[0].c_str());
285 default_planning_pipeline = pipeline_names[0];
289 RCLCPP_WARN(nh->get_logger(),
"Falling back to using the the move_group node namespace (deprecated behavior).");
290 default_planning_pipeline =
"move_group";
296 nh->set_parameter(rclcpp::Parameter(
"default_planning_pipeline", default_planning_pipeline));
300 const auto moveit_cpp = std::make_shared<moveit_cpp::MoveItCpp>(nh, moveit_cpp_options);
306 for (
int i = 1; i < argc; ++i)
308 if (strncmp(argv[i],
"--debug", 7) == 0)
317 RCLCPP_INFO(nh->get_logger(),
"MoveGroup debug mode is ON");
321 RCLCPP_INFO(nh->get_logger(),
"MoveGroup debug mode is OFF");
324 rclcpp::executors::MultiThreadedExecutor executor;
328 bool monitor_dynamics;
329 if (nh->get_parameter(
"monitor_dynamics", monitor_dynamics) && monitor_dynamics)
331 RCLCPP_INFO(nh->get_logger(),
"MoveGroup monitors robot dynamics (higher load)");
338 executor.add_node(nh);
344 RCLCPP_ERROR(nh->get_logger(),
"Planning scene not configured");