Public Member Functions | Protected Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
fkie_message_filters::Subscriber< M, Translate > Class Template Reference

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

#include <subscriber.h>

Inheritance diagram for fkie_message_filters::Subscriber< M, Translate >:
Inheritance graph
[legend]

Public Member Functions

void set_subscribe_options (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=nullptr) noexcept
 Configure ROS topic that is to be subscribed. More...
 
virtual void subscribe ()
 Subscribe to the configured ROS topic. More...
 
void subscribe (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=nullptr) 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...
 
 Subscriber () noexcept
 Constructs an empty subscriber. More...
 
 Subscriber (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=nullptr) noexcept
 Constructor that subscribes to the given ROS topic. More...
 
virtual std::string topic () const noexcept override
 Return the subscribed topic name. More...
 
virtual void unsubscribe ()
 Unsubscribe from the configured ROS topic. 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< RosMessageEvent< M >::FilterType >
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 ()
 

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< RosMessageEvent< M >::FilterType >
void send (const Outputs &... out)
 Pass data to all connected sinks. More...
 

Private Types

using EventType = typename Translate< M >::EventType
 
using FilterType = typename Translate< M >::FilterType
 

Private Member Functions

void cb (const EventType &event)
 

Private Attributes

std::shared_ptr< ros::NodeHandlenh_
 
ros::SubscribeOptions opts_
 
ros::Subscriber sub_
 

Additional Inherited Members

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

Detailed Description

template<class M, template< typename > class Translate = RosMessageEvent>
class fkie_message_filters::Subscriber< M, Translate >

Subscribe to a ROS topic as data provider.

This class together with the Publisher class is the generic interface between ROS and this library. All messages which are received on the subscribed topic will be passed to the connected sinks for further processing. For maximum flexibility, you can choose one of four ways how to pass the received message:

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
CameraSubscriber, ImageSubscriber

Definition at line 72 of file subscriber.h.

Member Typedef Documentation

◆ EventType

template<class M , template< typename > class Translate = RosMessageEvent>
using fkie_message_filters::Subscriber< M, Translate >::EventType = typename Translate<M>::EventType
private

Definition at line 161 of file subscriber.h.

◆ FilterType

template<class M , template< typename > class Translate = RosMessageEvent>
using fkie_message_filters::Subscriber< M, Translate >::FilterType = typename Translate<M>::FilterType
private

Definition at line 162 of file subscriber.h.

Constructor & Destructor Documentation

◆ Subscriber() [1/2]

template<class M , template< typename > class Translate>
fkie_message_filters::Subscriber< M, Translate >::Subscriber
noexcept

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.

\nothrow

Definition at line 47 of file subscriber_impl.h.

◆ Subscriber() [2/2]

template<class M , template< typename > class Translate>
fkie_message_filters::Subscriber< M, Translate >::Subscriber ( ros::NodeHandle nh,
const std::string &  topic,
uint32_t  queue_size,
const ros::TransportHints transport_hints = ros::TransportHints(),
ros::CallbackQueueInterface callback_queue = nullptr 
)
noexcept

Constructor that subscribes to the given ROS topic.

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

  • nh ROS node handle to create the ROS subscription
  • topic name of the ROS topic, subject to remapping
  • queue_size size of the ROS subscription queue
  • transport_hints low-level transport hints for the ROS client library
  • callback_queue custom ROS callback queue

\nothrow

Definition at line 52 of file subscriber_impl.h.

Member Function Documentation

◆ cb()

template<class M , template< typename > class Translate>
void fkie_message_filters::Subscriber< M, Translate >::cb ( const EventType event)
private

Definition at line 106 of file subscriber_impl.h.

◆ is_configured()

template<class M , template< typename > class Translate>
bool fkie_message_filters::Subscriber< M, Translate >::is_configured
overrideprotectedvirtualnoexcept

Check if the ROS subscriber is properly configured.

\nothrow

Implements fkie_message_filters::SubscriberBase.

Definition at line 85 of file subscriber_impl.h.

◆ set_subscribe_options()

template<class M , template< typename > class Translate>
void fkie_message_filters::Subscriber< M, Translate >::set_subscribe_options ( ros::NodeHandle nh,
const std::string &  topic,
uint32_t  queue_size,
const ros::TransportHints transport_hints = ros::TransportHints(),
ros::CallbackQueueInterface callback_queue = nullptr 
)
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.

  • nh ROS node handle to create the ROS subscription
  • topic name of the ROS topic, subject to remapping
  • queue_size size of the ROS subscription queue
  • transport_hints low-level transport hints for the ROS client library
  • callback_queue custom ROS callback queue

\nothrow

Definition at line 64 of file subscriber_impl.h.

◆ subscribe() [1/2]

template<class M , template< typename > class Translate = RosMessageEvent>
void fkie_message_filters::SubscriberBase::subscribe

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.

\implthrow

Definition at line 64 of file publisher_subscriber_base.cpp.

◆ subscribe() [2/2]

template<class M , template< typename > class Translate>
void fkie_message_filters::Subscriber< M, Translate >::subscribe ( ros::NodeHandle nh,
const std::string &  topic,
uint32_t  queue_size,
const ros::TransportHints transport_hints = ros::TransportHints(),
ros::CallbackQueueInterface callback_queue = nullptr 
)
noexcept

Convenience function to subscribe to a ROS topic.

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

  • nh ROS node handle to create the ROS subscription
  • topic name of the ROS topic, subject to remapping
  • queue_size size of the ROS subscription queue
  • transport_hints low-level transport hints for the ROS client library
  • callback_queue custom ROS callback queue

\nothrow

Definition at line 77 of file subscriber_impl.h.

◆ subscribe_impl()

template<class M , template< typename > class Translate>
void fkie_message_filters::Subscriber< M, Translate >::subscribe_impl
overrideprotectedvirtualnoexcept

Create a ROS subscriber.

\nothrow

Implements fkie_message_filters::SubscriberBase.

Definition at line 91 of file subscriber_impl.h.

◆ subscribe_on_demand()

template<class M , template< typename > class Translate = RosMessageEvent>
void fkie_message_filters::SubscriberBase::subscribe_on_demand

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

\implthrow

Definition at line 76 of file publisher_subscriber_base.cpp.

◆ topic()

template<class M , template< typename > class Translate>
std::string fkie_message_filters::Subscriber< M, Translate >::topic ( ) const
overridevirtualnoexcept

Return the subscribed topic name.

\abstractthrow

Implements fkie_message_filters::SubscriberBase.

Definition at line 58 of file subscriber_impl.h.

◆ unsubscribe()

template<class M , template< typename > class Translate = RosMessageEvent>
void fkie_message_filters::SubscriberBase::unsubscribe

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.

\implthrow

Definition at line 70 of file publisher_subscriber_base.cpp.

◆ unsubscribe_impl()

template<class M , template< typename > class Translate>
void fkie_message_filters::Subscriber< M, Translate >::unsubscribe_impl
overrideprotectedvirtualnoexcept

Shut the ROS subscriber down.

\nothrow

Implements fkie_message_filters::SubscriberBase.

Definition at line 100 of file subscriber_impl.h.

Member Data Documentation

◆ nh_

template<class M , template< typename > class Translate = RosMessageEvent>
std::shared_ptr<ros::NodeHandle> fkie_message_filters::Subscriber< M, Translate >::nh_
private

Definition at line 166 of file subscriber.h.

◆ opts_

template<class M , template< typename > class Translate = RosMessageEvent>
ros::SubscribeOptions fkie_message_filters::Subscriber< M, Translate >::opts_
private

Definition at line 165 of file subscriber.h.

◆ sub_

template<class M , template< typename > class Translate = RosMessageEvent>
ros::Subscriber fkie_message_filters::Subscriber< M, Translate >::sub_
private

Definition at line 164 of file subscriber.h.


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


fkie_message_filters
Author(s): Timo Röhling
autogenerated on Wed Mar 2 2022 00:18:57