moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
The representation of a plan solution. More...
#include <planning_component.h>
Public Member Functions | |
operator bool () const | |
Public Attributes | |
moveit_msgs::msg::RobotState | start_state |
The full starting state used for planning. More... | |
robot_trajectory::RobotTrajectoryPtr | trajectory |
The trajectory of the robot (may not contain joints that are the same as for the start_state_) More... | |
moveit::core::MoveItErrorCode | error_code |
Reason why the plan failed. More... | |
The representation of a plan solution.
Definition at line 59 of file planning_component.h.
|
inlineexplicit |
Definition at line 70 of file planning_component.h.
moveit::core::MoveItErrorCode moveit_cpp::PlanningComponent::PlanSolution::error_code |
Reason why the plan failed.
Definition at line 68 of file planning_component.h.
moveit_msgs::msg::RobotState moveit_cpp::PlanningComponent::PlanSolution::start_state |
The full starting state used for planning.
Definition at line 62 of file planning_component.h.
robot_trajectory::RobotTrajectoryPtr moveit_cpp::PlanningComponent::PlanSolution::trajectory |
The trajectory of the robot (may not contain joints that are the same as for the start_state_)
Definition at line 65 of file planning_component.h.