Classes | Public Member Functions | Private Member Functions | Private Attributes
plan_execution::PlanExecution Class Reference

#include <plan_execution.h>

List of all members.

Classes

class  DynamicReconfigureImpl
struct  Options

Public Member Functions

std::string getErrorCodeString (const moveit_msgs::MoveItErrorCodes &error_code)
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 Options &opt)
void planAndExecute (ExecutableMotionPlan &plan, const moveit_msgs::PlanningScene &scene_diff, 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)
moveit_msgs::MoveItErrorCodes executeAndMonitor (const ExecutableMotionPlan &plan)
bool isRemainingPathValid (const ExecutableMotionPlan &plan)
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_
bool preempt_requested_
DynamicReconfigureImplreconfigure_impl_
trajectory_execution_manager::TrajectoryExecutionManagerPtr trajectory_execution_manager_
planning_scene_monitor::TrajectoryMonitorPtr trajectory_monitor_

Detailed Description

Definition at line 52 of file plan_execution.h.


Constructor & Destructor Documentation

Definition at line 74 of file plan_execution.cpp.

Definition at line 94 of file plan_execution.cpp.


Member Function Documentation

Definition at line 458 of file plan_execution.cpp.

moveit_msgs::MoveItErrorCodes plan_execution::PlanExecution::executeAndMonitor ( const ExecutableMotionPlan plan) [private]

Definition at line 309 of file plan_execution.cpp.

std::string plan_execution::PlanExecution::getErrorCodeString ( const moveit_msgs::MoveItErrorCodes &  error_code)

Definition at line 104 of file plan_execution.cpp.

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

Definition at line 122 of file plan_execution.h.

Definition at line 93 of file plan_execution.h.

Definition at line 98 of file plan_execution.h.

Definition at line 103 of file plan_execution.h.

Definition at line 264 of file plan_execution.cpp.

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

Definition at line 271 of file plan_execution.cpp.

Definition at line 144 of file plan_execution.cpp.

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

Definition at line 151 of file plan_execution.cpp.

Definition at line 166 of file plan_execution.cpp.

Definition at line 452 of file plan_execution.cpp.

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

Definition at line 117 of file plan_execution.h.

Definition at line 111 of file plan_execution.h.

Definition at line 99 of file plan_execution.cpp.

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

Definition at line 463 of file plan_execution.cpp.


Member Data Documentation

Definition at line 150 of file plan_execution.h.

Definition at line 155 of file plan_execution.h.

Definition at line 153 of file plan_execution.h.

Definition at line 145 of file plan_execution.h.

Definition at line 156 of file plan_execution.h.

Definition at line 146 of file plan_execution.h.

Definition at line 152 of file plan_execution.h.

Definition at line 158 of file plan_execution.h.

Definition at line 147 of file plan_execution.h.

Definition at line 148 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 Wed Aug 26 2015 12:43:31