Class PerceptionHandler

Inheritance Relationships

Derived Types

Class Documentation

class PerceptionHandler

Abstract base interface for group-specific perception handlers.

Each handler is responsible for a sensor group (e.g., “points”, “image”, “dummy”). It creates appropriate PerceptionBase instances and handles the conversion from ROS messages.

Subclassed by easynav::DetectionsPerceptionsHandler, easynav::GNSSPerceptionHandler, easynav::IMUPerceptionHandler, easynav::ImagePerceptionHandler, easynav::PointPerceptionHandler

Public Functions

virtual ~PerceptionHandler() = default
virtual std::shared_ptr<PerceptionBase> create(const std::string &sensor_id) = 0

Creates a new instance of a perception object managed by this handler.

Parameters:

sensor_id – Name or ID of the sensor (optional use by handler).

Returns:

Shared pointer to a new instance of a class derived from PerceptionBase.

virtual rclcpp::SubscriptionBase::SharedPtr create_subscription(rclcpp_lifecycle::LifecycleNode &node, const std::string &topic, const std::string &type, std::shared_ptr<PerceptionBase> target, rclcpp::CallbackGroup::SharedPtr cb_group) = 0

Creates a subscription that processes messages into PerceptionBase instances.

The handler is expected to parse the message received on topic of type type and store the result in target.

Parameters:
  • node – Reference to the lifecycle node used for creating the subscription.

  • topic – Topic name to subscribe to.

  • type – ROS message type name (e.g., "sensor_msgs/msg/LaserScan").

  • target – Shared pointer where perception results are stored.

  • cb_group – Callback group where the subscription callback will be executed.

Returns:

Shared pointer to the created subscription.

virtual std::string group() const = 0

Returns the group identifier associated with this handler.

This identifier is used to match sensors to the appropriate handler. Example: "points", "image", "dummy".

Returns:

String representing the group name.