#include <plan_execution.h>
Definition at line 86 of file plan_execution.h.
◆ PlanExecution()
plan_execution::PlanExecution::PlanExecution |
( |
const planning_scene_monitor::PlanningSceneMonitorPtr & |
planning_scene_monitor, |
|
|
const trajectory_execution_manager::TrajectoryExecutionManagerPtr & |
trajectory_execution |
|
) |
| |
◆ ~PlanExecution()
plan_execution::PlanExecution::~PlanExecution |
( |
| ) |
|
◆ doneWithTrajectoryExecution()
◆ executeAndMonitor()
moveit_msgs::MoveItErrorCodes plan_execution::PlanExecution::executeAndMonitor |
( |
ExecutableMotionPlan & |
plan, |
|
|
bool |
reset_preempted = true |
|
) |
| |
◆ getMaxReplanAttempts()
unsigned int plan_execution::PlanExecution::getMaxReplanAttempts |
( |
| ) |
const |
|
inline |
◆ getPlanningSceneMonitor()
const planning_scene_monitor::PlanningSceneMonitorPtr& plan_execution::PlanExecution::getPlanningSceneMonitor |
( |
| ) |
const |
|
inline |
◆ getTrajectoryExecutionManager()
const trajectory_execution_manager::TrajectoryExecutionManagerPtr& plan_execution::PlanExecution::getTrajectoryExecutionManager |
( |
| ) |
const |
|
inline |
◆ getTrajectoryStateRecordingFrequency()
double plan_execution::PlanExecution::getTrajectoryStateRecordingFrequency |
( |
| ) |
const |
|
inline |
◆ isRemainingPathValid()
bool plan_execution::PlanExecution::isRemainingPathValid |
( |
const ExecutableMotionPlan & |
plan, |
|
|
const std::pair< int, int > & |
path_segment |
|
) |
| |
|
private |
◆ planAndExecute() [1/2]
void plan_execution::PlanExecution::planAndExecute |
( |
ExecutableMotionPlan & |
plan, |
|
|
const moveit_msgs::PlanningScene & |
scene_diff, |
|
|
const Options & |
opt |
|
) |
| |
◆ planAndExecute() [2/2]
◆ planAndExecuteHelper()
◆ planningSceneUpdatedCallback()
◆ setMaxReplanAttempts()
void plan_execution::PlanExecution::setMaxReplanAttempts |
( |
unsigned int |
attempts | ) |
|
|
inline |
◆ setTrajectoryStateRecordingFrequency()
void plan_execution::PlanExecution::setTrajectoryStateRecordingFrequency |
( |
double |
freq | ) |
|
|
inline |
◆ stop()
void plan_execution::PlanExecution::stop |
( |
| ) |
|
◆ successfulTrajectorySegmentExecution()
void plan_execution::PlanExecution::successfulTrajectorySegmentExecution |
( |
const ExecutableMotionPlan & |
plan, |
|
|
std::size_t |
index |
|
) |
| |
|
private |
◆ default_max_replan_attempts_
unsigned int plan_execution::PlanExecution::default_max_replan_attempts_ |
|
private |
◆ execution_complete_
bool plan_execution::PlanExecution::execution_complete_ |
|
private |
◆ new_scene_update_
bool plan_execution::PlanExecution::new_scene_update_ |
|
private |
◆ node_handle_
◆ path_became_invalid_
bool plan_execution::PlanExecution::path_became_invalid_ |
|
private |
◆ planning_scene_monitor_
planning_scene_monitor::PlanningSceneMonitorPtr plan_execution::PlanExecution::planning_scene_monitor_ |
|
private |
◆ preempt_
class { ... } plan_execution::PlanExecution::preempt_ |
◆ preemption_requested
std::atomic<bool> plan_execution::PlanExecution::preemption_requested { false } |
|
private |
◆ reconfigure_impl_
◆ trajectory_execution_manager_
trajectory_execution_manager::TrajectoryExecutionManagerPtr plan_execution::PlanExecution::trajectory_execution_manager_ |
|
private |
◆ trajectory_monitor_
planning_scene_monitor::TrajectoryMonitorPtr plan_execution::PlanExecution::trajectory_monitor_ |
|
private |
The documentation for this class was generated from the following files: