Class RawSubscriber
Defined in File raw_subscriber.hpp
Inheritance Relationships
Base Type
public image_transport::SimpleSubscriberPlugin< sensor_msgs::msg::Image >
(Template Class SimpleSubscriberPlugin)
Class Documentation
-
class RawSubscriber : public image_transport::SimpleSubscriberPlugin<sensor_msgs::msg::Image>
The default SubscriberPlugin.
RawSubscriber is a simple wrapper for ros::Subscriber which listens for Image messages and passes them through to the callback.
Public Functions
-
inline virtual ~RawSubscriber()
-
inline virtual std::string getTransportName() const override
Get a string identifier for the transport provided by this plugin.
Protected Functions
-
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>.
-
inline virtual void subscribeImpl(rclcpp::Node *node, const std::string &base_topic, const Callback &callback, rmw_qos_profile_t custom_qos, rclcpp::SubscriptionOptions options) override
-
void subscribeImpl(rclcpp::Node *node, const std::string &base_topic, const Callback &callback, rmw_qos_profile_t custom_qos = rmw_qos_profile_default) = 0
Subscribe to an image transport topic. Must be implemented by the subclass.
-
inline void subscribeImpl(rclcpp::Node *node, const std::string &base_topic, const Callback &callback, rmw_qos_profile_t custom_qos, rclcpp::SubscriptionOptions options)
-
inline virtual ~RawSubscriber()