Public Member Functions | Static Public Member Functions | Public Attributes
ros::AdvertiseOptions Struct Reference

Encapsulates all options available for creating a Publisher. More...

#include <advertise_options.h>

List of all members.

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

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.

Public Attributes

CallbackQueueInterfacecallback_queue
 Queue to add callbacks to. If NULL, the global callback queue will be used.
SubscriberStatusCallback connect_cb
 The function to call when a subscriber connects to this topic.
std::string datatype
 The datatype of the message published on this topic (eg. "std_msgs/String")
SubscriberStatusCallback disconnect_cb
 The function to call when a subscriber disconnects from this topic.
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.
bool latch
 Whether or not this publication should "latch". A latching publication will automatically send out the last published message to any new subscribers.
std::string md5sum
 The md5sum of the message datatype published on this topic.
std::string message_definition
 The full definition of the message published on this topic.
uint32_t queue_size
 The maximum number of outgoing messages to be queued for delivery to subscribers.
std::string topic
 The topic to publish on.
VoidConstPtr tracked_object
 An object whose destruction will prevent the callbacks associated with this advertisement from being called.

Detailed Description

Encapsulates all options available for creating a Publisher.

Definition at line 41 of file advertise_options.h.


Constructor & Destructor Documentation

Definition at line 43 of file advertise_options.h.

ros::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() 
) [inline]

Definition at line 58 of file advertise_options.h.


Member Function Documentation

template<class M >
static AdvertiseOptions ros::AdvertiseOptions::create ( const std::string &  topic,
uint32_t  queue_size,
const SubscriberStatusCallback &  connect_cb,
const SubscriberStatusCallback &  disconnect_cb,
const VoidConstPtr &  tracked_object,
CallbackQueueInterface queue 
) [inline, static]

Templated helper function for creating an AdvertiseOptions for a message type with most options.

Parameters:
M[template] Message type
topicTopic to publish on
queue_sizeMaximum number of outgoing messages to be queued for delivery to subscribers
connect_cbFunction to call when a subscriber connects to this topic
disconnect_cbFunction to call when a subscriber disconnects from this topic
tracked_objecttracked object to use (see AdvertiseOptions::tracked_object)
queueThe callback queue to use (see AdvertiseOptions::callback_queue)
Returns:
an AdvertiseOptions which embodies the parameters

Definition at line 148 of file advertise_options.h.

template<class M >
void ros::AdvertiseOptions::init ( const std::string &  _topic,
uint32_t  _queue_size,
const SubscriberStatusCallback &  _connect_cb = SubscriberStatusCallback(),
const SubscriberStatusCallback &  _disconnect_cb = SubscriberStatusCallback() 
) [inline]

templated helper function for automatically filling out md5sum, datatype and message definition

Parameters:
M[template] Message type
_topicTopic to publish on
_queue_sizeMaximum number of outgoing messages to be queued for delivery to subscribers
_connect_cbFunction to call when a subscriber connects to this topic
_disconnect_cbFunction to call when a subscriber disconnects from this topic

Definition at line 84 of file advertise_options.h.


Member Data Documentation

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.

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.

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.

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.

The md5sum of the message datatype published on this topic.

Definition at line 101 of file advertise_options.h.

The full definition of the message published on this topic.

Definition at line 103 of file advertise_options.h.

The maximum number of outgoing messages to be queued for delivery to subscribers.

Definition at line 99 of file advertise_options.h.

The topic to publish on.

Definition at line 98 of file advertise_options.h.

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.

Note:
Note that setting this will cause a new reference to be added to the object before the callback, and for it to go out of scope (and potentially be deleted) in the code path (and therefore thread) that the callback is invoked from.

Definition at line 120 of file advertise_options.h.


The documentation for this struct was generated from the following file:


roscpp
Author(s): Morgan Quigley mquigley@cs.stanford.edu, Josh Faust jfaust@willowgarage.com, Brian Gerkey gerkey@willowgarage.com, Troy Straszheim straszheim@willowgarage.com
autogenerated on Sat Dec 28 2013 17:35:53