Base class to simplify implementing most plugins to Publisher. More...
#include <simple_publisher_plugin.h>
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::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 void | publish (const sensor_msgs::ImageConstPtr &message) const |
Publish an image using the transport associated with this PublisherPlugin. 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::Publisher & | getPublisher () 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::NodeHandle & | nh () 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< SimplePublisherPluginImpl > | simple_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... | |
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 93 of file simple_publisher_plugin.h.
|
private |
Definition at line 284 of file simple_publisher_plugin.h.
|
protected |
Generic function for publishing the internal message type.
Definition at line 173 of file simple_publisher_plugin.h.
|
private |
Definition at line 243 of file simple_publisher_plugin.h.
|
inlinevirtual |
Definition at line 128 of file simple_publisher_plugin.h.
|
inlineprotectedvirtual |
Advertise a topic. Must be implemented by the subclass.
Implements image_transport::PublisherPlugin.
Definition at line 158 of file simple_publisher_plugin.h.
|
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 249 of file simple_publisher_plugin.h.
|
inlineprivate |
Returns a function object for publishing the transport-specific message type through some ROS publisher type.
pub | An object with method void publish(const M&) |
Definition at line 293 of file simple_publisher_plugin.h.
|
inlineprotectedvirtual |
Function called when a subscriber connects to the internal publisher.
Defaults to noop.
Definition at line 200 of file simple_publisher_plugin.h.
|
inlineprotectedvirtual |
Function called when a subscriber disconnects from the internal publisher.
Defaults to noop.
Definition at line 207 of file simple_publisher_plugin.h.
|
inlinevirtual |
Returns the number of subscribers that are currently connected to this PublisherPlugin.
Implements image_transport::PublisherPlugin.
Definition at line 130 of file simple_publisher_plugin.h.
|
inlineprotected |
Returns the internal ros::Publisher.
This really only exists so RawPublisher can implement no-copy intraprocess message passing easily.
Definition at line 223 of file simple_publisher_plugin.h.
|
inlinevirtual |
Returns the communication topic that this PublisherPlugin will publish on.
Implements image_transport::PublisherPlugin.
Definition at line 136 of file simple_publisher_plugin.h.
|
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 190 of file simple_publisher_plugin.h.
|
inlineprotected |
Returns the ros::NodeHandle to be used for parameter lookup.
Definition at line 212 of file simple_publisher_plugin.h.
|
inlinevirtual |
Publish an image using the transport associated with this PublisherPlugin.
Implements image_transport::PublisherPlugin.
Definition at line 142 of file simple_publisher_plugin.h.
|
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.
|
inlinevirtual |
Shutdown any advertisements associated with this PublisherPlugin.
Implements image_transport::PublisherPlugin.
Definition at line 152 of file simple_publisher_plugin.h.
|
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 264 of file simple_publisher_plugin.h.
|
private |
Definition at line 241 of file simple_publisher_plugin.h.