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

#include <moveit_planning_pipeline.h>

Inheritance diagram for moveit::hybrid_planning::MoveItPlanningPipeline:
Inheritance graph
[legend]
Collaboration diagram for moveit::hybrid_planning::MoveItPlanningPipeline:
Collaboration graph
[legend]

Public Member Functions

 MoveItPlanningPipeline ()=default
 
 ~MoveItPlanningPipeline () override=default
 
bool initialize (const rclcpp::Node::SharedPtr &node) override
 
bool reset () noexcept override
 
moveit_msgs::msg::MotionPlanResponse plan (const std::shared_ptr< rclcpp_action::ServerGoalHandle< moveit_msgs::action::GlobalPlanner >> global_goal_handle) override
 
- Public Member Functions inherited from moveit::hybrid_planning::GlobalPlannerInterface
 GlobalPlannerInterface ()=default
 
 GlobalPlannerInterface (const GlobalPlannerInterface &)=default
 
 GlobalPlannerInterface (GlobalPlannerInterface &&)=default
 
GlobalPlannerInterfaceoperator= (const GlobalPlannerInterface &)=default
 
GlobalPlannerInterfaceoperator= (GlobalPlannerInterface &&)=default
 
virtual ~GlobalPlannerInterface ()=default
 

Detailed Description

Definition at line 49 of file moveit_planning_pipeline.h.

Constructor & Destructor Documentation

◆ MoveItPlanningPipeline()

moveit::hybrid_planning::MoveItPlanningPipeline::MoveItPlanningPipeline ( )
default

◆ ~MoveItPlanningPipeline()

moveit::hybrid_planning::MoveItPlanningPipeline::~MoveItPlanningPipeline ( )
overridedefault

Member Function Documentation

◆ initialize()

bool moveit::hybrid_planning::MoveItPlanningPipeline::initialize ( const rclcpp::Node::SharedPtr &  node)
overridevirtual

Initialize global planner

Returns
True if initialization was successful

Implements moveit::hybrid_planning::GlobalPlannerInterface.

Definition at line 51 of file moveit_planning_pipeline.cpp.

◆ plan()

moveit_msgs::msg::MotionPlanResponse moveit::hybrid_planning::MoveItPlanningPipeline::plan ( const std::shared_ptr< rclcpp_action::ServerGoalHandle< moveit_msgs::action::GlobalPlanner >>  global_goal_handle)
overridevirtual

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

Implements moveit::hybrid_planning::GlobalPlannerInterface.

Definition at line 97 of file moveit_planning_pipeline.cpp.

Here is the caller graph for this function:

◆ reset()

bool moveit::hybrid_planning::MoveItPlanningPipeline::reset ( )
overridevirtualnoexcept

Reset global planner plugin. This should never fail.

Returns
True if reset was successful

Implements moveit::hybrid_planning::GlobalPlannerInterface.

Definition at line 91 of file moveit_planning_pipeline.cpp.


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