Classes | Public Member Functions | Protected Member Functions | Private Attributes | List of all members
image_transport::SimpleSubscriberPlugin< M > Class Template Referenceabstract

Base class to simplify implementing most plugins to Subscriber. More...

#include <simple_subscriber_plugin.h>

Inheritance diagram for image_transport::SimpleSubscriberPlugin< M >:
Inheritance graph
[legend]

Classes

struct  SimpleSubscriberPluginImpl
 

Public Member Functions

virtual uint32_t getNumPublishers () const
 Returns the number of publishers this subscriber is connected to. More...
 
virtual std::string getTopic () const
 Get the transport-specific communication topic. More...
 
virtual void shutdown ()
 Unsubscribe the callback associated with this SubscriberPlugin. More...
 
virtual ~SimpleSubscriberPlugin ()
 
- Public Member Functions inherited from image_transport::SubscriberPlugin
virtual std::string getTransportName () const =0
 Get a string identifier for the transport provided by this plugin. More...
 
void subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
 Subscribe to an image topic, version for arbitrary boost::function object. More...
 
void subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(*fp)(const sensor_msgs::ImageConstPtr &), const TransportHints &transport_hints=TransportHints())
 Subscribe to an image topic, version for bare function. More...
 
template<class T >
void subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &), T *obj, const TransportHints &transport_hints=TransportHints())
 Subscribe to an image topic, version for class member function with bare pointer. More...
 
template<class T >
void subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 Subscribe to an image topic, version for class member function with shared_ptr. More...
 
virtual ~SubscriberPlugin ()
 

Protected Member Functions

virtual std::string getTopicToSubscribe (const std::string &base_topic) const
 Return the communication topic name for a given base topic. More...
 
virtual void internalCallback (const typename M::ConstPtr &message, const Callback &user_cb)=0
 Process a message. Must be implemented by the subclass. More...
 
const ros::NodeHandlenh () const
 Returns the ros::NodeHandle to be used for parameter lookup. More...
 
virtual void subscribeImpl (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const Callback &callback, const ros::VoidPtr &tracked_object, const TransportHints &transport_hints)
 Subscribe to an image transport topic. Must be implemented by the subclass. More...
 

Private Attributes

boost::scoped_ptr< SimpleSubscriberPluginImplsimple_impl_
 

Additional Inherited Members

- Public Types inherited from image_transport::SubscriberPlugin
typedef boost::function< void(const sensor_msgs::ImageConstPtr &)> Callback
 
- Static Public Member Functions inherited from image_transport::SubscriberPlugin
static std::string getLookupName (const std::string &transport_type)
 Return the lookup name of the SubscriberPlugin associated with a specific transport identifier. More...
 

Detailed Description

template<class M>
class image_transport::SimpleSubscriberPlugin< M >

Base class to simplify implementing most plugins to Subscriber.

The base class simplifies implementing a SubscriberPlugin in the common case that all communication with the matching PublisherPlugin happens over a single ROS topic using a transport-specific message type. SimpleSubscriberPlugin is templated on the transport-specific message type.

A subclass need implement only two methods:

For access to the parameter server and name remappings, use nh().

getTopicToSubscribe() controls the name of the internal communication topic. It defaults to <base topic>/<transport name>.

Definition at line 62 of file simple_subscriber_plugin.h.

Constructor & Destructor Documentation

◆ ~SimpleSubscriberPlugin()

template<class M>
virtual image_transport::SimpleSubscriberPlugin< M >::~SimpleSubscriberPlugin ( )
inlinevirtual

Definition at line 65 of file simple_subscriber_plugin.h.

Member Function Documentation

◆ getNumPublishers()

template<class M>
virtual uint32_t image_transport::SimpleSubscriberPlugin< M >::getNumPublishers ( ) const
inlinevirtual

Returns the number of publishers this subscriber is connected to.

Implements image_transport::SubscriberPlugin.

Definition at line 73 of file simple_subscriber_plugin.h.

◆ getTopic()

template<class M>
virtual std::string image_transport::SimpleSubscriberPlugin< M >::getTopic ( ) const
inlinevirtual

Get the transport-specific communication topic.

Implements image_transport::SubscriberPlugin.

Definition at line 67 of file simple_subscriber_plugin.h.

◆ getTopicToSubscribe()

template<class M>
virtual std::string image_transport::SimpleSubscriberPlugin< M >::getTopicToSubscribe ( const std::string &  base_topic) const
inlineprotectedvirtual

Return the communication topic name for a given base topic.

Defaults to <base topic>/<transport name>.

Reimplemented in image_transport::RawSubscriber.

Definition at line 98 of file simple_subscriber_plugin.h.

◆ internalCallback()

template<class M>
virtual void image_transport::SimpleSubscriberPlugin< M >::internalCallback ( const typename M::ConstPtr &  message,
const Callback user_cb 
)
protectedpure virtual

Process a message. Must be implemented by the subclass.

Parameters
messageA message from the PublisherPlugin.
user_cbThe user Image callback to invoke, if appropriate.

◆ nh()

template<class M>
const ros::NodeHandle& image_transport::SimpleSubscriberPlugin< M >::nh ( ) const
inlineprotected

Returns the ros::NodeHandle to be used for parameter lookup.

Definition at line 119 of file simple_subscriber_plugin.h.

◆ shutdown()

template<class M>
virtual void image_transport::SimpleSubscriberPlugin< M >::shutdown ( )
inlinevirtual

Unsubscribe the callback associated with this SubscriberPlugin.

Implements image_transport::SubscriberPlugin.

Definition at line 79 of file simple_subscriber_plugin.h.

◆ subscribeImpl()

template<class M>
virtual void image_transport::SimpleSubscriberPlugin< M >::subscribeImpl ( ros::NodeHandle nh,
const std::string &  base_topic,
uint32_t  queue_size,
const Callback callback,
const ros::VoidPtr tracked_object,
const TransportHints transport_hints 
)
inlineprotectedvirtual

Subscribe to an image transport topic. Must be implemented by the subclass.

Implements image_transport::SubscriberPlugin.

Definition at line 103 of file simple_subscriber_plugin.h.

Member Data Documentation

◆ simple_impl_

template<class M>
boost::scoped_ptr<SimpleSubscriberPluginImpl> image_transport::SimpleSubscriberPlugin< M >::simple_impl_
private

Definition at line 136 of file simple_subscriber_plugin.h.


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


image_transport
Author(s): Patrick Mihelich
autogenerated on Mon Feb 28 2022 22:31:45