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>
55 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.plan_execution");
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)
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());
88 default_max_replan_attempts_ = 5;
90 new_scene_update_ =
false;
93 planning_scene_monitor_->addUpdateCallback(
95 planningSceneUpdatedCallback(update_type);
114 if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::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)
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";
143 plan.planning_scene_monitor_ = planning_scene_monitor_;
144 plan.planning_scene_ = planning_scene_monitor_->getPlanningScene();
145 planAndExecuteHelper(
plan,
opt);
149 const moveit_msgs::msg::PlanningScene& scene_diff,
156 plan.planning_scene_monitor_ = planning_scene_monitor_;
162 plan.planning_scene_ = lscene->diff(scene_diff);
164 planAndExecuteHelper(
plan,
opt);
171 preempt_.checkAndClear();
173 bool preempt_requested =
false;
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;
186 RCLCPP_INFO(LOGGER,
"Planning attempt %u of at most %u", replan_attempts, max_replan_attempts);
188 if (
opt.before_plan_callback_)
189 opt.before_plan_callback_();
191 new_scene_update_ =
false;
197 (!previously_solved || !
opt.repair_plan_callback_) ?
199 opt.repair_plan_callback_(
plan, trajectory_execution_manager_->getCurrentExpectedTrajectoryIndex());
201 preempt_requested = preempt_.checkAndClear();
202 if (preempt_requested)
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)
211 if (
plan.error_code_.val == moveit_msgs::msg::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA &&
212 opt.replan_delay_ > 0.0)
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));
222 previously_solved =
true;
226 if (
plan.error_code_.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
228 if (
opt.before_execution_callback_)
229 opt.before_execution_callback_();
231 preempt_requested = preempt_.checkAndClear();
232 if (preempt_requested)
236 plan.error_code_ = executeAndMonitor(
plan,
false);
239 if (
plan.error_code_.val == moveit_msgs::msg::MoveItErrorCodes::PREEMPTED)
240 preempt_requested =
true;
243 if (
plan.error_code_.val != moveit_msgs::msg::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE)
248 if (
opt.replan_delay_ > 0.0)
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");
257 preempt_requested = preempt_.checkAndClear();
258 if (preempt_requested)
261 }
while (replan_attempts < max_replan_attempts);
263 if (preempt_requested)
265 RCLCPP_DEBUG(LOGGER,
"PlanExecution was preempted");
266 plan.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
269 if (
opt.done_callback_)
270 opt.done_callback_();
272 if (
plan.error_code_.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
274 RCLCPP_DEBUG(LOGGER,
"PlanExecution finished successfully.");
278 RCLCPP_DEBUG(LOGGER,
"PlanExecution terminating with error code %d - '%s'",
plan.error_code_.val,
279 getErrorCodeString(
plan.error_code_).c_str());
283 bool plan_execution::PlanExecution::isRemainingPathValid(
const ExecutableMotionPlan&
plan,
284 const std::pair<int, int>& path_segment)
286 if (path_segment.first >= 0 &&
287 plan.plan_components_[path_segment.first].trajectory_monitoring_)
296 plan.plan_components_[path_segment.first].allowed_collision_matrix_.get();
300 for (std::size_t i = std::max(path_segment.second - 1, 0); i < wpc; ++i)
304 plan.planning_scene_->checkCollisionUnpadded(req, res, t.
getWayPoint(i), *acm);
306 plan.planning_scene_->checkCollisionUnpadded(req, res, t.
getWayPoint(i));
311 RCLCPP_INFO(LOGGER,
"Trajectory component '%s' is invalid",
312 plan.plan_components_[path_segment.first].description_.c_str());
319 plan.planning_scene_->checkCollisionUnpadded(req, res, t.
getWayPoint(i), *acm);
321 plan.planning_scene_->checkCollisionUnpadded(req, res, t.
getWayPoint(i));
330 bool reset_preempted)
333 preempt_.checkAndClear();
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();
340 moveit_msgs::msg::MoveItErrorCodes result;
343 execution_complete_ =
true;
345 if (!trajectory_execution_manager_)
347 RCLCPP_ERROR(LOGGER,
"No trajectory execution manager");
348 result.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
352 if (
plan.plan_components_.empty())
354 result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
358 execution_complete_ =
false;
362 for (std::size_t i = 0; i <
plan.plan_components_.size(); ++i)
369 bool unwound =
false;
370 for (std::size_t j = 0; j < i; ++j)
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())
376 plan.plan_components_[i].trajectory_->unwind(
plan.plan_components_[j].trajectory_->getLastWayPoint());
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());
390 plan.plan_components_[i].trajectory_->unwind(
plan.plan_components_[prev].trajectory_->getLastWayPoint());
393 if (
plan.plan_components_[i].trajectory_ && !
plan.plan_components_[i].trajectory_->empty())
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_))
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;
409 if (!trajectory_monitor_ && planning_scene_monitor_->getStateMonitor())
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);
419 if (trajectory_monitor_)
420 trajectory_monitor_->startTrajectoryMonitor();
423 trajectory_execution_manager_->execute(
425 [
this, &
plan](std::size_t index) { successfulTrajectorySegmentExecution(
plan, index); });
427 rclcpp::WallRate
r(100);
428 path_became_invalid_ =
false;
429 bool preempt_requested =
false;
431 while (rclcpp::ok() && !execution_complete_ && !path_became_invalid_)
435 if (new_scene_update_)
437 new_scene_update_ =
false;
438 std::pair<int, int> current_index = trajectory_execution_manager_->getCurrentExpectedTrajectoryIndex();
439 if (!isRemainingPathValid(
plan, current_index))
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;
448 preempt_requested = preempt_.checkAndClear();
449 if (preempt_requested)
454 if (preempt_requested)
456 RCLCPP_INFO(LOGGER,
"Stopping execution due to preempt request");
457 trajectory_execution_manager_->stopExecution();
459 else if (path_became_invalid_)
461 RCLCPP_INFO(LOGGER,
"Stopping execution because the path to execute became invalid"
462 "(probably the environment changed)");
463 trajectory_execution_manager_->stopExecution();
465 else if (!execution_complete_)
467 RCLCPP_WARN(LOGGER,
"Stopping execution due to unknown reason."
468 "Possibly the node is about to shut down.");
469 trajectory_execution_manager_->stopExecution();
473 if (trajectory_monitor_)
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_);
482 if (path_became_invalid_)
483 result.val = moveit_msgs::msg::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE;
486 if (preempt_requested)
488 result.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
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;
499 result.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
505 void plan_execution::PlanExecution::planningSceneUpdatedCallback(
510 new_scene_update_ =
true;
513 void plan_execution::PlanExecution::doneWithTrajectoryExecution(
516 execution_complete_ =
true;
519 void plan_execution::PlanExecution::successfulTrajectorySegmentExecution(
const ExecutableMotionPlan&
plan,
522 if (
plan.plan_components_.empty())
524 RCLCPP_WARN(LOGGER,
"Length of provided motion plan is zero.");
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))
534 RCLCPP_ERROR(LOGGER,
"Execution of path-completion side-effect failed. Preempting.");
541 if (index <
plan.plan_components_.size() &&
plan.plan_components_[index].trajectory_ &&
542 !
plan.plan_components_[index].trajectory_->empty())
544 std::pair<int, int> next_index(
static_cast<int>(index), 0);
545 if (!isRemainingPathValid(
plan, next_index))
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;
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
std::size_t getWayPointCount() 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.
const rclcpp::Logger LOGGER
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.
The reported execution status.
A generic representation on what a computed motion plan looks like.