EasyNav Gridmap Stack
|
Lifecycle node that subscribes to point cloud sensor data and builds a grid map. More...
#include <GridmapMapsBuilderNode.hpp>
Public Types | |
using | CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn |
Public Member Functions | |
void | cycle () |
Perform a processing cycle on the perception data and update the grid map. | |
const grid_map::GridMap & | get_map () const |
GridmapMapsBuilderNode (const rclcpp::NodeOptions &options=rclcpp::NodeOptions()) | |
Constructor. | |
CallbackReturnT | on_activate (const rclcpp_lifecycle::State &state) override |
Lifecycle activate callback. | |
CallbackReturnT | on_cleanup (const rclcpp_lifecycle::State &state) override |
Lifecycle cleanup callback. | |
CallbackReturnT | on_configure (const rclcpp_lifecycle::State &state) override |
Lifecycle configure callback. | |
CallbackReturnT | on_deactivate (const rclcpp_lifecycle::State &state) override |
Lifecycle deactivate callback. | |
void | register_handler (std::shared_ptr< PerceptionHandler > handler) |
Registers a perception handler. | |
void | set_map (const grid_map::GridMap &map) |
~GridmapMapsBuilderNode () | |
Destructor. | |
Lifecycle node that subscribes to point cloud sensor data and builds a grid map.
This node processes perception data (point clouds) to generate a single outdoor grid map. It uses ROS 2 lifecycle management for clean startup, activation, deactivation, and cleanup. The node publishes the resulting grid map for downstream use.
using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn |
|
explicit |
Constructor.
options | Options for node initialization. |
Destructor.
void cycle | ( | ) |
Perform a processing cycle on the perception data and update the grid map.
This method should be called periodically (e.g., in a timer or main loop) to process incoming sensor data, update the internal grid map representation, and publish outputs.
const grid_map::GridMap & get_map | ( | ) | const |
|
override |
Lifecycle activate callback.
state | Current lifecycle state. |
|
override |
Lifecycle cleanup callback.
state | Current lifecycle state. |
|
override |
Lifecycle configure callback.
state | Current lifecycle state. |
|
override |
Lifecycle deactivate callback.
state | Current lifecycle state. |
void register_handler | ( | std::shared_ptr< PerceptionHandler > | handler | ) |
Registers a perception handler.
handler | Shared pointer to a PerceptionHandler instance. |
void set_map | ( | const grid_map::GridMap & | map | ) |