message_transport::Publisher Class Reference

Manages advertisements of multiple transport options on an Message topic. More...

#include <publisher.h>

List of all members.

Public Member Functions

template<class M >
void do_initialise (ros::NodeHandle &nh, const std::string &package_name, const std::string &class_name, const std::string &base_topic, uint32_t queue_size, const typename SingleSubscriberPublisher< M >::StatusCB &connect_cb, const typename SingleSubscriberPublisher< M >::StatusCB &disconnect_cb, const ros::VoidPtr &tracked_object, bool latch)
uint32_t getNumSubscribers () const
 Returns the number of subscribers that are currently connected to this Publisher.
std::string getTopic () const
 Returns the base topic of this Publisher.
 operator void * () const
bool operator!= (const Publisher &rhs) const
bool operator< (const Publisher &rhs) const
bool operator== (const Publisher &rhs) const
template<class M >
void publish (const typename M::ConstPtr &message) const
 Publish an image on the topics associated with this Publisher.
template<class M >
void publish (const M &message) const
 Publish an image on the topics associated with this Publisher.
 Publisher (ros::NodeHandle &nh)
 Publisher ()
void shutdown ()
 Shutdown the advertisements associated with this Publisher.

Private Types

typedef boost::shared_ptr
< PublisherImplGen
ImplPtr

Private Member Functions

template<class M >
SingleSubscriberPublisher< M >
::StatusCB 
rebindCB (const typename SingleSubscriberPublisher< M >::StatusCB &user_cb)

Private Attributes

ImplPtr impl_

Detailed Description

Manages advertisements of multiple transport options on an Message topic.

Publisher is a drop-in replacement for ros::Publisher when publishing Message topics. In a minimally built environment, they behave the same; however, Publisher is extensible via plugins to publish alternative representations of the image on related subtopics. This is especially useful for limiting bandwidth and latency over a network connection, when you might (for example) use the theora plugin to transport the images as streamed video. All topics are published only on demand (i.e. if there are subscribers).

A Publisher should always be created through a call to MessageTransport::advertise(), or copied from one that was. Once all copies of a specific Publisher go out of scope, any subscriber callbacks associated with that handle will stop being called. Once all Publisher for a given base topic go out of scope the topic (and all subtopics) will be unadvertised.

Definition at line 61 of file publisher.h.


Member Typedef Documentation

typedef boost::shared_ptr<PublisherImplGen> message_transport::Publisher::ImplPtr [private]

Definition at line 164 of file publisher.h.


Constructor & Destructor Documentation

message_transport::Publisher::Publisher (  )  [inline]

Definition at line 64 of file publisher.h.

message_transport::Publisher::Publisher ( ros::NodeHandle &  nh  ) 

Definition at line 44 of file publisher.cpp.


Member Function Documentation

template<class M >
void message_transport::Publisher::do_initialise ( ros::NodeHandle &  nh,
const std::string &  package_name,
const std::string &  class_name,
const std::string &  base_topic,
uint32_t  queue_size,
const typename SingleSubscriberPublisher< M >::StatusCB &  connect_cb,
const typename SingleSubscriberPublisher< M >::StatusCB &  disconnect_cb,
const ros::VoidPtr &  tracked_object,
bool  latch 
) [inline]

Definition at line 120 of file publisher.h.

uint32_t message_transport::Publisher::getNumSubscribers (  )  const

Returns the number of subscribers that are currently connected to this Publisher.

Returns the total number of subscribers to all advertised topics.

Definition at line 47 of file publisher.cpp.

std::string message_transport::Publisher::getTopic (  )  const

Returns the base topic of this Publisher.

Definition at line 53 of file publisher.cpp.

message_transport::Publisher::operator void * (  )  const

Definition at line 68 of file publisher.cpp.

bool message_transport::Publisher::operator!= ( const Publisher rhs  )  const [inline]

Definition at line 115 of file publisher.h.

bool message_transport::Publisher::operator< ( const Publisher rhs  )  const [inline]

Definition at line 114 of file publisher.h.

bool message_transport::Publisher::operator== ( const Publisher rhs  )  const [inline]

Definition at line 116 of file publisher.h.

template<class M >
void message_transport::Publisher::publish ( const typename M::ConstPtr &  message  )  const [inline]

Publish an image on the topics associated with this Publisher.

Definition at line 98 of file publisher.h.

template<class M >
void message_transport::Publisher::publish ( const M &  message  )  const [inline]

Publish an image on the topics associated with this Publisher.

Definition at line 84 of file publisher.h.

template<class M >
SingleSubscriberPublisher<M>::StatusCB message_transport::Publisher::rebindCB ( const typename SingleSubscriberPublisher< M >::StatusCB &  user_cb  )  [inline, private]

Definition at line 154 of file publisher.h.

void message_transport::Publisher::shutdown (  ) 

Shutdown the advertisements associated with this Publisher.

Definition at line 60 of file publisher.cpp.


Member Data Documentation

Definition at line 166 of file publisher.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


message_transport_common
Author(s): Cedric Pradalier
autogenerated on Fri Jan 11 09:52:58 2013