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, 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. | |
Publisher | advertise (const std::string &base_topic, uint32_t queue_size, bool latch=false) |
Advertise an image topic, simple version. | |
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. | |
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. | |
std::vector< std::string > | getDeclaredTransports () const |
Returns the names of all transports declared available in the system. Declared transports are not necessarily built or loadable. | |
ImageTransport (const ros::NodeHandle &nh) | |
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
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. | |
~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 16 of file image_transport.h.
typedef boost::shared_ptr<Impl> image_transport::ImageTransport::ImplPtr [private] |
Definition at line 146 of file image_transport.h.
typedef boost::weak_ptr<Impl> image_transport::ImageTransport::ImplWPtr [private] |
Definition at line 148 of file image_transport.h.
image_transport::ImageTransport::ImageTransport | ( | const ros::NodeHandle & | nh | ) | [explicit] |
Definition at line 21 of file image_transport.cpp.
image_transport::ImageTransport::~ImageTransport | ( | ) |
Definition at line 26 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 36 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 30 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 59 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 51 of file image_transport.cpp.
std::vector< std::string > image_transport::ImageTransport::getDeclaredTransports | ( | ) | const |
Returns the names of all transports declared available in the system. Declared transports are not necessarily built or loadable.
Definition at line 78 of file image_transport.cpp.
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 62 of file image_transport.h.
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 51 of file image_transport.h.
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 38 of file image_transport.h.
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 44 of file image_transport.cpp.
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 129 of file image_transport.h.
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 115 of file image_transport.h.
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 101 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 70 of file image_transport.cpp.
Definition at line 150 of file image_transport.h.