Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
plan_execution::PlanExecution Class Reference

#include <plan_execution.h>

Classes

class  DynamicReconfigureImpl
 
struct  Options
 

Public Member Functions

moveit_msgs::MoveItErrorCodes executeAndMonitor (ExecutableMotionPlan &plan, bool reset_preempted=true)
 Execute and monitor a previously created plan. More...
 
unsigned int getMaxReplanAttempts () const
 
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor () const
 
const trajectory_execution_manager::TrajectoryExecutionManagerPtr & getTrajectoryExecutionManager () const
 
double getTrajectoryStateRecordingFrequency () const
 
void planAndExecute (ExecutableMotionPlan &plan, const moveit_msgs::PlanningScene &scene_diff, const Options &opt)
 
void planAndExecute (ExecutableMotionPlan &plan, const Options &opt)
 
 PlanExecution (const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor, const trajectory_execution_manager::TrajectoryExecutionManagerPtr &trajectory_execution)
 
void setMaxReplanAttempts (unsigned int attempts)
 
void setTrajectoryStateRecordingFrequency (double freq)
 
void stop ()
 
 ~PlanExecution ()
 

Private Member Functions

void doneWithTrajectoryExecution (const moveit_controller_manager::ExecutionStatus &status)
 
bool isRemainingPathValid (const ExecutableMotionPlan &plan, const std::pair< int, int > &path_segment)
 
void planAndExecuteHelper (ExecutableMotionPlan &plan, const Options &opt)
 
void planningSceneUpdatedCallback (const planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type)
 
void successfulTrajectorySegmentExecution (const ExecutableMotionPlan &plan, std::size_t index)
 

Private Attributes

unsigned int default_max_replan_attempts_
 
bool execution_complete_
 
bool new_scene_update_
 
ros::NodeHandle node_handle_
 
bool path_became_invalid_
 
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
 
class {
   std::atomic< bool >   preemption_requested { false }
 
preempt_
 
DynamicReconfigureImplreconfigure_impl_
 
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_
 
planning_scene_monitor::TrajectoryMonitorPtr trajectory_monitor_
 

Detailed Description

Definition at line 86 of file plan_execution.h.

Constructor & Destructor Documentation

◆ PlanExecution()

plan_execution::PlanExecution::PlanExecution ( const planning_scene_monitor::PlanningSceneMonitorPtr &  planning_scene_monitor,
const trajectory_execution_manager::TrajectoryExecutionManagerPtr &  trajectory_execution 
)

Definition at line 74 of file plan_execution.cpp.

◆ ~PlanExecution()

plan_execution::PlanExecution::~PlanExecution ( )

Definition at line 98 of file plan_execution.cpp.

Member Function Documentation

◆ doneWithTrajectoryExecution()

void plan_execution::PlanExecution::doneWithTrajectoryExecution ( const moveit_controller_manager::ExecutionStatus status)
private

Definition at line 471 of file plan_execution.cpp.

◆ executeAndMonitor()

moveit_msgs::MoveItErrorCodes plan_execution::PlanExecution::executeAndMonitor ( ExecutableMotionPlan plan,
bool  reset_preempted = true 
)

Execute and monitor a previously created plan.

In case there is no planning_scene or planning_scene_monitor set in the plan they will be set at the start of the method. They are then used to monitor the execution.

Definition at line 287 of file plan_execution.cpp.

◆ getMaxReplanAttempts()

unsigned int plan_execution::PlanExecution::getMaxReplanAttempts ( ) const
inline

Definition at line 158 of file plan_execution.h.

◆ getPlanningSceneMonitor()

const planning_scene_monitor::PlanningSceneMonitorPtr& plan_execution::PlanExecution::getPlanningSceneMonitor ( ) const
inline

Definition at line 129 of file plan_execution.h.

◆ getTrajectoryExecutionManager()

const trajectory_execution_manager::TrajectoryExecutionManagerPtr& plan_execution::PlanExecution::getTrajectoryExecutionManager ( ) const
inline

Definition at line 134 of file plan_execution.h.

◆ getTrajectoryStateRecordingFrequency()

double plan_execution::PlanExecution::getTrajectoryStateRecordingFrequency ( ) const
inline

Definition at line 139 of file plan_execution.h.

◆ isRemainingPathValid()

bool plan_execution::PlanExecution::isRemainingPathValid ( const ExecutableMotionPlan plan,
const std::pair< int, int > &  path_segment 
)
private

Definition at line 245 of file plan_execution.cpp.

◆ planAndExecute() [1/2]

void plan_execution::PlanExecution::planAndExecute ( ExecutableMotionPlan plan,
const moveit_msgs::PlanningScene &  scene_diff,
const Options opt 
)

Definition at line 115 of file plan_execution.cpp.

◆ planAndExecute() [2/2]

void plan_execution::PlanExecution::planAndExecute ( ExecutableMotionPlan plan,
const Options opt 
)

Definition at line 108 of file plan_execution.cpp.

◆ planAndExecuteHelper()

void plan_execution::PlanExecution::planAndExecuteHelper ( ExecutableMotionPlan plan,
const Options opt 
)
private

Definition at line 134 of file plan_execution.cpp.

◆ planningSceneUpdatedCallback()

void plan_execution::PlanExecution::planningSceneUpdatedCallback ( const planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType  update_type)
private

Definition at line 463 of file plan_execution.cpp.

◆ setMaxReplanAttempts()

void plan_execution::PlanExecution::setMaxReplanAttempts ( unsigned int  attempts)
inline

Definition at line 153 of file plan_execution.h.

◆ setTrajectoryStateRecordingFrequency()

void plan_execution::PlanExecution::setTrajectoryStateRecordingFrequency ( double  freq)
inline

Definition at line 147 of file plan_execution.h.

◆ stop()

void plan_execution::PlanExecution::stop ( )

Definition at line 103 of file plan_execution.cpp.

◆ successfulTrajectorySegmentExecution()

void plan_execution::PlanExecution::successfulTrajectorySegmentExecution ( const ExecutableMotionPlan plan,
std::size_t  index 
)
private

Definition at line 477 of file plan_execution.cpp.

Member Data Documentation

◆ default_max_replan_attempts_

unsigned int plan_execution::PlanExecution::default_max_replan_attempts_
private

Definition at line 187 of file plan_execution.h.

◆ execution_complete_

bool plan_execution::PlanExecution::execution_complete_
private

Definition at line 210 of file plan_execution.h.

◆ new_scene_update_

bool plan_execution::PlanExecution::new_scene_update_
private

Definition at line 208 of file plan_execution.h.

◆ node_handle_

ros::NodeHandle plan_execution::PlanExecution::node_handle_
private

Definition at line 182 of file plan_execution.h.

◆ path_became_invalid_

bool plan_execution::PlanExecution::path_became_invalid_
private

Definition at line 211 of file plan_execution.h.

◆ planning_scene_monitor_

planning_scene_monitor::PlanningSceneMonitorPtr plan_execution::PlanExecution::planning_scene_monitor_
private

Definition at line 183 of file plan_execution.h.

◆ preempt_

class { ... } plan_execution::PlanExecution::preempt_

◆ preemption_requested

std::atomic<bool> plan_execution::PlanExecution::preemption_requested { false }
private

Definition at line 192 of file plan_execution.h.

◆ reconfigure_impl_

DynamicReconfigureImpl* plan_execution::PlanExecution::reconfigure_impl_
private

Definition at line 213 of file plan_execution.h.

◆ trajectory_execution_manager_

trajectory_execution_manager::TrajectoryExecutionManagerPtr plan_execution::PlanExecution::trajectory_execution_manager_
private

Definition at line 184 of file plan_execution.h.

◆ trajectory_monitor_

planning_scene_monitor::TrajectoryMonitorPtr plan_execution::PlanExecution::trajectory_monitor_
private

Definition at line 185 of file plan_execution.h.


The documentation for this class was generated from the following files:


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sun Mar 3 2024 03:24:16