A Publication manages an advertised topic.
More...
#include <publication.h>
|
void | addCallbacks (const SubscriberCallbacksPtr &callbacks) |
|
void | addSubscriberLink (const SubscriberLinkPtr &sub_link) |
| Adds a publisher to our list. More...
|
|
void | drop () |
| Drop this publication. Disconnects all publishers. More...
|
|
bool | enqueueMessage (const SerializedMessage &m) |
| queues an outgoing message into each of the publishers, so that it gets sent to every subscriber More...
|
|
const std::string & | getDataType () const |
| Returns the data type of the message published by this publication. More...
|
|
void | getInfo (XmlRpc::XmlRpcValue &info) |
| Get the accumulated info for this publication. More...
|
|
size_t | getMaxQueue () |
| returns the max queue size of this publication More...
|
|
const std::string & | getMD5Sum () const |
| Returns the md5sum of the message published by this publication. More...
|
|
const std::string & | getMessageDefinition () const |
| Returns the full definition of the message published by this publication. More...
|
|
const std::string & | getName () const |
| Returns the name of the topic this publication broadcasts to. More...
|
|
size_t | getNumCallbacks () |
|
uint32_t | getNumSubscribers () |
| Returns the number of subscribers this publication has. More...
|
|
void | getPublishTypes (bool &serialize, bool &nocopy, const std::type_info &ti) |
|
uint32_t | getSequence () |
| Returns the sequence number. More...
|
|
XmlRpc::XmlRpcValue | getStats () |
| Get the accumulated stats for this publication. More...
|
|
bool | hasSubscribers () |
| Returns whether or not this publication has any subscribers. More...
|
|
uint32_t | incrementSequence () |
|
bool | isDropped () |
| Returns if this publication is valid or not. More...
|
|
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) More...
|
|
bool | validateHeader (const Header &h, std::string &error_msg) |
|
| ~Publication () |
|
A Publication manages an advertised topic.
Definition at line 53 of file publication.h.
◆ V_Callback
◆ V_SerializedMessage
◆ Publication()
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 |
|
) |
| |
◆ ~Publication()
ros::Publication::~Publication |
( |
| ) |
|
◆ addCallbacks()
◆ addSubscriberLink()
◆ drop()
void ros::Publication::drop |
( |
| ) |
|
Drop this publication. Disconnects all publishers.
Definition at line 138 of file publication.cpp.
◆ dropAllConnections()
void ros::Publication::dropAllConnections |
( |
| ) |
|
|
private |
◆ enqueueMessage()
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.
◆ getDataType()
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.
◆ getInfo()
Get the accumulated info for this publication.
Definition at line 287 of file publication.cpp.
◆ getMaxQueue()
size_t ros::Publication::getMaxQueue |
( |
| ) |
|
|
inline |
returns the max queue size of this publication
Definition at line 76 of file publication.h.
◆ getMD5Sum()
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.
◆ getMessageDefinition()
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.
◆ getName()
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.
◆ getNumCallbacks()
size_t ros::Publication::getNumCallbacks |
( |
| ) |
|
◆ getNumSubscribers()
uint32_t ros::Publication::getNumSubscribers |
( |
| ) |
|
Returns the number of subscribers this publication has.
Definition at line 374 of file publication.cpp.
◆ getPublishTypes()
void ros::Publication::getPublishTypes |
( |
bool & |
serialize, |
|
|
bool & |
nocopy, |
|
|
const std::type_info & |
ti |
|
) |
| |
◆ getSequence()
uint32_t ros::Publication::getSequence |
( |
| ) |
|
|
inline |
◆ getStats()
Get the accumulated stats for this publication.
Definition at line 255 of file publication.cpp.
◆ hasSubscribers()
bool ros::Publication::hasSubscribers |
( |
| ) |
|
Returns whether or not this publication has any subscribers.
Definition at line 401 of file publication.cpp.
◆ incrementSequence()
uint32_t ros::Publication::incrementSequence |
( |
| ) |
|
◆ isDropped()
bool ros::Publication::isDropped |
( |
| ) |
|
|
inline |
Returns if this publication is valid or not.
Definition at line 136 of file publication.h.
◆ isLatched()
bool ros::Publication::isLatched |
( |
| ) |
|
|
inline |
◆ isLatching()
bool ros::Publication::isLatching |
( |
| ) |
|
|
inline |
◆ peerConnect()
Called when a new peer has connected. Calls the connection callback.
Definition at line 325 of file publication.cpp.
◆ peerDisconnect()
Called when a peer has disconnected. Calls the disconnection callback.
Definition at line 342 of file publication.cpp.
◆ processPublishQueue()
void ros::Publication::processPublishQueue |
( |
| ) |
|
◆ publish()
◆ removeCallbacks()
◆ removeSubscriberLink()
Removes a publisher from our list (deleting it if it's the last reference)
Definition at line 225 of file publication.cpp.
◆ validateHeader()
bool ros::Publication::validateHeader |
( |
const Header & |
h, |
|
|
std::string & |
error_msg |
|
) |
| |
◆ callbacks_
◆ callbacks_mutex_
boost::mutex ros::Publication::callbacks_mutex_ |
|
private |
◆ datatype_
std::string ros::Publication::datatype_ |
|
private |
◆ dropped_
bool ros::Publication::dropped_ |
|
private |
◆ has_header_
bool ros::Publication::has_header_ |
|
private |
◆ intraprocess_subscriber_count_
uint32_t ros::Publication::intraprocess_subscriber_count_ |
|
private |
◆ last_message_
◆ latch_
bool ros::Publication::latch_ |
|
private |
◆ max_queue_
size_t ros::Publication::max_queue_ |
|
private |
◆ md5sum_
std::string ros::Publication::md5sum_ |
|
private |
◆ message_definition_
std::string ros::Publication::message_definition_ |
|
private |
◆ name_
std::string ros::Publication::name_ |
|
private |
◆ publish_queue_
◆ publish_queue_mutex_
boost::mutex ros::Publication::publish_queue_mutex_ |
|
private |
◆ seq_
uint32_t ros::Publication::seq_ |
|
private |
◆ seq_mutex_
boost::mutex ros::Publication::seq_mutex_ |
|
private |
◆ subscriber_links_
◆ subscriber_links_mutex_
boost::mutex ros::Publication::subscriber_links_mutex_ |
|
private |
The documentation for this class was generated from the following files:
roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Feb 28 2022 23:33:27