#include <resized_subscriber.h>
Public Member Functions | |
virtual std::string | getTransportName () const |
Get a string identifier for the transport provided by this plugin. More... | |
virtual | ~ResizedSubscriber () |
Public Member Functions inherited from image_transport::SimpleSubscriberPlugin< image_transport_tutorial::ResizedImage > | |
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 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... | |
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 void | internalCallback (const typename image_transport_tutorial::ResizedImage::ConstPtr &message, const Callback &user_cb) |
Protected Member Functions inherited from image_transport::SimpleSubscriberPlugin< image_transport_tutorial::ResizedImage > | |
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 image_transport_tutorial::ResizedImage ::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... | |
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... | |
Definition at line 4 of file resized_subscriber.h.
|
inlinevirtual |
Definition at line 7 of file resized_subscriber.h.
|
inlinevirtual |
Get a string identifier for the transport provided by this plugin.
Implements image_transport::SubscriberPlugin.
Definition at line 9 of file resized_subscriber.h.
|
protectedvirtual |
Definition at line 5 of file resized_subscriber.cpp.