45 #include <pluginlib/class_loader.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_)
111 return trajectory_monitor_->getSamplingFrequency();
118 if (trajectory_monitor_)
119 trajectory_monitor_->setSamplingFrequency(freq);
124 default_max_replan_attempts_ = attempts;
129 return default_max_replan_attempts_;
153 const rclcpp::Node::SharedPtr node_;
154 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
155 trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_;
156 planning_scene_monitor::TrajectoryMonitorPtr trajectory_monitor_;
158 unsigned int default_max_replan_attempts_;
163 std::atomic<bool> preemption_requested{
false };
169 inline bool checkAndClear()
171 return preemption_requested.exchange(
false);
173 inline void request()
175 preemption_requested.store(
true);
179 bool new_scene_update_;
181 bool execution_complete_;
182 bool path_became_invalid_;
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor() const
void planAndExecute(ExecutableMotionPlan &plan, const Options &opt)
std::string getErrorCodeString(const moveit_msgs::msg::MoveItErrorCodes &error_code)
double getTrajectoryStateRecordingFrequency() const
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.
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.
MOVEIT_CLASS_FORWARD(PlanExecution)
The reported execution status.
A generic representation on what a computed motion plan looks like.
unsigned int replan_attempts_
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_
double replan_delay_
The amount of time to wait in between replanning attempts (in seconds)
std::function< void()> before_plan_callback_
bool replan_
Flag indicating whether replanning is allowed.
std::function< void()> done_callback_