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 &), T *obj, const TransportHints &transport_hints=TransportHints()) |
Subscribe to an image topic, version for class member function with bare pointer. 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... | |
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 &), 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... | |
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... | |
~ImageTransport () | |
Private Types | |
typedef boost::shared_ptr< Impl > | ImplPtr |
typedef boost::weak_ptr< Impl > | ImplWPtr |
Private Attributes | |
ImplPtr | impl_ |
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 52 of file image_transport.h.
|
private |
Definition at line 196 of file image_transport.h.
|
private |
Definition at line 198 of file image_transport.h.
|
explicit |
Definition at line 59 of file image_transport.cpp.
image_transport::ImageTransport::~ImageTransport | ( | ) |
Definition at line 64 of file image_transport.cpp.
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 68 of file image_transport.cpp.
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 74 of file image_transport.cpp.
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 89 of file image_transport.cpp.
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 97 of file image_transport.cpp.
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 116 of file image_transport.cpp.
std::vector< std::string > image_transport::ImageTransport::getLoadableTransports | ( | ) | const |
Returns the names of all transports that are loadable in the system.
Definition at line 126 of file image_transport.cpp.
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 82 of file image_transport.cpp.
|
inline |
Subscribe to an image topic, version for bare function.
Definition at line 83 of file image_transport.h.
|
inline |
Subscribe to an image topic, version for class member function with bare pointer.
Definition at line 96 of file image_transport.h.
|
inline |
Subscribe to an image topic, version for class member function with shared_ptr.
Definition at line 107 of file image_transport.h.
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 108 of file image_transport.cpp.
|
inline |
Subscribe to a synchronized image & camera info topic pair, version for bare function.
Definition at line 146 of file image_transport.h.
|
inline |
Subscribe to a synchronized image & camera info topic pair, version for class member function with bare pointer.
Definition at line 160 of file image_transport.h.
|
inline |
Subscribe to a synchronized image & camera info topic pair, version for class member function with shared_ptr.
Definition at line 174 of file image_transport.h.
|
private |
Definition at line 200 of file image_transport.h.