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 
45 #include <dynamic_reconfigure/server.h>
46 #include <moveit_ros_planning/PlanExecutionDynamicReconfigureConfig.h>
47 
48 namespace plan_execution
49 {
50 using namespace moveit_ros_planning;
51 
52 class PlanExecution::DynamicReconfigureImpl
53 {
54 public:
55  DynamicReconfigureImpl(PlanExecution* owner)
56  : owner_(owner), dynamic_reconfigure_server_(ros::NodeHandle("~/plan_execution"))
57  {
58  dynamic_reconfigure_server_.setCallback(
59  [this](const auto& config, uint32_t level) { dynamicReconfigureCallback(config, level); });
60  }
61 
62 private:
63  void dynamicReconfigureCallback(const PlanExecutionDynamicReconfigureConfig& config, uint32_t /*level*/)
64  {
65  owner_->setMaxReplanAttempts(config.max_replan_attempts);
66  owner_->setTrajectoryStateRecordingFrequency(config.record_trajectory_state_frequency);
67  }
68 
69  PlanExecution* owner_;
70  dynamic_reconfigure::Server<PlanExecutionDynamicReconfigureConfig> dynamic_reconfigure_server_;
71 };
72 } // namespace plan_execution
73 
75  const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor,
76  const trajectory_execution_manager::TrajectoryExecutionManagerPtr& trajectory_execution)
77  : node_handle_("~")
78  , planning_scene_monitor_(planning_scene_monitor)
79  , trajectory_execution_manager_(trajectory_execution)
80 {
82  trajectory_execution_manager_ = std::make_shared<trajectory_execution_manager::TrajectoryExecutionManager>(
83  planning_scene_monitor_->getRobotModel(), planning_scene_monitor_->getStateMonitor());
84 
86 
88 
89  // we want to be notified when new information is available
92  });
93 
94  // start the dynamic-reconfigure server
96 }
97 
99 {
100  delete reconfigure_impl_;
101 }
102 
104 {
105  preempt_.request();
106 }
107 
109 {
110  plan.planning_scene_monitor_ = planning_scene_monitor_;
111  plan.planning_scene_ = planning_scene_monitor_->getPlanningScene();
112  planAndExecuteHelper(plan, opt);
113 }
114 
116  const moveit_msgs::PlanningScene& scene_diff, const Options& opt)
117 {
118  if (moveit::core::isEmpty(scene_diff))
119  planAndExecute(plan, opt);
120  else
121  {
122  plan.planning_scene_monitor_ = planning_scene_monitor_;
123  {
124  planning_scene_monitor::LockedPlanningSceneRO lscene(planning_scene_monitor_); // lock the scene so that it does
125  // not modify the world
126  // representation while diff() is
127  // called
128  plan.planning_scene_ = lscene->diff(scene_diff);
129  }
130  planAndExecuteHelper(plan, opt);
131  }
132 }
133 
135 {
136  // perform initial configuration steps & various checks
137  preempt_.checkAndClear(); // clear any previous preempt_ request
138 
139  bool preempt_requested = false;
140 
141  // run the actual motion plan & execution
142  unsigned int max_replan_attempts =
143  opt.replan_ ? (opt.replan_attempts_ > 0 ? opt.replan_attempts_ : default_max_replan_attempts_) : 1;
144  unsigned int replan_attempts = 0;
145  bool previously_solved = false;
146 
147  // run a planning loop for at most the maximum replanning attempts;
148  // re-planning is executed only in case of known types of failures (e.g., environment changed)
149  do
150  {
151  replan_attempts++;
152  ROS_INFO_NAMED("plan_execution", "Planning attempt %u of at most %u", replan_attempts, max_replan_attempts);
153 
154  if (opt.before_plan_callback_)
155  opt.before_plan_callback_();
156 
157  new_scene_update_ = false; // we clear any scene updates to be evaluated because we are about to compute a new
158  // plan, which should consider most recent updates already
159 
160  // if we never had a solved plan, or there is no specified way of fixing plans, just call the planner; otherwise,
161  // try to repair the plan we previously had;
162  bool solved =
163  (!previously_solved || !opt.repair_plan_callback_) ?
164  opt.plan_callback_(plan) :
165  opt.repair_plan_callback_(plan, trajectory_execution_manager_->getCurrentExpectedTrajectoryIndex());
166 
167  preempt_requested = preempt_.checkAndClear();
168  if (preempt_requested)
169  break;
170 
171  // if planning fails in a manner that is not recoverable, we exit the loop,
172  // otherwise, we attempt to continue, if replanning attempts are left
173  if (plan.error_code_.val == moveit_msgs::MoveItErrorCodes::PLANNING_FAILED ||
174  plan.error_code_.val == moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN ||
175  plan.error_code_.val == moveit_msgs::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA)
176  {
177  if (plan.error_code_.val == moveit_msgs::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA && opt.replan_delay_ > 0.0)
178  {
180  d.sleep();
181  }
182  continue;
183  }
184 
185  // abort if no plan was found
186  if (solved)
187  previously_solved = true;
188  else
189  break;
190 
191  if (plan.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
192  {
195 
196  preempt_requested = preempt_.checkAndClear();
197  if (preempt_requested)
198  break;
199 
200  // execute the trajectory, and monitor its execution
201  plan.error_code_ = executeAndMonitor(plan, false);
202  }
203 
204  if (plan.error_code_.val == moveit_msgs::MoveItErrorCodes::PREEMPTED)
205  preempt_requested = true;
206 
207  // if execution succeeded or failed in a manner that we do not consider recoverable, we exit the loop (with failure)
208  if (plan.error_code_.val != moveit_msgs::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE)
209  break;
210  else
211  {
212  // otherwise, we wait (if needed)
213  if (opt.replan_delay_ > 0.0)
214  {
215  ROS_INFO_NAMED("plan_execution", "Waiting for a %lf seconds before attempting a new plan ...",
216  opt.replan_delay_);
218  d.sleep();
219  ROS_INFO_NAMED("plan_execution", "Done waiting");
220  }
221  }
222 
223  preempt_requested = preempt_.checkAndClear();
224  if (preempt_requested)
225  break;
226 
227  } while (replan_attempts < max_replan_attempts);
228 
229  if (preempt_requested)
230  {
231  ROS_DEBUG_NAMED("plan_execution", "PlanExecution was preempted");
232  plan.error_code_.val = moveit_msgs::MoveItErrorCodes::PREEMPTED;
233  }
234 
235  if (opt.done_callback_)
236  opt.done_callback_();
237 
238  if (plan.error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
239  ROS_DEBUG_NAMED("plan_execution", "PlanExecution finished successfully.");
240  else
241  ROS_DEBUG_NAMED("plan_execution", "PlanExecution terminating with error code %d - '%s'", plan.error_code_.val,
243 }
244 
246  const std::pair<int, int>& path_segment)
247 {
248  if (path_segment.first >= 0 &&
249  plan.plan_components_[path_segment.first].trajectory_monitoring_) // If path_segment.second <= 0, the function
250  // will fallback to check the entire trajectory
251  {
252  planning_scene_monitor::LockedPlanningSceneRO lscene(plan.planning_scene_monitor_); // lock the scene so that it
253  // does not modify the world
254  // representation while
255  // isStateValid() is called
256  const robot_trajectory::RobotTrajectory& t = *plan.plan_components_[path_segment.first].trajectory_;
258  plan.plan_components_[path_segment.first].allowed_collision_matrix_.get();
259  std::size_t wpc = t.getWayPointCount();
261  req.group_name = t.getGroupName();
262  for (std::size_t i = std::max(path_segment.second - 1, 0); i < wpc; ++i)
263  {
265  if (acm)
266  plan.planning_scene_->checkCollisionUnpadded(req, res, t.getWayPoint(i), *acm);
267  else
268  plan.planning_scene_->checkCollisionUnpadded(req, res, t.getWayPoint(i));
269 
270  if (res.collision || !plan.planning_scene_->isStateFeasible(t.getWayPoint(i), false))
271  {
272  // call the same functions again, in verbose mode, to show what issues have been detected
273  plan.planning_scene_->isStateFeasible(t.getWayPoint(i), true);
274  req.verbose = true;
275  res.clear();
276  if (acm)
277  plan.planning_scene_->checkCollisionUnpadded(req, res, t.getWayPoint(i), *acm);
278  else
279  plan.planning_scene_->checkCollisionUnpadded(req, res, t.getWayPoint(i));
280  return false;
281  }
282  }
283  }
284  return true;
285 }
286 
288  bool reset_preempted)
289 {
290  if (reset_preempted)
291  preempt_.checkAndClear();
292 
293  if (!plan.planning_scene_monitor_)
294  plan.planning_scene_monitor_ = planning_scene_monitor_;
295  if (!plan.planning_scene_)
296  plan.planning_scene_ = planning_scene_monitor_->getPlanningScene();
297 
298  moveit_msgs::MoveItErrorCodes result;
299 
300  // try to execute the trajectory
301  execution_complete_ = true;
302 
303  if (!trajectory_execution_manager_)
304  {
305  ROS_ERROR_NAMED("plan_execution", "No trajectory execution manager");
306  result.val = moveit_msgs::MoveItErrorCodes::CONTROL_FAILED;
307  return result;
308  }
309 
310  if (plan.plan_components_.empty())
311  {
312  result.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
313  return result;
314  }
315 
316  execution_complete_ = false;
317 
318  // push the trajectories we have slated for execution to the trajectory execution manager
319  int prev = -1;
320  for (std::size_t i = 0; i < plan.plan_components_.size(); ++i)
321  {
322  // \todo should this be in trajectory_execution ? Maybe. Then that will have to use kinematic_trajectory too;
323  // spliting trajectories for controllers becomes interesting: tied to groups instead of joints. this could cause
324  // some problems
325  // in the meantime we do a hack:
326 
327  bool unwound = false;
328  for (std::size_t j = 0; j < i; ++j)
329  // if we ran unwind on a path for the same group
330  if (plan.plan_components_[j].trajectory_ &&
331  plan.plan_components_[j].trajectory_->getGroup() == plan.plan_components_[i].trajectory_->getGroup() &&
332  !plan.plan_components_[j].trajectory_->empty())
333  {
334  plan.plan_components_[i].trajectory_->unwind(plan.plan_components_[j].trajectory_->getLastWayPoint());
335  unwound = true;
336  break;
337  }
338 
339  if (!unwound)
340  {
341  // unwind the path to execute based on the current state of the system
342  if (prev < 0)
343  plan.plan_components_[i].trajectory_->unwind(
344  plan.planning_scene_monitor_ && plan.planning_scene_monitor_->getStateMonitor() ?
345  *plan.planning_scene_monitor_->getStateMonitor()->getCurrentState() :
346  plan.planning_scene_->getCurrentState());
347  else
348  plan.plan_components_[i].trajectory_->unwind(plan.plan_components_[prev].trajectory_->getLastWayPoint());
349  }
350 
351  if (plan.plan_components_[i].trajectory_ && !plan.plan_components_[i].trajectory_->empty())
352  prev = i;
353 
354  // convert to message, pass along
355  moveit_msgs::RobotTrajectory msg;
356  plan.plan_components_[i].trajectory_->getRobotTrajectoryMsg(msg);
357  if (!trajectory_execution_manager_->push(msg, plan.plan_components_[i].controller_names_))
358  {
359  trajectory_execution_manager_->clear();
360  ROS_ERROR_STREAM_NAMED("plan_execution", "Apparently trajectory initialization failed");
361  execution_complete_ = true;
362  result.val = moveit_msgs::MoveItErrorCodes::CONTROL_FAILED;
363  return result;
364  }
365  }
366 
367  if (!trajectory_monitor_ && planning_scene_monitor_->getStateMonitor())
368  {
369  // Pass current value of reconfigurable parameter plan_execution/record_trajectory_state_frequency
370  double sampling_frequency = 0.0;
371  node_handle_.getParam("plan_execution/record_trajectory_state_frequency", sampling_frequency);
372  trajectory_monitor_ = std::make_shared<planning_scene_monitor::TrajectoryMonitor>(
373  planning_scene_monitor_->getStateMonitor(), sampling_frequency);
374  }
375 
376  // start recording trajectory states
377  if (trajectory_monitor_)
378  trajectory_monitor_->startTrajectoryMonitor();
379 
380  // start a trajectory execution thread
381  trajectory_execution_manager_->execute(
382  [this](const moveit_controller_manager::ExecutionStatus& status) { doneWithTrajectoryExecution(status); },
383  [this, &plan](std::size_t index) { successfulTrajectorySegmentExecution(plan, index); });
384  // wait for path to be done, while checking that the path does not become invalid
385  ros::Rate r(100);
386  path_became_invalid_ = false;
387  bool preempt_requested = false;
388 
389  while (node_handle_.ok() && !execution_complete_ && !path_became_invalid_)
390  {
391  r.sleep();
392  // check the path if there was an environment update in the meantime
393  if (new_scene_update_)
394  {
395  new_scene_update_ = false;
396  std::pair<int, int> current_index = trajectory_execution_manager_->getCurrentExpectedTrajectoryIndex();
397  if (!isRemainingPathValid(plan, current_index))
398  {
399  ROS_WARN_NAMED("plan_execution", "Trajectory component '%s' is invalid after scene update",
400  plan.plan_components_[current_index.first].description_.c_str());
401  path_became_invalid_ = true;
402  break;
403  }
404  }
405 
406  preempt_requested = preempt_.checkAndClear();
407  if (preempt_requested)
408  break;
409  }
410 
411  // stop execution if needed
412  if (preempt_requested)
413  {
414  ROS_INFO_NAMED("plan_execution", "Stopping execution due to preempt request");
415  trajectory_execution_manager_->stopExecution();
416  }
417  else if (path_became_invalid_)
418  {
419  ROS_INFO_NAMED("plan_execution", "Stopping execution because the path to execute became invalid"
420  "(probably the environment changed)");
421  trajectory_execution_manager_->stopExecution();
422  }
423  else if (!execution_complete_)
424  {
425  ROS_WARN_NAMED("plan_execution", "Stopping execution due to unknown reason."
426  "Possibly the node is about to shut down.");
427  trajectory_execution_manager_->stopExecution();
428  }
429 
430  // stop recording trajectory states
431  if (trajectory_monitor_)
432  {
433  trajectory_monitor_->stopTrajectoryMonitor();
434  plan.executed_trajectory_ =
435  std::make_shared<robot_trajectory::RobotTrajectory>(planning_scene_monitor_->getRobotModel(), "");
436  trajectory_monitor_->swapTrajectory(*plan.executed_trajectory_);
437  }
438 
439  // decide return value
440  if (path_became_invalid_)
441  result.val = moveit_msgs::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE;
442  else
443  {
444  if (preempt_requested)
445  {
446  result.val = moveit_msgs::MoveItErrorCodes::PREEMPTED;
447  }
448  else
449  {
450  if (trajectory_execution_manager_->getLastExecutionStatus() ==
452  result.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
453  else if (trajectory_execution_manager_->getLastExecutionStatus() ==
455  result.val = moveit_msgs::MoveItErrorCodes::TIMED_OUT;
456  else
457  result.val = moveit_msgs::MoveItErrorCodes::CONTROL_FAILED;
458  }
459  }
460  return result;
461 }
462 
465 {
468  new_scene_update_ = true;
469 }
470 
473 {
474  execution_complete_ = true;
475 }
476 
478  std::size_t index)
479 {
480  if (plan.plan_components_.empty())
481  {
482  ROS_WARN_NAMED("plan_execution", "Length of provided motion plan is zero.");
483  return;
484  }
485 
486  // if any side-effects are associated to the trajectory part that just completed, execute them
487  ROS_DEBUG_NAMED("plan_execution", "Completed '%s'", plan.plan_components_[index].description_.c_str());
488  if (plan.plan_components_[index].effect_on_success_)
489  if (!plan.plan_components_[index].effect_on_success_(&plan))
490  {
491  // execution of side-effect failed
492  ROS_ERROR_NAMED("plan_execution", "Execution of path-completion side-effect failed. Preempting.");
493  preempt_.request();
494  return;
495  }
496 
497  // if there is a next trajectory, check it for validity, before we start execution
498  ++index;
499  if (index < plan.plan_components_.size() && plan.plan_components_[index].trajectory_ &&
500  !plan.plan_components_[index].trajectory_->empty())
501  {
502  std::pair<int, int> next_index(static_cast<int>(index), 0);
503  if (!isRemainingPathValid(plan, next_index))
504  {
505  ROS_INFO_NAMED("plan_execution", "Upcoming trajectory component '%s' is invalid",
506  plan.plan_components_[next_index.first].description_.c_str());
507  path_became_invalid_ = true;
508  }
509  }
510 }
plan_execution::ExecutableMotionPlan::planning_scene_
planning_scene::PlanningSceneConstPtr planning_scene_
Definition: plan_representation.h:108
plan_execution::PlanExecution::~PlanExecution
~PlanExecution()
Definition: plan_execution.cpp:98
planning_scene_monitor
Definition: current_state_monitor.h:47
plan_execution::ExecutableMotionPlan::executed_trajectory_
robot_trajectory::RobotTrajectoryPtr executed_trajectory_
The trace of the trajectory recorded during execution.
Definition: plan_representation.h:113
plan_execution::PlanExecution::reconfigure_impl_
DynamicReconfigureImpl * reconfigure_impl_
Definition: plan_execution.h:213
plan_execution::ExecutableMotionPlan::planning_scene_monitor_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
Definition: plan_representation.h:107
collision_tools.h
ros
plan_execution::PlanExecution::Options
Definition: plan_execution.h:89
plan_execution::PlanExecution::Options::replan_
bool replan_
Flag indicating whether replanning is allowed.
Definition: plan_execution.h:96
moveit_controller_manager::ExecutionStatus::TIMED_OUT
TIMED_OUT
moveit::core::MoveItErrorCode::toString
static const char * toString(const moveit_msgs::MoveItErrorCodes &error_code)
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
plan_execution::PlanExecution::default_max_replan_attempts_
unsigned int default_max_replan_attempts_
Definition: plan_execution.h:187
robot_trajectory::RobotTrajectory
collision_detection::CollisionRequest
plan_execution::PlanExecution::DynamicReconfigureImpl
Definition: plan_execution.cpp:84
plan_execution::PlanExecution::new_scene_update_
bool new_scene_update_
Definition: plan_execution.h:208
planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType
SceneUpdateType
Definition: planning_scene_monitor.h:96
collision_detection::AllowedCollisionMatrix
message_checks.h
plan_execution::PlanExecution::trajectory_execution_manager_
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_
Definition: plan_execution.h:184
moveit::core::isEmpty
bool isEmpty(const geometry_msgs::Pose &msg)
plan_execution::PlanExecution::planAndExecuteHelper
void planAndExecuteHelper(ExecutableMotionPlan &plan, const Options &opt)
Definition: plan_execution.cpp:134
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
plan_execution::ExecutableMotionPlan::plan_components_
std::vector< ExecutableTrajectory > plan_components_
Definition: plan_representation.h:110
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
collision_detection::CollisionResult
moveit_controller_manager::ExecutionStatus::SUCCEEDED
SUCCEEDED
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
collision_detection::CollisionRequest::verbose
bool verbose
collision_detection::CollisionRequest::group_name
std::string group_name
plan_execution.h
plan_execution::PlanExecution::Options::repair_plan_callback_
boost::function< bool(ExecutableMotionPlan &plan_to_update, const std::pair< int, int > &trajectory_index)> repair_plan_callback_
Definition: plan_execution.h:118
d
d
prev
EndPoint * prev[3]
plan_execution::PlanExecution::doneWithTrajectoryExecution
void doneWithTrajectoryExecution(const moveit_controller_manager::ExecutionStatus &status)
Definition: plan_execution.cpp:471
plan_execution::PlanExecution::Options::plan_callback_
ExecutableMotionPlanComputationFn plan_callback_
Callback for computing motion plans. This callback must always be specified.
Definition: plan_execution.h:106
plan_execution::PlanExecution::Options::replan_delay_
double replan_delay_
The amount of time to wait in between replanning attempts (in seconds)
Definition: plan_execution.h:103
plan_execution::PlanExecution::Options::before_plan_callback_
boost::function< void()> before_plan_callback_
Definition: plan_execution.h:120
r
S r
plan_execution::PlanExecution::Options::replan_attempts_
unsigned int replan_attempts_
Definition: plan_execution.h:100
plan_execution::ExecutableMotionPlan::error_code_
moveit_msgs::MoveItErrorCodes error_code_
An error code reflecting what went wrong (if anything)
Definition: plan_representation.h:116
plan_execution::PlanExecution::planningSceneUpdatedCallback
void planningSceneUpdatedCallback(const planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
Definition: plan_execution.cpp:463
plan_execution::PlanExecution::Options::done_callback_
boost::function< void()> done_callback_
Definition: plan_execution.h:122
plan_execution
This namespace includes functionality specific to the execution and monitoring of motion plans.
Definition: plan_execution.h:50
plan_execution::PlanExecution::planning_scene_monitor_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
Definition: plan_execution.h:183
plan_execution::PlanExecution::stop
void stop()
Definition: plan_execution.cpp:103
plan_execution::PlanExecution::Options::before_execution_callback_
boost::function< void()> before_execution_callback_
Definition: plan_execution.h:121
plan_execution::ExecutableMotionPlan
A generic representation on what a computed motion plan looks like.
Definition: plan_representation.h:105
planning_scene_monitor::LockedPlanningSceneRO
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
Definition: planning_scene_monitor.h:643
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
index
unsigned int index
plan_execution::PlanExecution::executeAndMonitor
moveit_msgs::MoveItErrorCodes executeAndMonitor(ExecutableMotionPlan &plan, bool reset_preempted=true)
Execute and monitor a previously created plan.
Definition: plan_execution.cpp:287
planning_scene_monitor::PlanningSceneMonitor::UPDATE_GEOMETRY
@ UPDATE_GEOMETRY
The geometry of the scene was updated. This includes receiving new octomaps, collision objects,...
Definition: planning_scene_monitor.h:109
plan_execution::PlanExecution::PlanExecution
PlanExecution(const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor, const trajectory_execution_manager::TrajectoryExecutionManagerPtr &trajectory_execution)
Definition: plan_execution.cpp:74
collision_detection::CollisionResult::collision
bool collision
conversions.h
ros::Rate
plan_execution::PlanExecution::planAndExecute
void planAndExecute(ExecutableMotionPlan &plan, const Options &opt)
Definition: plan_execution.cpp:108
ros::WallDuration
trajectory_tools.h
collision_detection::CollisionResult::clear
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
planning_scene_monitor::PlanningSceneMonitor::UPDATE_TRANSFORMS
@ UPDATE_TRANSFORMS
The maintained set of fixed transforms in the monitored scene was updated.
Definition: planning_scene_monitor.h:105
moveit_controller_manager::ExecutionStatus
t
geometry_msgs::TransformStamped t
plan_execution::PlanExecution::successfulTrajectorySegmentExecution
void successfulTrajectorySegmentExecution(const ExecutableMotionPlan &plan, std::size_t index)
Definition: plan_execution.cpp:477
moveit_error_code.h
plan_execution::PlanExecution::isRemainingPathValid
bool isRemainingPathValid(const ExecutableMotionPlan &plan, const std::pair< int, int > &path_segment)
Definition: plan_execution.cpp:245


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sat Apr 27 2024 02:26:03