moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Member Functions | List of all members
plan_execution::PlanExecution Class Reference

#include <plan_execution.h>

Classes

struct  Options
 

Public Member Functions

 PlanExecution (const rclcpp::Node::SharedPtr &node, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor, const trajectory_execution_manager::TrajectoryExecutionManagerPtr &trajectory_execution)
 
 ~PlanExecution ()
 
const planning_scene_monitor::PlanningSceneMonitorPtr & getPlanningSceneMonitor () const
 
const trajectory_execution_manager::TrajectoryExecutionManagerPtr & getTrajectoryExecutionManager () const
 
double getTrajectoryStateRecordingFrequency () const
 
void setTrajectoryStateRecordingFrequency (double freq)
 
void setMaxReplanAttempts (unsigned int attempts)
 
unsigned int getMaxReplanAttempts () const
 
void planAndExecute (ExecutableMotionPlan &plan, const Options &opt)
 
void planAndExecute (ExecutableMotionPlan &plan, const moveit_msgs::msg::PlanningScene &scene_diff, const Options &opt)
 
moveit_msgs::msg::MoveItErrorCodes executeAndMonitor (ExecutableMotionPlan &plan, bool reset_preempted=true)
 Execute and monitor a previously created plan. More...
 
void stop ()
 
std::string getErrorCodeString (const moveit_msgs::msg::MoveItErrorCodes &error_code)
 

Detailed Description

Definition at line 54 of file plan_execution.h.

Constructor & Destructor Documentation

◆ 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 
)

Definition at line 79 of file plan_execution.cpp.

◆ ~PlanExecution()

plan_execution::PlanExecution::~PlanExecution ( )

Definition at line 102 of file plan_execution.cpp.

Member Function Documentation

◆ executeAndMonitor()

moveit_msgs::msg::MoveItErrorCodes plan_execution::PlanExecution::executeAndMonitor ( ExecutableMotionPlan plan,
bool  reset_preempted = true 
)

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 329 of file plan_execution.cpp.

◆ getErrorCodeString()

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

Definition at line 112 of file plan_execution.cpp.

◆ getMaxReplanAttempts()

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

Definition at line 127 of file plan_execution.h.

◆ getPlanningSceneMonitor()

const planning_scene_monitor::PlanningSceneMonitorPtr& plan_execution::PlanExecution::getPlanningSceneMonitor ( ) const
inline

Definition at line 98 of file plan_execution.h.

◆ getTrajectoryExecutionManager()

const trajectory_execution_manager::TrajectoryExecutionManagerPtr& plan_execution::PlanExecution::getTrajectoryExecutionManager ( ) const
inline

Definition at line 103 of file plan_execution.h.

◆ getTrajectoryStateRecordingFrequency()

double plan_execution::PlanExecution::getTrajectoryStateRecordingFrequency ( ) const
inline

Definition at line 108 of file plan_execution.h.

◆ planAndExecute() [1/2]

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

Definition at line 148 of file plan_execution.cpp.

Here is the call graph for this function:

◆ planAndExecute() [2/2]

void plan_execution::PlanExecution::planAndExecute ( ExecutableMotionPlan plan,
const Options opt 
)

Definition at line 141 of file plan_execution.cpp.

◆ setMaxReplanAttempts()

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

Definition at line 122 of file plan_execution.h.

◆ setTrajectoryStateRecordingFrequency()

void plan_execution::PlanExecution::setTrajectoryStateRecordingFrequency ( double  freq)
inline

Definition at line 116 of file plan_execution.h.

◆ stop()

void plan_execution::PlanExecution::stop ( )

Definition at line 107 of file plan_execution.cpp.


The documentation for this class was generated from the following files: