Class PointPerceptionHandler

Inheritance Relationships

Base Type

Class Documentation

class PointPerceptionHandler : public easynav::PerceptionHandler

PerceptionHandler implementation for sensors producing point-based data.

Supports both sensor_msgs::msg::LaserScan and sensor_msgs::msg::PointCloud2, converting incoming messages into PointPerception instances.

Public Functions

inline virtual std::string group() const override

Returns the sensor group handled by this handler.

Returns:

The string literal "points".

inline virtual std::shared_ptr<PerceptionBase> create(const std::string&) override

Creates a new PointPerception instance.

Parameters:

sensor_id – Identifier of the sensor (currently unused, kept for future extensions).

Returns:

Shared pointer to a new PointPerception.

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) override

Creates a subscription to LaserScan or PointCloud2 messages and updates the perception.

The created subscription decodes incoming messages from topic according to type, converts them into a point cloud, and writes the result into target (including metadata such as stamp and frame_id).

Parameters:
  • node – Lifecycle node used to create the subscription.

  • topic – Topic name to subscribe to.

  • type – ROS message type name. Must be either "sensor_msgs/msg/LaserScan" or "sensor_msgs/msg/PointCloud2".

  • target – Shared pointer to the perception instance to be updated.

  • cb_group – Callback group for the subscription callback (executor-level concurrency control).

Returns:

Shared pointer to the created subscription.