image_transport::SimplePublisherPlugin< M > Class Template Reference

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

#include <simple_publisher_plugin.h>

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

List of all members.

Classes

struct  SimplePublisherPluginImpl

Public Member Functions

virtual uint32_t getNumSubscribers () const
 Returns the number of subscribers that are currently connected to this PublisherPlugin.
virtual std::string getTopic () const
 Returns the communication topic that this PublisherPlugin will publish on.
virtual void publish (const sensor_msgs::Image &message) const
 Publish an image using the transport associated with this PublisherPlugin.
virtual void shutdown ()
 Shutdown any advertisements associated with this PublisherPlugin.
virtual ~SimplePublisherPlugin ()

Protected Types

typedef boost::function< void(const
M &)> 
PublishFn
 Generic function for publishing the internal message type.

Protected Member Functions

virtual void advertiseImpl (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const SubscriberStatusCallback &user_connect_cb, const SubscriberStatusCallback &user_disconnect_cb, const ros::VoidPtr &tracked_object, bool latch)
 Advertise a topic. Must be implemented by the subclass.
virtual void connectCallback (const ros::SingleSubscriberPublisher &pub)
 Function called when a subscriber connects to the internal publisher.
virtual void disconnectCallback (const ros::SingleSubscriberPublisher &pub)
 Function called when a subscriber disconnects from the internal publisher.
const ros::Publisher & getPublisher () const
 Returns the internal ros::Publisher.
virtual std::string getTopicToAdvertise (const std::string &base_topic) const
 Return the communication topic name for a given base topic.
const ros::NodeHandle & nh () const
 Returns the ros::NodeHandle to be used for parameter lookup.
virtual void publish (const sensor_msgs::Image &message, const PublishFn &publish_fn) const =0
 Publish an image using the specified publish function. Must be implemented by the subclass.

Private Types

typedef boost::function< void(const
sensor_msgs::Image &)> 
ImagePublishFn
typedef void(SimplePublisherPlugin::* SubscriberStatusMemFn )(const ros::SingleSubscriberPublisher &pub)

Private Member Functions

ros::SubscriberStatusCallback bindCB (const SubscriberStatusCallback &user_cb, SubscriberStatusMemFn internal_cb_fn)
template<class PubT >
PublishFn bindInternalPublisher (const PubT &pub) const
void subscriberCB (const ros::SingleSubscriberPublisher &ros_ssp, const SubscriberStatusCallback &user_cb, const ros::SubscriberStatusCallback &internal_cb)

Private Attributes

boost::scoped_ptr
< SimplePublisherPluginImpl
simple_impl_

Detailed Description

template<class M>
class image_transport::SimplePublisherPlugin< M >

Base class to simplify implementing most plugins to Publisher.

This base class vastly simplifies implementing a PublisherPlugin in the common case that all communication with the matching SubscriberPlugin happens over a single ROS topic using a transport-specific message type. SimplePublisherPlugin 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().

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

Definition at line 27 of file simple_publisher_plugin.h.


Member Typedef Documentation

template<class M>
typedef boost::function<void(const sensor_msgs::Image&)> image_transport::SimplePublisherPlugin< M >::ImagePublishFn [private]

Definition at line 186 of file simple_publisher_plugin.h.

template<class M>
typedef boost::function<void(const M&)> image_transport::SimplePublisherPlugin< M >::PublishFn [protected]

Generic function for publishing the internal message type.

Definition at line 75 of file simple_publisher_plugin.h.

template<class M>
typedef void(SimplePublisherPlugin::* image_transport::SimplePublisherPlugin< M >::SubscriberStatusMemFn)(const ros::SingleSubscriberPublisher &pub) [private]

Definition at line 145 of file simple_publisher_plugin.h.


Constructor & Destructor Documentation

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

Definition at line 30 of file simple_publisher_plugin.h.


Member Function Documentation

template<class M>
virtual void image_transport::SimplePublisherPlugin< M >::advertiseImpl ( ros::NodeHandle &  nh,
const std::string &  base_topic,
uint32_t  queue_size,
const SubscriberStatusCallback connect_cb,
const SubscriberStatusCallback disconnect_cb,
const ros::VoidPtr &  tracked_object,
bool  latch 
) [inline, protected, virtual]

Advertise a topic. Must be implemented by the subclass.

Implements image_transport::PublisherPlugin.

Definition at line 60 of file simple_publisher_plugin.h.

template<class M>
ros::SubscriberStatusCallback image_transport::SimplePublisherPlugin< M >::bindCB ( const SubscriberStatusCallback user_cb,
SubscriberStatusMemFn  internal_cb_fn 
) [inline, private]

Binds the user callback to subscriberCB(), which acts as an intermediary to expose a publish(Image) interface to the user while publishing to an internal topic.

Definition at line 151 of file simple_publisher_plugin.h.

template<class M>
template<class PubT >
PublishFn image_transport::SimplePublisherPlugin< M >::bindInternalPublisher ( const PubT &  pub  )  const [inline, private]

Returns a function object for publishing the transport-specific message type through some ROS publisher type.

Parameters:
pub An object with method void publish(const M&)

Definition at line 195 of file simple_publisher_plugin.h.

template<class M>
virtual void image_transport::SimplePublisherPlugin< M >::connectCallback ( const ros::SingleSubscriberPublisher &  pub  )  [inline, protected, virtual]

Function called when a subscriber connects to the internal publisher.

Defaults to noop.

Definition at line 102 of file simple_publisher_plugin.h.

template<class M>
virtual void image_transport::SimplePublisherPlugin< M >::disconnectCallback ( const ros::SingleSubscriberPublisher &  pub  )  [inline, protected, virtual]

Function called when a subscriber disconnects from the internal publisher.

Defaults to noop.

Definition at line 109 of file simple_publisher_plugin.h.

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

Returns the number of subscribers that are currently connected to this PublisherPlugin.

Implements image_transport::PublisherPlugin.

Definition at line 32 of file simple_publisher_plugin.h.

template<class M>
const ros::Publisher& image_transport::SimplePublisherPlugin< M >::getPublisher (  )  const [inline, protected]

Returns the internal ros::Publisher.

This really only exists so RawPublisher can implement no-copy intraprocess message passing easily.

Definition at line 125 of file simple_publisher_plugin.h.

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

Returns the communication topic that this PublisherPlugin will publish on.

Implements image_transport::PublisherPlugin.

Definition at line 38 of file simple_publisher_plugin.h.

template<class M>
virtual std::string image_transport::SimplePublisherPlugin< M >::getTopicToAdvertise ( 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::RawPublisher.

Definition at line 92 of file simple_publisher_plugin.h.

template<class M>
const ros::NodeHandle& image_transport::SimplePublisherPlugin< M >::nh (  )  const [inline, protected]

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

Definition at line 114 of file simple_publisher_plugin.h.

template<class M>
virtual void image_transport::SimplePublisherPlugin< M >::publish ( const sensor_msgs::Image &  message,
const PublishFn publish_fn 
) const [protected, pure virtual]

Publish an image using the specified publish function. Must be implemented by the subclass.

The PublishFn publishes the transport-specific message type. This indirection allows SimpleSubscriberPlugin to use this function for both normal broadcast publishing and single subscriber publishing (in subscription callbacks).

Implemented in image_transport::RawPublisher.

template<class M>
virtual void image_transport::SimplePublisherPlugin< M >::publish ( const sensor_msgs::Image &  message  )  const [inline, virtual]

Publish an image using the transport associated with this PublisherPlugin.

Implements image_transport::PublisherPlugin.

Definition at line 44 of file simple_publisher_plugin.h.

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

Shutdown any advertisements associated with this PublisherPlugin.

Implements image_transport::PublisherPlugin.

Definition at line 54 of file simple_publisher_plugin.h.

template<class M>
void image_transport::SimplePublisherPlugin< M >::subscriberCB ( const ros::SingleSubscriberPublisher &  ros_ssp,
const SubscriberStatusCallback user_cb,
const ros::SubscriberStatusCallback &  internal_cb 
) [inline, private]

Forms the ros::SingleSubscriberPublisher for the internal communication topic into an image_transport::SingleSubscriberPublisher for Image messages and passes it to the user subscriber status callback.

Definition at line 166 of file simple_publisher_plugin.h.


Member Data Documentation

template<class M>
boost::scoped_ptr<SimplePublisherPluginImpl> image_transport::SimplePublisherPlugin< M >::simple_impl_ [private]

Definition at line 143 of file simple_publisher_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