Class RawSubscriber

Inheritance Relationships

Base Type

Class Documentation

class RawSubscriber : public point_cloud_transport::SimpleSubscriberPlugin<sensor_msgs::msg::PointCloud2>

The default SubscriberPlugin.

RawSubscriber is a simple wrapper for rclcpp::Subscription which listens for PointCloud2 messages and passes them through to the callback.

Public Functions

inline virtual ~RawSubscriber()
POINT_CLOUD_TRANSPORT_PUBLIC SubscriberPlugin::DecodeResult decodeTyped (const sensor_msgs::msg::PointCloud2::ConstSharedPtr &compressed) const
virtual POINT_CLOUD_TRANSPORT_PUBLIC SubscriberPlugin::DecodeResult decodeTyped (const sensor_msgs::msg::PointCloud2 &compressed) const

Decode the given compressed pointcloud into a raw message.

Parameters:

compressed[in] The input compressed pointcloud.

Returns:

The raw cloud message (if encoding succeeds), or an error message.

virtual POINT_CLOUD_TRANSPORT_PUBLIC std::string getDataType () const override

Return the datatype of the transported messages (as text in the form package/Message).

virtual POINT_CLOUD_TRANSPORT_PUBLIC void declareParameters () override

Declare parameter with this SubscriberPlugin.

virtual POINT_CLOUD_TRANSPORT_PUBLIC std::string getTransportName () const override

Get a string identifier for the transport provided by this plugin.

Protected Functions

POINT_CLOUD_TRANSPORT_PUBLIC void callback (const sensor_msgs::msg::PointCloud2::ConstSharedPtr &message, const Callback &user_cb) override
virtual POINT_CLOUD_TRANSPORT_PUBLIC std::string getTopicToSubscribe (const std::string &base_topic) const override

Get the name of the topic that this SubscriberPlugin will subscribe to.

Parameters:

base_topic[in] The topic that the subscriber was constructed with.

Returns:

The name of the topic that this SubscriberPlugin will subscribe to (e.g. <base_topic>/<transport_name>).

void subscribeImpl(std::shared_ptr<rclcpp::Node> node, const std::string &base_topic, const Callback &callback, rmw_qos_profile_t custom_qos = rmw_qos_profile_default) = 0

Subscribe to a point cloud transport topic. Must be implemented by the subclass.

void subscribeImpl(std::shared_ptr<rclcpp::Node> node, const std::string &base_topic, const Callback &callback, rmw_qos_profile_t custom_qos, rclcpp::SubscriptionOptions options) = 0