moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
moveit::hybrid_planning::GlobalPlannerInterface Class Referenceabstract

#include <global_planner_interface.h>

Inheritance diagram for moveit::hybrid_planning::GlobalPlannerInterface:
Inheritance graph
[legend]

Public Member Functions

 GlobalPlannerInterface ()=default
 
 GlobalPlannerInterface (const GlobalPlannerInterface &)=default
 
 GlobalPlannerInterface (GlobalPlannerInterface &&)=default
 
GlobalPlannerInterfaceoperator= (const GlobalPlannerInterface &)=default
 
GlobalPlannerInterfaceoperator= (GlobalPlannerInterface &&)=default
 
virtual ~GlobalPlannerInterface ()=default
 
virtual bool initialize (const rclcpp::Node::SharedPtr &node)=0
 
virtual moveit_msgs::msg::MotionPlanResponse plan (const std::shared_ptr< rclcpp_action::ServerGoalHandle< moveit_msgs::action::GlobalPlanner >> global_goal_handle)=0
 
virtual bool reset () noexcept=0
 

Detailed Description

Class GlobalPlannerInterface - Base class for a global planner implementation

Definition at line 55 of file global_planner_interface.h.

Constructor & Destructor Documentation

◆ GlobalPlannerInterface() [1/3]

moveit::hybrid_planning::GlobalPlannerInterface::GlobalPlannerInterface ( )
default

◆ GlobalPlannerInterface() [2/3]

moveit::hybrid_planning::GlobalPlannerInterface::GlobalPlannerInterface ( const GlobalPlannerInterface )
default

◆ GlobalPlannerInterface() [3/3]

moveit::hybrid_planning::GlobalPlannerInterface::GlobalPlannerInterface ( GlobalPlannerInterface &&  )
default

◆ ~GlobalPlannerInterface()

virtual moveit::hybrid_planning::GlobalPlannerInterface::~GlobalPlannerInterface ( )
virtualdefault

Member Function Documentation

◆ initialize()

virtual bool moveit::hybrid_planning::GlobalPlannerInterface::initialize ( const rclcpp::Node::SharedPtr &  node)
pure virtual

Initialize global planner

Returns
True if initialization was successful

Implemented in moveit::hybrid_planning::MoveItPlanningPipeline.

◆ operator=() [1/2]

GlobalPlannerInterface& moveit::hybrid_planning::GlobalPlannerInterface::operator= ( const GlobalPlannerInterface )
default

◆ operator=() [2/2]

GlobalPlannerInterface& moveit::hybrid_planning::GlobalPlannerInterface::operator= ( GlobalPlannerInterface &&  )
default

◆ plan()

virtual moveit_msgs::msg::MotionPlanResponse moveit::hybrid_planning::GlobalPlannerInterface::plan ( const std::shared_ptr< rclcpp_action::ServerGoalHandle< moveit_msgs::action::GlobalPlanner >>  global_goal_handle)
pure virtual

Solve global planning problem

Parameters
global_goal_handleAction goal handle to access the planning goal and publish feedback during planning
Returns
Motion Plan that contains the solution for a given motion planning problem

Implemented in moveit::hybrid_planning::MoveItPlanningPipeline.

Here is the caller graph for this function:

◆ reset()

virtual bool moveit::hybrid_planning::GlobalPlannerInterface::reset ( )
pure virtualnoexcept

Reset global planner plugin. This should never fail.

Returns
True if reset was successful

Implemented in moveit::hybrid_planning::MoveItPlanningPipeline.


The documentation for this class was generated from the following file: