Note: This tutorial assumes that you have completed the previous tutorials: Tivaware and toolchain setup.
(!) 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.

RGB subscriber

Description: EK-TM4C123GXL board over CDC USB device subscribes to ColorRGB msg type and change LED color.

Tutorial Level: INTERMEDIATE

Next Tutorial: RGB service

Introduction

Having created several publishers on the previous tutorials, its about time we implement a subscriber.

Our application will subscribe to the topic /led and change the color accordingly to the data on the ColorRGBA message.

Source code explained

   1 #include <stdbool.h>
   2 #include <stdint.h>
   3 // TivaC specific includes
   4 extern "C"
   5 {
   6   #include <driverlib/sysctl.h>
   7   #include <driverlib/gpio.h>
   8   #include <rgb.h>
   9 }
  10 // ROS includes
  11 #include <ros.h>
  12 #include <std_msgs/ColorRGBA.h>
  13 
  14 uint32_t current_color[3] = {0xFFFE, 0xFFFE, 0xFFFE};
  15 float current_intensity = 1.f;
  16 void color_cb(const std_msgs::ColorRGBA& msg)
  17 {
  18   current_color[0] = msg.r * 0xFFFE;
  19   current_color[1] = msg.g * 0xFFFE;
  20   current_color[2] = msg.b * 0xFFFE;
  21   current_intensity = msg.a;
  22   RGBSet(current_color, current_intensity);
  23 }
  24 
  25 // ROS nodehandle and subscriber
  26 ros::NodeHandle nh;
  27 ros::Subscriber<std_msgs::ColorRGBA> rgb_sub("led", &color_cb);
  28 
  29 int main(void)
  30 {
  31   // TivaC application specific code
  32   MAP_FPUEnable();
  33   MAP_FPULazyStackingEnable();
  34   // TivaC system clock configuration. Set to 80MHz.
  35   MAP_SysCtlClockSet(SYSCTL_SYSDIV_2_5 | SYSCTL_USE_PLL | SYSCTL_XTAL_16MHZ | SYSCTL_OSC_MAIN);
  36 
  37   // Setup RGB driver
  38   RGBInit(0);
  39   RGBSet(current_color, current_intensity);
  40 
  41   // ROS nodehandle initialization and topic registration
  42   nh.initNode();
  43   nh.subscribe(rgb_sub);
  44   bool nh_prev_state = false;
  45 
  46   while (1)
  47   {
  48     // If subscribed, enable RGB driver
  49     if (nh.connected() && !nh_prev_state)
  50     {
  51       RGBEnable();
  52       nh_prev_state = true;
  53     }
  54     if (!nh.connected() && nh_prev_state)
  55     {
  56       RGBDisable();
  57       nh_prev_state = false;
  58     }
  59 
  60     // Handle all communications and callbacks.
  61     nh.spinOnce();
  62 
  63     // Delay for a bit.
  64     nh.getHardware()->delay(1000);
  65   }
  66 }

Again, use the project rgb_led from `rosserial_tivac_tutorials package as reference to follow the tutorial.

  42   nh.initNode();
  43   nh.subscribe(rgb_sub);

As always, the node is initiated and all the publishers and subscribers must be registered.

  25 // ROS nodehandle and subscriber
  26 ros::NodeHandle nh;
  27 ros::Subscriber<std_msgs::ColorRGBA> rgb_sub("led", &color_cb);

Here we instantiate a new subscriber on the topic /led of message type ColorRGBA, handled by color_cb function.

  14 uint32_t current_color[3] = {0xFFFE, 0xFFFE, 0xFFFE};
  15 float current_intensity = 1.f;
  16 void color_cb(const std_msgs::ColorRGBA& msg)
  17 {
  18   current_color[0] = msg.r * 0xFFFE;
  19   current_color[1] = msg.g * 0xFFFE;
  20   current_color[2] = msg.b * 0xFFFE;
  21   current_intensity = msg.a;
  22   RGBSet(current_color, current_intensity);
  23 }

The callback function will be executed for each new received message. It takes color and intensity values in the range [0 1] and applies the color to the board LED using the board specific library.

  46   while (1)
  47   {
  48     // If subscribed, enable RGB driver
  49     if (nh.connected() && !nh_prev_state)
  50     {
  51       RGBEnable();
  52       nh_prev_state = true;
  53     }
  54     if (!nh.connected() && nh_prev_state)
  55     {
  56       RGBDisable();
  57       nh_prev_state = false;
  58     }
  59 
  60     // Handle all communications and callbacks.
  61     nh.spinOnce();
  62 
  63     // Delay for a bit.
  64     nh.getHardware()->delay(1000);
  65   }

Then execution is trapped inside a loop, continuously waiting for new messages on the topic.

However the LED will only be enabled when a valid node connection is present.

Build and flash

By now you're an expert at this. Build and flash the binary file into your board.

catkin_make
catkin_make rosserial_tivac_tutorials_rgb_led_flash

Test it!

Don't forget to connect the device USB port to your computer!

Run roscore and run serial_node.py from rosserial_python on the correct port /dev/ttyACM#.

roscore

When you successfully connect using `serial_node the LED will light up.

rosrun rosserial_python serial_node.py _port:=/dev/ttyACM0

On a new terminal window, publish a new color.

rostopic pub /led std_msgs/ColorRGBA "r: 0.0
g: 1.0
b: 0.0
a: 1.0"

It should change to the brightest green.

Wiki: rosserial_tivac/Tutorials/RGB led (last edited 2015-12-03 09:36:33 by RoboSavvy)