37 #ifndef MOVEIT_PLAN_EXECUTION_PLAN_EXECUTION_ 38 #define MOVEIT_PLAN_EXECUTION_PLAN_EXECUTION_ 84 boost::function<bool(ExecutableMotionPlan& plan_to_update, const std::pair<int, int>& trajectory_index)>
93 const trajectory_execution_manager::TrajectoryExecutionManagerPtr& trajectory_execution);
bool path_became_invalid_
unsigned int replan_attempts_
double getTrajectoryStateRecordingFrequency() const
void planAndExecuteHelper(ExecutableMotionPlan &plan, const Options &opt)
boost::function< bool(ExecutableMotionPlan &plan_to_update, const std::pair< int, int > &trajectory_index)> repair_plan_callback_
unsigned int getMaxReplanAttempts() const
planning_scene_monitor::TrajectoryMonitorPtr trajectory_monitor_
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_
void planningSceneUpdatedCallback(const planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
void setTrajectoryStateRecordingFrequency(double freq)
boost::function< bool(ExecutableMotionPlan &plan)> ExecutableMotionPlanComputationFn
The signature of a function that can compute a motion plan.
ros::NodeHandle node_handle_
void planAndExecute(ExecutableMotionPlan &plan, const Options &opt)
boost::function< void()> done_callback_
ExecutableMotionPlanComputationFn plan_callback_
Callback for computing motion plans. This callback must always be specified.
boost::function< void()> before_plan_callback_
PlanExecution(const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor, const trajectory_execution_manager::TrajectoryExecutionManagerPtr &trajectory_execution)
double replan_delay_
The amount of time to wait in between replanning attempts (in seconds)
bool isRemainingPathValid(const ExecutableMotionPlan &plan)
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
bool replan_
Flag indicating whether replanning is allowed.
void setMaxReplanAttempts(unsigned int attempts)
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor() const
This namespace includes functionality specific to the execution and monitoring of motion plans...
MOVEIT_CLASS_FORWARD(PlanExecution)
A generic representation on what a computed motion plan looks like.
void successfulTrajectorySegmentExecution(const ExecutableMotionPlan *plan, std::size_t index)
unsigned int default_max_replan_attempts_
boost::function< void()> before_execution_callback_
const trajectory_execution_manager::TrajectoryExecutionManagerPtr & getTrajectoryExecutionManager() const
DynamicReconfigureImpl * reconfigure_impl_
std::string getErrorCodeString(const moveit_msgs::MoveItErrorCodes &error_code)
void doneWithTrajectoryExecution(const moveit_controller_manager::ExecutionStatus &status)
moveit_msgs::MoveItErrorCodes executeAndMonitor(ExecutableMotionPlan &plan)
Execute and monitor a previously created plan.