#include <resized_subscriber.h>
|
virtual std::string | getTransportName () const |
| Get a string identifier for the transport provided by this plugin. More...
|
|
virtual | ~ResizedSubscriber () |
|
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 () |
|
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 &), T *obj, const TransportHints &transport_hints=TransportHints()) |
| Subscribe to an image topic, version for class member function with bare pointer. 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...
|
|
virtual | ~SubscriberPlugin () |
|
|
typedef boost::function< void(const sensor_msgs::ImageConstPtr &)> | Callback |
|
static std::string | getLookupName (const std::string &transport_type) |
| Return the lookup name of the SubscriberPlugin associated with a specific transport identifier. More...
|
|
Definition at line 4 of file resized_subscriber.h.
virtual ResizedSubscriber::~ResizedSubscriber |
( |
| ) |
|
|
inlinevirtual |
virtual std::string ResizedSubscriber::getTransportName |
( |
| ) |
const |
|
inlinevirtual |
void ResizedSubscriber::internalCallback |
( |
const typename image_transport_tutorial::ResizedImage::ConstPtr & |
message, |
|
|
const Callback & |
user_cb |
|
) |
| |
|
protectedvirtual |
The documentation for this class was generated from the following files: