Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions
image_transport::SubscriberPlugin Class Reference

Base class for plugins to Subscriber. More...

#include <subscriber_plugin.h>

Inheritance diagram for image_transport::SubscriberPlugin:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::function< void(const
sensor_msgs::ImageConstPtr &)> 
Callback

Public Member Functions

virtual uint32_t getNumPublishers () const =0
 Returns the number of publishers this subscriber is connected to.
virtual std::string getTopic () const =0
 Get the transport-specific communication topic.
virtual std::string getTransportName () const =0
 Get a string identifier for the transport provided by this plugin.
virtual void shutdown ()=0
 Unsubscribe the callback associated with this SubscriberPlugin.
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.
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.
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.
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.
virtual ~SubscriberPlugin ()

Static Public Member Functions

static std::string getLookupName (const std::string &transport_type)
 Return the lookup name of the SubscriberPlugin associated with a specific transport identifier.

Protected Member Functions

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)=0
 Subscribe to an image transport topic. Must be implemented by the subclass.

Detailed Description

Base class for plugins to Subscriber.

Definition at line 14 of file subscriber_plugin.h.


Member Typedef Documentation

typedef boost::function<void(const sensor_msgs::ImageConstPtr&)> image_transport::SubscriberPlugin::Callback

Definition at line 17 of file subscriber_plugin.h.


Constructor & Destructor Documentation

Definition at line 19 of file subscriber_plugin.h.


Member Function Documentation

static std::string image_transport::SubscriberPlugin::getLookupName ( const std::string &  transport_type) [inline, static]

Return the lookup name of the SubscriberPlugin associated with a specific transport identifier.

Definition at line 91 of file subscriber_plugin.h.

virtual uint32_t image_transport::SubscriberPlugin::getNumPublishers ( ) const [pure virtual]

Returns the number of publishers this subscriber is connected to.

Implemented in image_transport::SimpleSubscriberPlugin< M >, and image_transport::SimpleSubscriberPlugin< sensor_msgs::Image >.

virtual std::string image_transport::SubscriberPlugin::getTopic ( ) const [pure virtual]

Get the transport-specific communication topic.

Implemented in image_transport::SimpleSubscriberPlugin< M >, and image_transport::SimpleSubscriberPlugin< sensor_msgs::Image >.

virtual std::string image_transport::SubscriberPlugin::getTransportName ( ) const [pure virtual]

Get a string identifier for the transport provided by this plugin.

Implemented in image_transport::RawSubscriber.

virtual void image_transport::SubscriberPlugin::shutdown ( ) [pure virtual]
void image_transport::SubscriberPlugin::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() 
) [inline]

Subscribe to an image topic, version for arbitrary boost::function object.

Definition at line 30 of file subscriber_plugin.h.

void image_transport::SubscriberPlugin::subscribe ( ros::NodeHandle nh,
const std::string &  base_topic,
uint32_t  queue_size,
void(*)(const sensor_msgs::ImageConstPtr &)  fp,
const TransportHints transport_hints = TransportHints() 
) [inline]

Subscribe to an image topic, version for bare function.

Definition at line 40 of file subscriber_plugin.h.

template<class T >
void image_transport::SubscriberPlugin::subscribe ( ros::NodeHandle nh,
const std::string &  base_topic,
uint32_t  queue_size,
void(T::*)(const sensor_msgs::ImageConstPtr &)  fp,
T *  obj,
const TransportHints transport_hints = TransportHints() 
) [inline]

Subscribe to an image topic, version for class member function with bare pointer.

Definition at line 53 of file subscriber_plugin.h.

template<class T >
void image_transport::SubscriberPlugin::subscribe ( ros::NodeHandle nh,
const std::string &  base_topic,
uint32_t  queue_size,
void(T::*)(const sensor_msgs::ImageConstPtr &)  fp,
const boost::shared_ptr< T > &  obj,
const TransportHints transport_hints = TransportHints() 
) [inline]

Subscribe to an image topic, version for class member function with shared_ptr.

Definition at line 64 of file subscriber_plugin.h.

virtual void image_transport::SubscriberPlugin::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 
) [protected, pure virtual]

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

Implemented in image_transport::SimpleSubscriberPlugin< M >, and image_transport::SimpleSubscriberPlugin< sensor_msgs::Image >.


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


image_transport
Author(s): Patrick Mihelich
autogenerated on Fri Jan 3 2014 11:24:09