moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | Public Attributes | List of all members
planning_interface::MotionPlanResponse Struct Reference

Response to a planning query. More...

#include <planning_response.h>

Collaboration diagram for planning_interface::MotionPlanResponse:
Collaboration graph
[legend]

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
 

Detailed Description

Response to a planning query.

Definition at line 48 of file planning_response.h.

Constructor & Destructor Documentation

◆ MotionPlanResponse()

planning_interface::MotionPlanResponse::MotionPlanResponse ( )
inline

Constructor.

Definition at line 51 of file planning_response.h.

Member Function Documentation

◆ getMessage()

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.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ operator bool()

planning_interface::MotionPlanResponse::operator bool ( ) const
inlineexplicit

Definition at line 74 of file planning_response.h.

Member Data Documentation

◆ added_path_index

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.

◆ error_code

moveit::core::MoveItErrorCode planning_interface::MotionPlanResponse::error_code

Definition at line 63 of file planning_response.h.

◆ planner_id

std::string planning_interface::MotionPlanResponse::planner_id

Definition at line 66 of file planning_response.h.

◆ planning_time

double planning_interface::MotionPlanResponse::planning_time

Definition at line 61 of file planning_response.h.

◆ start_state

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.

◆ trajectory

robot_trajectory::RobotTrajectoryPtr planning_interface::MotionPlanResponse::trajectory

Definition at line 59 of file planning_response.h.


The documentation for this struct was generated from the following files: