Class SubscriberFilter

Inheritance Relationships

Base Type

  • public message_filters::SimpleFilter< sensor_msgs::msg::Image >

Class Documentation

class SubscriberFilter : public message_filters::SimpleFilter<sensor_msgs::msg::Image>

Image subscription filter.

This class wraps Subscriber as a “filter” compatible with the message_filters package. It acts as a highest-level filter, simply passing messages from an image transport subscription through to the filters which have connected to it.

When this object is destroyed it will unsubscribe from the ROS subscription.

CONNECTIONS

SubscriberFilter has no input connection.

The output connection for the SubscriberFilter object is the same signature as for roscpp subscription callbacks, ie.

void callback(const std::shared_ptr<const sensor_msgs::msg::Image>&);

Public Functions

inline IMAGE_TRANSPORT_PUBLIC SubscriberFilter(rclcpp::Node *node, const std::string &base_topic, const std::string &transport)

Constructor.

See the ros::NodeHandle::subscribe() variants for more information on the parameters

Parameters:
  • nh – The ros::NodeHandle to use to subscribe.

  • base_topic – The topic to subscribe to.

  • queue_size – The subscription queue size

  • transport – The transport hint to pass along

inline IMAGE_TRANSPORT_PUBLIC SubscriberFilter()

Empty constructor, use subscribe() to subscribe to a topic.

inline IMAGE_TRANSPORT_PUBLIC ~SubscriberFilter()
inline IMAGE_TRANSPORT_PUBLIC void subscribe (rclcpp::Node *node, const std::string &base_topic, const std::string &transport, rmw_qos_profile_t custom_qos=rmw_qos_profile_default, rclcpp::SubscriptionOptions options=rclcpp::SubscriptionOptions())

Subscribe to a topic.

If this Subscriber is already subscribed to a topic, this function will first unsubscribe.

Parameters:
  • nh – The ros::NodeHandle to use to subscribe.

  • base_topic – The topic to subscribe to.

inline IMAGE_TRANSPORT_PUBLIC void unsubscribe ()

Force immediate unsubscription of this subscriber from its topic.

inline IMAGE_TRANSPORT_PUBLIC std::string getTopic () const
inline IMAGE_TRANSPORT_PUBLIC size_t getNumPublishers () const

Returns the number of publishers this subscriber is connected to.

inline IMAGE_TRANSPORT_PUBLIC std::string getTransport () const

Returns the name of the transport being used.

inline IMAGE_TRANSPORT_PUBLIC const Subscriber & getSubscriber () const

Returns the internal image_transport::Subscriber object.