44#include <pluginlib/class_loader.hpp>
45#include <rclcpp/logger.hpp>
85 std::function<bool(
ExecutableMotionPlan& plan_to_update,
const std::pair<int, int>& trajectory_index)>
95 const trajectory_execution_manager::TrajectoryExecutionManagerPtr& trajectory_execution);
100 return planning_scene_monitor_;
105 return trajectory_execution_manager_;
110 if (trajectory_monitor_)
112 return trajectory_monitor_->getSamplingFrequency();
122 if (trajectory_monitor_)
123 trajectory_monitor_->setSamplingFrequency(freq);
128 default_max_replan_attempts_ = attempts;
133 return default_max_replan_attempts_;
149 bool isRemainingPathValid(
const ExecutableMotionPlan& plan,
const std::pair<int, int>& path_segment);
155 const rclcpp::Node::SharedPtr node_;
156 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
157 trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_;
158 planning_scene_monitor::TrajectoryMonitorPtr trajectory_monitor_;
160 unsigned int default_max_replan_attempts_;
165 std::atomic<bool> preemption_requested_{
false };
171 inline bool checkAndClear()
173 return preemption_requested_.exchange(
false);
175 inline void request()
177 preemption_requested_.store(
true);
181 bool new_scene_update_;
183 bool execution_complete_;
184 bool path_became_invalid_;
186 rclcpp::Logger logger_;
#define MOVEIT_CLASS_FORWARD(C)
void planAndExecute(ExecutableMotionPlan &plan, const Options &opt)
double getTrajectoryStateRecordingFrequency() const
moveit_msgs::msg::MoveItErrorCodes executeAndMonitor(ExecutableMotionPlan &plan, bool reset_preempted=true)
Execute and monitor a previously created plan.
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor() const
const trajectory_execution_manager::TrajectoryExecutionManagerPtr & getTrajectoryExecutionManager() const
void setTrajectoryStateRecordingFrequency(double freq)
void setMaxReplanAttempts(unsigned int attempts)
unsigned int getMaxReplanAttempts() const
This namespace includes functionality specific to the execution and monitoring of motion plans.
std::function< bool(ExecutableMotionPlan &)> ExecutableMotionPlanComputationFn
The signature of a function that can compute a motion plan.
The reported execution status.
A generic representation on what a computed motion plan looks like.
double replan_delay
The amount of time to wait in between replanning attempts (in seconds)
unsigned int replan_attemps
ExecutableMotionPlanComputationFn plan_callback
Callback for computing motion plans. This callback must always be specified.
std::function< bool(ExecutableMotionPlan &plan_to_update, const std::pair< int, int > &trajectory_index)> repair_plan_callback_
std::function< void()> before_execution_callback_
bool replan
Flag indicating whether replanning is allowed.
std::function< void()> before_plan_callback_
std::function< void()> done_callback_