Advertise and subscribe to image topics. More...
#include <message_transport.h>
Public Member Functions | |
Publisher | advertise (const std::string &base_topic, uint32_t queue_size, const typename SingleSubscriberPublisher< M >::StatusCB &connect_cb, const typename SingleSubscriberPublisher< M >::StatusCB &disconnect_cb=SingleSubscriberPublisher< M >::StatusCB(), 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. | |
MessageTransport (const ros::NodeHandle &nh, const std::string &package_name, const std::string &class_name) | |
template<class T > | |
Subscriber | subscribe (const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const typename M::ConstPtr &), 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 typename M::ConstPtr &), 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 typename M::ConstPtr &), 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 typename M::ConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints()) |
Subscribe to an image topic, version for arbitrary boost::function object. | |
~MessageTransport () | |
Protected Attributes | |
std::string | class_name_ |
ros::NodeHandle | nh_ |
std::string | package_name_ |
Advertise and subscribe to image topics.
MessageTransport is analogous to ros::NodeHandle in that it contains advertise() and subscribe() functions for creating advertisements and subscriptions of image topics.
Definition at line 15 of file message_transport.h.
message_transport::MessageTransport< M >::MessageTransport | ( | const ros::NodeHandle & | nh, | |
const std::string & | package_name, | |||
const std::string & | class_name | |||
) | [inline, explicit] |
Definition at line 8 of file message_transport.h.
message_transport::MessageTransport< M >::~MessageTransport | ( | ) | [inline] |
Definition at line 14 of file message_transport.h.
Publisher message_transport::MessageTransport< M >::advertise | ( | const std::string & | base_topic, | |
uint32_t | queue_size, | |||
const typename SingleSubscriberPublisher< M >::StatusCB & | connect_cb, | |||
const typename SingleSubscriberPublisher< M >::StatusCB & | disconnect_cb = SingleSubscriberPublisher<M>::StatusCB() , |
|||
const ros::VoidPtr & | tracked_object = ros::VoidPtr() , |
|||
bool | latch = false | |||
) | [inline] |
Advertise an image topic with subcriber status callbacks.
Definition at line 31 of file message_transport.h.
Publisher message_transport::MessageTransport< M >::advertise | ( | const std::string & | base_topic, | |
uint32_t | queue_size, | |||
bool | latch = false | |||
) | [inline] |
Advertise an image topic, simple version.
Definition at line 20 of file message_transport.h.
Subscriber message_transport::MessageTransport< M >::subscribe | ( | const std::string & | base_topic, | |
uint32_t | queue_size, | |||
void(T::*)(const typename M::ConstPtr &) | 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 86 of file message_transport.h.
Subscriber message_transport::MessageTransport< M >::subscribe | ( | const std::string & | base_topic, | |
uint32_t | queue_size, | |||
void(T::*)(const typename M::ConstPtr &) | 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 75 of file message_transport.h.
Subscriber message_transport::MessageTransport< M >::subscribe | ( | const std::string & | base_topic, | |
uint32_t | queue_size, | |||
void(*)(const typename M::ConstPtr &) | fp, | |||
const TransportHints & | transport_hints = TransportHints() | |||
) | [inline] |
Subscribe to an image topic, version for bare function.
Definition at line 62 of file message_transport.h.
Subscriber message_transport::MessageTransport< M >::subscribe | ( | const std::string & | base_topic, | |
uint32_t | queue_size, | |||
const boost::function< void(const typename M::ConstPtr &)> & | callback, | |||
const ros::VoidPtr & | tracked_object = ros::VoidPtr() , |
|||
const TransportHints & | transport_hints = TransportHints() | |||
) | [inline] |
Subscribe to an image topic, version for arbitrary boost::function object.
Definition at line 46 of file message_transport.h.
std::string message_transport::MessageTransport< M >::class_name_ [protected] |
Definition at line 100 of file message_transport.h.
ros::NodeHandle message_transport::MessageTransport< M >::nh_ [protected] |
Definition at line 98 of file message_transport.h.
std::string message_transport::MessageTransport< M >::package_name_ [protected] |
Definition at line 99 of file message_transport.h.