|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <local_planner_component.h>
Classes | |
| struct | LocalPlannerConfig |
| Struct that contains configuration of the local planner component node. More... | |
Public Member Functions | |
| LocalPlannerComponent (const rclcpp::NodeOptions &options) | |
| Constructor. More... | |
| ~LocalPlannerComponent () | |
| Destructor. More... | |
| bool | initialize () |
| void | executeIteration () |
| rclcpp::node_interfaces::NodeBaseInterface::SharedPtr | get_node_base_interface () |
Class LocalPlannerComponent - ROS 2 component node that implements a local planner.
Definition at line 100 of file local_planner_component.h.
| moveit::hybrid_planning::LocalPlannerComponent::LocalPlannerComponent | ( | const rclcpp::NodeOptions & | options | ) |
Constructor.
Definition at line 57 of file local_planner_component.cpp.

|
inline |
Destructor.
Definition at line 149 of file local_planner_component.h.
| void moveit::hybrid_planning::LocalPlannerComponent::executeIteration | ( | ) |
Handle the planners current job based on the internal state each iteration when the planner is started.
Definition at line 245 of file local_planner_component.cpp.
|
inline |
Definition at line 173 of file local_planner_component.h.
| bool moveit::hybrid_planning::LocalPlannerComponent::initialize | ( | ) |
Initialize and start planning scene monitor to listen to the planning scene topic. Load trajectory_operator and constraint solver plugin. Initialize ROS 2 interfaces
Definition at line 69 of file local_planner_component.cpp.

