39 #include <tf2_ros/transform_listener.h>
42 #include <boost/tokenizer.hpp>
49 static const std::string ROBOT_DESCRIPTION =
64 static const char*
const DEFAULT_CAPABILITIES[] = {
65 "move_group/LoadGeometryFromFileService",
66 "move_group/SaveGeometryToFileService",
67 "move_group/GetUrdfService",
68 "move_group/MoveGroupCartesianPathService",
69 "move_group/MoveGroupKinematicsService",
70 "move_group/MoveGroupExecuteTrajectoryAction",
71 "move_group/MoveGroupMoveAction",
72 "move_group/MoveGroupPlanService",
73 "move_group/MoveGroupQueryPlannersService",
74 "move_group/MoveGroupStateValidationService",
75 "move_group/MoveGroupGetPlanningSceneService",
76 "move_group/ApplyPlanningSceneService",
77 "move_group/ClearOctomapService",
87 bool allow_trajectory_execution;
88 moveit_cpp->getNode()->get_parameter_or(
"allow_trajectory_execution", allow_trajectory_execution,
true);
91 std::make_shared<MoveGroupContext>(
moveit_cpp, default_planning_pipeline, allow_trajectory_execution, debug);
94 configureCapabilities();
99 capabilities_.clear();
101 capability_plugin_loader_.reset();
108 if (context_->status())
110 if (capabilities_.empty())
123 RCLCPP_ERROR(
getLogger(),
"No MoveGroup context created. Nothing will work.");
132 void configureCapabilities()
136 capability_plugin_loader_ = std::make_shared<pluginlib::ClassLoader<MoveGroupCapability>>(
137 "moveit_ros_move_group",
"move_group::MoveGroupCapability");
139 catch (pluginlib::PluginlibException& ex)
142 "Exception while creating plugin loader for move_group capabilities: " << ex.what());
146 std::set<std::string> capabilities;
149 for (
const char* capability : DEFAULT_CAPABILITIES)
150 capabilities.insert(capability);
153 std::string capability_plugins;
154 if (context_->moveit_cpp_->getNode()->get_parameter(
"capabilities", capability_plugins))
156 boost::char_separator<char> sep(
" ");
157 boost::tokenizer<boost::char_separator<char>> tok(capability_plugins, sep);
158 capabilities.insert(tok.begin(), tok.end());
162 for (
const auto& pipeline_entry : context_->moveit_cpp_->getPlanningPipelines())
164 const auto& pipeline_name = pipeline_entry.first;
165 std::string pipeline_capabilities;
166 if (context_->moveit_cpp_->getNode()->get_parameter(pipeline_name +
".capabilities", pipeline_capabilities))
168 boost::char_separator<char> sep(
" ");
169 boost::tokenizer<boost::char_separator<char>> tok(pipeline_capabilities, sep);
170 capabilities.insert(tok.begin(), tok.end());
175 if (context_->moveit_cpp_->getNode()->get_parameter(
"disable_capabilities", capability_plugins))
177 boost::char_separator<char> sep(
" ");
178 boost::tokenizer<boost::char_separator<char>> tok(capability_plugins, sep);
179 for (boost::tokenizer<boost::char_separator<char>>::iterator cap_name = tok.begin(); cap_name != tok.end();
181 capabilities.erase(*cap_name);
184 for (
const std::string& capability : capabilities)
189 MoveGroupCapabilityPtr cap = capability_plugin_loader_->createUniqueInstance(capability);
190 cap->setContext(context_);
192 capabilities_.push_back(cap);
194 catch (pluginlib::PluginlibException& ex)
197 "Exception while loading move_group capability '" << capability <<
"': " << ex.what());
201 std::stringstream ss;
204 ss <<
"********************************************************" <<
'\n';
205 ss <<
"* MoveGroup using: " <<
'\n';
206 for (
const MoveGroupCapabilityPtr& cap : capabilities_)
207 ss <<
"* - " << cap->getName() <<
'\n';
208 ss <<
"********************************************************" <<
'\n';
209 RCLCPP_INFO(
getLogger(),
"%s", ss.str().c_str());
212 MoveGroupContextPtr context_;
213 std::shared_ptr<pluginlib::ClassLoader<MoveGroupCapability>> capability_plugin_loader_;
214 std::vector<MoveGroupCapabilityPtr> capabilities_;
218 int main(
int argc,
char** argv)
220 rclcpp::init(argc, argv);
222 rclcpp::NodeOptions opt;
223 opt.allow_undeclared_parameters(
true);
224 opt.automatically_declare_parameters_from_overrides(
true);
225 rclcpp::Node::SharedPtr nh = rclcpp::Node::make_shared(
"move_group", opt);
231 std::vector<std::string> planning_pipeline_configs;
232 if (nh->get_parameter(
"planning_pipelines", planning_pipeline_configs))
234 if (planning_pipeline_configs.empty())
236 RCLCPP_ERROR(nh->get_logger(),
"Failed to read parameter 'move_group.planning_pipelines'");
240 for (
const auto& config : planning_pipeline_configs)
249 std::string default_planning_pipeline;
250 if (nh->get_parameter(
"default_planning_pipeline", default_planning_pipeline))
253 if (std::find(pipeline_names.begin(), pipeline_names.end(), default_planning_pipeline) == pipeline_names.end())
255 RCLCPP_WARN(nh->get_logger(),
256 "MoveGroup launched with ~default_planning_pipeline '%s' not configured in ~planning_pipelines",
257 default_planning_pipeline.c_str());
258 default_planning_pipeline =
"";
261 else if (pipeline_names.size() > 1)
264 RCLCPP_WARN(nh->get_logger(),
265 "MoveGroup launched without ~default_planning_pipeline specifying the namespace for the default "
266 "planning pipeline configuration");
270 if (default_planning_pipeline.empty())
272 if (!pipeline_names.empty())
274 RCLCPP_WARN(nh->get_logger(),
"Using default pipeline '%s'", pipeline_names[0].c_str());
275 default_planning_pipeline = pipeline_names[0];
279 RCLCPP_WARN(nh->get_logger(),
"Falling back to using the the move_group node namespace (deprecated behavior).");
280 default_planning_pipeline =
"move_group";
286 nh->set_parameter(rclcpp::Parameter(
"default_planning_pipeline", default_planning_pipeline));
290 const auto moveit_cpp = std::make_shared<moveit_cpp::MoveItCpp>(nh, moveit_cpp_options);
296 for (
int i = 1; i < argc; ++i)
298 if (strncmp(argv[i],
"--debug", 7) == 0)
307 RCLCPP_INFO(nh->get_logger(),
"MoveGroup debug mode is ON");
311 RCLCPP_INFO(nh->get_logger(),
"MoveGroup debug mode is OFF");
314 rclcpp::executors::MultiThreadedExecutor executor;
318 bool monitor_dynamics;
319 if (nh->get_parameter(
"monitor_dynamics", monitor_dynamics) && monitor_dynamics)
321 RCLCPP_INFO(nh->get_logger(),
"MoveGroup monitors robot dynamics (higher load)");
328 executor.add_node(nh);
334 RCLCPP_ERROR(nh->get_logger(),
"Planning scene not configured");
MoveGroupContextPtr getContext()
MoveGroupExe(const moveit_cpp::MoveItCppPtr &moveit_cpp, const std::string &default_planning_pipeline, bool debug)
#define MOVEIT_CONSOLE_COLOR_BLUE
#define MOVEIT_CONSOLE_COLOR_GREEN
#define MOVEIT_CONSOLE_COLOR_RESET
#define MOVEIT_CONSOLE_COLOR_CYAN
int main(int argc, char **argv)
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
Parameter container for initializing MoveItCpp.
PlanningPipelineOptions planning_pipeline_options
std::vector< std::string > pipeline_names
std::string parent_namespace