Base class for plugins to Subscriber.
More...
#include <subscriber_plugin.h>
|
typedef boost::function< void(const sensor_msgs::ImageConstPtr &)> | Callback |
|
|
virtual uint32_t | getNumPublishers () const =0 |
| Returns the number of publishers this subscriber is connected to. More...
|
|
virtual std::string | getTopic () const =0 |
| Get the transport-specific communication topic. More...
|
|
virtual std::string | getTransportName () const =0 |
| Get a string identifier for the transport provided by this plugin. More...
|
|
virtual void | shutdown ()=0 |
| Unsubscribe the callback associated with this SubscriberPlugin. 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 () |
|
Base class for plugins to Subscriber.
Definition at line 80 of file subscriber_plugin.h.
◆ Callback
◆ ~SubscriberPlugin()
virtual image_transport::SubscriberPlugin::~SubscriberPlugin |
( |
| ) |
|
|
inlinevirtual |
◆ getLookupName()
static std::string image_transport::SubscriberPlugin::getLookupName |
( |
const std::string & |
transport_type | ) |
|
|
inlinestatic |
◆ getNumPublishers()
virtual uint32_t image_transport::SubscriberPlugin::getNumPublishers |
( |
| ) |
const |
|
pure virtual |
◆ getTopic()
virtual std::string image_transport::SubscriberPlugin::getTopic |
( |
| ) |
const |
|
pure virtual |
◆ getTransportName()
virtual std::string image_transport::SubscriberPlugin::getTransportName |
( |
| ) |
const |
|
pure virtual |
◆ shutdown()
virtual void image_transport::SubscriberPlugin::shutdown |
( |
| ) |
|
|
pure virtual |
◆ subscribe() [1/4]
Subscribe to an image topic, version for arbitrary boost::function object.
Definition at line 128 of file subscriber_plugin.h.
◆ subscribe() [2/4]
void image_transport::SubscriberPlugin::subscribe |
( |
ros::NodeHandle & |
nh, |
|
|
const std::string & |
base_topic, |
|
|
uint32_t |
queue_size, |
|
|
void(*)(const sensor_msgs::ImageConstPtr &) |
fp, |
|
|
const TransportHints & |
transport_hints = TransportHints() |
|
) |
| |
|
inline |
◆ subscribe() [3/4]
Subscribe to an image topic, version for class member function with shared_ptr.
Definition at line 162 of file subscriber_plugin.h.
◆ subscribe() [4/4]
template<class T >
void image_transport::SubscriberPlugin::subscribe |
( |
ros::NodeHandle & |
nh, |
|
|
const std::string & |
base_topic, |
|
|
uint32_t |
queue_size, |
|
|
void(T::*)(const sensor_msgs::ImageConstPtr &) |
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 151 of file subscriber_plugin.h.
◆ subscribeImpl()
The documentation for this class was generated from the following file: