moveit2
The MoveIt Motion Planning Framework for ROS 2.
plan_execution.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 
43 #include <boost/algorithm/string/join.hpp>
44 #include <rclcpp/logger.hpp>
45 #include <rclcpp/logging.hpp>
46 #include <rclcpp/node.hpp>
47 #include <rclcpp/parameter_value.hpp>
48 #include <rclcpp/rate.hpp>
49 #include <rclcpp/utilities.hpp>
50 #include <moveit/utils/logger.hpp>
51 
52 // #include <dynamic_reconfigure/server.h>
53 // #include <moveit_ros_planning/PlanExecutionDynamicReconfigureConfig.h>
54 
55 namespace plan_execution
56 {
57 
58 // class PlanExecution::DynamicReconfigureImpl
59 // {
60 // public:
61 // DynamicReconfigureImpl(PlanExecution* owner)
62 // : owner_(owner) //, dynamic_reconfigure_server_(ros::NodeHandle("~/plan_execution"))
63 // {
64 // // dynamic_reconfigure_server_.setCallback(
65 // // [this](const auto& config, uint32_t level) { dynamicReconfigureCallback(config, level); });
66 // }
67 //
68 // private:
69 // // void dynamicReconfigureCallback(const PlanExecutionDynamicReconfigureConfig& config, uint32_t level)
70 // // {
71 // // owner_->setMaxReplanAttempts(config.max_replan_attempts);
72 // // owner_->setTrajectoryStateRecordingFrequency(config.record_trajectory_state_frequency);
73 // // }
74 //
75 // PlanExecution* owner_;
76 // // dynamic_reconfigure::Server<PlanExecutionDynamicReconfigureConfig> dynamic_reconfigure_server_;
77 // };
78 } // namespace plan_execution
79 
81  const rclcpp::Node::SharedPtr& node, const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor,
82  const trajectory_execution_manager::TrajectoryExecutionManagerPtr& trajectory_execution)
83  : node_(node)
84  , planning_scene_monitor_(planning_scene_monitor)
85  , trajectory_execution_manager_(trajectory_execution)
86  , logger_(moveit::getLogger("add_time_optimal_parameterization"))
87 {
88  if (!trajectory_execution_manager_)
89  {
90  trajectory_execution_manager_ = std::make_shared<trajectory_execution_manager::TrajectoryExecutionManager>(
91  node_, planning_scene_monitor_->getRobotModel(), planning_scene_monitor_->getStateMonitor());
92  }
93 
94  default_max_replan_attempts_ = 5;
95 
96  new_scene_update_ = false;
97 
98  // we want to be notified when new information is available
99  planning_scene_monitor_->addUpdateCallback(
101  planningSceneUpdatedCallback(update_type);
102  });
103 
104  // start the dynamic-reconfigure server
105  // reconfigure_impl_ = new DynamicReconfigureImpl(this);
106 }
107 
109 {
110  // delete reconfigure_impl_;
111 }
112 
114 {
115  preempt_.request();
116 }
117 
119 {
120  plan.planning_scene_monitor = planning_scene_monitor_;
121  plan.planning_scene = planning_scene_monitor_->getPlanningScene();
122  planAndExecuteHelper(plan, opt);
123 }
124 
126  const moveit_msgs::msg::PlanningScene& scene_diff,
127  const Options& opt)
128 {
129  if (moveit::core::isEmpty(scene_diff))
130  {
131  planAndExecute(plan, opt);
132  }
133  else
134  {
135  plan.planning_scene_monitor = planning_scene_monitor_;
136  {
137  planning_scene_monitor::LockedPlanningSceneRO lscene(planning_scene_monitor_); // lock the scene so that it does
138  // not modify the world
139  // representation while diff() is
140  // called
141  plan.planning_scene = lscene->diff(scene_diff);
142  }
143  planAndExecuteHelper(plan, opt);
144  }
145 }
146 
147 void plan_execution::PlanExecution::planAndExecuteHelper(ExecutableMotionPlan& plan, const Options& opt)
148 {
149  // perform initial configuration steps & various checks
150  preempt_.checkAndClear(); // clear any previous preempt_ request
151 
152  bool preempt_requested = false;
153 
154  // run the actual motion plan & execution
155  unsigned int max_replan_attempts =
156  opt.replan ? (opt.replan_attemps > 0 ? opt.replan_attemps : default_max_replan_attempts_) : 1;
157  unsigned int replan_attempts = 0;
158  bool previously_solved = false;
159 
160  // run a planning loop for at most the maximum replanning attempts;
161  // re-planning is executed only in case of known types of failures (e.g., environment changed)
162  do
163  {
164  replan_attempts++;
165  RCLCPP_INFO(logger_, "Planning attempt %u of at most %u", replan_attempts, max_replan_attempts);
166 
167  if (opt.before_plan_callback_)
168  opt.before_plan_callback_();
169 
170  new_scene_update_ = false; // we clear any scene updates to be evaluated because we are about to compute a new
171  // plan, which should consider most recent updates already
172 
173  // if we never had a solved plan, or there is no specified way of fixing plans, just call the planner; otherwise,
174  // try to repair the plan we previously had;
175  bool solved =
176  (!previously_solved || !opt.repair_plan_callback_) ?
177  opt.plan_callback(plan) :
178  opt.repair_plan_callback_(plan, trajectory_execution_manager_->getCurrentExpectedTrajectoryIndex());
179 
180  preempt_requested = preempt_.checkAndClear();
181  if (preempt_requested)
182  break;
183 
184  // if planning fails in a manner that is not recoverable, we exit the loop,
185  // otherwise, we attempt to continue, if replanning attempts are left
186  if (plan.error_code.val == moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED ||
187  plan.error_code.val == moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN ||
188  plan.error_code.val == moveit_msgs::msg::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA)
189  {
190  if (plan.error_code.val == moveit_msgs::msg::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA &&
191  opt.replan_delay > 0.0)
192  {
193  auto replan_delay_seconds = std::chrono::duration<double>(opt.replan_delay);
194  rclcpp::sleep_for(std::chrono::duration_cast<std::chrono::nanoseconds>(replan_delay_seconds));
195  }
196  continue;
197  }
198 
199  // abort if no plan was found
200  if (solved)
201  {
202  previously_solved = true;
203  }
204  else
205  {
206  break;
207  }
208 
209  if (plan.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
210  {
211  if (opt.before_execution_callback_)
212  opt.before_execution_callback_();
213 
214  preempt_requested = preempt_.checkAndClear();
215  if (preempt_requested)
216  break;
217 
218  // execute the trajectory, and monitor its execution
219  plan.error_code = executeAndMonitor(plan, false);
220  }
221 
222  if (plan.error_code.val == moveit_msgs::msg::MoveItErrorCodes::PREEMPTED)
223  preempt_requested = true;
224 
225  // if execution succeeded or failed in a manner that we do not consider recoverable, we exit the loop (with failure)
226  if (plan.error_code.val != moveit_msgs::msg::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE)
227  {
228  break;
229  }
230  else
231  {
232  // otherwise, we wait (if needed)
233  if (opt.replan_delay > 0.0)
234  {
235  RCLCPP_INFO(logger_, "Waiting for a %lf seconds before attempting a new plan ...", opt.replan_delay);
236  auto replan_delay_seconds = std::chrono::duration<double>(opt.replan_delay);
237  rclcpp::sleep_for(std::chrono::duration_cast<std::chrono::nanoseconds>(replan_delay_seconds));
238  RCLCPP_INFO(logger_, "Done waiting");
239  }
240  }
241 
242  preempt_requested = preempt_.checkAndClear();
243  if (preempt_requested)
244  break;
245 
246  } while (replan_attempts < max_replan_attempts);
247 
248  if (preempt_requested)
249  {
250  RCLCPP_DEBUG(logger_, "PlanExecution was preempted");
251  plan.error_code.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
252  }
253 
254  if (opt.done_callback_)
255  opt.done_callback_();
256 
257  if (plan.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
258  {
259  RCLCPP_DEBUG(logger_, "PlanExecution finished successfully.");
260  }
261  else
262  {
263  RCLCPP_DEBUG(logger_, "PlanExecution terminating with error code %d - '%s'", plan.error_code.val,
265  }
266 }
267 
268 bool plan_execution::PlanExecution::isRemainingPathValid(const ExecutableMotionPlan& plan,
269  const std::pair<int, int>& path_segment)
270 {
271  if (path_segment.first >= 0 &&
272  plan.plan_components[path_segment.first].trajectory_monitoring) // If path_segment.second <= 0, the function
273  // will fallback to check the entire trajectory
274  {
275  planning_scene_monitor::LockedPlanningSceneRO lscene(plan.planning_scene_monitor); // lock the scene so that it
276  // does not modify the world
277  // representation while
278  // isStateValid() is called
279  const robot_trajectory::RobotTrajectory& t = *plan.plan_components[path_segment.first].trajectory;
281  plan.plan_components[path_segment.first].allowed_collision_matrix.get();
282  std::size_t wpc = t.getWayPointCount();
284  req.group_name = t.getGroupName();
285  for (std::size_t i = std::max(path_segment.second - 1, 0); i < wpc; ++i)
286  {
288  if (acm)
289  {
290  plan.planning_scene->checkCollisionUnpadded(req, res, t.getWayPoint(i), *acm);
291  }
292  else
293  {
294  plan.planning_scene->checkCollisionUnpadded(req, res, t.getWayPoint(i));
295  }
296 
297  if (res.collision || !plan.planning_scene->isStateFeasible(t.getWayPoint(i), false))
298  {
299  // Dave's debacle
300  RCLCPP_INFO(logger_, "Trajectory component '%s' is invalid",
301  plan.plan_components[path_segment.first].description.c_str());
302 
303  // call the same functions again, in verbose mode, to show what issues have been detected
304  plan.planning_scene->isStateFeasible(t.getWayPoint(i), true);
305  req.verbose = true;
306  res.clear();
307  if (acm)
308  {
309  plan.planning_scene->checkCollisionUnpadded(req, res, t.getWayPoint(i), *acm);
310  }
311  else
312  {
313  plan.planning_scene->checkCollisionUnpadded(req, res, t.getWayPoint(i));
314  }
315  return false;
316  }
317  }
318  }
319  return true;
320 }
321 
323  bool reset_preempted)
324 {
325  if (reset_preempted)
326  preempt_.checkAndClear();
327 
328  if (!plan.planning_scene_monitor)
329  plan.planning_scene_monitor = planning_scene_monitor_;
330  if (!plan.planning_scene)
331  plan.planning_scene = planning_scene_monitor_->getPlanningScene();
332 
333  moveit_msgs::msg::MoveItErrorCodes result;
334 
335  // try to execute the trajectory
336  execution_complete_ = true;
337 
338  if (!trajectory_execution_manager_)
339  {
340  RCLCPP_ERROR(logger_, "No trajectory execution manager");
341  result.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
342  return result;
343  }
344 
345  if (plan.plan_components.empty())
346  {
347  result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
348  return result;
349  }
350 
351  execution_complete_ = false;
352 
353  // push the trajectories we have slated for execution to the trajectory execution manager
354  int prev = -1;
355  for (size_t component_idx = 0; component_idx < plan.plan_components.size(); ++component_idx)
356  {
357  // \todo should this be in trajectory_execution ? Maybe. Then that will have to use kinematic_trajectory too;
358  // splitting trajectories for controllers becomes interesting: tied to groups instead of joints. this could cause
359  // some problems
360  // in the meantime we do a hack:
361 
362  bool unwound = false;
363  for (int prev_component = component_idx - 1; prev_component >= 0; --prev_component)
364  {
365  // Search backward for a previous component having the same group.
366  // If the group is the same, unwind this component based on the last waypoint of the previous one.
367  if (plan.plan_components.at(prev_component).trajectory &&
368  plan.plan_components.at(prev_component).trajectory->getGroup() ==
369  plan.plan_components.at(prev_component).trajectory->getGroup() &&
370  !plan.plan_components.at(prev_component).trajectory->empty())
371  {
372  plan.plan_components.at(component_idx)
373  .trajectory->unwind(plan.plan_components.at(prev_component).trajectory->getLastWayPoint());
374  unwound = true;
375  // Break so each component is only unwound once
376  break;
377  }
378  }
379 
380  if (!unwound)
381  {
382  // unwind the path to execute based on the current state of the system
383  if (prev < 0)
384  {
385  plan.plan_components[component_idx].trajectory->unwind(
386  plan.planning_scene_monitor && plan.planning_scene_monitor->getStateMonitor() ?
387  *plan.planning_scene_monitor->getStateMonitor()->getCurrentState() :
388  plan.planning_scene->getCurrentState());
389  }
390  else
391  {
392  plan.plan_components[component_idx].trajectory->unwind(plan.plan_components[prev].trajectory->getLastWayPoint());
393  }
394  }
395 
396  if (plan.plan_components[component_idx].trajectory && !plan.plan_components[component_idx].trajectory->empty())
397  prev = component_idx;
398 
399  // convert to message, pass along
400  moveit_msgs::msg::RobotTrajectory msg;
401  plan.plan_components[component_idx].trajectory->getRobotTrajectoryMsg(msg);
402  if (!trajectory_execution_manager_->push(msg, plan.plan_components[component_idx].controller_name))
403  {
404  trajectory_execution_manager_->clear();
405  RCLCPP_ERROR(logger_, "Apparently trajectory initialization failed");
406  execution_complete_ = true;
407  result.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
408  return result;
409  }
410  }
411 
412  if (!trajectory_monitor_ && planning_scene_monitor_->getStateMonitor())
413  {
414  // Pass current value of reconfigurable parameter plan_execution/record_trajectory_state_frequency
415  double sampling_frequency = 0.0;
416  node_->get_parameter_or("plan_execution.record_trajectory_state_frequency", sampling_frequency, 0.0);
417  trajectory_monitor_ = std::make_shared<planning_scene_monitor::TrajectoryMonitor>(
418  planning_scene_monitor_->getStateMonitor(), sampling_frequency);
419  }
420 
421  // start recording trajectory states
422  if (trajectory_monitor_)
423  trajectory_monitor_->startTrajectoryMonitor();
424 
425  // start a trajectory execution thread
426  trajectory_execution_manager_->execute(
427  [this](const moveit_controller_manager::ExecutionStatus& status) { doneWithTrajectoryExecution(status); },
428  [this, &plan](std::size_t index) { successfulTrajectorySegmentExecution(plan, index); });
429  // wait for path to be done, while checking that the path does not become invalid
430  rclcpp::WallRate r(100);
431  path_became_invalid_ = false;
432  bool preempt_requested = false;
433 
434  while (rclcpp::ok() && !execution_complete_ && !path_became_invalid_)
435  {
436  r.sleep();
437  // check the path if there was an environment update in the meantime
438  if (new_scene_update_)
439  {
440  new_scene_update_ = false;
441  std::pair<int, int> current_index = trajectory_execution_manager_->getCurrentExpectedTrajectoryIndex();
442  if (!isRemainingPathValid(plan, current_index))
443  {
444  RCLCPP_INFO(logger_, "Trajectory component '%s' is invalid after scene update",
445  plan.plan_components[current_index.first].description.c_str());
446  path_became_invalid_ = true;
447  break;
448  }
449  }
450 
451  preempt_requested = preempt_.checkAndClear();
452  if (preempt_requested)
453  break;
454  }
455 
456  // stop execution if needed
457  if (preempt_requested)
458  {
459  RCLCPP_INFO(logger_, "Stopping execution due to preempt request");
460  trajectory_execution_manager_->stopExecution();
461  }
462  else if (path_became_invalid_)
463  {
464  RCLCPP_INFO(logger_, "Stopping execution because the path to execute became invalid"
465  "(probably the environment changed)");
466  trajectory_execution_manager_->stopExecution();
467  }
468  else if (!execution_complete_)
469  {
470  RCLCPP_WARN(logger_, "Stopping execution due to unknown reason."
471  "Possibly the node is about to shut down.");
472  trajectory_execution_manager_->stopExecution();
473  }
474 
475  // stop recording trajectory states
476  if (trajectory_monitor_)
477  {
478  trajectory_monitor_->stopTrajectoryMonitor();
479  plan.executed_trajectory =
480  std::make_shared<robot_trajectory::RobotTrajectory>(planning_scene_monitor_->getRobotModel(), "");
481  trajectory_monitor_->swapTrajectory(*plan.executed_trajectory);
482  }
483 
484  // decide return value
485  if (path_became_invalid_)
486  {
487  result.val = moveit_msgs::msg::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE;
488  }
489  else
490  {
491  if (preempt_requested)
492  {
493  result.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
494  }
495  else
496  {
497  if (trajectory_execution_manager_->getLastExecutionStatus() ==
499  {
500  result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
501  }
502  else if (trajectory_execution_manager_->getLastExecutionStatus() ==
504  {
505  result.val = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
506  }
507  else
508  {
509  result.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
510  }
511  }
512  }
513  return result;
514 }
515 
516 void plan_execution::PlanExecution::planningSceneUpdatedCallback(
518 {
521  new_scene_update_ = true;
522 }
523 
524 void plan_execution::PlanExecution::doneWithTrajectoryExecution(
526 {
527  execution_complete_ = true;
528 }
529 
530 void plan_execution::PlanExecution::successfulTrajectorySegmentExecution(const ExecutableMotionPlan& plan,
531  std::size_t index)
532 {
533  if (plan.plan_components.empty())
534  {
535  RCLCPP_WARN(logger_, "Length of provided motion plan is zero.");
536  return;
537  }
538 
539  // if any side-effects are associated to the trajectory part that just completed, execute them
540  RCLCPP_DEBUG(logger_, "Completed '%s'", plan.plan_components[index].description.c_str());
541  if (plan.plan_components[index].effect_on_success)
542  {
543  if (!plan.plan_components[index].effect_on_success(&plan))
544  {
545  // execution of side-effect failed
546  RCLCPP_ERROR(logger_, "Execution of path-completion side-effect failed. Preempting.");
547  preempt_.request();
548  return;
549  }
550  }
551 
552  // if there is a next trajectory, check it for validity, before we start execution
553  ++index;
554  if (index < plan.plan_components.size() && plan.plan_components[index].trajectory &&
555  !plan.plan_components[index].trajectory->empty())
556  {
557  std::pair<int, int> next_index(static_cast<int>(index), 0);
558  if (!isRemainingPathValid(plan, next_index))
559  {
560  RCLCPP_INFO(logger_, "Upcoming trajectory component '%s' is invalid",
561  plan.plan_components[next_index.first].description.c_str());
562  path_became_invalid_ = true;
563  }
564  }
565 }
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
void planAndExecute(ExecutableMotionPlan &plan, const Options &opt)
PlanExecution(const rclcpp::Node::SharedPtr &node, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor, const trajectory_execution_manager::TrajectoryExecutionManagerPtr &trajectory_execution)
moveit_msgs::msg::MoveItErrorCodes executeAndMonitor(ExecutableMotionPlan &plan, bool reset_preempted=true)
Execute and monitor a previously created plan.
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
@ UPDATE_GEOMETRY
The geometry of the scene was updated. This includes receiving new octomaps, collision objects,...
@ UPDATE_TRANSFORMS
The maintained set of fixed transforms in the monitored scene was updated.
Maintain a sequence of waypoints and the time durations between these waypoints.
const std::string & getGroupName() const
const moveit::core::RobotState & getWayPoint(std::size_t index) const
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
std::string errorCodeToString(const MoveItErrorCode &error_code)
Convenience function to translated error message into string.
planning_interface::MotionPlanResponse plan(std::shared_ptr< moveit_cpp::PlanningComponent > &planning_component, std::shared_ptr< moveit_cpp::PlanningComponent::PlanRequestParameters > &single_plan_parameters, std::shared_ptr< moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters > &multi_plan_parameters, std::shared_ptr< planning_scene::PlanningScene > &planning_scene, std::optional< const moveit::planning_pipeline_interfaces::SolutionSelectionFunction > solution_selection_function, std::optional< moveit::planning_pipeline_interfaces::StoppingCriterionFunction > stopping_criterion_callback)
Main namespace for MoveIt.
Definition: exceptions.h:43
This namespace includes functionality specific to the execution and monitoring of motion plans.
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)....
bool verbose
Flag indicating whether information about detected collisions should be reported.
Representation of a collision checking result.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
bool collision
True if collision was found, false otherwise.
A generic representation on what a computed motion plan looks like.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory