<> <> == Publishing to a Topic == See also: [[http://www.ros.org/doc/api/roscpp/html/classros_1_1NodeHandle.html#41fcdf7fd2a2bfa1c42d14d35f8f5a8e|ros::NodeHandle::advertise() API docs]], [[http://www.ros.org/doc/api/roscpp/html/classros_1_1Publisher.html|ros::Publisher API docs]], [[http://www.ros.org/doc/api/roscpp/html/classros_1_1NodeHandle.html|ros::NodeHandle API docs]] Creating a handle to publish messages to a topic is done using the `ros::NodeHandle` class, which is covered in more detail in the [[roscpp/Overview/NodeHandles|NodeHandles overview]]. The `NodeHandle::advertise()` methods are used to create a `ros::Publisher` which is used to publish on a topic, e.g.: {{{#!cplusplus ros::Publisher pub = nh.advertise("topic_name", 5); std_msgs::String str; str.data = "hello world"; pub.publish(str); }}} '''Note''': it is possible (though rare) for `NodeHandle::advertise()` to return an empty `ros::Publisher`. In the future these cases will probably throw exceptions, but for now they simply print an error. You can check for this with: {{{#!cplusplus if (!pub) { ... } }}} === Intraprocess Publishing === When a publisher and subscriber to the same topic both exist inside the same node, roscpp can skip the serialize/deserialize step (potentially saving a large amount of processing and latency). It can only do this though if the message is published as a `shared_ptr`: {{{#!cplusplus ros::Publisher pub = nh.advertise("topic_name", 5); std_msgs::StringPtr str(new std_msgs::String); str->data = "hello world"; pub.publish(str); }}} This form of publishing is what can make [[nodelet|nodelets]] such a large win over nodes in separate processes. Note that when publishing in this fashion, there is an implicit contract between you and roscpp: you may not modify the message you've sent after you send it, since that pointer will be passed directly to any intraprocess subscribers. If you want to send another message, you must allocate a new one and send that. === Publisher Options === The signature for the simple version of `advertise()` is: {{{#!cplusplus template ros::Publisher advertise(const std::string& topic, uint32_t queue_size, bool latch = false); }}} . `M` [required] . This is a template argument specifying the message type to be published on the topic `topic` [required] . This is the topic to publish on. `queue_size` [required] . This is the size of the outgoing message queue. If you are publishing faster than roscpp can send the messages over the wire, roscpp will start dropping old messages. A value of 0 here means an infinite queue, which can be dangerous. See the [[rospy/Overview/Publishers and Subscribers#Choosing_a_good_queue_size|rospy documentation on choosing a good queue_size]] for more information. `latch` [optional] . Enables "latching" on a connection. When a connection is latched, the last message published is saved and automatically sent to any future subscribers that connect. This is useful for slow-changing to static data like a map. Note that if there are multiple publishers on the same topic, instantiated in the same node, then only the last published message from that node will be sent, as opposed to the last published message from each publisher on that single topic. === Other Operations on the Publisher Handle === `ros::Publisher` is reference counted internally -- this means that copying them is very fast, and does not create a "new" version of the `ros::Publisher`. Once all copies of a `ros::Publisher` are destructed the topic will be shutdown. There are some exceptions to this: 1. `ros::shutdown()` is called -- this shuts down all publishers (and everything else). 1. `ros::Publisher::shutdown()` is called. This will shutdown this topic, unless there have been... 1. Multiple calls to `NodeHandle::advertise()` for the same topic, with the same message type. In this case all the `ros::Publisher`s on a specific topic are treated as copies of each other. `ros::Publisher` implements the `==`, `!=` and `<` operators, and it is possible to use them in `std::map`, `std::set`, etc. You can retrieve the topic of a publisher with the `ros::Publisher::getTopic()` method. === publish() behavior and queueing === `publish()` in roscpp is asynchronous, and only does work if there are subscribers connected on that topic. `publish()` itself is meant to be very fast, so it does as little work as possible: 1. Serialize the message to a buffer 1. Pushes that buffer onto a queue for later processing The queue it's pushed onto is then serviced as soon as possible by one of roscpp's internal threads, where it gets put onto a queue for each connected subscriber -- this second set of queues are the ones whose size is set with the queue_size parameter in `advertise()`. If one of these queues fills up the oldest message will be dropped before adding the next message to the queue. Note that there may also be an OS-level queue at the transport level, such as the TCP/UDP send buffer. == Subscribing to a Topic == See also: [[http://www.ros.org/doc/api/roscpp/html/classros_1_1NodeHandle.html#3b8e4b07d397119cd5c5e4439b170cbc|ros::NodeHandle::subscribe() API docs]], [[http://www.ros.org/doc/api/roscpp/html/classros_1_1Subscriber.html|ros::Subscriber API docs]], [[http://www.ros.org/doc/api/roscpp/html/classros_1_1NodeHandle.html|ros::NodeHandle API docs]], [[http://www.ros.org/doc/api/roscpp/html/classros_1_1TransportHints.html|ros::TransportHints API docs]] Subscribing to a topic is also done using the `ros::NodeHandle` class (covered in more detail in the [[roscpp/Overview/NodeHandles|NodeHandles overview]]). A simple subscription using a global function would look like: {{{#!cplusplus void callback(const std_msgs::StringConstPtr& str) { ... } ... ros::Subscriber sub = nh.subscribe("my_topic", 1, callback); }}} === Subscriber Options === There are many different versions of `ros::NodeHandle::subscribe()`, but the simple versions boil down to: {{{#!cplusplus template ros::Subscriber subscribe(const std::string& topic, uint32_t queue_size, , const ros::TransportHints& transport_hints = ros::TransportHints()); }}} . `M` [usually unnecessary] . This is a template argument specifying the message type to be published on the topic. For most versions of this `subscribe()` you do not need to explicitly define this, as the compiler can deduce it from the callback you specify. `topic` . The topic to subscribe to `queue_size` . This is the incoming message queue size roscpp will use for your callback. If messages are arriving too fast and you are unable to keep up, roscpp will start throwing away messages. A value of 0 here means an infinite queue, which can be dangerous. `` . Depending on the version of `subscribe()` you're using, this may be any of a few things. The most common is a class method pointer and a pointer to the instance of the class. This is explained in more detail later. `transport_hints` . The transport hints allow you to specify hints to roscpp's transport layer. This lets you specify things like preferring a UDP transport, using tcp nodelay, etc. This is explained in more detail later. === Callback Signature === The signature for the callback is: {{{#!cplusplus void callback(const boost::shared_ptr&); }}} Every generated message provides typedefs for the shared pointer type, so you can also use, for example: {{{#!cplusplus void callback(const std_msgs::StringConstPtr&); }}} or {{{#!cplusplus void callback(const std_msgs::String::ConstPtr&); }}} '''Other Valid Signatures [ROS 1.1+]''' As of ROS 1.1 we also support variations on the above callbacks: {{{#!cplusplus void callback(boost::shared_ptr); void callback(std_msgs::StringConstPtr); void callback(std_msgs::String::ConstPtr); void callback(const std_msgs::String&); void callback(std_msgs::String); void callback(const ros::MessageEvent&); }}} You can also request a non-const message, in which case a copy will be made if necessary (i.e. there are multiple subscriptions to the same topic in a single node): {{{#!cplusplus void callback(const boost::shared_ptr&); void callback(boost::shared_ptr); void callback(const std_msgs::StringPtr&); void callback(const std_msgs::String::Ptr&); void callback(std_msgs::StringPtr); void callback(std_msgs::String::Ptr); void callback(const ros::MessageEvent&); }}} The `MessageEvent` versions are described below. === Callback Types === roscpp supports any callback supported by [[http://www.boost.org/doc/libs/1_37_0/doc/html/function.html|boost::function]]: 1. functions 1. class methods 1. functor objects (including [[http://www.boost.org/doc/libs/1_37_0/libs/bind/bind.html|boost::bind]]) ==== Functions ==== Functions are the easiest to use: {{{#!cplusplus void callback(const std_msgs::StringConstPtr& str) { ... } ... ros::Subscriber sub = nh.subscribe("my_topic", 1, callback); }}} ==== Class Methods ==== Class methods are also easy, though they require an extra parameter: {{{#!cplusplus void Foo::callback(const std_msgs::StringConstPtr& message) { } ... Foo foo_object; ros::Subscriber sub = nh.subscribe("my_topic", 1, &Foo::callback, &foo_object); }}} ==== Functor Objects ==== A functor object is a class that declares `operator()`, e.g.: {{{#!cplusplus class Foo { public: void operator()(const std_msgs::StringConstPtr& message) { } }; }}} A functor passed to `subscribe()` must be '''copyable'''. The `Foo` functor could be used with `subscribe()` like so: {{{#!cplusplus ros::Subscriber sub = nh.subscribe("my_topic", 1, Foo()); }}} '''Note:''' when using functor objects (like boost::bind, for example) you must explicitly specify the message type as a template argument, because the compiler cannot deduce it in this case. === MessageEvent [ROS 1.1+] === The [[http://www.ros.org/doc/api/roscpp_traits/html/classros_1_1MessageEvent.html|MessageEvent]] class allows you to retrieve metadata about a message from within a subscription callback: {{{#!cplusplus void callback(const ros::MessageEvent& event) { const std::string& publisher_name = event.getPublisherName(); const ros::M_string& header = event.getConnectionHeader(); ros::Time receipt_time = event.getReceiptTime(); const std_msgs::StringConstPtr& msg = event.getMessage(); } }}} (see [[ROS/Connection Header]] for details on the fields in the connection header) === Queueing and Lazy Deserialization === When a message first arrives on a topic it gets put into a queue whose size is specified by the `queue_size` parameter in `subscribe()`. If the queue is full and a new message arrives, the oldest message will be thrown out. Additionally, the message is not actually deserialized until the first callback which needs it is about to be called. <> === Transport Hints === See also: [[http://www.ros.org/doc/api/roscpp/html/classros_1_1TransportHints.html|ros::TransportHints API docs]] `ros::TransportHints` are used to specify hints about how you want the transport layer to behave for this topic. For example, if you wanted to specify an "unreliable" connection (and not allow a "reliable" connection as a fall back): {{{#!cplusplus ros::Subscriber sub = nh.subscribe("my_topic", 1, callback, ros::TransportHints().unreliable()); }}} Note that `ros::TransportHints` uses the [[http://www.cs.technion.ac.il/users/yechiel/c++-faq/named-parameter-idiom.html|Named Parameter Idiom]], a form of method-chaining. This means you can do things like: {{{#!cplusplus ros::TransportHints() .unreliable() .reliable() .maxDatagramSize(1000) .tcpNoDelay(); }}} As is this example you can specify multiple different transport options (`unreliable` as well as `reliable`). If the publisher on the topic you're subscribing to does not support the first connection (`unreliable`), the connection will be made with the second (`reliable`) if supported. In this case the order of the two methods is important since it determines the order of considered transports. You cannot currently specify the transport hints on the `Publisher` side. This will likely be an option in the future.