moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <hybrid_planning_manager.h>
Public Member Functions | |
HybridPlanningManager (const rclcpp::NodeOptions &options) | |
Constructor. More... | |
~HybridPlanningManager () override | |
Destructor. More... | |
std::shared_ptr< HybridPlanningManager > | shared_from_this () |
bool | initialize () |
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) |
Class HybridPlanningManager - ROS 2 component node that implements the hybrid planning manager.
Definition at line 57 of file hybrid_planning_manager.h.
moveit::hybrid_planning::HybridPlanningManager::HybridPlanningManager | ( | const rclcpp::NodeOptions & | options | ) |
Constructor.
Definition at line 47 of file hybrid_planning_manager.cpp.
|
inlineoverride |
Destructor.
Definition at line 64 of file hybrid_planning_manager.h.
|
noexcept |
Cancel any active action goals, including global and local planners
Definition at line 192 of file hybrid_planning_manager.cpp.
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.
goal_handle | The action server goal |
Definition at line 206 of file hybrid_planning_manager.cpp.
bool moveit::hybrid_planning::HybridPlanningManager::initialize | ( | ) |
Load and initialized planner logic plugin and ROS 2 action and topic interfaces
Definition at line 70 of file hybrid_planning_manager.cpp.
bool moveit::hybrid_planning::HybridPlanningManager::sendGlobalPlannerAction | ( | ) |
Send global planning request to global planner component
Definition at line 228 of file hybrid_planning_manager.cpp.
void moveit::hybrid_planning::HybridPlanningManager::sendHybridPlanningResponse | ( | bool | success | ) |
Send back hybrid planning response
success | Indicates whether hybrid planning was successful |
Definition at line 378 of file hybrid_planning_manager.cpp.
bool moveit::hybrid_planning::HybridPlanningManager::sendLocalPlannerAction | ( | ) |
Send local planning request to local planner component
Definition at line 295 of file hybrid_planning_manager.cpp.
|
inline |
Allows creation of a smart pointer that references to instances of this object
Definition at line 77 of file hybrid_planning_manager.h.