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::ImagePublisher Class Referenceabstract

Publish consumed data to a ROS image topic. More...

#include <fkie_message_filters/image_publisher.h>

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

Public Types

using Input = IO< Inputs... >
 Grouped input types. More...
 

Public Member Functions

 ImagePublisher () noexcept
 Constructs an empty publisher. More...
 
 ImagePublisher (const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, bool latch=false) noexcept
 Constructor that advertises the given ROS image topic. More...
 
void advertise (const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, bool latch=false) noexcept
 Advertise ROS image topic. More...
 
void advertise (const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const image_transport::SubscriberStatusCallback &connect_cb, const image_transport::SubscriberStatusCallback &disconnect_cb=image_transport::SubscriberStatusCallback(), const ros::VoidPtr &tracked_object=ros::VoidPtr(), bool latch=false) noexcept
 Advertise ROS image topic with subscriber status callbacks. More...
 
Connection connect_to_source (Source< Inputs... > &src) noexcept
 Connect this sink to a source. More...
 
virtual void disconnect () noexcept override
 Disconnect from all connected sources. More...
 
void disconnect_from_all_sources () noexcept
 Disconnect from all connected sources. More...
 
virtual bool is_active () const noexcept override
 Check if the ROS publisher has at least one subscriber. More...
 
virtual void reset () noexcept
 Reset filter state. More...
 
virtual std::string topic () const noexcept override
 Return the configured ROS topic. More...
 

Static Public Attributes

static constexpr std::size_t NUM_INPUTS
 Number of input arguments.
 

Protected Member Functions

std::tuple< boost::signals2::connection, boost::signals2::connection > link_with_subscriber (SubscriberBase &sub)
 Add a new subscriber that will be controlled by this publisher. More...
 
virtual void receive (const Inputs &... in)=0
 Process incoming data. More...
 
void update_subscriber_state ()
 Cause all linked subscribers to subscribe or unsubscribe to their ROS topics. More...
 

Detailed Description

Publish consumed data to a ROS image topic.

This is a specialized publisher that uses image_transport to publish to a ROS image topic. All messages which are received from the connected sources will be published on the advertised ROS topic.

Unlike regular ROS publishers, this class can be associated with one or more subscriber instances. In that case, the subscribers will subscribe to their ROS topics only if the publisher is actively used. This is a convenient method to save processing power if the filter pipeline is used only intermittently.

See also
ImageSubscriber, CameraPublisher, Publisher

Member Typedef Documentation

◆ Input

using fkie_message_filters::Sink< Inputs >::Input = IO<Inputs...>
inherited

Grouped input types.

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

Constructor & Destructor Documentation

◆ ImagePublisher() [1/2]

fkie_message_filters::ImagePublisher::ImagePublisher ( )
inlinenoexcept

Constructs an empty publisher.

You need to call advertise() to actually publish to a ROS topic.

Exceptions
Does not throw any exceptions.

◆ ImagePublisher() [2/2]

fkie_message_filters::ImagePublisher::ImagePublisher ( const image_transport::ImageTransport &  it,
const std::string &  base_topic,
uint32_t  queue_size,
bool  latch = false 
)
noexcept

Constructor that advertises the given ROS image topic.

The constructor calls advertise() for you.

Exceptions
Does not throw any exceptions.

Member Function Documentation

◆ advertise() [1/2]

void fkie_message_filters::ImagePublisher::advertise ( const image_transport::ImageTransport &  it,
const std::string &  base_topic,
uint32_t  queue_size,
bool  latch = false 
)
noexcept

Advertise ROS image topic.

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

  • it ROS image_transport instance to handle the publishing
  • base_topic name of the ROS image topic, subject to remapping
  • queue_size size of the ROS publishing queue
  • latch if true, the last published message remains available for later subscribers
Exceptions
Does not throw any exceptions.

◆ advertise() [2/2]

void fkie_message_filters::ImagePublisher::advertise ( const image_transport::ImageTransport &  it,
const std::string &  base_topic,
uint32_t  queue_size,
const image_transport::SubscriberStatusCallback &  connect_cb,
const image_transport::SubscriberStatusCallback &  disconnect_cb = image_transport::SubscriberStatusCallback(),
const ros::VoidPtr &  tracked_object = ros::VoidPtr(),
bool  latch = false 
)
noexcept

Advertise ROS image topic with subscriber status callbacks.

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

  • it ROS image_transport instance to handle the publishing
  • base_topic name of the ROS image topic, subject to remapping
  • queue_size size of the ROS publishing queue
  • connect_cb callback that is invoked each time a new subscriber connects to the advertised topic
  • disconnect_cb callback that is invoked each time an existing subscriber disconnects from the advertised topic
  • tracked_object an associated object whose lifetime will limit the lifetime of the advertised topic
  • latch if true, the last published message remains available for later subscribers
Exceptions
Does not throw any exceptions.

◆ connect_to_source()

Connection fkie_message_filters::Sink< Inputs >::connect_to_source ( Source< Inputs... > &  src)
noexceptinherited

Connect this sink to a source.

Can be called multiple times to connect multiple sources; in that case, the sink receives data from all connected sources. This function does basically the same thing as Source::connect_to_sink(), only from the opposite point of view.

  • src the source 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::Sink< Inputs >::disconnect ( )
overridevirtualnoexceptinherited

Disconnect from all connected sources.

The sink implementation calls disconnect_from_all_sources().

Exceptions
Does not throw any exceptions.

Implements fkie_message_filters::FilterBase.

◆ disconnect_from_all_sources()

void fkie_message_filters::Sink< Inputs >::disconnect_from_all_sources ( )
noexceptinherited

Disconnect from all connected sources.

Severs the connection to all sources. The receive() method will not be called any more.

Exceptions
Does not throw any exceptions.

◆ is_active()

bool fkie_message_filters::ImagePublisher::is_active ( ) const
overridevirtualnoexcept

Check if the ROS publisher has at least one subscriber.

Exceptions
Does not throw any exceptions.

Implements fkie_message_filters::PublisherBase.

◆ link_with_subscriber()

std::tuple< boost::signals2::connection, boost::signals2::connection > fkie_message_filters::PublisherBase::link_with_subscriber ( SubscriberBase sub)
protectedinherited

Add a new subscriber that will be controlled by this publisher.

  • sub the subscriber
    Returns
    two connection objects for the signal to enable and disable the linked subscriber
    Exceptions
    Propagates exceptions raised by the implementation of the abstract class methods.

◆ receive()

virtual void fkie_message_filters::Sink< Inputs >::receive ( const Inputs &...  in)
protectedpure virtualinherited

Process incoming data.

Derived classes need to override this method to handle all data that is to be consumed by the sink.

Exceptions
Depends on the implementation.

◆ 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... >.

◆ topic()

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

Return the configured ROS topic.

Exceptions
Does not throw any exceptions.

Implements fkie_message_filters::PublisherBase.

◆ update_subscriber_state()

void fkie_message_filters::PublisherBase::update_subscriber_state ( )
protectedinherited

Cause all linked subscribers to subscribe or unsubscribe to their ROS topics.

This will check the return value of is_active() to determine if the publisher is active, and then call SubscriberBase::subscribe_impl() or SubscriberBase::unsubscribe_impl() accordingly.

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

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