[Documentation] [TitleIndex] [WordIndex

Publishing to a topic

You can create a handle to publish messages to a topic using the ros::Publisher class. You must first create a message to be used by the publisher, and then call advertise within the setup():

   1 #include <ros.h>
   2 ros::NodeHandle nh;
   3 
   4 // before your setup() function
   5 std_msgs::String str_msg;
   6 ros::Publisher pub("foo", &str_msg);
   7 
   8 void setup(){
   9     ...
  10     nh.advertise(pub);
  11     ...
  12 }

You can then call publish to post a message:

   1 void loop()
   2 {
   3    pub.publish( &str_msg );
   4    nh.spinOnce();
   5 }

Subscribing to a topic

The first step in subscribing to a topic is including the header file and creating the call back function. All rosserial messages will be located under the package_name/msg_name in your ros_lib folder. For example, a std_mgs/Float64 should be included via #include <std_msgs/Float64.h>

To define a call back, you create a function that returns void and takes a constant reference of your message type as its argument.

   1 #include <std_msgs/Float64.h>
   2 void messageCb(const std_msgs::Float64& msg)
   3   if(msg.data > 1.0)
   4     digitalWrite(13, HIGH-digitalRead(13));   // blink the led
   5 }

Then to actually setup the connection we have to create a statically allocated ros::Subscriber which is templated on your message type and call NodeHandle::subscribe within the setup() function:

   1 #include <ros.h>
   2 ros::NodeHandle nh;
   3 
   4 void messageCb(const std_msgs::Float64& msg)
   5   if(msg.data > 1.0)
   6     digitalWrite(13, HIGH-digitalRead(13));   // blink the led
   7 }
   8 
   9 ros::Subscriber<std_msgs::Float64> sub("your_topic", &messageCb);
  10 
  11 void setup()
  12 {
  13     ...
  14     nh.subscribe(sub);
  15     ...
  16 }

It is very important that your Subscriber never go out of scope during the life of this program. rosserial depends on global objects like the Subscriber to get around the limited memory of our target systems. If it goes out of scope, your program will crash when the next message is received.


2022-05-28 12:58