(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Blink (example subscriber)

Description: This tutorial shows step by step how to use rosserial with subscribers.

Tutorial Level: BEGINNER

Next Tutorial: Using Time and TF

  Show EOL distros: 

Blink: Creating a Subscriber

The Code

Now that we've created a ROS publisher in the previous tutorial, we'll create a subscriber.

Open the Blink example placed on your previously downloaded rosserial/rosserial_mbed/examples directory, and open the Blink.cpp file in your favorite text editor:

   1 /*
   2  * rosserial Subscriber Example
   3  * Blinks an LED on callback
   4  */
   5 #include "mbed.h"
   6 #include <ros.h>
   7 #include <std_msgs/Empty.h>
   8 
   9 ros::NodeHandle nh;
  10 DigitalOut myled(LED1);
  11 
  12 void messageCb(const std_msgs::Empty& toggle_msg){
  13     myled = !myled;   // blink the led
  14 }
  15 
  16 ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb);
  17 
  18 int main() {
  19     nh.initNode();
  20     nh.subscribe(sub);
  21 
  22     while (1) {
  23         nh.spinOnce();
  24         wait_ms(1);
  25     }
  26 }

The Code Explained

Now, let's break the code down.

   5 #include "mbed.h"
   6 

We need to include the mbed.h for every MBED program.

   6 #include <ros.h>
   7 #include <std_msgs/Empty.h>
   8 

As before, we need to include the ros.h as with any other ROS MBED program. We also include the header files for messages, in this case, the Empty message.

   9 ros::NodeHandle nh;

Next, we need to instantiate the node handle, which allows our program to create publishers and subscribers. The node handle also takes care of serial port communications.

invalid arguments: <> We then create the callback function for our subscriber. The call back function must take a constant reference of a message as its argument. In our callback messageCb, the type of message is std_msgs::Empty and the message name will be toggle_msg.

Inside our callback, we could reference toggle_msg, but since it is empty, there is no need to. We just blink the LED on the MBED board every time we receive a message.

  16 ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb);

We need to instantiate the publishers and subscribers that we will be using. Here we instantiate a Subscriber with a topic name of "toggle_led" and type std_msgs::Empty. With Subscribers, you must remember to template the subscriber upon the message. Its two arguments are the topic it will be subscribing to and the callback function it will be using.

  19     nh.initNode();
  20     nh.subscribe(sub);

In the main function you need to initialize your ROS node handle, advertise any topics being published, and subscribe to any topics you wish to listen to.

  23         nh.spinOnce();
  24         wait_ms(1);

Finally, inside the main function there's a loop in which we call ros::spinOnce() where all of the ROS communication callbacks are handled. We don't need to do any additional processing in the loop(), since ros::spinOnce() will handle passing messages to the subscriber callback.

Compiling and uploading the Code

As seen on the previous tutorial, you must compile the source code by using the makefile in order to generate the .bin file that will be uploaded later to your MBED board. This is no different from uploading any other mbed binary.

Running the Code

Now, launch the roscore in a new terminal window:

roscore

Next, run the rosserial client application that forwards your MBED messages to the rest of ROS. Make sure to use the correct serial port:

rosrun rosserial_python serial_node.py /dev/ttyACM0

Finally, you can toggle the LED using rostopic:

rostopic pub toggle_led std_msgs/Empty --once

Further Reading

Please see rosserial/Overview for more information on publishers and subscribers. Also see limitations for information about more complex data types.

Wiki: rosserial_mbed/Tutorials/Blink (last edited 2015-11-20 21:09:03 by AlexisPojomovsky)