#include <global_planner_interface.h>
Class GlobalPlannerInterface - Base class for a global planner implementation
Definition at line 55 of file global_planner_interface.h.
◆ GlobalPlannerInterface() [1/3]
moveit::hybrid_planning::GlobalPlannerInterface::GlobalPlannerInterface |
( |
| ) |
|
|
default |
◆ GlobalPlannerInterface() [2/3]
◆ GlobalPlannerInterface() [3/3]
◆ ~GlobalPlannerInterface()
virtual moveit::hybrid_planning::GlobalPlannerInterface::~GlobalPlannerInterface |
( |
| ) |
|
|
virtualdefault |
◆ initialize()
virtual bool moveit::hybrid_planning::GlobalPlannerInterface::initialize |
( |
const rclcpp::Node::SharedPtr & |
node | ) |
|
|
pure virtual |
◆ operator=() [1/2]
◆ operator=() [2/2]
◆ 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_handle | Action 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.
◆ reset()
virtual bool moveit::hybrid_planning::GlobalPlannerInterface::reset |
( |
| ) |
|
|
pure virtualnoexcept |
The documentation for this class was generated from the following file: