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>
81 const rclcpp::Node::SharedPtr& node,
const planning_scene_monitor::PlanningSceneMonitorPtr&
planning_scene_monitor,
82 const trajectory_execution_manager::TrajectoryExecutionManagerPtr& trajectory_execution)
85 , trajectory_execution_manager_(trajectory_execution)
86 , logger_(
moveit::
getLogger(
"moveit.ros.add_time_optimal_parameterization"))
88 if (!trajectory_execution_manager_)
90 trajectory_execution_manager_ = std::make_shared<trajectory_execution_manager::TrajectoryExecutionManager>(
91 node_, planning_scene_monitor_->getRobotModel(), planning_scene_monitor_->getStateMonitor());
94 default_max_replan_attempts_ = 5;
96 new_scene_update_ =
false;
99 planning_scene_monitor_->addUpdateCallback(
101 planningSceneUpdatedCallback(update_type);
120 plan.planning_scene_monitor = planning_scene_monitor_;
121 plan.planning_scene = planning_scene_monitor_->getPlanningScene();
122 planAndExecuteHelper(
plan, opt);
126 const moveit_msgs::msg::PlanningScene& scene_diff,
131 planAndExecute(
plan, opt);
135 plan.planning_scene_monitor = planning_scene_monitor_;
141 plan.planning_scene = lscene->diff(scene_diff);
143 planAndExecuteHelper(
plan, opt);
150 preempt_.checkAndClear();
152 bool preempt_requested =
false;
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;
165 RCLCPP_INFO(logger_,
"Planning attempt %u of at most %u", replan_attempts, max_replan_attempts);
167 if (opt.before_plan_callback_)
168 opt.before_plan_callback_();
170 new_scene_update_ =
false;
176 (!previously_solved || !opt.repair_plan_callback_) ?
177 opt.plan_callback(
plan) :
178 opt.repair_plan_callback_(
plan, trajectory_execution_manager_->getCurrentExpectedTrajectoryIndex());
180 preempt_requested = preempt_.checkAndClear();
181 if (preempt_requested)
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)
190 if (
plan.
error_code.val == moveit_msgs::msg::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA &&
191 opt.replan_delay > 0.0)
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));
202 previously_solved =
true;
209 if (
plan.
error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
211 if (opt.before_execution_callback_)
212 opt.before_execution_callback_();
214 preempt_requested = preempt_.checkAndClear();
215 if (preempt_requested)
222 if (
plan.
error_code.val == moveit_msgs::msg::MoveItErrorCodes::PREEMPTED)
223 preempt_requested =
true;
226 if (
plan.
error_code.val != moveit_msgs::msg::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE)
233 if (opt.replan_delay > 0.0)
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");
242 preempt_requested = preempt_.checkAndClear();
243 if (preempt_requested)
246 }
while (replan_attempts < max_replan_attempts);
248 if (preempt_requested)
250 RCLCPP_DEBUG(logger_,
"PlanExecution was preempted");
251 plan.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
254 if (opt.done_callback_)
255 opt.done_callback_();
257 if (
plan.
error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
259 RCLCPP_DEBUG(logger_,
"PlanExecution finished successfully.");
263 RCLCPP_DEBUG(logger_,
"PlanExecution terminating with error code %d - '%s'",
plan.
error_code.val,
268 bool plan_execution::PlanExecution::isRemainingPathValid(
const ExecutableMotionPlan&
plan,
269 const std::pair<int, int>& path_segment)
271 if (path_segment.first >= 0 &&
272 plan.plan_components[path_segment.first].trajectory_monitoring)
281 plan.plan_components[path_segment.first].allowed_collision_matrix.get();
286 for (std::size_t i = std::max(path_segment.second - 1, 0); i < wpc; ++i)
301 RCLCPP_INFO(logger_,
"Trajectory component '%s' is invalid",
302 plan.plan_components[path_segment.first].description.c_str());
324 bool reset_preempted)
327 preempt_.checkAndClear();
329 if (!
plan.planning_scene_monitor)
330 plan.planning_scene_monitor = planning_scene_monitor_;
331 if (!
plan.planning_scene)
332 plan.planning_scene = planning_scene_monitor_->getPlanningScene();
334 moveit_msgs::msg::MoveItErrorCodes result;
337 execution_complete_ =
true;
339 if (!trajectory_execution_manager_)
341 RCLCPP_ERROR(logger_,
"No trajectory execution manager");
342 result.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
346 if (
plan.plan_components.empty())
348 result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
352 execution_complete_ =
false;
356 for (
size_t component_idx = 0; component_idx <
plan.plan_components.size(); ++component_idx)
363 bool unwound =
false;
364 for (
int prev_component = component_idx - 1; prev_component >= 0; --prev_component)
373 plan.plan_components.at(component_idx)
387 plan.planning_scene_monitor &&
plan.planning_scene_monitor->getStateMonitor() ?
388 *
plan.planning_scene_monitor->getStateMonitor()->getCurrentState() :
389 plan.planning_scene->getCurrentState());
398 prev = component_idx;
401 moveit_msgs::msg::RobotTrajectory msg;
402 plan.plan_components[component_idx].
trajectory->getRobotTrajectoryMsg(msg);
403 if (!trajectory_execution_manager_->push(msg,
plan.plan_components[component_idx].controller_name))
405 trajectory_execution_manager_->clear();
406 RCLCPP_ERROR(logger_,
"Apparently trajectory initialization failed");
407 execution_complete_ =
true;
408 result.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
413 if (!trajectory_monitor_ && planning_scene_monitor_->getStateMonitor())
416 double sampling_frequency = 0.0;
417 node_->get_parameter_or(
"plan_execution.record_trajectory_state_frequency", sampling_frequency, 0.0);
418 trajectory_monitor_ = std::make_shared<planning_scene_monitor::TrajectoryMonitor>(
419 planning_scene_monitor_->getStateMonitor(), sampling_frequency);
423 if (trajectory_monitor_)
424 trajectory_monitor_->startTrajectoryMonitor();
427 trajectory_execution_manager_->execute(
429 [
this, &
plan](std::size_t index) { successfulTrajectorySegmentExecution(
plan, index); });
431 rclcpp::WallRate r(100);
432 path_became_invalid_ =
false;
433 bool preempt_requested =
false;
435 while (rclcpp::ok() && !execution_complete_ && !path_became_invalid_)
439 if (new_scene_update_)
441 new_scene_update_ =
false;
442 std::pair<int, int> current_index = trajectory_execution_manager_->getCurrentExpectedTrajectoryIndex();
443 if (!isRemainingPathValid(
plan, current_index))
445 RCLCPP_INFO(logger_,
"Trajectory component '%s' is invalid after scene update",
446 plan.plan_components[current_index.first].description.c_str());
447 path_became_invalid_ =
true;
452 preempt_requested = preempt_.checkAndClear();
453 if (preempt_requested)
458 if (preempt_requested)
460 RCLCPP_INFO(logger_,
"Stopping execution due to preempt request");
461 trajectory_execution_manager_->stopExecution();
463 else if (path_became_invalid_)
465 RCLCPP_INFO(logger_,
"Stopping execution because the path to execute became invalid"
466 "(probably the environment changed)");
467 trajectory_execution_manager_->stopExecution();
469 else if (!execution_complete_)
471 RCLCPP_WARN(logger_,
"Stopping execution due to unknown reason."
472 "Possibly the node is about to shut down.");
473 trajectory_execution_manager_->stopExecution();
477 if (trajectory_monitor_)
479 trajectory_monitor_->stopTrajectoryMonitor();
480 plan.executed_trajectory =
481 std::make_shared<robot_trajectory::RobotTrajectory>(planning_scene_monitor_->getRobotModel(),
"");
482 trajectory_monitor_->swapTrajectory(*
plan.executed_trajectory);
486 if (path_became_invalid_)
488 result.val = moveit_msgs::msg::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE;
492 if (preempt_requested)
494 result.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
498 if (trajectory_execution_manager_->getLastExecutionStatus() ==
501 result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
503 else if (trajectory_execution_manager_->getLastExecutionStatus() ==
506 result.val = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
510 result.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
517 void plan_execution::PlanExecution::planningSceneUpdatedCallback(
522 new_scene_update_ =
true;
525 void plan_execution::PlanExecution::doneWithTrajectoryExecution(
528 execution_complete_ =
true;
531 void plan_execution::PlanExecution::successfulTrajectorySegmentExecution(
const ExecutableMotionPlan&
plan,
534 if (
plan.plan_components.empty())
536 RCLCPP_WARN(logger_,
"Length of provided motion plan is zero.");
541 RCLCPP_DEBUG(logger_,
"Completed '%s'",
plan.plan_components[index].description.c_str());
542 if (
plan.plan_components[index].effect_on_success)
544 if (!
plan.plan_components[index].effect_on_success(&
plan))
547 RCLCPP_ERROR(logger_,
"Execution of path-completion side-effect failed. Preempting.");
558 std::pair<int, int> next_index(
static_cast<int>(index), 0);
559 if (!isRemainingPathValid(
plan, next_index))
561 RCLCPP_INFO(logger_,
"Upcoming trajectory component '%s' is invalid",
562 plan.plan_components[next_index.first].description.c_str());
563 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)
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
rclcpp::Logger getLogger()
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.
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.
bool pad_environment_collisions
If true, use padded collision environment.
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.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory