moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <hybrid_planning_manager.h>
Public Member Functions | |
HybridPlanningManager (const rclcpp::NodeOptions &options) | |
Constructor. | |
~HybridPlanningManager () | |
Destructor. | |
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. | |
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 52 of file hybrid_planning_manager.cpp.
|
inline |
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 138 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 152 of file hybrid_planning_manager.cpp.
|
inline |
Definition at line 81 of file hybrid_planning_manager.h.
bool moveit::hybrid_planning::HybridPlanningManager::initialize | ( | ) |
Load and initialized planner logic plugin and ROS 2 action and topic interfaces
void moveit::hybrid_planning::HybridPlanningManager::processReactionResult | ( | const ReactionResult & | result | ) |
Process the action result and do an action call if necessary.
result | Result to an event |
Definition at line 303 of file hybrid_planning_manager.cpp.
bool moveit::hybrid_planning::HybridPlanningManager::sendGlobalPlannerAction | ( | ) |
Send global planning request to global planner component
Definition at line 165 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 287 of file hybrid_planning_manager.cpp.
bool moveit::hybrid_planning::HybridPlanningManager::sendLocalPlannerAction | ( | ) |
Send local planning request to local planner component
Definition at line 224 of file hybrid_planning_manager.cpp.