moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Response to a planning query. More...
#include <planning_response.h>
Public Member Functions | |
MotionPlanResponse () | |
Constructor. More... | |
void | getMessage (moveit_msgs::msg::MotionPlanResponse &msg) const |
Construct a ROS message from struct data. More... | |
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. More... | |
std::string | planner_id |
std::vector< std::size_t > | added_path_index |
Response to a planning query.
Definition at line 48 of file planning_response.h.
|
inline |
Constructor.
Definition at line 51 of file planning_response.h.
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 74 of file planning_response.h.
std::vector<std::size_t> planning_interface::MotionPlanResponse::added_path_index |
Sometimes planning request adapters may add states on the solution path (e.g., add the current state of the robot as prefix, when the robot started to plan only from near that state, as the current state itself appears to touch obstacles). This is helpful because the added states should not be considered invalid in all situations.
Definition at line 71 of file planning_response.h.
moveit::core::MoveItErrorCode planning_interface::MotionPlanResponse::error_code |
Definition at line 63 of file planning_response.h.
std::string planning_interface::MotionPlanResponse::planner_id |
Definition at line 66 of file planning_response.h.
double planning_interface::MotionPlanResponse::planning_time |
Definition at line 61 of file planning_response.h.
moveit_msgs::msg::RobotState planning_interface::MotionPlanResponse::start_state |
The full starting state used for planning.
Definition at line 65 of file planning_response.h.
robot_trajectory::RobotTrajectoryPtr planning_interface::MotionPlanResponse::trajectory |
Definition at line 59 of file planning_response.h.