Class SubscriberPlugin
- Defined in File subscriber_plugin.hpp 
Inheritance Relationships
Derived Types
- public image_transport::SimpleSubscriberPlugin< sensor_msgs::msg::Image >(Template Class SimpleSubscriberPlugin)
- public image_transport::SimpleSubscriberPlugin< M >(Template Class SimpleSubscriberPlugin)
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 = 0
- Get a string identifier for the transport provided by this plugin. 
 - 
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. 
 - Subscribe to an image topic, version for bare function. 
 - Subscribe to an image topic, version for bare function. 
 - Subscribe to an image topic, version for class member function with bare pointer. 
 - Subscribe to an image topic, version for class member function with bare pointer. 
 - Subscribe to an image topic, version for class member function with shared_ptr. 
 - 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
 
- 
typedef std::function<void(const sensor_msgs::msg::Image::ConstSharedPtr&)> Callback