Class SubscriberPlugin

Inheritance Relationships

Derived Types

Class Documentation

class SubscriberPlugin

Base class for plugins to Subscriber.

Subclassed by point_cloud_transport::SimpleSubscriberPlugin< sensor_msgs::msg::PointCloud2 >, point_cloud_transport::SimpleSubscriberPlugin< M >

Public Types

typedef tl::expected<std::optional<sensor_msgs::msg::PointCloud2::ConstSharedPtr>, std::string> DecodeResult

Result of cloud decoding. Either a sensor_msgs::msg::PointCloud2 holding the raw message, empty value or error message.

typedef std::function<void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr&)> Callback

Public Functions

SubscriberPlugin() = default
SubscriberPlugin(const SubscriberPlugin&) = delete
SubscriberPlugin &operator=(const SubscriberPlugin&) = delete
virtual ~SubscriberPlugin() = default
virtual std::string getTransportName() const = 0

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

virtual DecodeResult decode(const std::shared_ptr<rclcpp::SerializedMessage> &compressed) const = 0

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.

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

Subscribe to an pointcloud topic, version for arbitrary std::function object.

inline void subscribe(std::shared_ptr<rclcpp::Node> node, const std::string &base_topic, void (*fp)(const sensor_msgs::msg::PointCloud2::ConstSharedPtr&), rmw_qos_profile_t custom_qos = rmw_qos_profile_default, rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions())

Subscribe to an pointcloud topic, version for bare function.

template<class T>
inline void subscribe(std::shared_ptr<rclcpp::Node> node, const std::string &base_topic, void (T::* fp)(const sensor_msgs::msg::PointCloud2::ConstSharedPtr&), T *obj, rmw_qos_profile_t custom_qos = rmw_qos_profile_default, rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions())

Subscribe to an pointcloud topic, version for class member function with bare pointer.

virtual std::string getTopic() const = 0

Get the transport-specific communication topic.

virtual uint32_t getNumPublishers() const = 0

Returns the number of publishers this subscriber is connected to.

virtual void shutdown() = 0

Unsubscribe the callback associated with this SubscriberPlugin.

virtual std::string getDataType() const = 0

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

virtual void declareParameters() = 0

Declare parameter with this SubscriberPlugin.

virtual std::string getTopicToSubscribe(const std::string &base_topic) const = 0

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>).

Public Static Functions

static inline std::string getLookupName(const std::string &transport_type)

Return the lookup name of the SubscriberPlugin associated with a specific transport identifier.

Parameters:

transport_type – The transport identifier.

Returns:

The lookup name of the SubscriberPlugin associated with a specific

Protected Functions

virtual 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.

virtual 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