37 #ifndef MOVEIT_PLANNING_INTERFACE_PLANNING_RESPONSE_ 38 #define MOVEIT_PLANNING_INTERFACE_PLANNING_RESPONSE_ 41 #include <moveit_msgs/MoveItErrorCodes.h> 42 #include <moveit_msgs/MotionPlanResponse.h> 43 #include <moveit_msgs/MotionPlanDetailedResponse.h> 53 void getMessage(moveit_msgs::MotionPlanResponse& msg)
const;
62 void getMessage(moveit_msgs::MotionPlanDetailedResponse& msg)
const;
64 std::vector<robot_trajectory::RobotTrajectoryPtr>
trajectory_;
robot_trajectory::RobotTrajectoryPtr trajectory_
std::vector< std::string > description_
moveit_msgs::MoveItErrorCodes error_code_
void getMessage(moveit_msgs::MotionPlanResponse &msg) const
moveit_msgs::MoveItErrorCodes error_code_
std::vector< double > processing_time_
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory_
This namespace includes the base class for MoveIt! planners.