moveit2
The MoveIt Motion Planning Framework for ROS 2.
move_group.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
39 #include <tf2_ros/transform_listener.h>
42 #include <boost/tokenizer.hpp>
45 #include <memory>
46 #include <set>
47 #include <moveit/utils/logger.hpp>
48 
49 static const std::string ROBOT_DESCRIPTION =
50  "robot_description"; // name of the robot description (a param name, so it can be changed externally)
51 
52 namespace move_group
53 {
54 namespace
55 {
56 rclcpp::Logger getLogger()
57 {
58  return moveit::getLogger("moveit.ros.move_group.executable");
59 }
60 } // namespace
61 
62 // These capabilities are loaded unless listed in disable_capabilities
63 // clang-format off
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",
78 };
79 // clang-format on
80 
82 {
83 public:
84  MoveGroupExe(const moveit_cpp::MoveItCppPtr& moveit_cpp, const std::string& default_planning_pipeline, bool debug)
85  {
86  // if the user wants to be able to disable execution of paths, they can just set this ROS param to false
87  bool allow_trajectory_execution;
88  moveit_cpp->getNode()->get_parameter_or("allow_trajectory_execution", allow_trajectory_execution, true);
89 
90  context_ =
91  std::make_shared<MoveGroupContext>(moveit_cpp, default_planning_pipeline, allow_trajectory_execution, debug);
92 
93  // start the capabilities
94  configureCapabilities();
95  }
96 
98  {
99  capabilities_.clear();
100  context_.reset();
101  capability_plugin_loader_.reset();
102  }
103 
104  void status()
105  {
106  if (context_)
107  {
108  if (context_->status())
109  {
110  if (capabilities_.empty())
111  {
112  printf("\n" MOVEIT_CONSOLE_COLOR_BLUE
113  "move_group is running but no capabilities are loaded." MOVEIT_CONSOLE_COLOR_RESET "\n\n");
114  }
115  else
116  {
117  printf("\n" MOVEIT_CONSOLE_COLOR_GREEN "You can start planning now!" MOVEIT_CONSOLE_COLOR_RESET "\n\n");
118  }
119  fflush(stdout);
120  }
121  }
122  else
123  RCLCPP_ERROR(getLogger(), "No MoveGroup context created. Nothing will work.");
124  }
125 
126  MoveGroupContextPtr getContext()
127  {
128  return context_;
129  }
130 
131 private:
132  void configureCapabilities()
133  {
134  try
135  {
136  capability_plugin_loader_ = std::make_shared<pluginlib::ClassLoader<MoveGroupCapability>>(
137  "moveit_ros_move_group", "move_group::MoveGroupCapability");
138  }
139  catch (pluginlib::PluginlibException& ex)
140  {
141  RCLCPP_FATAL_STREAM(getLogger(),
142  "Exception while creating plugin loader for move_group capabilities: " << ex.what());
143  return;
144  }
145 
146  std::set<std::string> capabilities;
147 
148  // add default capabilities
149  for (const char* capability : DEFAULT_CAPABILITIES)
150  capabilities.insert(capability);
151 
152  // add capabilities listed in ROS parameter
153  std::string capability_plugins;
154  if (context_->moveit_cpp_->getNode()->get_parameter("capabilities", capability_plugins))
155  {
156  boost::char_separator<char> sep(" ");
157  boost::tokenizer<boost::char_separator<char>> tok(capability_plugins, sep);
158  capabilities.insert(tok.begin(), tok.end());
159  }
160 
161  // add capabilities configured for planning pipelines
162  for (const auto& pipeline_entry : context_->moveit_cpp_->getPlanningPipelines())
163  {
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))
167  {
168  boost::char_separator<char> sep(" ");
169  boost::tokenizer<boost::char_separator<char>> tok(pipeline_capabilities, sep);
170  capabilities.insert(tok.begin(), tok.end());
171  }
172  }
173 
174  // drop capabilities that have been explicitly disabled
175  if (context_->moveit_cpp_->getNode()->get_parameter("disable_capabilities", capability_plugins))
176  {
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();
180  ++cap_name)
181  capabilities.erase(*cap_name);
182  }
183 
184  for (const std::string& capability : capabilities)
185  {
186  try
187  {
188  printf(MOVEIT_CONSOLE_COLOR_CYAN "Loading '%s'..." MOVEIT_CONSOLE_COLOR_RESET "\n", capability.c_str());
189  MoveGroupCapabilityPtr cap = capability_plugin_loader_->createUniqueInstance(capability);
190  cap->setContext(context_);
191  cap->initialize();
192  capabilities_.push_back(cap);
193  }
194  catch (pluginlib::PluginlibException& ex)
195  {
196  RCLCPP_ERROR_STREAM(getLogger(),
197  "Exception while loading move_group capability '" << capability << "': " << ex.what());
198  }
199  }
200 
201  std::stringstream ss;
202  ss << '\n';
203  ss << '\n';
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());
210  }
211 
212  MoveGroupContextPtr context_;
213  std::shared_ptr<pluginlib::ClassLoader<MoveGroupCapability>> capability_plugin_loader_;
214  std::vector<MoveGroupCapabilityPtr> capabilities_;
215 };
216 } // namespace move_group
217 
218 int main(int argc, char** argv)
219 {
220  rclcpp::init(argc, argv);
221 
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);
226  moveit::setNodeLoggerName(nh->get_name());
227  moveit_cpp::MoveItCpp::Options moveit_cpp_options(nh);
228 
229  // Prepare PlanningPipelineOptions
230  moveit_cpp_options.planning_pipeline_options.parent_namespace = nh->get_effective_namespace() + ".planning_pipelines";
231  std::vector<std::string> planning_pipeline_configs;
232  if (nh->get_parameter("planning_pipelines", planning_pipeline_configs))
233  {
234  if (planning_pipeline_configs.empty())
235  {
236  RCLCPP_ERROR(nh->get_logger(), "Failed to read parameter 'move_group.planning_pipelines'");
237  }
238  else
239  {
240  for (const auto& config : planning_pipeline_configs)
241  {
242  moveit_cpp_options.planning_pipeline_options.pipeline_names.push_back(config);
243  }
244  }
245  }
246 
247  // Retrieve default planning pipeline
248  auto& pipeline_names = moveit_cpp_options.planning_pipeline_options.pipeline_names;
249  std::string default_planning_pipeline;
250  if (nh->get_parameter("default_planning_pipeline", default_planning_pipeline))
251  {
252  // Ignore default_planning_pipeline if there is no matching entry in pipeline_names
253  if (std::find(pipeline_names.begin(), pipeline_names.end(), default_planning_pipeline) == pipeline_names.end())
254  {
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 = ""; // reset invalid pipeline id
259  }
260  }
261  else if (pipeline_names.size() > 1) // only warn if there are multiple pipelines to choose from
262  {
263  // Handle deprecated move_group.launch
264  RCLCPP_WARN(nh->get_logger(),
265  "MoveGroup launched without ~default_planning_pipeline specifying the namespace for the default "
266  "planning pipeline configuration");
267  }
268 
269  // If there is no valid default pipeline, either pick the first available one, or fall back to old behavior
270  if (default_planning_pipeline.empty())
271  {
272  if (!pipeline_names.empty())
273  {
274  RCLCPP_WARN(nh->get_logger(), "Using default pipeline '%s'", pipeline_names[0].c_str());
275  default_planning_pipeline = pipeline_names[0];
276  }
277  else
278  {
279  RCLCPP_WARN(nh->get_logger(), "Falling back to using the the move_group node namespace (deprecated behavior).");
280  default_planning_pipeline = "move_group";
281  moveit_cpp_options.planning_pipeline_options.pipeline_names = { default_planning_pipeline };
282  moveit_cpp_options.planning_pipeline_options.parent_namespace = nh->get_effective_namespace();
283  }
284 
285  // Reset invalid pipeline parameter for MGI requests
286  nh->set_parameter(rclcpp::Parameter("default_planning_pipeline", default_planning_pipeline));
287  }
288 
289  // Initialize MoveItCpp
290  const auto moveit_cpp = std::make_shared<moveit_cpp::MoveItCpp>(nh, moveit_cpp_options);
291  const auto planning_scene_monitor = moveit_cpp->getPlanningSceneMonitorNonConst();
292 
293  if (planning_scene_monitor->getPlanningScene())
294  {
295  bool debug = false;
296  for (int i = 1; i < argc; ++i)
297  {
298  if (strncmp(argv[i], "--debug", 7) == 0)
299  {
300  debug = true;
301  break;
302  }
303  }
304  debug = true;
305  if (debug)
306  {
307  RCLCPP_INFO(nh->get_logger(), "MoveGroup debug mode is ON");
308  }
309  else
310  {
311  RCLCPP_INFO(nh->get_logger(), "MoveGroup debug mode is OFF");
312  }
313 
314  rclcpp::executors::MultiThreadedExecutor executor;
315 
316  move_group::MoveGroupExe mge(moveit_cpp, default_planning_pipeline, debug);
317 
318  bool monitor_dynamics;
319  if (nh->get_parameter("monitor_dynamics", monitor_dynamics) && monitor_dynamics)
320  {
321  RCLCPP_INFO(nh->get_logger(), "MoveGroup monitors robot dynamics (higher load)");
322  planning_scene_monitor->getStateMonitor()->enableCopyDynamics(true);
323  }
324 
325  planning_scene_monitor->publishDebugInformation(debug);
326 
327  mge.status();
328  executor.add_node(nh);
329  executor.spin();
330 
331  rclcpp::shutdown();
332  }
333  else
334  RCLCPP_ERROR(nh->get_logger(), "Planning scene not configured");
335 
336  return 0;
337 }
MoveGroupContextPtr getContext()
Definition: move_group.cpp:126
MoveGroupExe(const moveit_cpp::MoveItCppPtr &moveit_cpp, const std::string &default_planning_pipeline, bool debug)
Definition: move_group.cpp:84
#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)
Definition: move_group.cpp:218
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
Definition: logger.cpp:73
Parameter container for initializing MoveItCpp.
Definition: moveit_cpp.hpp:100
PlanningPipelineOptions planning_pipeline_options
Definition: moveit_cpp.hpp:108
std::vector< std::string > pipeline_names
Definition: moveit_cpp.hpp:94