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

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]

Classes

struct  SimplePublisherPluginImpl
 

Public Member Functions

virtual uint32_t getNumSubscribers () const
 Returns the number of subscribers that are currently connected to this PublisherPlugin. More...
 
virtual std::string getTopic () const
 Returns the communication topic that this PublisherPlugin will publish on. More...
 
virtual void publish (const sensor_msgs::Image &message) const
 Publish an image using the transport associated with this PublisherPlugin. More...
 
virtual void shutdown ()
 Shutdown any advertisements associated with this PublisherPlugin. More...
 
virtual ~SimplePublisherPlugin ()
 
- Public Member Functions inherited from image_transport::PublisherPlugin
void advertise (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, bool latch=true)
 Advertise a topic, simple version. More...
 
void advertise (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const SubscriberStatusCallback &connect_cb, const SubscriberStatusCallback &disconnect_cb=SubscriberStatusCallback(), const ros::VoidPtr &tracked_object=ros::VoidPtr(), bool latch=true)
 Advertise a topic with subscriber status callbacks. More...
 
virtual std::string getTransportName () const =0
 Get a string identifier for the transport provided by this plugin. More...
 
virtual void publish (const sensor_msgs::ImageConstPtr &message) const
 Publish an image using the transport associated with this PublisherPlugin. More...
 
virtual void publish (const sensor_msgs::Image &message, const uint8_t *data) const
 Publish an image using the transport associated with this PublisherPlugin. This version of the function can be used to optimize cases where you don't want to fill a ROS message first to avoid useless copies. More...
 
virtual ~PublisherPlugin ()
 

Protected Types

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

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. More...
 
virtual void connectCallback (const ros::SingleSubscriberPublisher &pub)
 Function called when a subscriber connects to the internal publisher. More...
 
virtual void disconnectCallback (const ros::SingleSubscriberPublisher &pub)
 Function called when a subscriber disconnects from the internal publisher. More...
 
const ros::PublishergetPublisher () const
 Returns the internal ros::Publisher. More...
 
virtual std::string getTopicToAdvertise (const std::string &base_topic) const
 Return the communication topic name for a given base topic. More...
 
const ros::NodeHandlenh () const
 Returns the ros::NodeHandle to be used for parameter lookup. More...
 
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. More...
 

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< SimplePublisherPluginImplsimple_impl_
 

Additional Inherited Members

- Static Public Member Functions inherited from image_transport::PublisherPlugin
static std::string getLookupName (const std::string &transport_name)
 Return the lookup name of the PublisherPlugin associated with a specific transport identifier. More...
 

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 61 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 220 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 109 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 179 of file simple_publisher_plugin.h.

Constructor & Destructor Documentation

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

Definition at line 64 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 
)
inlineprotectedvirtual

Advertise a topic. Must be implemented by the subclass.

Implements image_transport::PublisherPlugin.

Definition at line 94 of file simple_publisher_plugin.h.

template<class M>
ros::SubscriberStatusCallback image_transport::SimplePublisherPlugin< M >::bindCB ( const SubscriberStatusCallback user_cb,
SubscriberStatusMemFn  internal_cb_fn 
)
inlineprivate

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 185 of file simple_publisher_plugin.h.

template<class M>
template<class PubT >
PublishFn image_transport::SimplePublisherPlugin< M >::bindInternalPublisher ( const PubT &  pub) const
inlineprivate

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

Parameters
pubAn object with method void publish(const M&)

Definition at line 229 of file simple_publisher_plugin.h.

template<class M>
virtual void image_transport::SimplePublisherPlugin< M >::connectCallback ( const ros::SingleSubscriberPublisher pub)
inlineprotectedvirtual

Function called when a subscriber connects to the internal publisher.

Defaults to noop.

Definition at line 136 of file simple_publisher_plugin.h.

template<class M>
virtual void image_transport::SimplePublisherPlugin< M >::disconnectCallback ( const ros::SingleSubscriberPublisher pub)
inlineprotectedvirtual

Function called when a subscriber disconnects from the internal publisher.

Defaults to noop.

Definition at line 143 of file simple_publisher_plugin.h.

template<class M>
virtual uint32_t image_transport::SimplePublisherPlugin< M >::getNumSubscribers ( ) const
inlinevirtual

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

Implements image_transport::PublisherPlugin.

Definition at line 66 of file simple_publisher_plugin.h.

template<class M>
const ros::Publisher& image_transport::SimplePublisherPlugin< M >::getPublisher ( ) const
inlineprotected

Returns the internal ros::Publisher.

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

Definition at line 159 of file simple_publisher_plugin.h.

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

Returns the communication topic that this PublisherPlugin will publish on.

Implements image_transport::PublisherPlugin.

Definition at line 72 of file simple_publisher_plugin.h.

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

Definition at line 126 of file simple_publisher_plugin.h.

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

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

Definition at line 148 of file simple_publisher_plugin.h.

template<class M>
virtual void image_transport::SimplePublisherPlugin< M >::publish ( const sensor_msgs::Image &  message) const
inlinevirtual

Publish an image using the transport associated with this PublisherPlugin.

Implements image_transport::PublisherPlugin.

Definition at line 78 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
protectedpure 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, and ResizedPublisher.

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

Shutdown any advertisements associated with this PublisherPlugin.

Implements image_transport::PublisherPlugin.

Definition at line 88 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 
)
inlineprivate

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 200 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 177 of file simple_publisher_plugin.h.


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


image_transport
Author(s): Patrick Mihelich
autogenerated on Thu Jun 6 2019 19:22:47