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. More... | |
virtual std::string | getTopic () const |
Get the transport-specific communication topic. More... | |
virtual void | shutdown () |
Unsubscribe the callback associated with this SubscriberPlugin. More... | |
virtual | ~SimpleSubscriberPlugin () |
Public Member Functions inherited from image_transport::SubscriberPlugin | |
virtual std::string | getTransportName () const =0 |
Get a string identifier for the transport provided by this plugin. More... | |
void | subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints()) |
Subscribe to an image topic, version for arbitrary boost::function object. More... | |
void | subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(*fp)(const sensor_msgs::ImageConstPtr &), const TransportHints &transport_hints=TransportHints()) |
Subscribe to an image topic, version for bare function. More... | |
template<class T > | |
void | subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints()) |
Subscribe to an image topic, version for class member function with shared_ptr. More... | |
template<class T > | |
void | subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &), T *obj, const TransportHints &transport_hints=TransportHints()) |
Subscribe to an image topic, version for class member function with bare pointer. More... | |
virtual | ~SubscriberPlugin () |
Protected Member Functions | |
virtual std::string | getTopicToSubscribe (const std::string &base_topic) const |
Return the communication topic name for a given base topic. More... | |
virtual void | internalCallback (const typename M::ConstPtr &message, const Callback &user_cb)=0 |
Process a message. Must be implemented by the subclass. More... | |
const ros::NodeHandle & | nh () const |
Returns the ros::NodeHandle to be used for parameter lookup. More... | |
virtual void | subscribeImpl (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const Callback &callback, const ros::VoidPtr &tracked_object, const TransportHints &transport_hints) |
Subscribe to an image transport topic. Must be implemented by the subclass. More... | |
Private Attributes | |
boost::scoped_ptr< SimpleSubscriberPluginImpl > | simple_impl_ |
Additional Inherited Members | |
Public Types inherited from image_transport::SubscriberPlugin | |
typedef boost::function< void(const sensor_msgs::ImageConstPtr &)> | Callback |
Static Public Member Functions inherited from image_transport::SubscriberPlugin | |
static std::string | getLookupName (const std::string &transport_type) |
Return the lookup name of the SubscriberPlugin associated with a specific transport identifier. More... | |
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 94 of file simple_subscriber_plugin.h.
|
inlinevirtual |
Definition at line 129 of file simple_subscriber_plugin.h.
|
inlinevirtual |
Returns the number of publishers this subscriber is connected to.
Implements image_transport::SubscriberPlugin.
Definition at line 137 of file simple_subscriber_plugin.h.
|
inlinevirtual |
Get the transport-specific communication topic.
Implements image_transport::SubscriberPlugin.
Definition at line 131 of file simple_subscriber_plugin.h.
|
inlineprotectedvirtual |
Return the communication topic name for a given base topic.
Defaults to <base topic>/<transport name>.
Reimplemented in image_transport::RawSubscriber.
Definition at line 162 of file simple_subscriber_plugin.h.
|
protectedpure virtual |
Process a message. Must be implemented by the subclass.
message | A message from the PublisherPlugin. |
user_cb | The user Image callback to invoke, if appropriate. |
|
inlineprotected |
Returns the ros::NodeHandle to be used for parameter lookup.
Definition at line 183 of file simple_subscriber_plugin.h.
|
inlinevirtual |
Unsubscribe the callback associated with this SubscriberPlugin.
Implements image_transport::SubscriberPlugin.
Definition at line 143 of file simple_subscriber_plugin.h.
|
inlineprotectedvirtual |
Subscribe to an image transport topic. Must be implemented by the subclass.
Implements image_transport::SubscriberPlugin.
Definition at line 167 of file simple_subscriber_plugin.h.
|
private |
Definition at line 200 of file simple_subscriber_plugin.h.