Class PublisherPlugin
Defined in File publisher_plugin.hpp
Inheritance Relationships
Derived Types
public point_cloud_transport::SimplePublisherPlugin< sensor_msgs::msg::PointCloud2 >
(Template Class SimplePublisherPlugin)public point_cloud_transport::SimplePublisherPlugin< M >
(Template Class SimplePublisherPlugin)
Class Documentation
-
class PublisherPlugin
Base class for plugins to Publisher.
Subclassed by point_cloud_transport::SimplePublisherPlugin< sensor_msgs::msg::PointCloud2 >, point_cloud_transport::SimplePublisherPlugin< M >
Public Types
-
typedef tl::expected<std::optional<const std::shared_ptr<rclcpp::SerializedMessage>>, std::string> EncodeResult
Result of cloud encoding. Either an holding the compressed cloud, empty value or error message.
Public Functions
-
PublisherPlugin() = default
-
PublisherPlugin(const PublisherPlugin&) = delete
-
PublisherPlugin &operator=(const PublisherPlugin&) = delete
-
virtual std::string getTransportName() const = 0
Get a string identifier for the transport provided by this plugin.
- POINT_CLOUD_TRANSPORT_PUBLIC void advertise (std::shared_ptr< rclcpp::Node > node, const std::string &base_topic, rmw_qos_profile_t custom_qos=rmw_qos_profile_default, const rclcpp::PublisherOptions &options=rclcpp::PublisherOptions())
Advertise a topic, simple version.
-
virtual uint32_t getNumSubscribers() const = 0
Returns the number of subscribers that are currently connected to this PublisherPlugin.
-
virtual std::string getTopic() const = 0
Returns the topic that this PublisherPlugin will publish on.
-
virtual std::string getDataType() const = 0
Return the datatype of the transported messages (as text in the form
package/Message
).
- virtual POINT_CLOUD_TRANSPORT_PUBLIC EncodeResult encode (const sensor_msgs::msg::PointCloud2 &raw) const
Encode the given raw pointcloud into EncodeResult.
- Parameters:
raw – [in] The input raw pointcloud.
- Returns:
The output EncodeResult holding the compressed cloud message (if encoding succeeds), or an error message.
-
virtual void publish(const sensor_msgs::msg::PointCloud2 &message) const = 0
Publish a point cloud using the transport associated with this PublisherPlugin.
- virtual POINT_CLOUD_TRANSPORT_PUBLIC void publish (const sensor_msgs::msg::PointCloud2::ConstSharedPtr &message) const
Publish a point cloud using the transport associated with this PublisherPlugin.
-
virtual void shutdown() = 0
Shutdown any advertisements associated with this PublisherPlugin.
-
virtual void declareParameters(const std::string &base_topic) = 0
Declare parameter with this PublisherPlugin.
-
virtual std::string getTopicToAdvertise(const std::string &base_topic) const = 0
Public Static Functions
- static POINT_CLOUD_TRANSPORT_PUBLIC std::string getLookupName (const std::string &transport_name)
Return the lookup name of the PublisherPlugin associated with a specific transport identifier.
Protected Functions
Advertise a topic. Must be implemented by the subclass.
-
typedef tl::expected<std::optional<const std::shared_ptr<rclcpp::SerializedMessage>>, std::string> EncodeResult