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 service

Description: EK-TM4C123GXL board over CDC USB device provides a custom message service for changing LED color.

Tutorial Level: INTERMEDIATE

Introduction

The last tutorial of this series will show you how to create a custom service message and service server over rosserial.

The code relative to this tutorial can be found in the directory rgb_srv.

ColoRGBA service message

Let's analyze the message file found in srv/ColorRGBA.srv.

std_msgs/ColorRGBA color
---
bool result

As a request we have a color field, of type std_msgs/ColorRGBA and as response we get a bool result.

package.xml & CMakeLists.txt

On the package's package.xml and top level CMakeLists.txt we need dependencies and rules to generate the new service message.

package.xml

Dependencies on package.xml:

  <build_depend>message_generation</build_depend>  
  <run_depend>message_runtime</run_depend>

CMakeLists.xml

(...)
find_package(catkin REQUIRED COMPONENTS
  message_generation
  rosserial_client
  rosserial_tivac
  std_msgs
)
add_service_files(
  FILES ColorRGBA.srv
)
generate_messages(
  DEPENDENCIES std_msgs
)
catkin_package(
  CATKIN_DEPENDS message_runtime std_msgs
)
(...)

The required dependencies and instructions to generate the service message files.

Code

Similarly to the subscriber tutorial, we need to register a service server and assign to it a callback to handle the incoming requests and produce responses.

   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 // Our custom service message
  13 #include "rosserial_tivac_tutorials/ColorRGBA.h"
  14 
  15 uint32_t current_color[3] = {0xFFFE, 0xFFFE, 0xFFFE};
  16 float current_intensity = 1.f;
  17 void color_cb(const rosserial_tivac_tutorials::ColorRGBARequest& req,
  18                     rosserial_tivac_tutorials::ColorRGBAResponse& resp)
  19 {
  20   current_color[0] = req.color.r * 0xFFFE;
  21   current_color[1] = req.color.g * 0xFFFE;
  22   current_color[2] = req.color.b * 0xFFFE;
  23   current_intensity = req.color.a;
  24   RGBSet(current_color, current_intensity);
  25 
  26   resp.result = true;
  27 }
  28 
  29 // ROS nodehandle and subscriber
  30 ros::NodeHandle nh;
  31 ros::ServiceServer<rosserial_tivac_tutorials::ColorRGBARequest,
  32                    rosserial_tivac_tutorials::ColorRGBAResponse> rgb_service("led", &color_cb);
  33 
  34 int main(void)
  35 {
  36   // TivaC application specific code
  37   MAP_FPUEnable();
  38   MAP_FPULazyStackingEnable();
  39   // TivaC system clock configuration. Set to 80MHz.
  40   MAP_SysCtlClockSet(SYSCTL_SYSDIV_2_5 | SYSCTL_USE_PLL | SYSCTL_XTAL_16MHZ | SYSCTL_OSC_MAIN);
  41 
  42   // Setup RGB driver
  43   RGBInit(0);
  44   RGBSet(current_color, current_intensity);
  45 
  46   // ROS nodehandle initialization and topic registration
  47   nh.initNode();
  48   nh.advertiseService<rosserial_tivac_tutorials::ColorRGBARequest,
  49                       rosserial_tivac_tutorials::ColorRGBAResponse>(rgb_service);
  50   bool nh_prev_state = false;
  51 
  52   while (1)
  53   {
  54     // If subscribed, enable RGB driver
  55     if (nh.connected() && !nh_prev_state)
  56     {
  57       RGBEnable();
  58       nh_prev_state = true;
  59     }
  60     if (!nh.connected() && nh_prev_state)
  61     {
  62       RGBDisable();
  63       nh_prev_state = false;
  64     }
  65 
  66     // Handle all communications and callbacks.
  67     nh.spinOnce();
  68 
  69     // Delay for a bit.
  70     nh.getHardware()->delay(1000);
  71   }
  72 }

The relevant parts for this tutorial are herein explained.

  29 // ROS nodehandle and subscriber
  30 ros::NodeHandle nh;
  31 ros::ServiceServer<rosserial_tivac_tutorials::ColorRGBARequest,

Node handle instantiation and service server definition. The service is available over the service topic /led, of type rosserial_tivac_tutorials::ColorRGBA, handled by the color_cb callback.

  47   nh.initNode();
  48   nh.advertiseService<rosserial_tivac_tutorials::ColorRGBARequest,
  49                       rosserial_tivac_tutorials::ColorRGBAResponse>(rgb_service);

After initializing the node, register the service server to the callback queue.

  17 void color_cb(const rosserial_tivac_tutorials::ColorRGBARequest& req,
  18                     rosserial_tivac_tutorials::ColorRGBAResponse& resp)
  19 {
  20   current_color[0] = req.color.r * 0xFFFE;
  21   current_color[1] = req.color.g * 0xFFFE;
  22   current_color[2] = req.color.b * 0xFFFE;
  23   current_intensity = req.color.a;
  24   RGBSet(current_color, current_intensity);
  25 
  26   resp.result = true;
  27 }

The service callback receives the request, converting the values from the message to the LED driver. It then always returns a true result.

Build, flash and test

catkin_make
catkin_make rosserial_tivac_tutorials_rgb_led_flash

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, call the service with a new color.

rosservice call /led std_msgs/ColorRGBA "r: 0.0
g: 0.0
b: 1.0
a: 1.0"

It should change to the brightest blue.

Wiki: rosserial_tivac/Tutorials/RGB srv (last edited 2015-12-03 09:37:19 by RoboSavvy)