Public Member Functions | Protected Member Functions | List of all members
image_transport::RawSubscriber Class Reference

The default SubscriberPlugin. More...

#include <raw_subscriber.h>

Inheritance diagram for image_transport::RawSubscriber:
Inheritance graph
[legend]

Public Member Functions

virtual std::string getTransportName () const
 Get a string identifier for the transport provided by this plugin. More...
 
virtual ~RawSubscriber ()
 
- Public Member Functions inherited from image_transport::SimpleSubscriberPlugin< sensor_msgs::Image >
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 std::string getTopicToSubscribe (const std::string &base_topic) const
 Return the communication topic name for a given base topic. More...
 
virtual void internalCallback (const sensor_msgs::ImageConstPtr &message, const Callback &user_cb)
 
- Protected Member Functions inherited from image_transport::SimpleSubscriberPlugin< sensor_msgs::Image >
virtual void internalCallback (const typename sensor_msgs::Image ::ConstPtr &message, const Callback &user_cb)=0
 Process a message. Must be implemented by the subclass. More...
 
const ros::NodeHandlenh () 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...
 

Detailed Description

The default SubscriberPlugin.

RawSubscriber is a simple wrapper for ros::Subscriber which listens for Image messages and passes them through to the callback.

Definition at line 80 of file raw_subscriber.h.

Constructor & Destructor Documentation

◆ ~RawSubscriber()

virtual image_transport::RawSubscriber::~RawSubscriber ( )
inlinevirtual

Definition at line 115 of file raw_subscriber.h.

Member Function Documentation

◆ getTopicToSubscribe()

virtual std::string image_transport::RawSubscriber::getTopicToSubscribe ( const std::string &  base_topic) const
inlineprotectedvirtual

Return the communication topic name for a given base topic.

Defaults to <base topic>/<transport name>.

Reimplemented from image_transport::SimpleSubscriberPlugin< sensor_msgs::Image >.

Definition at line 128 of file raw_subscriber.h.

◆ getTransportName()

virtual std::string image_transport::RawSubscriber::getTransportName ( ) const
inlinevirtual

Get a string identifier for the transport provided by this plugin.

Implements image_transport::SubscriberPlugin.

Definition at line 117 of file raw_subscriber.h.

◆ internalCallback()

virtual void image_transport::RawSubscriber::internalCallback ( const sensor_msgs::ImageConstPtr &  message,
const Callback user_cb 
)
inlineprotectedvirtual

Definition at line 123 of file raw_subscriber.h.


The documentation for this class was generated from the following file:


image_transport
Author(s): Patrick Mihelich
autogenerated on Sat Jan 20 2024 03:14:50