image_transport::SimpleSubscriberPlugin< M > Class Template Reference

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]

List of all members.

Classes

struct  SimpleSubscriberPluginImpl

Public Member Functions

virtual uint32_t getNumPublishers () const
 Returns the number of publishers this subscriber is connected to.
virtual std::string getTopic () const
 Get the transport-specific communication topic.
virtual void shutdown ()
 Unsubscribe the callback associated with this SubscriberPlugin.
virtual ~SimpleSubscriberPlugin ()

Protected Member Functions

virtual std::string getTopicToSubscribe (const std::string &base_topic) const
 Return the communication topic name for a given base topic.
virtual void internalCallback (const typename M::ConstPtr &message, const Callback &user_cb)=0
 Process a message. Must be implemented by the subclass.
const ros::NodeHandle & nh () const
 Returns the ros::NodeHandle to be used for parameter lookup.
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.

Private Attributes

boost::scoped_ptr
< SimpleSubscriberPluginImpl
simple_impl_

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 28 of file simple_subscriber_plugin.h.


Constructor & Destructor Documentation

template<class M>
virtual image_transport::SimpleSubscriberPlugin< M >::~SimpleSubscriberPlugin (  )  [inline, virtual]

Definition at line 31 of file simple_subscriber_plugin.h.


Member Function Documentation

template<class M>
virtual uint32_t image_transport::SimpleSubscriberPlugin< M >::getNumPublishers (  )  const [inline, virtual]

Returns the number of publishers this subscriber is connected to.

Implements image_transport::SubscriberPlugin.

Definition at line 39 of file simple_subscriber_plugin.h.

template<class M>
virtual std::string image_transport::SimpleSubscriberPlugin< M >::getTopic (  )  const [inline, virtual]

Get the transport-specific communication topic.

Implements image_transport::SubscriberPlugin.

Definition at line 33 of file simple_subscriber_plugin.h.

template<class M>
virtual std::string image_transport::SimpleSubscriberPlugin< M >::getTopicToSubscribe ( const std::string &  base_topic  )  const [inline, protected, virtual]

Return the communication topic name for a given base topic.

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

Reimplemented in image_transport::RawSubscriber.

Definition at line 64 of file simple_subscriber_plugin.h.

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

Process a message. Must be implemented by the subclass.

Parameters:
message A message from the PublisherPlugin.
user_cb The user Image callback to invoke, if appropriate.
template<class M>
const ros::NodeHandle& image_transport::SimpleSubscriberPlugin< M >::nh (  )  const [inline, protected]

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

Definition at line 85 of file simple_subscriber_plugin.h.

template<class M>
virtual void image_transport::SimpleSubscriberPlugin< M >::shutdown (  )  [inline, virtual]

Unsubscribe the callback associated with this SubscriberPlugin.

Implements image_transport::SubscriberPlugin.

Definition at line 45 of file simple_subscriber_plugin.h.

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 
) [inline, protected, virtual]

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

Implements image_transport::SubscriberPlugin.

Definition at line 69 of file simple_subscriber_plugin.h.


Member Data Documentation

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

Definition at line 102 of file simple_subscriber_plugin.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


image_transport
Author(s): Patrick Mihelich
autogenerated on Fri Jan 11 11:44:59 2013