Template Class SimplePublisherPlugin
Defined in File simple_publisher_plugin.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public point_cloud_transport::PublisherPlugin
(Class PublisherPlugin)
Class Documentation
-
template<class M>
class SimplePublisherPlugin : public point_cloud_transport::PublisherPlugin Base class to simplify implementing most plugins to Publisher.
This base class vastly simplifies implementing a PublisherPlugin in the common case that all communication with the matching SubscriberPlugin happens over a single ROS topic using a transport-specific message type. SimplePublisherPlugin is templated on the transport-specific message type and publisher dynamic reconfigure type.
A subclass needs to implement:
- Template Parameters:
M – Type of the published messages.
Public Types
Public Functions
-
inline ~SimplePublisherPlugin()
-
inline rclcpp::Logger getLogger() const
-
template<typename T>
inline bool getParam(const std::string ¶meter_name, T &value) const template function for getting parameter of a given type
-
template<typename T>
inline bool declareParam(const std::string parameter_name, const T value, const rcl_interfaces::msg::ParameterDescriptor ¶meter_descriptor = rcl_interfaces::msg::ParameterDescriptor())
-
inline void setParamCallback(rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType param_change_callback)
-
inline virtual uint32_t getNumSubscribers() const override
Returns the number of subscribers that are currently connected to this PublisherPlugin.
-
inline virtual std::string getTopic() const override
Returns the topic that this PublisherPlugin will publish on.
-
inline virtual void publish(const sensor_msgs::msg::PointCloud2 &message) const override
Publish a point cloud using the transport associated with this PublisherPlugin.
-
inline virtual void shutdown() override
Shutdown any advertisements associated with this PublisherPlugin.
-
virtual TypedEncodeResult encodeTyped(const sensor_msgs::msg::PointCloud2 &raw) const = 0
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.
-
inline virtual EncodeResult encode(const sensor_msgs::msg::PointCloud2 &raw) const override
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.
Protected Types
Protected Functions
Advertise a topic. Must be implemented by the subclass.
-
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 std::string getTopicToAdvertise(const std::string &base_topic) const override
Return the communication topic name for a given base topic.
Defaults to <base topic>/<transport name>.
Protected Attributes
-
std::string base_topic_