Base class to simplify implementing most plugins to Subscriber. More...
#include <simple_subscriber_plugin.h>

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 typename SubscriberPlugin< Base >::Callback &user_cb)=0 | 
| Process a message. Must be implemented by the subclass.   | |
| ros::NodeHandle & | nh () | 
| 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 typename SubscriberPlugin< Base >::Callback &callback, const ros::VoidPtr &tracked_object, const TransportHints &transport_hints) | 
Private Attributes | |
| boost::scoped_ptr < SimpleSubscriberPluginImpl >  | simple_impl_ | 
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.
| virtual message_transport::SimpleSubscriberPlugin< Base, M >::~SimpleSubscriberPlugin | ( | ) |  [inline, virtual] | 
        
Definition at line 31 of file simple_subscriber_plugin.h.
| virtual uint32_t message_transport::SimpleSubscriberPlugin< Base, M >::getNumPublishers | ( | ) |  const [inline, virtual] | 
        
Returns the number of publishers this subscriber is connected to.
Implements message_transport::SubscriberPluginGen.
Definition at line 39 of file simple_subscriber_plugin.h.
| virtual std::string message_transport::SimpleSubscriberPlugin< Base, M >::getTopic | ( | ) |  const [inline, virtual] | 
        
Get the transport-specific communication topic.
Implements message_transport::SubscriberPluginGen.
Definition at line 33 of file simple_subscriber_plugin.h.
| virtual std::string message_transport::SimpleSubscriberPlugin< Base, 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 message_transport::RawSubscriber< M >.
Definition at line 65 of file simple_subscriber_plugin.h.
| virtual void message_transport::SimpleSubscriberPlugin< Base, M >::internalCallback | ( | const typename M::ConstPtr & | message, | 
| const typename SubscriberPlugin< Base >::Callback & | user_cb | ||
| ) |  [protected, pure virtual] | 
        
Process a message. Must be implemented by the subclass.
| message | A message from the PublisherPlugin. | 
| user_cb | The user Message callback to invoke, if appropriate. | 
| ros::NodeHandle& message_transport::SimpleSubscriberPlugin< Base, M >::nh | ( | ) |  [inline, protected] | 
        
Returns the ros::NodeHandle to be used for parameter lookup.
Definition at line 84 of file simple_subscriber_plugin.h.
| virtual void message_transport::SimpleSubscriberPlugin< Base, M >::shutdown | ( | ) |  [inline, virtual] | 
        
Unsubscribe the callback associated with this SubscriberPlugin.
Implements message_transport::SubscriberPluginGen.
Definition at line 45 of file simple_subscriber_plugin.h.
| virtual void message_transport::SimpleSubscriberPlugin< Base, M >::subscribeImpl | ( | ros::NodeHandle & | nh, | 
| const std::string & | base_topic, | ||
| uint32_t | queue_size, | ||
| const typename SubscriberPlugin< Base >::Callback & | callback, | ||
| const ros::VoidPtr & | tracked_object, | ||
| const TransportHints & | transport_hints | ||
| ) |  [inline, protected, virtual] | 
        
Definition at line 70 of file simple_subscriber_plugin.h.
boost::scoped_ptr<SimpleSubscriberPluginImpl> message_transport::SimpleSubscriberPlugin< Base, M >::simple_impl_ [private] | 
        
Definition at line 101 of file simple_subscriber_plugin.h.