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

#include <hybrid_planning_manager.h>

Public Member Functions

 HybridPlanningManager (const rclcpp::NodeOptions &options)
 Constructor. More...
 
 ~HybridPlanningManager ()
 Destructor. More...
 
bool initialize ()
 
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr get_node_base_interface ()
 
void cancelHybridManagerGoals () noexcept
 
void executeHybridPlannerGoal (std::shared_ptr< rclcpp_action::ServerGoalHandle< moveit_msgs::action::HybridPlanner >> goal_handle)
 
bool sendGlobalPlannerAction ()
 
bool sendLocalPlannerAction ()
 
void sendHybridPlanningResponse (bool success)
 
void processReactionResult (const ReactionResult &result)
 Process the action result and do an action call if necessary. More...
 

Detailed Description

Class HybridPlanningManager - ROS 2 component node that implements the hybrid planning manager.

Definition at line 57 of file hybrid_planning_manager.h.

Constructor & Destructor Documentation

◆ HybridPlanningManager()

moveit::hybrid_planning::HybridPlanningManager::HybridPlanningManager ( const rclcpp::NodeOptions &  options)

Constructor.

Definition at line 52 of file hybrid_planning_manager.cpp.

Here is the call graph for this function:

◆ ~HybridPlanningManager()

moveit::hybrid_planning::HybridPlanningManager::~HybridPlanningManager ( )
inline

Destructor.

Definition at line 64 of file hybrid_planning_manager.h.

Member Function Documentation

◆ cancelHybridManagerGoals()

void moveit::hybrid_planning::HybridPlanningManager::cancelHybridManagerGoals ( )
noexcept

Cancel any active action goals, including global and local planners

Definition at line 138 of file hybrid_planning_manager.cpp.

Here is the caller graph for this function:

◆ executeHybridPlannerGoal()

void moveit::hybrid_planning::HybridPlanningManager::executeHybridPlannerGoal ( std::shared_ptr< rclcpp_action::ServerGoalHandle< moveit_msgs::action::HybridPlanner >>  goal_handle)

This handles execution of a hybrid planning goal in a new thread, to avoid blocking the executor.

Parameters
goal_handleThe action server goal

Definition at line 152 of file hybrid_planning_manager.cpp.

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

◆ get_node_base_interface()

rclcpp::node_interfaces::NodeBaseInterface::SharedPtr moveit::hybrid_planning::HybridPlanningManager::get_node_base_interface ( )
inline

Definition at line 81 of file hybrid_planning_manager.h.

◆ initialize()

bool moveit::hybrid_planning::HybridPlanningManager::initialize ( )

Load and initialized planner logic plugin and ROS 2 action and topic interfaces

Returns
Initialization successful yes/no

◆ processReactionResult()

void moveit::hybrid_planning::HybridPlanningManager::processReactionResult ( const ReactionResult result)

Process the action result and do an action call if necessary.

Parameters
resultResult to an event

Definition at line 303 of file hybrid_planning_manager.cpp.

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

◆ sendGlobalPlannerAction()

bool moveit::hybrid_planning::HybridPlanningManager::sendGlobalPlannerAction ( )

Send global planning request to global planner component

Returns
Global planner successfully started yes/no

Definition at line 165 of file hybrid_planning_manager.cpp.

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

◆ sendHybridPlanningResponse()

void moveit::hybrid_planning::HybridPlanningManager::sendHybridPlanningResponse ( bool  success)

Send back hybrid planning response

Parameters
successIndicates whether hybrid planning was successful

Definition at line 287 of file hybrid_planning_manager.cpp.

Here is the caller graph for this function:

◆ sendLocalPlannerAction()

bool moveit::hybrid_planning::HybridPlanningManager::sendLocalPlannerAction ( )

Send local planning request to local planner component

Returns
Local planner successfully started yes/no

Definition at line 224 of file hybrid_planning_manager.cpp.

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

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