moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Attributes | List of all members
plan_execution::ExecutableMotionPlan Struct Reference

A generic representation on what a computed motion plan looks like. More...

#include <plan_representation.h>

Collaboration diagram for plan_execution::ExecutableMotionPlan:
Collaboration graph
[legend]

Public Attributes

planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
 
planning_scene::PlanningSceneConstPtr planning_scene_
 
std::vector< ExecutableTrajectoryplan_components_
 
robot_trajectory::RobotTrajectoryPtr executed_trajectory_
 The trace of the trajectory recorded during execution. More...
 
moveit_msgs::msg::MoveItErrorCodes error_code_
 An error code reflecting what went wrong (if anything) More...
 

Detailed Description

A generic representation on what a computed motion plan looks like.

Definition at line 73 of file plan_representation.h.

Member Data Documentation

◆ error_code_

moveit_msgs::msg::MoveItErrorCodes plan_execution::ExecutableMotionPlan::error_code_

An error code reflecting what went wrong (if anything)

Definition at line 84 of file plan_representation.h.

◆ executed_trajectory_

robot_trajectory::RobotTrajectoryPtr plan_execution::ExecutableMotionPlan::executed_trajectory_

The trace of the trajectory recorded during execution.

Definition at line 81 of file plan_representation.h.

◆ plan_components_

std::vector<ExecutableTrajectory> plan_execution::ExecutableMotionPlan::plan_components_

Definition at line 78 of file plan_representation.h.

◆ planning_scene_

planning_scene::PlanningSceneConstPtr plan_execution::ExecutableMotionPlan::planning_scene_

Definition at line 76 of file plan_representation.h.

◆ planning_scene_monitor_

planning_scene_monitor::PlanningSceneMonitorPtr plan_execution::ExecutableMotionPlan::planning_scene_monitor_

Definition at line 75 of file plan_representation.h.


The documentation for this struct was generated from the following file: