41#include <moveit_msgs/msg/move_it_error_codes.hpp>
42#include <moveit_msgs/msg/motion_plan_response.hpp>
43#include <moveit_msgs/msg/motion_plan_detailed_response.hpp>
56 void getMessage(moveit_msgs::msg::MotionPlanResponse& msg)
const;
69 explicit operator bool()
const
77 void getMessage(moveit_msgs::msg::MotionPlanDetailedResponse& msg)
const;
79 std::vector<robot_trajectory::RobotTrajectoryPtr>
trajectory;
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
Main namespace for MoveIt.
This namespace includes the base class for MoveIt planners.
moveit_msgs::msg::MoveItErrorCodes error_code
void getMessage(moveit_msgs::msg::MotionPlanDetailedResponse &msg) const
std::vector< std::string > description
std::vector< double > processing_time
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory
Response to a planning query.
moveit_msgs::msg::RobotState start_state
The full starting state used for planning.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory
void getMessage(moveit_msgs::msg::MotionPlanResponse &msg) const
Construct a ROS message from struct data.
MotionPlanResponse()
Constructor.