Go to the documentation of this file.
85 boost::function<bool(
ExecutableMotionPlan& plan_to_update,
const std::pair<int, int>& trajectory_index)>
94 const trajectory_execution_manager::TrajectoryExecutionManagerPtr& trajectory_execution);
166 inline bool checkAndClear()
170 inline void request()
181 class DynamicReconfigureImpl;
DynamicReconfigureImpl * reconfigure_impl_
double getTrajectoryStateRecordingFrequency() const
MOVEIT_CLASS_FORWARD(PlanExecution)
void setMaxReplanAttempts(unsigned int attempts)
std::atomic< bool > preemption_requested
bool replan_
Flag indicating whether replanning is allowed.
unsigned int default_max_replan_attempts_
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_
void planAndExecuteHelper(ExecutableMotionPlan &plan, const Options &opt)
boost::function< bool(ExecutableMotionPlan &plan_to_update, const std::pair< int, int > &trajectory_index)> repair_plan_callback_
void doneWithTrajectoryExecution(const moveit_controller_manager::ExecutionStatus &status)
ExecutableMotionPlanComputationFn plan_callback_
Callback for computing motion plans. This callback must always be specified.
double replan_delay_
The amount of time to wait in between replanning attempts (in seconds)
boost::function< void()> before_plan_callback_
planning_scene_monitor::TrajectoryMonitorPtr trajectory_monitor_
unsigned int replan_attempts_
void planningSceneUpdatedCallback(const planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
boost::function< void()> done_callback_
ros::NodeHandle node_handle_
This namespace includes functionality specific to the execution and monitoring of motion plans.
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
void setTrajectoryStateRecordingFrequency(double freq)
boost::function< void()> before_execution_callback_
A generic representation on what a computed motion plan looks like.
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor() const
moveit_msgs::MoveItErrorCodes executeAndMonitor(ExecutableMotionPlan &plan, bool reset_preempted=true)
Execute and monitor a previously created plan.
PlanExecution(const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor, const trajectory_execution_manager::TrajectoryExecutionManagerPtr &trajectory_execution)
class plan_execution::PlanExecution::@0 preempt_
void planAndExecute(ExecutableMotionPlan &plan, const Options &opt)
unsigned int getMaxReplanAttempts() const
boost::function< bool(ExecutableMotionPlan &)> ExecutableMotionPlanComputationFn
The signature of a function that can compute a motion plan.
bool path_became_invalid_
void successfulTrajectorySegmentExecution(const ExecutableMotionPlan &plan, std::size_t index)
const trajectory_execution_manager::TrajectoryExecutionManagerPtr & getTrajectoryExecutionManager() const
bool isRemainingPathValid(const ExecutableMotionPlan &plan, const std::pair< int, int > &path_segment)
planning
Author(s): Ioan Sucan
, Sachin Chitta
autogenerated on Tue Dec 24 2024 03:27:52