Go to the documentation of this file.
41 #include <moveit_msgs/MotionPlanResponse.h>
42 #include <moveit_msgs/MotionPlanDetailedResponse.h>
46 struct MotionPlanResponse
54 [[deprecated(
"Use trajectory_ instead.")]]
const robot_trajectory::RobotTrajectoryPtr&
trajectory;
55 [[deprecated(
"Use planning_time_ instead.")]]
const double&
planning_time;
57 [[deprecated(
"Use start_state_ instead.")]]
const moveit_msgs::RobotState&
start_state;
59 #pragma GCC diagnostic push
60 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
69 #pragma GCC diagnostic pop
86 void getMessage(moveit_msgs::MotionPlanResponse& msg)
const;
89 explicit operator bool()
const
95 struct MotionPlanDetailedResponse
97 void getMessage(moveit_msgs::MotionPlanDetailedResponse& msg)
const;
99 std::vector<robot_trajectory::RobotTrajectoryPtr>
trajectory_;
107 explicit operator bool()
const
const std::string response
void getMessage(moveit_msgs::MotionPlanResponse &msg) const
const double & planning_time
moveit::core::MoveItErrorCode error_code_
MotionPlanResponse & operator=(const MotionPlanResponse &response)
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
robot_trajectory::RobotTrajectoryPtr trajectory_
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory_
const robot_trajectory::RobotTrajectoryPtr & trajectory
moveit_msgs::RobotState start_state_
moveit_msgs::RobotState start_state_
const moveit::core::MoveItErrorCode & error_code
This namespace includes the base class for MoveIt planners.
moveit::core::MoveItErrorCode error_code_
std::vector< std::string > description_
void getMessage(moveit_msgs::MotionPlanDetailedResponse &msg) const
std::vector< double > processing_time_
const moveit_msgs::RobotState & start_state
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:15