A generic representation on what a computed motion plan looks like. More...
#include <plan_representation.h>
Public Attributes | |
moveit_msgs::MoveItErrorCodes | error_code_ |
An error code reflecting what went wrong (if anything) | |
robot_trajectory::RobotTrajectoryPtr | executed_trajectory_ |
std::vector< ExecutableTrajectory > | plan_components_ |
planning_scene::PlanningSceneConstPtr | planning_scene_ |
planning_scene_monitor::PlanningSceneMonitorPtr | planning_scene_monitor_ |
A generic representation on what a computed motion plan looks like.
Definition at line 74 of file plan_representation.h.
moveit_msgs::MoveItErrorCodes plan_execution::ExecutableMotionPlan::error_code_ |
An error code reflecting what went wrong (if anything)
Definition at line 85 of file plan_representation.h.
Definition at line 82 of file plan_representation.h.
Definition at line 79 of file plan_representation.h.
Definition at line 77 of file plan_representation.h.
planning_scene_monitor::PlanningSceneMonitorPtr plan_execution::ExecutableMotionPlan::planning_scene_monitor_ |
Definition at line 76 of file plan_representation.h.