#include <plan_execution.h>
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_ |
DynamicReconfigureImpl * | reconfigure_impl_ |
trajectory_execution_manager::TrajectoryExecutionManagerPtr | trajectory_execution_manager_ |
planning_scene_monitor::TrajectoryMonitorPtr | trajectory_monitor_ |
Definition at line 54 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.
Definition at line 95 of file plan_execution.cpp.
void plan_execution::PlanExecution::doneWithTrajectoryExecution | ( | const moveit_controller_manager::ExecutionStatus & | status | ) | [private] |
Definition at line 471 of file plan_execution.cpp.
moveit_msgs::MoveItErrorCodes plan_execution::PlanExecution::executeAndMonitor | ( | const ExecutableMotionPlan & | plan | ) | [private] |
Definition at line 315 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.
unsigned int plan_execution::PlanExecution::getMaxReplanAttempts | ( | ) | const [inline] |
Definition at line 126 of file plan_execution.h.
const planning_scene_monitor::PlanningSceneMonitorPtr& plan_execution::PlanExecution::getPlanningSceneMonitor | ( | ) | const [inline] |
Definition at line 97 of file plan_execution.h.
const trajectory_execution_manager::TrajectoryExecutionManagerPtr& plan_execution::PlanExecution::getTrajectoryExecutionManager | ( | ) | const [inline] |
Definition at line 102 of file plan_execution.h.
double plan_execution::PlanExecution::getTrajectoryStateRecordingFrequency | ( | ) | const [inline] |
Definition at line 107 of file plan_execution.h.
bool plan_execution::PlanExecution::isRemainingPathValid | ( | const ExecutableMotionPlan & | plan | ) | [private] |
Definition at line 263 of file plan_execution.cpp.
bool plan_execution::PlanExecution::isRemainingPathValid | ( | const ExecutableMotionPlan & | plan, |
const std::pair< int, int > & | path_segment | ||
) | [private] |
Definition at line 270 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.
void plan_execution::PlanExecution::planAndExecuteHelper | ( | ExecutableMotionPlan & | plan, |
const Options & | opt | ||
) | [private] |
Definition at line 160 of file plan_execution.cpp.
void plan_execution::PlanExecution::planningSceneUpdatedCallback | ( | const planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType | update_type | ) | [private] |
Definition at line 463 of file plan_execution.cpp.
void plan_execution::PlanExecution::setMaxReplanAttempts | ( | unsigned int | attempts | ) | [inline] |
Definition at line 121 of file plan_execution.h.
void plan_execution::PlanExecution::setTrajectoryStateRecordingFrequency | ( | double | freq | ) | [inline] |
Definition at line 115 of file plan_execution.h.
void plan_execution::PlanExecution::stop | ( | void | ) |
Definition at line 100 of file plan_execution.cpp.
void plan_execution::PlanExecution::successfulTrajectorySegmentExecution | ( | const ExecutableMotionPlan * | plan, |
std::size_t | index | ||
) | [private] |
Definition at line 477 of file plan_execution.cpp.
unsigned int plan_execution::PlanExecution::default_max_replan_attempts_ [private] |
Definition at line 153 of file plan_execution.h.
bool plan_execution::PlanExecution::execution_complete_ [private] |
Definition at line 158 of file plan_execution.h.
bool plan_execution::PlanExecution::new_scene_update_ [private] |
Definition at line 156 of file plan_execution.h.
Definition at line 148 of file plan_execution.h.
bool plan_execution::PlanExecution::path_became_invalid_ [private] |
Definition at line 159 of file plan_execution.h.
planning_scene_monitor::PlanningSceneMonitorPtr plan_execution::PlanExecution::planning_scene_monitor_ [private] |
Definition at line 149 of file plan_execution.h.
bool plan_execution::PlanExecution::preempt_requested_ [private] |
Definition at line 155 of file plan_execution.h.
Definition at line 161 of file plan_execution.h.
trajectory_execution_manager::TrajectoryExecutionManagerPtr plan_execution::PlanExecution::trajectory_execution_manager_ [private] |
Definition at line 150 of file plan_execution.h.
planning_scene_monitor::TrajectoryMonitorPtr plan_execution::PlanExecution::trajectory_monitor_ [private] |
Definition at line 151 of file plan_execution.h.