Easy Navigation
Loading...
Searching...
No Matches
PointPerceptionHandler Class Reference

PerceptionHandler implementation for sensors producing point-based data. More...

#include <PointPerception.hpp>

Inheritance diagram for PointPerceptionHandler:
Collaboration diagram for PointPerceptionHandler:

Public Member Functions

std::shared_ptr< PerceptionBasecreate (const std::string &) override
 Creates a new PointPerception instance.
 
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.
 
std::string group () const override
 Returns the sensor group handled by this handler.
 
- Public Member Functions inherited from PerceptionHandler
virtual ~PerceptionHandler ()=default
 

Detailed Description

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.

Member Function Documentation

◆ create()

std::shared_ptr< PerceptionBase > create ( const std::string & )
overridevirtual

Creates a new PointPerception instance.

Parameters
sensor_idIdentifier of the sensor (currently unused, kept for future extensions).
Returns
Shared pointer to a new PointPerception.

Implements PerceptionHandler.

◆ create_subscription()

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

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
nodeLifecycle node used to create the subscription.
topicTopic name to subscribe to.
typeROS message type name. Must be either "sensor_msgs/msg/LaserScan" or "sensor_msgs/msg/PointCloud2".
targetShared pointer to the perception instance to be updated.
cb_groupCallback group for the subscription callback (executor-level concurrency control).
Returns
Shared pointer to the created subscription.

Implements PerceptionHandler.

◆ group()

std::string group ( ) const
overridevirtual

Returns the sensor group handled by this handler.

Returns
The string literal "points".

Implements PerceptionHandler.


The documentation for this class was generated from the following files: