#include <subscriber_plugin.h>

Public Types | |
| typedef boost::function< void(const  typename M::ConstPtr &)>  | Callback | 
Public Member Functions | |
| 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.   | |
| void | subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(*fp)(const typename M::ConstPtr &), const TransportHints &transport_hints=TransportHints()) | 
| Subscribe to an image topic, version for bare function.   | |
| template<class T > | |
| void | subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const typename M::ConstPtr &), T *obj, const TransportHints &transport_hints=TransportHints()) | 
| Subscribe to an image topic, version for class member function with bare pointer.   | |
| template<class T > | |
| void | subscribe (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const typename M::ConstPtr &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints()) | 
| Subscribe to an image topic, version for class member function with shared_ptr.   | |
| virtual | ~SubscriberPlugin () | 
Protected Member Functions | |
| 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)=0 | 
| Subscribe to an image transport topic. Must be implemented by the subclass.   | |
Definition at line 53 of file subscriber_plugin.h.
| typedef boost::function<void(const typename M::ConstPtr&)> message_transport::SubscriberPlugin< M >::Callback | 
Definition at line 56 of file subscriber_plugin.h.
| virtual message_transport::SubscriberPlugin< M >::~SubscriberPlugin | ( | ) |  [inline, virtual] | 
        
Definition at line 58 of file subscriber_plugin.h.
| void message_transport::SubscriberPlugin< M >::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()  | 
        ||
| ) |  [inline] | 
        
Subscribe to an image topic, version for arbitrary boost::function object.
Definition at line 63 of file subscriber_plugin.h.
| void message_transport::SubscriberPlugin< M >::subscribe | ( | ros::NodeHandle & | nh, | 
| const std::string & | base_topic, | ||
| uint32_t | queue_size, | ||
| void(*)(const typename M::ConstPtr &) | fp, | ||
| const TransportHints & | transport_hints = TransportHints()  | 
        ||
| ) |  [inline] | 
        
Subscribe to an image topic, version for bare function.
Definition at line 73 of file subscriber_plugin.h.
| void message_transport::SubscriberPlugin< M >::subscribe | ( | ros::NodeHandle & | nh, | 
| const std::string & | base_topic, | ||
| uint32_t | queue_size, | ||
| void(T::*)(const typename M::ConstPtr &) | fp, | ||
| T * | obj, | ||
| const TransportHints & | transport_hints = TransportHints()  | 
        ||
| ) |  [inline] | 
        
Subscribe to an image topic, version for class member function with bare pointer.
Definition at line 86 of file subscriber_plugin.h.
| void message_transport::SubscriberPlugin< M >::subscribe | ( | ros::NodeHandle & | nh, | 
| const std::string & | base_topic, | ||
| uint32_t | queue_size, | ||
| void(T::*)(const typename M::ConstPtr &) | fp, | ||
| const boost::shared_ptr< T > & | obj, | ||
| const TransportHints & | transport_hints = TransportHints()  | 
        ||
| ) |  [inline] | 
        
Subscribe to an image topic, version for class member function with shared_ptr.
Definition at line 97 of file subscriber_plugin.h.
| virtual void message_transport::SubscriberPlugin< M >::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 | ||
| ) |  [protected, pure virtual] | 
        
Subscribe to an image transport topic. Must be implemented by the subclass.