Public Member Functions | Private Types | Private Member Functions | Private Attributes
ros::Publication Class Reference

A Publication manages an advertised topic. More...

#include <publication.h>

List of all members.

Public Member Functions

void addCallbacks (const SubscriberCallbacksPtr &callbacks)
void addSubscriberLink (const SubscriberLinkPtr &sub_link)
 Adds a publisher to our list.
void drop ()
 Drop this publication. Disconnects all publishers.
bool enqueueMessage (const SerializedMessage &m)
 queues an outgoing message into each of the publishers, so that it gets sent to every subscriber
const std::string & getDataType () const
 Returns the data type of the message published by this publication.
void getInfo (XmlRpc::XmlRpcValue &info)
 Get the accumulated info for this publication.
size_t getMaxQueue ()
 returns the max queue size of this publication
const std::string & getMD5Sum () const
 Returns the md5sum of the message published by this publication.
const std::string & getMessageDefinition () const
 Returns the full definition of the message published by this publication.
const std::string & getName () const
 Returns the name of the topic this publication broadcasts to.
size_t getNumCallbacks ()
uint32_t getNumSubscribers ()
 Returns the number of subscribers this publication has.
void getPublishTypes (bool &serialize, bool &nocopy, const std::type_info &ti)
uint32_t getSequence ()
 Returns the sequence number.
XmlRpc::XmlRpcValue getStats ()
 Get the accumulated stats for this publication.
bool hasSubscribers ()
 Returns whether or not this publication has any subscribers.
uint32_t incrementSequence ()
bool isDropped ()
 Returns if this publication is valid or not.
bool isLatched ()
bool isLatching ()
void processPublishQueue ()
 Publication (const std::string &name, const std::string &datatype, const std::string &_md5sum, const std::string &message_definition, size_t max_queue, bool latch, bool has_header)
void publish (SerializedMessage &m)
void removeCallbacks (const SubscriberCallbacksPtr &callbacks)
void removeSubscriberLink (const SubscriberLinkPtr &sub_link)
 Removes a publisher from our list (deleting it if it's the last reference)
bool validateHeader (const Header &h, std::string &error_msg)
 ~Publication ()

Private Types

typedef std::vector
< SubscriberCallbacksPtr > 
V_Callback
typedef std::vector
< SerializedMessage
V_SerializedMessage

Private Member Functions

void dropAllConnections ()
void peerConnect (const SubscriberLinkPtr &sub_link)
 Called when a new peer has connected. Calls the connection callback.
void peerDisconnect (const SubscriberLinkPtr &sub_link)
 Called when a peer has disconnected. Calls the disconnection callback.

Private Attributes

V_Callback callbacks_
boost::mutex callbacks_mutex_
std::string datatype_
bool dropped_
bool has_header_
uint32_t intraprocess_subscriber_count_
SerializedMessage last_message_
bool latch_
size_t max_queue_
std::string md5sum_
std::string message_definition_
std::string name_
V_SerializedMessage publish_queue_
boost::mutex publish_queue_mutex_
uint32_t seq_
boost::mutex seq_mutex_
V_SubscriberLink subscriber_links_
boost::mutex subscriber_links_mutex_

Detailed Description

A Publication manages an advertised topic.

Definition at line 53 of file publication.h.


Member Typedef Documentation

typedef std::vector<SubscriberCallbacksPtr> ros::Publication::V_Callback [private]

Definition at line 169 of file publication.h.

Definition at line 185 of file publication.h.


Constructor & Destructor Documentation

ros::Publication::Publication ( const std::string &  name,
const std::string &  datatype,
const std::string &  _md5sum,
const std::string &  message_definition,
size_t  max_queue,
bool  latch,
bool  has_header 
)

Definition at line 76 of file publication.cpp.

Definition at line 96 of file publication.cpp.


Member Function Documentation

void ros::Publication::addCallbacks ( const SubscriberCallbacksPtr &  callbacks)

Definition at line 101 of file publication.cpp.

void ros::Publication::addSubscriberLink ( const SubscriberLinkPtr &  sub_link)

Adds a publisher to our list.

Definition at line 196 of file publication.cpp.

Drop this publication. Disconnects all publishers.

Definition at line 138 of file publication.cpp.

Definition at line 307 of file publication.cpp.

queues an outgoing message into each of the publishers, so that it gets sent to every subscriber

Definition at line 157 of file publication.cpp.

const std::string& ros::Publication::getDataType ( ) const [inline]

Returns the data type of the message published by this publication.

Definition at line 104 of file publication.h.

Get the accumulated info for this publication.

Definition at line 290 of file publication.cpp.

size_t ros::Publication::getMaxQueue ( ) [inline]

returns the max queue size of this publication

Definition at line 76 of file publication.h.

const std::string& ros::Publication::getMD5Sum ( ) const [inline]

Returns the md5sum of the message published by this publication.

Definition at line 108 of file publication.h.

const std::string& ros::Publication::getMessageDefinition ( ) const [inline]

Returns the full definition of the message published by this publication.

Definition at line 112 of file publication.h.

const std::string& ros::Publication::getName ( ) const [inline]

Returns the name of the topic this publication broadcasts to.

Definition at line 100 of file publication.h.

Definition at line 356 of file publication.cpp.

Returns the number of subscribers this publication has.

Definition at line 371 of file publication.cpp.

void ros::Publication::getPublishTypes ( bool &  serialize,
bool &  nocopy,
const std::type_info &  ti 
)

Definition at line 377 of file publication.cpp.

uint32_t ros::Publication::getSequence ( ) [inline]

Returns the sequence number.

Definition at line 116 of file publication.h.

Get the accumulated stats for this publication.

Definition at line 255 of file publication.cpp.

Returns whether or not this publication has any subscribers.

Definition at line 398 of file publication.cpp.

Definition at line 362 of file publication.cpp.

bool ros::Publication::isDropped ( ) [inline]

Returns if this publication is valid or not.

Definition at line 136 of file publication.h.

bool ros::Publication::isLatched ( ) [inline]

Definition at line 118 of file publication.h.

bool ros::Publication::isLatching ( ) [inline]

Definition at line 142 of file publication.h.

void ros::Publication::peerConnect ( const SubscriberLinkPtr &  sub_link) [private]

Called when a new peer has connected. Calls the connection callback.

Definition at line 326 of file publication.cpp.

void ros::Publication::peerDisconnect ( const SubscriberLinkPtr &  sub_link) [private]

Called when a peer has disconnected. Calls the disconnection callback.

Definition at line 341 of file publication.cpp.

Definition at line 430 of file publication.cpp.

Definition at line 404 of file publication.cpp.

void ros::Publication::removeCallbacks ( const SubscriberCallbacksPtr &  callbacks)

Definition at line 122 of file publication.cpp.

void ros::Publication::removeSubscriberLink ( const SubscriberLinkPtr &  sub_link)

Removes a publisher from our list (deleting it if it's the last reference)

Definition at line 225 of file publication.cpp.

bool ros::Publication::validateHeader ( const Header h,
std::string &  error_msg 
)

Definition at line 458 of file publication.cpp.


Member Data Documentation

Definition at line 170 of file publication.h.

boost::mutex ros::Publication::callbacks_mutex_ [private]

Definition at line 171 of file publication.h.

std::string ros::Publication::datatype_ [private]

Definition at line 162 of file publication.h.

Definition at line 177 of file publication.h.

Definition at line 180 of file publication.h.

Definition at line 183 of file publication.h.

Definition at line 181 of file publication.h.

bool ros::Publication::latch_ [private]

Definition at line 179 of file publication.h.

size_t ros::Publication::max_queue_ [private]

Definition at line 165 of file publication.h.

std::string ros::Publication::md5sum_ [private]

Definition at line 163 of file publication.h.

Definition at line 164 of file publication.h.

std::string ros::Publication::name_ [private]

Definition at line 161 of file publication.h.

Definition at line 186 of file publication.h.

Definition at line 187 of file publication.h.

uint32_t ros::Publication::seq_ [private]

Definition at line 166 of file publication.h.

boost::mutex ros::Publication::seq_mutex_ [private]

Definition at line 167 of file publication.h.

V_SubscriberLink ros::Publication::subscriber_links_ [private]

Definition at line 173 of file publication.h.

Definition at line 175 of file publication.h.


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


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Mon Oct 6 2014 11:46:44