moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
The representation of a motion plan (as ROS messasges) More...
#include <move_group_interface.h>
Public Attributes | |
moveit_msgs::msg::RobotState | start_state_ |
The full starting state used for planning. More... | |
moveit_msgs::msg::RobotTrajectory | trajectory_ |
The trajectory of the robot (may not contain joints that are the same as for the start_state_) More... | |
double | planning_time_ |
The amount of time it took to generate the plan. More... | |
The representation of a motion plan (as ROS messasges)
Definition at line 112 of file move_group_interface.h.
double moveit::planning_interface::MoveGroupInterface::Plan::planning_time_ |
The amount of time it took to generate the plan.
Definition at line 121 of file move_group_interface.h.
moveit_msgs::msg::RobotState moveit::planning_interface::MoveGroupInterface::Plan::start_state_ |
The full starting state used for planning.
Definition at line 115 of file move_group_interface.h.
moveit_msgs::msg::RobotTrajectory moveit::planning_interface::MoveGroupInterface::Plan::trajectory_ |
The trajectory of the robot (may not contain joints that are the same as for the start_state_)
Definition at line 118 of file move_group_interface.h.