Class Subscriber

Class Documentation

class Subscriber

Manages a subscription callback on a specific topic that can be interpreted as a PointCloud2 topic.

Subscriber is the client-side counterpart to Publisher. By loading the appropriate plugin, it can subscribe to a base point cloud topic using any available transport. The complexity of what transport is actually used is hidden from the user, who sees only a normal PointCloud2 callback.

A Subscriber should always be created through a call to PointCloudTransport::subscribe(), or copied from one that was. Once all copies of a specific Subscriber go out of scope, the subscription callback associated with that handle will stop being called. Once all Subscriber for a given topic go out of scope the topic will be unsubscribed.

Public Types

typedef std::function<void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr&)> Callback

Public Functions

POINT_CLOUD_TRANSPORT_PUBLIC Subscriber() = default
POINT_CLOUD_TRANSPORT_PUBLIC Subscriber(std::shared_ptr<rclcpp::Node> node, const std::string &base_topic, const Callback &callback, SubLoaderPtr loader, const std::string &transport, rmw_qos_profile_t custom_qos = rmw_qos_profile_default, rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions())
POINT_CLOUD_TRANSPORT_PUBLIC std::string getTopic () const

Returns the base point cloud topic.

The Subscriber may actually be subscribed to some transport-specific topic that differs from the base topic.

POINT_CLOUD_TRANSPORT_PUBLIC uint32_t getNumPublishers () const

Returns the number of publishers this subscriber is connected to.

POINT_CLOUD_TRANSPORT_PUBLIC std::string getTransport () const

Returns the name of the transport being used.

POINT_CLOUD_TRANSPORT_PUBLIC void shutdown ()

Unsubscribe the callback associated with this Subscriber.

operator void*() const
inline POINT_CLOUD_TRANSPORT_PUBLIC bool operator< (const point_cloud_transport::Subscriber &rhs) const
inline POINT_CLOUD_TRANSPORT_PUBLIC bool operator!= (const point_cloud_transport::Subscriber &rhs) const
inline POINT_CLOUD_TRANSPORT_PUBLIC bool operator== (const point_cloud_transport::Subscriber &rhs) const