#include <plan_execution.h>
Definition at line 54 of file plan_execution.h.
◆ PlanExecution()
plan_execution::PlanExecution::PlanExecution |
( |
const rclcpp::Node::SharedPtr & |
node, |
|
|
const planning_scene_monitor::PlanningSceneMonitorPtr & |
planning_scene_monitor, |
|
|
const trajectory_execution_manager::TrajectoryExecutionManagerPtr & |
trajectory_execution |
|
) |
| |
◆ ~PlanExecution()
plan_execution::PlanExecution::~PlanExecution |
( |
| ) |
|
◆ executeAndMonitor()
moveit_msgs::msg::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 |
◆ planAndExecute() [1/2]
void plan_execution::PlanExecution::planAndExecute |
( |
ExecutableMotionPlan & |
plan, |
|
|
const moveit_msgs::msg::PlanningScene & |
scene_diff, |
|
|
const Options & |
opt |
|
) |
| |
◆ planAndExecute() [2/2]
◆ 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 |
( |
| ) |
|
The documentation for this class was generated from the following files: