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