Encapsulates all options available for creating a Publisher. More...
#include <advertise_options.h>
Public Member Functions | |
AdvertiseOptions () | |
AdvertiseOptions (const std::string &_topic, uint32_t _queue_size, const std::string &_md5sum, const std::string &_datatype, const std::string &_message_definition, const SubscriberStatusCallback &_connect_cb=SubscriberStatusCallback(), const SubscriberStatusCallback &_disconnect_cb=SubscriberStatusCallback()) | |
template<class M > | |
void | init (const std::string &_topic, uint32_t _queue_size, const SubscriberStatusCallback &_connect_cb=SubscriberStatusCallback(), const SubscriberStatusCallback &_disconnect_cb=SubscriberStatusCallback()) |
templated helper function for automatically filling out md5sum, datatype and message definition More... | |
Static Public Member Functions | |
template<class M > | |
static AdvertiseOptions | create (const std::string &topic, uint32_t queue_size, const SubscriberStatusCallback &connect_cb, const SubscriberStatusCallback &disconnect_cb, const VoidConstPtr &tracked_object, CallbackQueueInterface *queue) |
Templated helper function for creating an AdvertiseOptions for a message type with most options. More... | |
Public Attributes | |
CallbackQueueInterface * | callback_queue |
Queue to add callbacks to. If NULL, the global callback queue will be used. More... | |
SubscriberStatusCallback | connect_cb |
The function to call when a subscriber connects to this topic. More... | |
std::string | datatype |
The datatype of the message published on this topic (eg. "std_msgs/String") More... | |
SubscriberStatusCallback | disconnect_cb |
The function to call when a subscriber disconnects from this topic. More... | |
bool | has_header |
Tells whether or not the message has a header. If it does, the sequence number will be written directly into the serialized bytes after the message has been serialized. More... | |
bool | latch |
Whether or not this publication should "latch". A latching publication will automatically send out the last published message to any new subscribers. More... | |
std::string | md5sum |
The md5sum of the message datatype published on this topic. More... | |
std::string | message_definition |
The full definition of the message published on this topic. More... | |
uint32_t | queue_size |
The maximum number of outgoing messages to be queued for delivery to subscribers. More... | |
std::string | topic |
The topic to publish on. More... | |
VoidConstPtr | tracked_object |
An object whose destruction will prevent the callbacks associated with this advertisement from being called. More... | |
Encapsulates all options available for creating a Publisher.
Definition at line 41 of file advertise_options.h.
|
inline |
Definition at line 43 of file advertise_options.h.
|
inline |
Definition at line 58 of file advertise_options.h.
|
inlinestatic |
Templated helper function for creating an AdvertiseOptions for a message type with most options.
M | [template] Message type |
topic | Topic to publish on |
queue_size | Maximum number of outgoing messages to be queued for delivery to subscribers |
connect_cb | Function to call when a subscriber connects to this topic |
disconnect_cb | Function to call when a subscriber disconnects from this topic |
tracked_object | tracked object to use (see AdvertiseOptions::tracked_object) |
queue | The callback queue to use (see AdvertiseOptions::callback_queue) |
Definition at line 148 of file advertise_options.h.
|
inline |
templated helper function for automatically filling out md5sum, datatype and message definition
M | [template] Message type |
_topic | Topic to publish on |
_queue_size | Maximum number of outgoing messages to be queued for delivery to subscribers |
_connect_cb | Function to call when a subscriber connects to this topic |
_disconnect_cb | Function to call when a subscriber disconnects from this topic |
Definition at line 84 of file advertise_options.h.
CallbackQueueInterface* ros::AdvertiseOptions::callback_queue |
Queue to add callbacks to. If NULL, the global callback queue will be used.
Definition at line 108 of file advertise_options.h.
SubscriberStatusCallback ros::AdvertiseOptions::connect_cb |
The function to call when a subscriber connects to this topic.
Definition at line 105 of file advertise_options.h.
std::string ros::AdvertiseOptions::datatype |
The datatype of the message published on this topic (eg. "std_msgs/String")
Definition at line 102 of file advertise_options.h.
SubscriberStatusCallback ros::AdvertiseOptions::disconnect_cb |
The function to call when a subscriber disconnects from this topic.
Definition at line 106 of file advertise_options.h.
bool ros::AdvertiseOptions::has_header |
Tells whether or not the message has a header. If it does, the sequence number will be written directly into the serialized bytes after the message has been serialized.
Definition at line 131 of file advertise_options.h.
bool ros::AdvertiseOptions::latch |
Whether or not this publication should "latch". A latching publication will automatically send out the last published message to any new subscribers.
Definition at line 126 of file advertise_options.h.
std::string ros::AdvertiseOptions::md5sum |
The md5sum of the message datatype published on this topic.
Definition at line 101 of file advertise_options.h.
std::string ros::AdvertiseOptions::message_definition |
The full definition of the message published on this topic.
Definition at line 103 of file advertise_options.h.
uint32_t ros::AdvertiseOptions::queue_size |
The maximum number of outgoing messages to be queued for delivery to subscribers.
Definition at line 99 of file advertise_options.h.
std::string ros::AdvertiseOptions::topic |
The topic to publish on.
Definition at line 98 of file advertise_options.h.
VoidConstPtr ros::AdvertiseOptions::tracked_object |
An object whose destruction will prevent the callbacks associated with this advertisement from being called.
A shared pointer to an object to track for these callbacks. If set, the a weak_ptr will be created to this object, and if the reference count goes to 0 the subscriber callbacks will not get called.
Definition at line 120 of file advertise_options.h.