planning_pipeline.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 
41 #include <moveit_msgs/DisplayTrajectory.h>
42 #include <visualization_msgs/MarkerArray.h>
43 #include <boost/tokenizer.hpp>
44 #include <boost/algorithm/string/join.hpp>
45 #include <sstream>
46 
47 const std::string planning_pipeline::PlanningPipeline::DISPLAY_PATH_TOPIC = "display_planned_path";
48 const std::string planning_pipeline::PlanningPipeline::MOTION_PLAN_REQUEST_TOPIC = "motion_plan_request";
49 const std::string planning_pipeline::PlanningPipeline::MOTION_CONTACTS_TOPIC = "display_contacts";
50 
51 planning_pipeline::PlanningPipeline::PlanningPipeline(const moveit::core::RobotModelConstPtr& model,
52  const ros::NodeHandle& pipeline_nh,
53  const std::string& planner_plugin_param_name,
54  const std::string& adapter_plugins_param_name)
55  : active_{ false }, pipeline_nh_(pipeline_nh), private_nh_("~"), robot_model_(model)
56 {
57  std::string planner;
58  if (pipeline_nh_.getParam(planner_plugin_param_name, planner))
59  planner_plugin_name_ = planner;
60 
61  std::string adapters;
62  if (pipeline_nh_.getParam(adapter_plugins_param_name, adapters))
63  {
64  boost::char_separator<char> sep(" ");
65  boost::tokenizer<boost::char_separator<char>> tok(adapters, sep);
66  for (boost::tokenizer<boost::char_separator<char>>::iterator beg = tok.begin(); beg != tok.end(); ++beg)
67  adapter_plugin_names_.push_back(*beg);
68  }
69 
70  configure();
71 }
72 
73 planning_pipeline::PlanningPipeline::PlanningPipeline(const moveit::core::RobotModelConstPtr& model,
74  const ros::NodeHandle& pipeline_nh,
75  const std::string& planner_plugin_name,
76  const std::vector<std::string>& adapter_plugin_names)
77  : active_{ false }
78  , pipeline_nh_(pipeline_nh)
79  , private_nh_("~")
80  , planner_plugin_name_(planner_plugin_name)
81  , adapter_plugin_names_(adapter_plugin_names)
82  , robot_model_(model)
83 {
84  configure();
85 }
86 
88 {
89  check_solution_paths_ = false; // this is set to true below
90  publish_received_requests_ = false;
91  display_computed_motion_plans_ = false; // this is set to true below
92 
93  // load the planning plugin
94  try
95  {
96  planner_plugin_loader_ = std::make_unique<pluginlib::ClassLoader<planning_interface::PlannerManager>>(
97  "moveit_core", "planning_interface::PlannerManager");
98  }
100  {
101  ROS_FATAL_STREAM("Exception while creating planning plugin loader " << ex.what());
102  }
103 
104  std::vector<std::string> classes;
105  if (planner_plugin_loader_)
106  classes = planner_plugin_loader_->getDeclaredClasses();
107  if (planner_plugin_name_.empty() && classes.size() == 1)
108  {
109  planner_plugin_name_ = classes[0];
110  ROS_INFO("No '~planning_plugin' parameter specified, but only '%s' planning plugin is available. Using that one.",
111  planner_plugin_name_.c_str());
112  }
113  if (planner_plugin_name_.empty() && classes.size() > 1)
114  {
115  planner_plugin_name_ = classes[0];
116  ROS_INFO("Multiple planning plugins available. You should specify the '~planning_plugin' parameter. Using '%s' for "
117  "now.",
118  planner_plugin_name_.c_str());
119  }
120  try
121  {
122  planner_instance_ = planner_plugin_loader_->createUniqueInstance(planner_plugin_name_);
123  if (!planner_instance_->initialize(robot_model_, pipeline_nh_.getNamespace()))
124  throw std::runtime_error("Unable to initialize planning plugin");
125  ROS_INFO_STREAM("Using planning interface '" << planner_instance_->getDescription() << "'");
126  }
128  {
129  ROS_ERROR_STREAM("Exception while loading planner '"
130  << planner_plugin_name_ << "': " << ex.what() << std::endl
131  << "Available plugins: " << boost::algorithm::join(classes, ", "));
132  }
133 
134  // load the planner request adapters
135  if (!adapter_plugin_names_.empty())
136  {
137  std::vector<planning_request_adapter::PlanningRequestAdapterConstPtr> ads;
138  try
139  {
140  adapter_plugin_loader_ =
141  std::make_unique<pluginlib::ClassLoader<planning_request_adapter::PlanningRequestAdapter>>(
142  "moveit_core", "planning_request_adapter::PlanningRequestAdapter");
143  }
145  {
146  ROS_ERROR_STREAM("Exception while creating planning plugin loader " << ex.what());
147  }
148 
149  if (adapter_plugin_loader_)
150  for (const std::string& adapter_plugin_name : adapter_plugin_names_)
151  {
152  planning_request_adapter::PlanningRequestAdapterPtr ad;
153  try
154  {
155  ad = adapter_plugin_loader_->createUniqueInstance(adapter_plugin_name);
156  }
158  {
159  ROS_ERROR_STREAM("Exception while loading planning adapter plugin '" << adapter_plugin_name
160  << "': " << ex.what());
161  }
162  if (ad)
163  {
164  ad->initialize(pipeline_nh_);
165  ads.push_back(std::move(ad));
166  }
167  }
168  if (!ads.empty())
169  {
170  adapter_chain_ = std::make_unique<planning_request_adapter::PlanningRequestAdapterChain>();
171  for (planning_request_adapter::PlanningRequestAdapterConstPtr& ad : ads)
172  {
173  ROS_INFO_STREAM("Using planning request adapter '" << ad->getDescription() << "'");
174  adapter_chain_->addAdapter(ad);
175  }
176  }
177  }
178  displayComputedMotionPlans(true);
179  checkSolutionPaths(true);
180 }
181 
183 {
184  if (display_computed_motion_plans_ && !flag)
185  display_path_publisher_.shutdown();
186  else if (!display_computed_motion_plans_ && flag)
187  display_path_publisher_ = private_nh_.advertise<moveit_msgs::DisplayTrajectory>(DISPLAY_PATH_TOPIC, 10, true);
188  display_computed_motion_plans_ = flag;
189 }
190 
192 {
193  if (publish_received_requests_ && !flag)
194  received_request_publisher_.shutdown();
195  else if (!publish_received_requests_ && flag)
196  received_request_publisher_ =
197  private_nh_.advertise<moveit_msgs::MotionPlanRequest>(MOTION_PLAN_REQUEST_TOPIC, 10, true);
198  publish_received_requests_ = flag;
199 }
200 
202 {
203  if (check_solution_paths_ && !flag)
204  contacts_publisher_.shutdown();
205  else if (!check_solution_paths_ && flag)
206  contacts_publisher_ = private_nh_.advertise<visualization_msgs::MarkerArray>(MOTION_CONTACTS_TOPIC, 100, true);
207  check_solution_paths_ = flag;
208 }
209 
210 bool planning_pipeline::PlanningPipeline::generatePlan(const planning_scene::PlanningSceneConstPtr& planning_scene,
213 {
214  std::vector<std::size_t> dummy;
215  return generatePlan(planning_scene, req, res, dummy);
216 }
217 
218 bool planning_pipeline::PlanningPipeline::generatePlan(const planning_scene::PlanningSceneConstPtr& planning_scene,
221  std::vector<std::size_t>& adapter_added_state_index) const
222 {
223  // Set planning pipeline active
224  active_ = true;
225 
226  // broadcast the request we are about to work on, if needed
227  if (publish_received_requests_)
228  received_request_publisher_.publish(req);
229  adapter_added_state_index.clear();
230 
231  if (!planner_instance_)
232  {
233  ROS_ERROR("No planning plugin loaded. Cannot plan.");
234  // Set planning pipeline to inactive
235  active_ = false;
236  return false;
237  }
238 
239  bool solved = false;
240  try
241  {
242  if (adapter_chain_)
243  {
244  solved = adapter_chain_->adaptAndPlan(planner_instance_, planning_scene, req, res, adapter_added_state_index);
245  if (!adapter_added_state_index.empty())
246  {
247  std::stringstream ss;
248  for (std::size_t added_index : adapter_added_state_index)
249  ss << added_index << " ";
250  ROS_INFO("Planning adapters have added states at index positions: [ %s]", ss.str().c_str());
251  }
252  }
253  else
254  {
255  planning_interface::PlanningContextPtr context =
256  planner_instance_->getPlanningContext(planning_scene, req, res.error_code_);
257  solved = context ? context->solve(res) : false;
258  }
259  }
260  catch (std::exception& ex)
261  {
262  ROS_ERROR("Exception caught: '%s'", ex.what());
263  // Set planning pipeline to inactive
264  active_ = false;
265  return false;
266  }
267  bool valid = true;
268 
269  if (solved && res.trajectory_)
270  {
271  std::size_t state_count = res.trajectory_->getWayPointCount();
272  ROS_DEBUG_STREAM("Motion planner reported a solution path with " << state_count << " states");
273  if (check_solution_paths_)
274  {
275  visualization_msgs::MarkerArray arr;
276  visualization_msgs::Marker m;
277  m.action = visualization_msgs::Marker::DELETEALL;
278  arr.markers.push_back(m);
279 
280  std::vector<std::size_t> index;
281  if (!planning_scene->isPathValid(*res.trajectory_, req.path_constraints, req.group_name, false, &index))
282  {
283  // check to see if there is any problem with the states that are found to be invalid
284  // they are considered ok if they were added by a planning request adapter
285  bool problem = false;
286  for (std::size_t i = 0; i < index.size() && !problem; ++i)
287  {
288  bool found = false;
289  for (std::size_t added_index : adapter_added_state_index)
290  if (index[i] == added_index)
291  {
292  found = true;
293  break;
294  }
295  if (!found)
296  problem = true;
297  }
298  if (problem)
299  {
300  if (index.size() == 1 && index[0] == 0) // ignore cases when the robot starts at invalid location
301  ROS_DEBUG("It appears the robot is starting at an invalid state, but that is ok.");
302  else
303  {
304  valid = false;
305  res.error_code_.val = moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN;
306 
307  // display error messages
308  std::stringstream ss;
309  for (std::size_t it : index)
310  ss << it << " ";
311  ROS_ERROR_STREAM("Computed path is not valid. Invalid states at index locations: [ "
312  << ss.str() << "] out of " << state_count
313  << ". Explanations follow in command line. Contacts are published on "
314  << private_nh_.resolveName(MOTION_CONTACTS_TOPIC));
315 
316  // call validity checks in verbose mode for the problematic states
317  for (std::size_t it : index)
318  {
319  // check validity with verbose on
320  const moveit::core::RobotState& robot_state = res.trajectory_->getWayPoint(it);
321  planning_scene->isStateValid(robot_state, req.path_constraints, req.group_name, true);
322 
323  // compute the contacts if any
326  c_req.contacts = true;
327  c_req.max_contacts = 10;
328  c_req.max_contacts_per_pair = 3;
329  c_req.verbose = false;
330  planning_scene->checkCollision(c_req, c_res, robot_state);
331  if (c_res.contact_count > 0)
332  {
333  visualization_msgs::MarkerArray arr_i;
335  c_res.contacts);
336  arr.markers.insert(arr.markers.end(), arr_i.markers.begin(), arr_i.markers.end());
337  }
338  }
339  ROS_ERROR_STREAM("Completed listing of explanations for invalid states.");
340  }
341  }
342  else
343  ROS_DEBUG("Planned path was found to be valid, except for states that were added by planning request "
344  "adapters, but that is ok.");
345  }
346  else
347  ROS_DEBUG("Planned path was found to be valid when rechecked");
348  contacts_publisher_.publish(arr);
349  }
350  }
351 
352  // display solution path if needed
353  if (display_computed_motion_plans_ && solved)
354  {
355  moveit_msgs::DisplayTrajectory disp;
356  disp.model_id = robot_model_->getName();
357  disp.trajectory.resize(1);
358  res.trajectory_->getRobotTrajectoryMsg(disp.trajectory[0]);
359  moveit::core::robotStateToRobotStateMsg(res.trajectory_->getFirstWayPoint(), disp.trajectory_start);
360  display_path_publisher_.publish(disp);
361  }
362 
363  if (!solved)
364  {
365  // This should alert the user if planning failed because of contradicting constraints.
366  // Could be checked more thoroughly, but it is probably not worth going to that length.
367  bool stacked_constraints = false;
368  if (req.path_constraints.position_constraints.size() > 1 || req.path_constraints.orientation_constraints.size() > 1)
369  stacked_constraints = true;
370  for (const auto& constraint : req.goal_constraints)
371  {
372  if (constraint.position_constraints.size() > 1 || constraint.orientation_constraints.size() > 1)
373  stacked_constraints = true;
374  }
375  if (stacked_constraints)
376  ROS_WARN("More than one constraint is set. If your move_group does not have multiple end effectors/arms, this is "
377  "unusual. Are you using a move_group_interface and forgetting to call clearPoseTargets() or "
378  "equivalent?");
379  }
380  // Set planning pipeline to inactive
381  active_ = false;
382  return solved && valid;
383 }
384 
386 {
387  if (planner_instance_)
388  planner_instance_->terminate();
389 }
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
collision_tools.h
planning_pipeline::PlanningPipeline::DISPLAY_PATH_TOPIC
static const std::string DISPLAY_PATH_TOPIC
When motion plans are computed and they are supposed to be automatically displayed,...
Definition: planning_pipeline.h:125
planning_interface::MotionPlanResponse
ROS_FATAL_STREAM
#define ROS_FATAL_STREAM(args)
planning_pipeline::PlanningPipeline::terminate
void terminate() const
Request termination, if a generatePlan() function is currently computing plans.
Definition: planning_pipeline.cpp:385
planning_interface::MotionPlanResponse::error_code_
moveit::core::MoveItErrorCode error_code_
collision_detection::getCollisionMarkersFromContacts
void getCollisionMarkersFromContacts(visualization_msgs::MarkerArray &arr, const std::string &frame_id, const CollisionResult::ContactMap &con)
ROS_DEBUG
#define ROS_DEBUG(...)
planning_pipeline::PlanningPipeline::MOTION_CONTACTS_TOPIC
static const std::string MOTION_CONTACTS_TOPIC
When contacts are found in the solution path reported by a planner, they can be published as markers ...
Definition: planning_pipeline.h:133
moveit::core::RobotState
planning_pipeline::PlanningPipeline::MOTION_PLAN_REQUEST_TOPIC
static const std::string MOTION_PLAN_REQUEST_TOPIC
When motion planning requests are received and they are supposed to be automatically published,...
Definition: planning_pipeline.h:129
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
planning_pipeline::PlanningPipeline::generatePlan
bool generatePlan(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res) const
Call the motion planner plugin and the sequence of planning request adapters (if any).
Definition: planning_pipeline.cpp:210
collision_detection::CollisionRequest
pluginlib::PluginlibException
planning_pipeline::PlanningPipeline::checkSolutionPaths
void checkSolutionPaths(bool flag)
Pass a flag telling the pipeline whether or not to re-check the solution paths reported by the planne...
Definition: planning_pipeline.cpp:201
planning_pipeline::PlanningPipeline::PlanningPipeline
PlanningPipeline(const moveit::core::RobotModelConstPtr &model, const ros::NodeHandle &pipeline_nh=ros::NodeHandle("~"), const std::string &planning_plugin_param_name="planning_plugin", const std::string &adapter_plugins_param_name="request_adapters")
Given a robot model (model), a node handle (pipeline_nh), initialize the planning pipeline.
Definition: planning_pipeline.cpp:51
planning_pipeline::PlanningPipeline::configure
void configure()
Definition: planning_pipeline.cpp:87
planning_interface::MotionPlanResponse::trajectory_
robot_trajectory::RobotTrajectoryPtr trajectory_
planning_pipeline::PlanningPipeline::displayComputedMotionPlans
void displayComputedMotionPlans(bool flag)
Pass a flag telling the pipeline whether or not to publish the computed motion plans on DISPLAY_PATH_...
Definition: planning_pipeline.cpp:182
planning_pipeline::PlanningPipeline::publishReceivedRequests
void publishReceivedRequests(bool flag)
Pass a flag telling the pipeline whether or not to publish the received motion planning requests on M...
Definition: planning_pipeline.cpp:191
collision_detection::CollisionResult
collision_detection::CollisionRequest::max_contacts
std::size_t max_contacts
collision_detection::CollisionRequest::verbose
bool verbose
ROS_ERROR
#define ROS_ERROR(...)
ROS_WARN
#define ROS_WARN(...)
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
collision_detection::CollisionResult::contacts
ContactMap contacts
planning_pipeline.h
collision_detection::CollisionRequest::contacts
bool contacts
index
unsigned int index
conversions.h
collision_detection::CollisionRequest::max_contacts_per_pair
std::size_t max_contacts_per_pair
trajectory_tools.h
ROS_INFO
#define ROS_INFO(...)
planning_scene
collision_detection::CollisionResult::contact_count
std::size_t contact_count
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
ros::NodeHandle


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Apr 18 2024 02:24:19