Class CloudiniSubscriberPCL

Class Documentation

class CloudiniSubscriberPCL

ROS2 subscriber class that receives CompressedPointCloud2 messages and converts them directly to pcl::PCLPointCloud2 format.

This class provides a convenient way to subscribe to Cloudini-compressed point cloud topics and receive the decompressed data as PCL point clouds, bypassing the intermediate ROS sensor_msgs::PointCloud2 format.

Public Types

using CallbackType = std::function<void(const pcl::PCLPointCloud2::Ptr&)>

Public Functions

CloudiniSubscriberPCL(rclcpp::Node::SharedPtr node, const std::string &topic_name, CallbackType callback, const rclcpp::QoS &qos_profile = rclcpp::QoS(10))

Constructor for CloudiniSubscriberPCL.

Parameters:
  • node – Shared pointer to the ROS2 node

  • topic_name – Name of the topic to subscribe to (CompressedPointCloud2)

  • callback – User callback function that will be invoked with decompressed PCL cloud

  • qos_profile – QoS profile for the subscription (default: system default)

CloudiniSubscriberPCL(rclcpp::Node *node, const std::string &topic_name, CallbackType callback, const rclcpp::QoS &qos_profile = rclcpp::QoS(10))

Constructor overload using raw node pointer.

Parameters:
  • node – Raw pointer to the ROS2 node

  • topic_name – Name of the topic to subscribe to (CompressedPointCloud2)

  • callback – User callback function that will be invoked with decompressed PCL cloud

  • qos_profile – QoS profile for the subscription (default: system default)

~CloudiniSubscriberPCL()

Destructor - cleans up object pool.

inline rclcpp::SubscriptionBase::SharedPtr getSubscription() const

Get the underlying ROS2 subscription object.

Returns:

Shared pointer to the subscription

std::string getTopicName() const

Get the topic name this subscriber is listening to.

Returns:

Topic name string