Class RawPublisher

Inheritance Relationships

Base Type

Class Documentation

class RawPublisher : public point_cloud_transport::SimplePublisherPlugin<sensor_msgs::msg::PointCloud2>

RawPublisher is a simple wrapper for ros::Publisher, publishing unaltered PointCloud2 messages on the base topic.

Public Functions

inline virtual ~RawPublisher()
inline virtual std::string getTransportName() const

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

inline virtual std::string getDataType() const override

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

inline virtual void declareParameters(const std::string&) override

Declare parameter with this PublisherPlugin.

inline virtual RawPublisher::TypedEncodeResult encodeTyped(const sensor_msgs::msg::PointCloud2 &raw) const

Encode the given raw pointcloud into a compressed message.

Parameters:

raw[in] The input raw pointcloud.

Returns:

The output rmw serialized msg holding the compressed cloud message (if encoding succeeds), or an error message.

Protected Functions

inline virtual void publish(const sensor_msgs::msg::PointCloud2 &message, const PublishFn &publish_fn) const

Publish a point cloud using the specified publish function.

The PublishFn publishes the transport-specific message type. This indirection allows SimplePublisherPlugin to use this function for both normal broadcast publishing and single subscriber publishing (in subscription callbacks).

inline virtual void publish(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &message_ptr, const PublishFn &publish_fn) const
inline virtual std::string getTopicToAdvertise(const std::string &base_topic) const