moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <planning_response.h>
Public Member Functions | |
void | getMessage (moveit_msgs::msg::MotionPlanDetailedResponse &msg) const |
Public Attributes | |
std::vector< robot_trajectory::RobotTrajectoryPtr > | trajectory |
std::vector< std::string > | description |
std::vector< double > | processing_time |
moveit_msgs::msg::MoveItErrorCodes | error_code |
std::string | planner_id |
Definition at line 75 of file planning_response.h.
void planning_interface::MotionPlanDetailedResponse::getMessage | ( | moveit_msgs::msg::MotionPlanDetailedResponse & | msg | ) | const |
std::vector<std::string> planning_interface::MotionPlanDetailedResponse::description |
Definition at line 80 of file planning_response.h.
moveit_msgs::msg::MoveItErrorCodes planning_interface::MotionPlanDetailedResponse::error_code |
Definition at line 82 of file planning_response.h.
std::string planning_interface::MotionPlanDetailedResponse::planner_id |
Definition at line 83 of file planning_response.h.
std::vector<double> planning_interface::MotionPlanDetailedResponse::processing_time |
Definition at line 81 of file planning_response.h.
std::vector<robot_trajectory::RobotTrajectoryPtr> planning_interface::MotionPlanDetailedResponse::trajectory |
Definition at line 79 of file planning_response.h.