#include <plan_execution.h>
Classes | |
class | DynamicReconfigureImpl |
struct | Options |
Public Member Functions | |
moveit_msgs::MoveItErrorCodes | executeAndMonitor (ExecutableMotionPlan &plan) |
Execute and monitor a previously created plan. More... | |
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) |
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_ |
DynamicReconfigureImpl * | reconfigure_impl_ |
trajectory_execution_manager::TrajectoryExecutionManagerPtr | trajectory_execution_manager_ |
planning_scene_monitor::TrajectoryMonitorPtr | trajectory_monitor_ |
Definition at line 53 of file plan_execution.h.
plan_execution::PlanExecution::PlanExecution | ( | const planning_scene_monitor::PlanningSceneMonitorPtr & | planning_scene_monitor, |
const trajectory_execution_manager::TrajectoryExecutionManagerPtr & | trajectory_execution | ||
) |
Definition at line 72 of file plan_execution.cpp.
plan_execution::PlanExecution::~PlanExecution | ( | ) |
Definition at line 95 of file plan_execution.cpp.
|
private |
Definition at line 478 of file plan_execution.cpp.
moveit_msgs::MoveItErrorCodes plan_execution::PlanExecution::executeAndMonitor | ( | ExecutableMotionPlan & | plan | ) |
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 317 of file plan_execution.cpp.
std::string plan_execution::PlanExecution::getErrorCodeString | ( | const moveit_msgs::MoveItErrorCodes & | error_code | ) |
Definition at line 105 of file plan_execution.cpp.
|
inline |
Definition at line 125 of file plan_execution.h.
|
inline |
Definition at line 96 of file plan_execution.h.
|
inline |
Definition at line 101 of file plan_execution.h.
|
inline |
Definition at line 106 of file plan_execution.h.
|
private |
Definition at line 264 of file plan_execution.cpp.
|
private |
Definition at line 271 of file plan_execution.cpp.
void plan_execution::PlanExecution::planAndExecute | ( | ExecutableMotionPlan & | plan, |
const Options & | opt | ||
) |
Definition at line 134 of file plan_execution.cpp.
void plan_execution::PlanExecution::planAndExecute | ( | ExecutableMotionPlan & | plan, |
const moveit_msgs::PlanningScene & | scene_diff, | ||
const Options & | opt | ||
) |
Definition at line 141 of file plan_execution.cpp.
|
private |
Definition at line 160 of file plan_execution.cpp.
|
private |
Definition at line 470 of file plan_execution.cpp.
|
inline |
Definition at line 120 of file plan_execution.h.
|
inline |
Definition at line 114 of file plan_execution.h.
void plan_execution::PlanExecution::stop | ( | void | ) |
Definition at line 100 of file plan_execution.cpp.
|
private |
Definition at line 484 of file plan_execution.cpp.
|
private |
Definition at line 157 of file plan_execution.h.
|
private |
Definition at line 162 of file plan_execution.h.
|
private |
Definition at line 160 of file plan_execution.h.
|
private |
Definition at line 152 of file plan_execution.h.
|
private |
Definition at line 163 of file plan_execution.h.
|
private |
Definition at line 153 of file plan_execution.h.
|
private |
Definition at line 159 of file plan_execution.h.
|
private |
Definition at line 165 of file plan_execution.h.
|
private |
Definition at line 154 of file plan_execution.h.
|
private |
Definition at line 155 of file plan_execution.h.