Classes | Public Member Functions | Private Types | Private Attributes | List of all members
image_transport::ImageTransport Class Reference

Advertise and subscribe to image topics. More...

#include <image_transport.h>

Classes

struct  Impl
 

Public Member Functions

Publisher advertise (const std::string &base_topic, uint32_t queue_size, bool latch=false)
 Advertise an image topic, simple version. More...
 
Publisher advertise (const std::string &base_topic, uint32_t queue_size, const SubscriberStatusCallback &connect_cb, const SubscriberStatusCallback &disconnect_cb=SubscriberStatusCallback(), const ros::VoidPtr &tracked_object=ros::VoidPtr(), bool latch=false)
 Advertise an image topic with subcriber status callbacks. More...
 
CameraPublisher advertiseCamera (const std::string &base_topic, uint32_t queue_size, bool latch=false)
 Advertise a synchronized camera raw image + info topic pair, simple version. More...
 
CameraPublisher advertiseCamera (const std::string &base_topic, uint32_t queue_size, const SubscriberStatusCallback &image_connect_cb, const SubscriberStatusCallback &image_disconnect_cb=SubscriberStatusCallback(), const ros::SubscriberStatusCallback &info_connect_cb=ros::SubscriberStatusCallback(), const ros::SubscriberStatusCallback &info_disconnect_cb=ros::SubscriberStatusCallback(), const ros::VoidPtr &tracked_object=ros::VoidPtr(), bool latch=false)
 Advertise a synchronized camera raw image + info topic pair with subscriber status callbacks. More...
 
std::vector< std::string > getDeclaredTransports () const
 Returns the names of all transports declared in the system. Declared transports are not necessarily built or loadable. More...
 
std::vector< std::string > getLoadableTransports () const
 Returns the names of all transports that are loadable in the system. More...
 
 ImageTransport (const ros::NodeHandle &nh)
 
Subscriber subscribe (const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &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...
 
Subscriber subscribe (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 >
Subscriber subscribe (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 >
Subscriber subscribe (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...
 
CameraSubscriber subscribeCamera (const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
 Subscribe to a synchronized image & camera info topic pair, version for arbitrary boost::function object. More...
 
CameraSubscriber subscribeCamera (const std::string &base_topic, uint32_t queue_size, void(*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &), const TransportHints &transport_hints=TransportHints())
 Subscribe to a synchronized image & camera info topic pair, version for bare function. More...
 
template<class T >
CameraSubscriber subscribeCamera (const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
 Subscribe to a synchronized image & camera info topic pair, version for class member function with shared_ptr. More...
 
template<class T >
CameraSubscriber subscribeCamera (const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &), T *obj, const TransportHints &transport_hints=TransportHints())
 Subscribe to a synchronized image & camera info topic pair, version for class member function with bare pointer. More...
 
 ~ImageTransport ()
 

Private Types

typedef boost::shared_ptr< ImplImplPtr
 
typedef boost::weak_ptr< ImplImplWPtr
 

Private Attributes

ImplPtr impl_
 

Detailed Description

Advertise and subscribe to image topics.

ImageTransport is analogous to ros::NodeHandle in that it contains advertise() and subscribe() functions for creating advertisements and subscriptions of image topics.

Definition at line 84 of file image_transport.h.

Member Typedef Documentation

◆ ImplPtr

Definition at line 260 of file image_transport.h.

◆ ImplWPtr

typedef boost::weak_ptr<Impl> image_transport::ImageTransport::ImplWPtr
private

Definition at line 262 of file image_transport.h.

Constructor & Destructor Documentation

◆ ImageTransport()

image_transport::ImageTransport::ImageTransport ( const ros::NodeHandle nh)
explicit

Definition at line 91 of file image_transport.cpp.

◆ ~ImageTransport()

image_transport::ImageTransport::~ImageTransport ( )

Definition at line 96 of file image_transport.cpp.

Member Function Documentation

◆ advertise() [1/2]

Publisher image_transport::ImageTransport::advertise ( const std::string &  base_topic,
uint32_t  queue_size,
bool  latch = false 
)

Advertise an image topic, simple version.

Definition at line 100 of file image_transport.cpp.

◆ advertise() [2/2]

Publisher image_transport::ImageTransport::advertise ( const std::string &  base_topic,
uint32_t  queue_size,
const SubscriberStatusCallback connect_cb,
const SubscriberStatusCallback disconnect_cb = SubscriberStatusCallback(),
const ros::VoidPtr tracked_object = ros::VoidPtr(),
bool  latch = false 
)

Advertise an image topic with subcriber status callbacks.

Definition at line 106 of file image_transport.cpp.

◆ advertiseCamera() [1/2]

CameraPublisher image_transport::ImageTransport::advertiseCamera ( const std::string &  base_topic,
uint32_t  queue_size,
bool  latch = false 
)

Advertise a synchronized camera raw image + info topic pair, simple version.

Definition at line 121 of file image_transport.cpp.

◆ advertiseCamera() [2/2]

CameraPublisher image_transport::ImageTransport::advertiseCamera ( const std::string &  base_topic,
uint32_t  queue_size,
const SubscriberStatusCallback image_connect_cb,
const SubscriberStatusCallback image_disconnect_cb = SubscriberStatusCallback(),
const ros::SubscriberStatusCallback info_connect_cb = ros::SubscriberStatusCallback(),
const ros::SubscriberStatusCallback info_disconnect_cb = ros::SubscriberStatusCallback(),
const ros::VoidPtr tracked_object = ros::VoidPtr(),
bool  latch = false 
)

Advertise a synchronized camera raw image + info topic pair with subscriber status callbacks.

Definition at line 129 of file image_transport.cpp.

◆ getDeclaredTransports()

std::vector< std::string > image_transport::ImageTransport::getDeclaredTransports ( ) const

Returns the names of all transports declared in the system. Declared transports are not necessarily built or loadable.

Definition at line 148 of file image_transport.cpp.

◆ getLoadableTransports()

std::vector< std::string > image_transport::ImageTransport::getLoadableTransports ( ) const

Returns the names of all transports that are loadable in the system.

Definition at line 158 of file image_transport.cpp.

◆ subscribe() [1/4]

Subscriber image_transport::ImageTransport::subscribe ( const std::string &  base_topic,
uint32_t  queue_size,
const boost::function< void(const sensor_msgs::ImageConstPtr &)> &  callback,
const ros::VoidPtr tracked_object = ros::VoidPtr(),
const TransportHints transport_hints = TransportHints() 
)

Subscribe to an image topic, version for arbitrary boost::function object.

Definition at line 114 of file image_transport.cpp.

◆ subscribe() [2/4]

Subscriber image_transport::ImageTransport::subscribe ( const std::string &  base_topic,
uint32_t  queue_size,
void(*)(const sensor_msgs::ImageConstPtr &)  fp,
const TransportHints transport_hints = TransportHints() 
)
inline

Subscribe to an image topic, version for bare function.

Definition at line 147 of file image_transport.h.

◆ subscribe() [3/4]

template<class T >
Subscriber image_transport::ImageTransport::subscribe ( const std::string &  base_topic,
uint32_t  queue_size,
void(T::*)(const sensor_msgs::ImageConstPtr &)  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 171 of file image_transport.h.

◆ subscribe() [4/4]

template<class T >
Subscriber image_transport::ImageTransport::subscribe ( 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 160 of file image_transport.h.

◆ subscribeCamera() [1/4]

CameraSubscriber image_transport::ImageTransport::subscribeCamera ( const std::string &  base_topic,
uint32_t  queue_size,
const CameraSubscriber::Callback callback,
const ros::VoidPtr tracked_object = ros::VoidPtr(),
const TransportHints transport_hints = TransportHints() 
)

Subscribe to a synchronized image & camera info topic pair, version for arbitrary boost::function object.

This version assumes the standard topic naming scheme, where the info topic is named "camera_info" in the same namespace as the base image topic.

Definition at line 140 of file image_transport.cpp.

◆ subscribeCamera() [2/4]

CameraSubscriber image_transport::ImageTransport::subscribeCamera ( const std::string &  base_topic,
uint32_t  queue_size,
void(*)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)  fp,
const TransportHints transport_hints = TransportHints() 
)
inline

Subscribe to a synchronized image & camera info topic pair, version for bare function.

Definition at line 210 of file image_transport.h.

◆ subscribeCamera() [3/4]

template<class T >
CameraSubscriber image_transport::ImageTransport::subscribeCamera ( const std::string &  base_topic,
uint32_t  queue_size,
void(T::*)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)  fp,
const boost::shared_ptr< T > &  obj,
const TransportHints transport_hints = TransportHints() 
)
inline

Subscribe to a synchronized image & camera info topic pair, version for class member function with shared_ptr.

Definition at line 238 of file image_transport.h.

◆ subscribeCamera() [4/4]

template<class T >
CameraSubscriber image_transport::ImageTransport::subscribeCamera ( const std::string &  base_topic,
uint32_t  queue_size,
void(T::*)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)  fp,
T *  obj,
const TransportHints transport_hints = TransportHints() 
)
inline

Subscribe to a synchronized image & camera info topic pair, version for class member function with bare pointer.

Definition at line 224 of file image_transport.h.

Member Data Documentation

◆ impl_

ImplPtr image_transport::ImageTransport::impl_
private

Definition at line 264 of file image_transport.h.


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


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