Image subscription filter. More...
#include <subscriber_filter.h>
Public Member Functions | |
uint32_t | getNumPublishers () const |
Returns the number of publishers this subscriber is connected to. More... | |
const Subscriber & | getSubscriber () const |
Returns the internal image_transport::Subscriber object. More... | |
std::string | getTopic () const |
std::string | getTransport () const |
Returns the name of the transport being used. More... | |
void | subscribe (ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints()) |
Subscribe to a topic. More... | |
SubscriberFilter (ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints()) | |
Constructor. More... | |
SubscriberFilter () | |
Empty constructor, use subscribe() to subscribe to a topic. More... | |
void | unsubscribe () |
Force immediate unsubscription of this subscriber from its topic. More... | |
~SubscriberFilter () | |
Private Member Functions | |
void | cb (const sensor_msgs::ImageConstPtr &m) |
Private Attributes | |
Subscriber | sub_ |
Additional Inherited Members |
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.
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 boost::shared_ptr<const sensor_msgs::Image>&);
Definition at line 64 of file subscriber_filter.h.
|
inline |
Constructor.
See the ros::NodeHandle::subscribe() variants for more information on the parameters
nh | The ros::NodeHandle to use to subscribe. |
base_topic | The topic to subscribe to. |
queue_size | The subscription queue size |
transport_hints | The transport hints to pass along |
Definition at line 77 of file subscriber_filter.h.
|
inline |
Empty constructor, use subscribe() to subscribe to a topic.
Definition at line 86 of file subscriber_filter.h.
|
inline |
Definition at line 90 of file subscriber_filter.h.
|
inlineprivate |
Definition at line 153 of file subscriber_filter.h.
|
inline |
Returns the number of publishers this subscriber is connected to.
Definition at line 130 of file subscriber_filter.h.
|
inline |
Returns the internal image_transport::Subscriber object.
Definition at line 146 of file subscriber_filter.h.
|
inline |
Definition at line 122 of file subscriber_filter.h.
|
inline |
Returns the name of the transport being used.
Definition at line 138 of file subscriber_filter.h.
|
inline |
Subscribe to a topic.
If this Subscriber is already subscribed to a topic, this function will first unsubscribe.
nh | The ros::NodeHandle to use to subscribe. |
base_topic | The topic to subscribe to. |
queue_size | The subscription queue size |
transport_hints | The transport hints to pass along |
Definition at line 105 of file subscriber_filter.h.
|
inline |
Force immediate unsubscription of this subscriber from its topic.
Definition at line 117 of file subscriber_filter.h.
|
private |
Definition at line 158 of file subscriber_filter.h.