FKIE Message Filters
Improved filters for processing ROS messages
Public Types | Public Member Functions | Static Public Attributes | Protected Member Functions | List of all members
fkie_message_filters::CameraSubscriber Class Reference

Subscribe to ROS camera topics as data provider. More...

#include <fkie_message_filters/camera_subscriber.h>

Inheritance diagram for fkie_message_filters::CameraSubscriber:
Inheritance graph
[legend]
Collaboration diagram for fkie_message_filters::CameraSubscriber:
Collaboration graph
[legend]

Public Types

using Output = IO< Outputs... >
 Grouped output types. More...
 

Public Member Functions

 CameraSubscriber () noexcept
 Constructs an empty subscriber. More...
 
 CameraSubscriber (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 camera base topic. More...
 
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 void reset () noexcept
 Reset filter state. 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...
 
virtual void subscribe ()
 Subscribe to the configured ROS topic. 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 void subscribe_on_demand (PublisherBase &pub)
 Subscribe to the configured ROS topic whenever the given publisher is active. More...
 
virtual std::string topic () const noexcept
 Return the configured ROS topic. More...
 
virtual void unsubscribe ()
 Unsubscribe from the configured ROS topic. More...
 

Static Public Attributes

static constexpr std::size_t NUM_OUTPUTS
 Number of output arguments.
 

Protected Member Functions

virtual bool is_configured () const noexcept override
 Check if the ROS subscriber is properly configured. More...
 
void link_with_publisher (PublisherBase &pub)
 Add self to the list of subscribers which are controlled by a publisher. More...
 
void send (const Outputs &... out)
 Pass data to all connected sinks. More...
 
virtual void subscribe_impl () noexcept override
 Create a ROS subscriber. More...
 
void unlink_from_publisher ()
 Remove self from the list of subscribers which are controlled by a publisher. More...
 
virtual void unsubscribe_impl () noexcept override
 Shut the ROS subscriber down. More...
 

Detailed Description

Subscribe to ROS camera topics as data provider.

This is a specialized subscriber that uses image_transport to subscribe to ROS camera topics. All messages which are received on the subscribed topics 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
CameraPublisher, ImageSubscriber, Subscriber

Member Typedef Documentation

◆ Output

using fkie_message_filters::Source< Outputs >::Output = IO<Outputs...>
inherited

Grouped output types.

This type can be used to define sinks with matching types.

Constructor & Destructor Documentation

◆ CameraSubscriber() [1/2]

fkie_message_filters::CameraSubscriber::CameraSubscriber ( )
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.

◆ CameraSubscriber() [2/2]

fkie_message_filters::CameraSubscriber::CameraSubscriber ( 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 camera base 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 camera base topic, subject to remapping
  • queue_size size of the ROS subscription queue
  • transport_hints transport hints for the ROS image_transport framework
Exceptions
Does not throw any exceptions.

Member Function Documentation

◆ connect_to_sink()

Connection fkie_message_filters::Source< Outputs >::connect_to_sink ( Sink< Outputs... > &  dst)
noexceptinherited

Connect this source to a sink.

Can be called multiple times to connect multiple sinks; in that case, the sinks receive data in the same order as they have been connected. This function does basically the same thing as Sink::connect_to_source(), only from the opposite point of view.

  • dst the sink that is to be connected
Returns
a connection object that can be used to monitor or sever the created connection
Exceptions
Does not throw any exceptions.

◆ disconnect()

virtual void fkie_message_filters::Source< Outputs >::disconnect ( )
overridevirtualnoexceptinherited

Disconnect from all connected sinks.

The source implementation calls disconnect_from_all_sinks().

Exceptions
Does not throw any exceptions.

Implements fkie_message_filters::FilterBase.

◆ disconnect_from_all_sinks()

void fkie_message_filters::Source< Outputs >::disconnect_from_all_sinks ( )
noexceptinherited

Disconnect from all connected sinks.

Severs the connection to all sinks, turning the send() method into a no-op.

Exceptions
Does not throw any exceptions.

◆ is_configured()

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

Check if the ROS subscriber is properly configured.

Exceptions
Does not throw any exceptions.

Implements fkie_message_filters::SubscriberBase.

◆ link_with_publisher()

void fkie_message_filters::SubscriberBase::link_with_publisher ( PublisherBase pub)
protectedinherited

Add self to the list of subscribers which are controlled by a publisher.

A subscriber can be linked with one publisher only. Any previously linked publisher is unlinked first.

  • pub publisher
Exceptions
Propagates exceptions raised by the implementation of the abstract class methods.
See also
PublisherBase::link_with_subscriber()

◆ reset()

virtual void fkie_message_filters::FilterBase::reset ( )
inlinevirtualnoexceptinherited

Reset filter state.

For stateful filters, this method resets the internal state as if the filter had just been created. Existing connections to sources and sinks are unaffected.

The default implementation does nothing.

Exceptions
Does not throw any exceptions.

Reimplemented in fkie_message_filters::Buffer< Inputs >, fkie_message_filters::Buffer< Inputs... >, fkie_message_filters::TfFilter< Inputs >, fkie_message_filters::TfFilter< Inputs... >, fkie_message_filters::Combiner< PolicyTmpl, IOs >, fkie_message_filters::Sequencer< Inputs >, and fkie_message_filters::Sequencer< Inputs... >.

◆ send()

void fkie_message_filters::Source< Outputs >::send ( const Outputs &...  out)
protectedinherited

Pass data to all connected sinks.

  • out data
Exceptions
Does not throw any exceptions, but will propagate uncaught exceptions from filter callbacks.

◆ set_subscribe_options()

void fkie_message_filters::CameraSubscriber::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 camera base topic, subject to remapping
  • queue_size size of the ROS subscription queue
  • transport_hints transport hints for the ROS image_transport framework
Exceptions
Does not throw any exceptions.

◆ subscribe() [1/2]

void fkie_message_filters::SubscriberBase::subscribe ( )
virtualinherited

Subscribe to the configured ROS topic.

This method does nothing if no ROS topic was configured or if the subscriber is subscribed already. Cancels the effect of subscribe_on_demand(), i.e. the subscriber will remain subscribed permanently.

Exceptions
Propagates exceptions raised by the implementation of the abstract class methods.

◆ subscribe() [2/2]

void fkie_message_filters::CameraSubscriber::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 camera base topic, subject to remapping
  • queue_size size of the ROS subscription queue
  • transport_hints transport hints for the ROS image_transport framework
Exceptions
Does not throw any exceptions.

◆ subscribe_impl()

void fkie_message_filters::CameraSubscriber::subscribe_impl ( )
overrideprotectedvirtualnoexcept

Create a ROS subscriber.

Exceptions
Does not throw any exceptions.

Implements fkie_message_filters::SubscriberBase.

◆ subscribe_on_demand()

void fkie_message_filters::SubscriberBase::subscribe_on_demand ( PublisherBase pub)
virtualinherited

Subscribe to the configured ROS topic whenever the given publisher is active.

This method does nothing if no ROS topic was configured. Otherwise, it will immediately subscribe or unsubscribe depending on the publisher's current state. If the publisher becomes active or inactive, the subscriber's state will update accordingly.

  • pub publisher
Exceptions
Propagates exceptions raised by the implementation of the abstract class methods.

◆ topic()

std::string fkie_message_filters::CameraSubscriber::topic ( ) const
virtualnoexcept

Return the configured ROS topic.

Exceptions
Does not throw any exceptions.

Implements fkie_message_filters::SubscriberBase.

◆ unlink_from_publisher()

void fkie_message_filters::SubscriberBase::unlink_from_publisher ( )
protectedinherited

Remove self from the list of subscribers which are controlled by a publisher.

This will not affect the current subscription state. It will only prevent further updates from the previously linked publisher.

Exceptions
Does not throw any exceptions.

◆ unsubscribe()

void fkie_message_filters::SubscriberBase::unsubscribe ( )
virtualinherited

Unsubscribe from the configured ROS topic.

You can call subscribe() afterwards to re-subscribe to the ROS topic. This method does nothing if the subscriber is not subscribed to any ROS topic. Cancels the effect of subscribe_on_demand(), i.e. the subscriber will remain unsubscribed permanently.

Exceptions
Propagates exceptions raised by the implementation of the abstract class methods.

◆ unsubscribe_impl()

void fkie_message_filters::CameraSubscriber::unsubscribe_impl ( )
overrideprotectedvirtualnoexcept

Shut the ROS subscriber down.

Exceptions
Does not throw any exceptions.

Implements fkie_message_filters::SubscriberBase.


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