|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Response to a planning query. More...
#include <planning_response.hpp>

Public Member Functions | |
| MotionPlanResponse () | |
| Constructor. | |
| void | getMessage (moveit_msgs::msg::MotionPlanResponse &msg) const |
| Construct a ROS message from struct data. | |
| operator bool () const | |
Public Attributes | |
| robot_trajectory::RobotTrajectoryPtr | trajectory |
| double | planning_time |
| moveit::core::MoveItErrorCode | error_code |
| moveit_msgs::msg::RobotState | start_state |
| The full starting state used for planning. | |
| std::string | planner_id |
Response to a planning query.
Definition at line 48 of file planning_response.hpp.
|
inline |
Constructor.
Definition at line 51 of file planning_response.hpp.
| void planning_interface::MotionPlanResponse::getMessage | ( | moveit_msgs::msg::MotionPlanResponse & | msg | ) | const |
Construct a ROS message from struct data.
Definition at line 40 of file planning_response.cpp.


|
inlineexplicit |
Definition at line 69 of file planning_response.hpp.
| moveit::core::MoveItErrorCode planning_interface::MotionPlanResponse::error_code |
Definition at line 63 of file planning_response.hpp.
| std::string planning_interface::MotionPlanResponse::planner_id |
Definition at line 66 of file planning_response.hpp.
| double planning_interface::MotionPlanResponse::planning_time |
Definition at line 61 of file planning_response.hpp.
| moveit_msgs::msg::RobotState planning_interface::MotionPlanResponse::start_state |
The full starting state used for planning.
Definition at line 65 of file planning_response.hpp.
| robot_trajectory::RobotTrajectoryPtr planning_interface::MotionPlanResponse::trajectory |
Definition at line 59 of file planning_response.hpp.