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. | |
virtual std::string | getTopic () const |
Returns the communication topic that this PublisherPlugin will publish on. | |
virtual void | publish (const Base &message) const |
Publish an image using the transport associated with this PublisherPlugin. | |
virtual void | shutdown () |
Shutdown any advertisements associated with this PublisherPlugin. | |
SimplePublisherPlugin (bool forceLatch=false) | |
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 typename SingleSubscriberPublisher< Base >::StatusCB &user_connect_cb, const typename SingleSubscriberPublisher< Base >::StatusCB &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. | |
void | connectCallbackHandle (const ros::SingleSubscriberPublisher &pub) |
virtual void | disconnectCallback (const ros::SingleSubscriberPublisher &pub) |
Function called when a subscriber disconnects from the internal publisher. | |
void | disconnectCallbackHandle (const ros::SingleSubscriberPublisher &pub) |
ros::NodeHandle & | getNodeHandle () |
const ros::NodeHandle & | getParamNode () const |
Returns the ros::NodeHandle to be used for parameter lookup. | |
virtual std::string | getTopicToAdvertise (const std::string &base_topic) const |
Return the communication topic name for a given base topic. | |
virtual void | postAdvertiseInit () |
Can be overloaded by an implementation to call some. | |
virtual void | publish (const Base &message, const PublishFn &publish_fn) const =0 |
Publish an image using the specified publish function. Must be implemented by the subclass. | |
void | publishInternal (const M &message) const |
Private Types | |
typedef boost::function< void(const Base &)> | MessagePublishFn |
typedef void(SimplePublisherPlugin::* | SubscriberStatusMemFn )(const ros::SingleSubscriberPublisher &pub) |
Private Member Functions | |
ros::SubscriberStatusCallback | bindCB (const typename SingleSubscriberPublisher< Base >::StatusCB &user_cb, SubscriberStatusMemFn internal_cb_fn) |
template<class PubT > | |
PublishFn | bindInternalPublisher (const PubT &pub) const |
void | subscriberCB (const ros::SingleSubscriberPublisher &ros_ssp, const typename SingleSubscriberPublisher< Base >::StatusCB &user_cb, const ros::SubscriberStatusCallback &internal_cb) |
Private Attributes | |
bool | forcelatch_ |
boost::scoped_ptr < SimplePublisherPluginImpl > | simple_impl_ |
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.
typedef boost::function<void(const Base&)> message_transport::SimplePublisherPlugin< Base, M >::MessagePublishFn [private] |
Definition at line 199 of file simple_publisher_plugin.h.
typedef boost::function<void(const M&)> message_transport::SimplePublisherPlugin< Base, M >::PublishFn [protected] |
Generic function for publishing the internal message type.
Definition at line 83 of file simple_publisher_plugin.h.
typedef void(SimplePublisherPlugin::* message_transport::SimplePublisherPlugin< Base, M >::SubscriberStatusMemFn)(const ros::SingleSubscriberPublisher &pub) [private] |
Definition at line 158 of file simple_publisher_plugin.h.
message_transport::SimplePublisherPlugin< Base, M >::SimplePublisherPlugin | ( | bool | forceLatch = false | ) | [inline] |
Definition at line 30 of file simple_publisher_plugin.h.
virtual message_transport::SimplePublisherPlugin< Base, M >::~SimplePublisherPlugin | ( | ) | [inline, virtual] |
Definition at line 31 of file simple_publisher_plugin.h.
virtual void message_transport::SimplePublisherPlugin< Base, M >::advertiseImpl | ( | ros::NodeHandle & | nh, |
const std::string & | base_topic, | ||
uint32_t | queue_size, | ||
const typename SingleSubscriberPublisher< Base >::StatusCB & | connect_cb, | ||
const typename SingleSubscriberPublisher< Base >::StatusCB & | disconnect_cb, | ||
const ros::VoidPtr & | tracked_object, | ||
bool | latch | ||
) | [inline, protected, virtual] |
Advertise a topic. Must be implemented by the subclass.
Implements message_transport::PublisherPlugin< Base >.
Definition at line 61 of file simple_publisher_plugin.h.
ros::SubscriberStatusCallback message_transport::SimplePublisherPlugin< Base, M >::bindCB | ( | const typename SingleSubscriberPublisher< Base >::StatusCB & | user_cb, |
SubscriberStatusMemFn | internal_cb_fn | ||
) | [inline, private] |
Binds the user callback to subscriberCB(), which acts as an intermediary to expose a publish(Message) interface to the user while publishing to an internal topic.
Definition at line 164 of file simple_publisher_plugin.h.
PublishFn message_transport::SimplePublisherPlugin< Base, M >::bindInternalPublisher | ( | const PubT & | pub | ) | const [inline, private] |
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 208 of file simple_publisher_plugin.h.
virtual void message_transport::SimplePublisherPlugin< Base, 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 114 of file simple_publisher_plugin.h.
void message_transport::SimplePublisherPlugin< Base, M >::connectCallbackHandle | ( | const ros::SingleSubscriberPublisher & | pub | ) | [inline, protected] |
Definition at line 115 of file simple_publisher_plugin.h.
virtual void message_transport::SimplePublisherPlugin< Base, 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 124 of file simple_publisher_plugin.h.
void message_transport::SimplePublisherPlugin< Base, M >::disconnectCallbackHandle | ( | const ros::SingleSubscriberPublisher & | pub | ) | [inline, protected] |
Definition at line 125 of file simple_publisher_plugin.h.
ros::NodeHandle& message_transport::SimplePublisherPlugin< Base, M >::getNodeHandle | ( | ) | [inline, protected] |
Definition at line 137 of file simple_publisher_plugin.h.
virtual uint32_t message_transport::SimplePublisherPlugin< Base, M >::getNumSubscribers | ( | ) | const [inline, virtual] |
Returns the number of subscribers that are currently connected to this PublisherPlugin.
Implements message_transport::PublisherPluginGen.
Definition at line 33 of file simple_publisher_plugin.h.
const ros::NodeHandle& message_transport::SimplePublisherPlugin< Base, M >::getParamNode | ( | ) | const [inline, protected] |
Returns the ros::NodeHandle to be used for parameter lookup.
Definition at line 132 of file simple_publisher_plugin.h.
virtual std::string message_transport::SimplePublisherPlugin< Base, M >::getTopic | ( | ) | const [inline, virtual] |
Returns the communication topic that this PublisherPlugin will publish on.
Implements message_transport::PublisherPluginGen.
Definition at line 39 of file simple_publisher_plugin.h.
virtual std::string message_transport::SimplePublisherPlugin< Base, 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 message_transport::RawPublisher< M >.
Definition at line 104 of file simple_publisher_plugin.h.
virtual void message_transport::SimplePublisherPlugin< Base, M >::postAdvertiseInit | ( | ) | [inline, protected, virtual] |
Can be overloaded by an implementation to call some.
Definition at line 78 of file simple_publisher_plugin.h.
virtual void message_transport::SimplePublisherPlugin< Base, M >::publish | ( | const Base & | message | ) | const [inline, virtual] |
Publish an image using the transport associated with this PublisherPlugin.
Implements message_transport::PublisherPlugin< Base >.
Definition at line 45 of file simple_publisher_plugin.h.
virtual void message_transport::SimplePublisherPlugin< Base, M >::publish | ( | const Base & | 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).
void message_transport::SimplePublisherPlugin< Base, M >::publishInternal | ( | const M & | message | ) | const [inline, protected] |
Definition at line 95 of file simple_publisher_plugin.h.
virtual void message_transport::SimplePublisherPlugin< Base, M >::shutdown | ( | ) | [inline, virtual] |
Shutdown any advertisements associated with this PublisherPlugin.
Implements message_transport::PublisherPluginGen.
Definition at line 55 of file simple_publisher_plugin.h.
void message_transport::SimplePublisherPlugin< Base, M >::subscriberCB | ( | const ros::SingleSubscriberPublisher & | ros_ssp, |
const typename SingleSubscriberPublisher< Base >::StatusCB & | user_cb, | ||
const ros::SubscriberStatusCallback & | internal_cb | ||
) | [inline, private] |
Forms the ros::SingleSubscriberPublisher for the internal communication topic into an message_transport::SingleSubscriberPublisher for Message messages and passes it to the user subscriber status callback.
Definition at line 179 of file simple_publisher_plugin.h.
bool message_transport::SimplePublisherPlugin< Base, M >::forcelatch_ [private] |
Definition at line 156 of file simple_publisher_plugin.h.
boost::scoped_ptr<SimplePublisherPluginImpl> message_transport::SimplePublisherPlugin< Base, M >::simple_impl_ [private] |
Definition at line 155 of file simple_publisher_plugin.h.