|
Easy Navigation
|
Abstract base class for pluginlib-based sensor perception handlers. More...
#include <Perceptions.hpp>


Public Member Functions | |
| virtual bool | cycle_rt (std::shared_ptr< NavState > nav_state) |
| Run one real-time sensor processing cycle. | |
| const std::string & | get_sensor_name () const |
| Returns the sensor name provided during initialize. | |
| void | initialize (const std::shared_ptr< rclcpp_lifecycle::LifecycleNode > parent_node, const rclcpp::CallbackGroup::SharedPtr realtime_cbg, const std::string &sensor_name) |
| Initializes the handler with the parent node and sensor name. | |
| virtual void | on_initialize () |
| Optional post-initialization hook for subclasses. | |
| virtual | ~PerceptionHandler ()=default |
Protected Member Functions | |
| std::shared_ptr< rclcpp_lifecycle::LifecycleNode > | get_node () const |
| Returns the parent lifecycle node. | |
| rclcpp::CallbackGroup::SharedPtr | get_realtime_cbg () const |
| Returns the parent lifecycle node. | |
Protected Attributes | |
| std::weak_ptr< rclcpp_lifecycle::LifecycleNode > | parent_node_ |
| Shared pointer to the parent lifecycle node. | |
| rclcpp::CallbackGroup::SharedPtr | realtime_cbg_ |
| Callback group for real-time operations. | |
| std::string | sensor_name_ |
| Name of the sensor (used as YAML parameter namespace prefix). | |
Abstract base class for pluginlib-based sensor perception handlers.
Each handler is responsible for a single sensor input (e.g., "lidar_center", "image_color", "imu_0"). Concrete handlers are registered as pluginlib plugins and loaded at runtime. A user can implement a new sensor input handler by deriving from this class and registering it as a plugin in the corresponding package's plugin XML file. The handler is the owner of the sensor data. It is also responsible for reserving memory to hold the sensor data and must keep the data address consistent during the whole execution. The handler must populate the NavState with the sensor data
|
virtualdefault |
|
virtual |
Run one real-time sensor processing cycle.
This method is called by the SensorsNode before executing its cycle_rt. Here the handler should update the NavState with the sensor data. If new data arrived before this call and the state is updated, it must return true.
| nav_state | Pointer to the NavState to store the sensor data. |
Reimplemented in DummyHandler, DetectionsPerceptionsHandler, GNSSPerceptionHandler, ImagePerceptionHandler, IMUPerceptionHandler, and PointPerceptionHandler.
|
protected |
Returns the parent lifecycle node.
|
protected |
Returns the parent lifecycle node.
| const std::string & get_sensor_name | ( | ) | const |
Returns the sensor name provided during initialize.
| void initialize | ( | const std::shared_ptr< rclcpp_lifecycle::LifecycleNode > | parent_node, |
| const rclcpp::CallbackGroup::SharedPtr | realtime_cbg, | ||
| const std::string & | sensor_name ) |
Initializes the handler with the parent node and sensor name.
Must be called once before any other method. Stores the node and sensor name, then delegates to on_initialize for subclass-specific setup.
| parent_node | Shared pointer to the lifecycle node managing this handler. |
| sensor_name | Name of the sensor (used as parameter namespace prefix). |
|
virtual |
Optional post-initialization hook for subclasses.
Here, the handler must reserve memory to store the perception data and create any Subscription or similar objects to read the data.
Reimplemented in DummyHandler, DetectionsPerceptionsHandler, GNSSPerceptionHandler, ImagePerceptionHandler, IMUPerceptionHandler, and PointPerceptionHandler.
|
protected |
Shared pointer to the parent lifecycle node.
|
protected |
Callback group for real-time operations.
|
protected |
Name of the sensor (used as YAML parameter namespace prefix).