43 #include <boost/algorithm/string/join.hpp>
45 #include <dynamic_reconfigure/server.h>
46 #include <moveit_ros_planning/PlanExecutionDynamicReconfigureConfig.h>
50 using namespace moveit_ros_planning;
52 class PlanExecution::DynamicReconfigureImpl
55 DynamicReconfigureImpl(PlanExecution* owner)
56 : owner_(owner), dynamic_reconfigure_server_(
ros::NodeHandle(
"~/plan_execution"))
58 dynamic_reconfigure_server_.setCallback(
59 [
this](
const auto& config, uint32_t level) { dynamicReconfigureCallback(config, level); });
63 void dynamicReconfigureCallback(
const PlanExecutionDynamicReconfigureConfig& config, uint32_t )
65 owner_->setMaxReplanAttempts(config.max_replan_attempts);
66 owner_->setTrajectoryStateRecordingFrequency(config.record_trajectory_state_frequency);
69 PlanExecution* owner_;
70 dynamic_reconfigure::Server<PlanExecutionDynamicReconfigureConfig> dynamic_reconfigure_server_;
76 const trajectory_execution_manager::TrajectoryExecutionManagerPtr& trajectory_execution)
79 , trajectory_execution_manager_(trajectory_execution)
100 delete reconfigure_impl_;
112 planAndExecuteHelper(plan, opt);
116 const moveit_msgs::PlanningScene& scene_diff,
const Options& opt)
119 planAndExecute(plan, opt);
130 planAndExecuteHelper(plan, opt);
137 preempt_.checkAndClear();
139 bool preempt_requested =
false;
142 unsigned int max_replan_attempts =
144 unsigned int replan_attempts = 0;
145 bool previously_solved =
false;
152 ROS_INFO_NAMED(
"plan_execution",
"Planning attempt %u of at most %u", replan_attempts, max_replan_attempts);
157 new_scene_update_ =
false;
167 preempt_requested = preempt_.checkAndClear();
168 if (preempt_requested)
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)
187 previously_solved =
true;
191 if (plan.
error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
196 preempt_requested = preempt_.checkAndClear();
197 if (preempt_requested)
204 if (plan.
error_code_.val == moveit_msgs::MoveItErrorCodes::PREEMPTED)
205 preempt_requested =
true;
208 if (plan.
error_code_.val != moveit_msgs::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE)
215 ROS_INFO_NAMED(
"plan_execution",
"Waiting for a %lf seconds before attempting a new plan ...",
223 preempt_requested = preempt_.checkAndClear();
224 if (preempt_requested)
227 }
while (replan_attempts < max_replan_attempts);
229 if (preempt_requested)
232 plan.
error_code_.val = moveit_msgs::MoveItErrorCodes::PREEMPTED;
238 if (plan.
error_code_.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
239 ROS_DEBUG_NAMED(
"plan_execution",
"PlanExecution finished successfully.");
246 const std::pair<int, int>& path_segment)
248 if (path_segment.first >= 0 &&
259 std::size_t wpc =
t.getWayPointCount();
262 for (std::size_t i = std::max(path_segment.second - 1, 0); i < wpc; ++i)
266 plan.
planning_scene_->checkCollisionUnpadded(req, res,
t.getWayPoint(i), *acm);
277 plan.
planning_scene_->checkCollisionUnpadded(req, res,
t.getWayPoint(i), *acm);
288 bool reset_preempted)
291 preempt_.checkAndClear();
298 moveit_msgs::MoveItErrorCodes result;
301 execution_complete_ =
true;
303 if (!trajectory_execution_manager_)
306 result.val = moveit_msgs::MoveItErrorCodes::CONTROL_FAILED;
312 result.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
316 execution_complete_ =
false;
327 bool unwound =
false;
328 for (std::size_t j = 0; j < i; ++j)
355 moveit_msgs::RobotTrajectory msg;
357 if (!trajectory_execution_manager_->push(msg, plan.
plan_components_[i].controller_names_))
359 trajectory_execution_manager_->clear();
361 execution_complete_ =
true;
362 result.val = moveit_msgs::MoveItErrorCodes::CONTROL_FAILED;
367 if (!trajectory_monitor_ && planning_scene_monitor_->getStateMonitor())
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);
377 if (trajectory_monitor_)
378 trajectory_monitor_->startTrajectoryMonitor();
381 trajectory_execution_manager_->execute(
383 [
this, &plan](std::size_t
index) { successfulTrajectorySegmentExecution(plan,
index); });
386 path_became_invalid_ =
false;
387 bool preempt_requested =
false;
389 while (node_handle_.ok() && !execution_complete_ && !path_became_invalid_)
393 if (new_scene_update_)
395 new_scene_update_ =
false;
396 std::pair<int, int> current_index = trajectory_execution_manager_->getCurrentExpectedTrajectoryIndex();
397 if (!isRemainingPathValid(plan, current_index))
399 ROS_WARN_NAMED(
"plan_execution",
"Trajectory component '%s' is invalid after scene update",
401 path_became_invalid_ =
true;
406 preempt_requested = preempt_.checkAndClear();
407 if (preempt_requested)
412 if (preempt_requested)
414 ROS_INFO_NAMED(
"plan_execution",
"Stopping execution due to preempt request");
415 trajectory_execution_manager_->stopExecution();
417 else if (path_became_invalid_)
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();
423 else if (!execution_complete_)
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();
431 if (trajectory_monitor_)
433 trajectory_monitor_->stopTrajectoryMonitor();
435 std::make_shared<robot_trajectory::RobotTrajectory>(planning_scene_monitor_->getRobotModel(),
"");
440 if (path_became_invalid_)
441 result.val = moveit_msgs::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE;
444 if (preempt_requested)
446 result.val = moveit_msgs::MoveItErrorCodes::PREEMPTED;
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;
457 result.val = moveit_msgs::MoveItErrorCodes::CONTROL_FAILED;
468 new_scene_update_ =
true;
474 execution_complete_ =
true;
482 ROS_WARN_NAMED(
"plan_execution",
"Length of provided motion plan is zero.");
492 ROS_ERROR_NAMED(
"plan_execution",
"Execution of path-completion side-effect failed. Preempting.");
502 std::pair<int, int> next_index(
static_cast<int>(
index), 0);
503 if (!isRemainingPathValid(plan, next_index))
505 ROS_INFO_NAMED(
"plan_execution",
"Upcoming trajectory component '%s' is invalid",
507 path_became_invalid_ =
true;