Manages an advertisement on a specific topic. More...
#include <publisher.h>
Classes | |
class | Impl |
Public Member Functions | |
uint32_t | getNumSubscribers () const |
Returns the number of subscribers that are currently connected to this Publisher. | |
std::string | getTopic () const |
Returns the topic that this Publisher will publish on. | |
bool | isLatched () const |
Returns whether or not this topic is latched. | |
operator void * () const | |
bool | operator!= (const Publisher &rhs) const |
bool | operator< (const Publisher &rhs) const |
bool | operator== (const Publisher &rhs) const |
template<typename M > | |
void | publish (const M &message) const |
Publish a message on the topic associated with this Publisher. | |
template<typename M > | |
void | publish (const boost::shared_ptr< M > &message) const |
Publish a message on the topic associated with this Publisher. | |
Publisher (const Publisher &rhs) | |
Publisher () | |
void | shutdown () |
Shutdown the advertisement associated with this Publisher. | |
~Publisher () | |
Private Types | |
typedef boost::shared_ptr< Impl > | ImplPtr |
typedef boost::weak_ptr< Impl > | ImplWPtr |
Private Member Functions | |
void | incrementSequence () const |
void | publish (const boost::function< SerializedMessage(void)> &serfunc, SerializedMessage &m) const |
Publisher (const std::string &topic, const std::string &md5sum, const std::string &datatype, const NodeHandle &node_handle, const SubscriberCallbacksPtr &callbacks) | |
Private Attributes | |
ImplPtr | impl_ |
Friends | |
class | NodeHandle |
class | NodeHandleBackingCollection |
Manages an advertisement on a specific topic.
A Publisher should always be created through a call to NodeHandle::advertise(), or copied from one that was. Once all copies of a specific Publisher go out of scope, any subscriber status callbacks associated with that handle will stop being called. Once all Publishers for a given topic go out of scope the topic will be unadvertised.
Definition at line 48 of file publisher.h.
typedef boost::shared_ptr<Impl> ros::Publisher::ImplPtr [private] |
Definition at line 185 of file publisher.h.
typedef boost::weak_ptr<Impl> ros::Publisher::ImplWPtr [private] |
Definition at line 186 of file publisher.h.
ros::Publisher::Publisher | ( | ) | [inline] |
Definition at line 51 of file publisher.h.
ros::Publisher::Publisher | ( | const Publisher & | rhs | ) |
Definition at line 72 of file publisher.cpp.
ros::Publisher::~Publisher | ( | ) |
Definition at line 77 of file publisher.cpp.
ros::Publisher::Publisher | ( | const std::string & | topic, | |
const std::string & | md5sum, | |||
const std::string & | datatype, | |||
const NodeHandle & | node_handle, | |||
const SubscriberCallbacksPtr & | callbacks | |||
) | [private] |
Definition at line 62 of file publisher.cpp.
uint32_t ros::Publisher::getNumSubscribers | ( | ) | const |
Returns the number of subscribers that are currently connected to this Publisher.
Definition at line 125 of file publisher.cpp.
std::string ros::Publisher::getTopic | ( | ) | const |
Returns the topic that this Publisher will publish on.
Definition at line 115 of file publisher.cpp.
void ros::Publisher::incrementSequence | ( | ) | const [private] |
Definition at line 98 of file publisher.cpp.
bool ros::Publisher::isLatched | ( | ) | const |
Returns whether or not this topic is latched.
ros::Publisher::operator void * | ( | ) | const [inline] |
Definition at line 145 of file publisher.h.
bool ros::Publisher::operator!= | ( | const Publisher & | rhs | ) | const [inline] |
Definition at line 157 of file publisher.h.
bool ros::Publisher::operator< | ( | const Publisher & | rhs | ) | const [inline] |
Definition at line 147 of file publisher.h.
bool ros::Publisher::operator== | ( | const Publisher & | rhs | ) | const [inline] |
Definition at line 152 of file publisher.h.
void ros::Publisher::publish | ( | const boost::function< SerializedMessage(void)> & | serfunc, | |
SerializedMessage & | m | |||
) | const [private] |
Definition at line 81 of file publisher.cpp.
void ros::Publisher::publish | ( | const M & | message | ) | const [inline] |
Publish a message on the topic associated with this Publisher.
Definition at line 94 of file publisher.h.
void ros::Publisher::publish | ( | const boost::shared_ptr< M > & | message | ) | const [inline] |
Publish a message on the topic associated with this Publisher.
This version of publish will allow fast intra-process message-passing in the future, so you may not mutate the message after it has been passed in here (since it will be passed directly into a callback function)
Definition at line 64 of file publisher.h.
void ros::Publisher::shutdown | ( | ) |
Shutdown the advertisement associated with this Publisher.
This method usually does not need to be explicitly called, as automatic shutdown happens when all copies of this Publisher go out of scope
This method overrides the automatic reference counted unadvertise, and does so immediately.
Definition at line 106 of file publisher.cpp.
friend class NodeHandle [friend] |
Definition at line 190 of file publisher.h.
friend class NodeHandleBackingCollection [friend] |
Definition at line 191 of file publisher.h.
ImplPtr ros::Publisher::impl_ [private] |
Definition at line 188 of file publisher.h.