Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
fkie_message_filters::ImageSubscriber Class Reference

Subscribe to a ROS image topic as data provider. More...

#include <image_subscriber.h>

Inheritance diagram for fkie_message_filters::ImageSubscriber:
Inheritance graph
[legend]

Public Member Functions

 ImageSubscriber () noexcept
 Constructs an empty subscriber. More...
 
 ImageSubscriber (const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const image_transport::TransportHints &transport_hints=image_transport::TransportHints()) noexcept
 Constructor that subscribes to the given ROS image topic. More...
 
void set_subscribe_options (const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const image_transport::TransportHints &transport_hints=image_transport::TransportHints()) noexcept
 Configure ROS topic that is to be subscribed. More...
 
void subscribe (const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const image_transport::TransportHints &transport_hints=image_transport::TransportHints()) noexcept
 Convenience function to subscribe to a ROS topic. More...
 
virtual std::string topic () const noexcept override
 Return the subscribed topic name. More...
 
- Public Member Functions inherited from fkie_message_filters::SubscriberBase
virtual void subscribe ()
 Subscribe to the configured ROS topic. More...
 
virtual void subscribe_on_demand (PublisherBase &pub)
 Subscribe to the configured ROS topic whenever the given publisher is active. More...
 
virtual void unsubscribe ()
 Unsubscribe from the configured ROS topic. More...
 
virtual ~SubscriberBase ()
 
- Public Member Functions inherited from fkie_message_filters::Source< sensor_msgs::ImageConstPtr >
Connection connect_to_sink (Sink< Outputs... > &dst) noexcept
 Connect this source to a sink. More...
 
virtual void disconnect () noexcept override
 Disconnect from all connected sinks. More...
 
void disconnect_from_all_sinks () noexcept
 Disconnect from all connected sinks. More...
 
virtual ~Source ()
 
- Public Member Functions inherited from fkie_message_filters::FilterBase
virtual void reset () noexcept
 Reset filter state. More...
 
virtual ~FilterBase ()
 

Protected Member Functions

virtual bool is_configured () const noexcept override
 Check if the ROS subscriber is properly configured. More...
 
virtual void subscribe_impl () noexcept override
 Create a ROS subscriber. More...
 
virtual void unsubscribe_impl () noexcept override
 Shut the ROS subscriber down. More...
 
- Protected Member Functions inherited from fkie_message_filters::SubscriberBase
void link_with_publisher (PublisherBase &pub)
 Add self to the list of subscribers which are controlled by a publisher. More...
 
void unlink_from_publisher ()
 Remove self from the list of subscribers which are controlled by a publisher. More...
 
- Protected Member Functions inherited from fkie_message_filters::Source< sensor_msgs::ImageConstPtr >
void send (const Outputs &... out)
 Pass data to all connected sinks. More...
 

Private Member Functions

void cb (const sensor_msgs::ImageConstPtr &)
 

Private Attributes

std::string base_topic_
 
image_transport::TransportHints hints_
 
std::shared_ptr< image_transport::ImageTransportit_
 
uint32_t queue_size_
 
image_transport::Subscriber sub_
 

Additional Inherited Members

- Public Types inherited from fkie_message_filters::Source< sensor_msgs::ImageConstPtr >
using Output = IO< Outputs... >
 Grouped output types. More...
 
- Static Public Attributes inherited from fkie_message_filters::Source< sensor_msgs::ImageConstPtr >
static constexpr std::size_t NUM_OUTPUTS
 Number of output arguments. More...
 

Detailed Description

Subscribe to a ROS image topic as data provider.

This is a specialized subscriber that uses image_transport to subscribe to a ROS image topic. All messages which are received on the subscribed topic will be passed to the connected sinks for further processing.

Unlike regular ROS subscribers, this class can be associated with a publisher instance. In that case, the subscriber will delay subscription until the publisher is actively used and will unsubscribe (and stop passing data) as soon as the publisher becomes idle. This is a convenient method to save processing power if the filter pipeline is used only intermittently.

See also
ImagePublisher, CameraSubscriber, Subscriber

Definition at line 43 of file image_subscriber.h.

Constructor & Destructor Documentation

◆ ImageSubscriber() [1/2]

fkie_message_filters::ImageSubscriber::ImageSubscriber ( )
inlinenoexcept

Constructs an empty subscriber.

You need to call set_subscribe_options() and either subscribe() or subscribe_on_demand() to actually subscribe to a ROS topic.

Definition at line 52 of file image_subscriber.h.

◆ ImageSubscriber() [2/2]

fkie_message_filters::ImageSubscriber::ImageSubscriber ( const image_transport::ImageTransport it,
const std::string &  base_topic,
uint32_t  queue_size,
const image_transport::TransportHints transport_hints = image_transport::TransportHints() 
)
noexcept

Constructor that subscribes to the given ROS image topic.

This constructor calls set_subscribe_options() and subscribe() for you.

  • it ROS image_transport instance to handle the subscription
  • base_topic name of the ROS image topic, subject to remapping
  • queue_size size of the ROS subscription queue
  • transport_hints transport hints for the ROS image_transport framework

Definition at line 26 of file image_subscriber.cpp.

Member Function Documentation

◆ cb()

void fkie_message_filters::ImageSubscriber::cb ( const sensor_msgs::ImageConstPtr &  m)
private

Definition at line 76 of file image_subscriber.cpp.

◆ is_configured()

bool fkie_message_filters::ImageSubscriber::is_configured ( ) const
overrideprotectedvirtualnoexcept

Check if the ROS subscriber is properly configured.

Implements fkie_message_filters::SubscriberBase.

Definition at line 51 of file image_subscriber.cpp.

◆ set_subscribe_options()

void fkie_message_filters::ImageSubscriber::set_subscribe_options ( const image_transport::ImageTransport it,
const std::string &  base_topic,
uint32_t  queue_size,
const image_transport::TransportHints transport_hints = image_transport::TransportHints() 
)
noexcept

Configure ROS topic that is to be subscribed.

All arguments are passed to the ROS client library; see the ROS documentation for further information. Calling this method will automatically unsubscribe any previously subscribed ROS topic.

  • it ROS image_transport instance to handle the subscription
  • base_topic name of the ROS image topic, subject to remapping
  • queue_size size of the ROS subscription queue
  • transport_hints transport hints for the ROS image_transport framework

Definition at line 32 of file image_subscriber.cpp.

◆ subscribe()

void fkie_message_filters::ImageSubscriber::subscribe ( const image_transport::ImageTransport it,
const std::string &  base_topic,
uint32_t  queue_size,
const image_transport::TransportHints transport_hints = image_transport::TransportHints() 
)
noexcept

Convenience function to subscribe to a ROS topic.

This function is equivalent to calling set_subscribe_options() and then subscribe().

  • it ROS image_transport instance to handle the subscription
  • base_topic name of the ROS image topic, subject to remapping
  • queue_size size of the ROS subscription queue
  • transport_hints transport hints for the ROS image_transport framework

Definition at line 40 of file image_subscriber.cpp.

◆ subscribe_impl()

void fkie_message_filters::ImageSubscriber::subscribe_impl ( )
overrideprotectedvirtualnoexcept

Create a ROS subscriber.

Implements fkie_message_filters::SubscriberBase.

Definition at line 56 of file image_subscriber.cpp.

◆ topic()

std::string fkie_message_filters::ImageSubscriber::topic ( ) const
overridevirtualnoexcept

Return the subscribed topic name.

Implements fkie_message_filters::SubscriberBase.

Definition at line 46 of file image_subscriber.cpp.

◆ unsubscribe_impl()

void fkie_message_filters::ImageSubscriber::unsubscribe_impl ( )
overrideprotectedvirtualnoexcept

Shut the ROS subscriber down.

Implements fkie_message_filters::SubscriberBase.

Definition at line 71 of file image_subscriber.cpp.

Member Data Documentation

◆ base_topic_

std::string fkie_message_filters::ImageSubscriber::base_topic_
private

Definition at line 114 of file image_subscriber.h.

◆ hints_

image_transport::TransportHints fkie_message_filters::ImageSubscriber::hints_
private

Definition at line 116 of file image_subscriber.h.

◆ it_

std::shared_ptr<image_transport::ImageTransport> fkie_message_filters::ImageSubscriber::it_
private

Definition at line 113 of file image_subscriber.h.

◆ queue_size_

uint32_t fkie_message_filters::ImageSubscriber::queue_size_
private

Definition at line 115 of file image_subscriber.h.

◆ sub_

image_transport::Subscriber fkie_message_filters::ImageSubscriber::sub_
private

Definition at line 117 of file image_subscriber.h.


The documentation for this class was generated from the following files:


fkie_message_filters
Author(s): Timo Röhling
autogenerated on Mon Feb 28 2022 22:21:44