Class SubscriberPlugin

Inheritance Relationships

Derived Types

Class Documentation

class SubscriberPlugin

Base class for plugins to Subscriber.

Subclassed by image_transport::SimpleSubscriberPlugin< sensor_msgs::msg::Image >, image_transport::SimpleSubscriberPlugin< M >

Public Types

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

Public Functions

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

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

The default implementation auto-discovers the name from the pluginlib manifest XML (without instantiating any plugin) by matching the demangled C++ type name of *this against the type attribute of each <class> element. The result is cached after the first call.

Plugins that override getTransportName() continue to work unchanged — user-supplied overrides always take precedence over the base implementation. Returning a different value than what is in the manifest is considered problematic.

virtual std::string getMessageType() const

Get the primary message type used by this plugin.

Returns the value of the <message_type> element from the plugin manifest XML (e.g. "sensor_msgs/msg/Image"). The result is cached after the first call. Override this method if you need a different value at runtime. Returning a different value than what is in the manifest is considered problematic.

inline void subscribe(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 image topic, version for arbitrary std::function object.

inline void subscribe(RequiredInterfaces node_interfaces, const std::string &base_topic, const Callback &callback, rclcpp::QoS custom_qos, rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions())

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

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

Subscribe to an image topic, version for bare function.

inline void subscribe(RequiredInterfaces node_interfaces, const std::string &base_topic, void (*fp)(const sensor_msgs::msg::Image::ConstSharedPtr&), rclcpp::QoS custom_qos, rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions())

Subscribe to an image topic, version for bare function.

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

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

template<class T>
inline void subscribe(RequiredInterfaces node_interfaces, const std::string &base_topic, void (T::* fp)(const sensor_msgs::msg::Image::ConstSharedPtr&), T *obj, rclcpp::QoS custom_qos, rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions())

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

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

Subscribe to an image topic, version for class member function with shared_ptr.

template<class T>
inline void subscribe(RequiredInterfaces node_interfaces, const std::string &base_topic, void (T::* fp)(const sensor_msgs::msg::Image::ConstSharedPtr&), std::shared_ptr<T> &obj, rclcpp::QoS custom_qos)

Subscribe to an image topic, version for class member function with shared_ptr.

virtual std::string getTopic() const = 0

Get the transport-specific communication topic.

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

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.

Protected Functions

inline virtual void subscribeImpl(rclcpp::Node *node, const std::string &base_topic, const Callback &callback, rmw_qos_profile_t custom_qos, rclcpp::SubscriptionOptions options)
virtual void subscribeImpl(RequiredInterfaces node_interfaces, const std::string &base_topic, const Callback &callback, rclcpp::QoS custom_qos, rclcpp::SubscriptionOptions options) = 0