Template Class SimpleSubscriberPlugin
Defined in File simple_subscriber_plugin.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public point_cloud_transport::SubscriberPlugin
(Class SubscriberPlugin)
Class Documentation
-
template<class M>
class SimpleSubscriberPlugin : public point_cloud_transport::SubscriberPlugin Base class to simplify implementing most plugins to Subscriber.
The base class simplifies implementing a SubscriberPlugin in the common case that all communication with the matching PublisherPlugin happens over a single ROS topic using a transport-specific message type. SimpleSubscriberPlugin is templated on the transport-specific message type.
A subclass needs to implement:
- Template Parameters:
M – Type of the subscribed messages.
Public Functions
-
inline virtual ~SimpleSubscriberPlugin()
-
inline rclcpp::Logger getLogger() const
-
inline virtual std::string getTopic() const override
Get the transport-specific communication topic.
-
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 getNumPublishers() const override
Returns the number of publishers this subscriber is connected to.
-
inline virtual void shutdown() override
Unsubscribe the callback associated with this SubscriberPlugin.
-
virtual DecodeResult decodeTyped(const M &compressed) const = 0
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.
Decode the given compressed pointcloud into a raw cloud.
- Parameters:
compressed – [in] The rclcpp::SerializedMessage of the compressed pointcloud to be decoded.
- Returns:
The decoded raw pointcloud (if decoding succeeds), or an error message.
Protected Functions
Process a message. Must be implemented by the subclass.
-
inline virtual std::string getTopicToSubscribe(const std::string &base_topic) const override
Return the communication topic name for a given base topic.
Defaults to <base topic>/<transport name>.
Subscribe to a point cloud transport topic. Must be implemented by the subclass.