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.

Hello world publisher on TM4C123GXL

Description: Chatter publisher for the EK-TM4C123GXL board using UART over debug USB port.

Tutorial Level: INTERMEDIATE

Next Tutorial: Hello world publisher on TM4C1294XL

Introduction

This tutorial will take you step-by-step on how to set up your TivaC project on a catkin package using rosserial_client and rosserial_tivac.

All these tutorials are available on the repository.

Create your project

On your catkin workspace we'll create a new package.

catkin_create_pkg rosserial_tivac_tutorials rosserial_tivac rosserial_client std_msgs

Since you're completely familiar with ROS, you know this command will create a new package on your workspace with the name rosserial_tivac_tutorials. We're establishing a dependency on rosserial_tivac for the required libraries and rosserial_client for the client build macros. std_msgs is also required since we use these messages on our examples.

package.xml

Your package.xml should look like:

   1 <?xml version="1.0"?>
   2 <package>
   3   <name>rosserial_tivac_tutorials</name>
   4   <version>0.0.0</version>
   5   <description>The rosserial_tivac_tutorials package</description>
   6   <maintainer email="todo@todo.todo">todo</maintainer>
   7   <license>TODO</license>
   8 
   9   <buildtool_depend>catkin</buildtool_depend>
  10   
  11   <build_depend>rosserial_client</build_depend>
  12   <build_depend>rosserial_tivac</build_depend>  
  13   <build_depend>std_msgs</build_depend>
  14   
  15   <run_depend>rosserial_client</run_depend>
  16   <run_depend>rosserial_tivac</run_depend>
  17   <run_depend>std_msgs</run_depend>
  18 </package>

CMakeLists.txt

And your CMakeLists.txt file ought to contain the minimal dependency definitions by now.

   1 cmake_minimum_required(VERSION 2.8.3)
   2 project(rosserial_tivac_tutorials)
   3 
   4 find_package(catkin REQUIRED COMPONENTS
   5   message_generation
   6   rosserial_client
   7   rosserial_tivac
   8   std_msgs
   9 )

Write your code

Create a new directory 'chatter' and a new file inside called chatter.cpp with the following code:

   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 }
   9 // ROS includes
  10 #include <ros.h>
  11 #include <std_msgs/String.h>
  12 
  13 // ROS nodehandle
  14 ros::NodeHandle nh;
  15 
  16 std_msgs::String str_msg;
  17 ros::Publisher chatter("chatter", &str_msg);
  18 char hello[13] = "Hello world!";
  19 
  20 int main(void)
  21 {
  22   // TivaC application specific code
  23   MAP_FPUEnable();
  24   MAP_FPULazyStackingEnable();
  25   // TivaC system clock configuration. Set to 80MHz.
  26   MAP_SysCtlClockSet(SYSCTL_SYSDIV_2_5 | SYSCTL_USE_PLL | SYSCTL_XTAL_16MHZ | SYSCTL_OSC_MAIN);
  27 
  28   // ROS nodehandle initialization and topic registration
  29   nh.initNode();
  30   nh.advertise(chatter);
  31 
  32   while (1)
  33   {
  34     // Publish message to be transmitted.
  35     str_msg.data = hello;
  36     chatter.publish(&str_msg);
  37 
  38     // Handle all communications and callbacks.
  39     nh.spinOnce();
  40 
  41     // Delay for a bit.
  42     nh.getHardware()->delay(100);
  43   }
  44 }

Code explained

You should be familiar with developing C applications for these evaluation boards by now. Very little changes from your typical Tiva C application using Tivaware libraries.

   4 extern "C"
   5 {
   6   #include <driverlib/sysctl.h>
   7   #include <driverlib/gpio.h>
   8 }

But we are now compiling a C++ application with use Tivaware C libraries.

   9 // ROS includes
  10 #include <ros.h>
  11 #include <std_msgs/String.h>
  12 

Like a typical ROS application, we include the required headers.

  13 // ROS nodehandle
  14 ros::NodeHandle nh;
  15 
  16 std_msgs::String str_msg;
  17 ros::Publisher chatter("chatter", &str_msg);
  18 char hello[13] = "Hello world!";

We then declare:

  1. Our one and only node handle.
  2. The message to be published.
  3. The publisher with topic name chatter.

  4. The string we're publishing.

  23   MAP_FPUEnable();
  24   MAP_FPULazyStackingEnable();
  25   // TivaC system clock configuration. Set to 80MHz.
  26   MAP_SysCtlClockSet(SYSCTL_SYSDIV_2_5 | SYSCTL_USE_PLL | SYSCTL_XTAL_16MHZ | SYSCTL_OSC_MAIN);

These are MCU specific instructions to set up and configure the system.

  29   nh.initNode();
  30   nh.advertise(chatter);

Then the node is initialized, and any publisher, subscriber and service should be added to the callback queue.

  32   while (1)
  33   {
  34     // Publish message to be transmitted.
  35     str_msg.data = hello;
  36     chatter.publish(&str_msg);
  37 
  38     // Handle all communications and callbacks.
  39     nh.spinOnce();
  40 
  41     // Delay for a bit.
  42     nh.getHardware()->delay(100);
  43   }

Finally we trap the execution on a infinite loop, with the node publishing the string "Hello world!" when ros::spinOnce() is called, and all ROS communication callbacks are handled.

Revisiting CMakeLists.txt

Now it's time to include in our package's CMakeLists.txt file the rosserial_client macros to generate ROS libraries for our target and generate our catkin sub-project.

   1 cmake_minimum_required(VERSION 2.8.3)
   2 project(rosserial_tivac_tutorials)
   3 
   4 find_package(catkin REQUIRED COMPONENTS
   5   message_generation
   6   rosserial_client
   7   rosserial_tivac
   8   std_msgs
   9 )
  10 
  11 rosserial_generate_ros_lib(
  12   PACKAGE rosserial_tivac
  13   SCRIPT make_libraries_tiva
  14 )
  15 
  16 # Chatter tutorial
  17 rosserial_configure_client(
  18   DIRECTORY chatter
  19   TOOLCHAIN_FILE ${ROSSERIAL_TIVAC_TOOLCHAIN}
  20 )
  21 rosserial_add_client_target(chatter chatter.axf ALL)
  22 rosserial_add_client_target(chatter flash)
  23 rosserial_add_client_target(chatter size)
  24 rosserial_add_client_target(chatter dump)

  11 rosserial_generate_ros_lib(
  12   PACKAGE rosserial_tivac
  13   SCRIPT make_libraries_tiva

The rosserial_generate_ros_lib function creates a target called which will generate the rosserial client library, including messages headers. Called rosserial_tivac_tutorials_ros_lib.

  16 # Chatter tutorial
  17 rosserial_configure_client(
  18   DIRECTORY chatter
  19   TOOLCHAIN_FILE ${ROSSERIAL_TIVAC_TOOLCHAIN}

rosserial_configure_client will configure a new client subproject chatter with the specified toolchain file, provided by the package rosserial_tivac.

  20 )
  21 rosserial_add_client_target(chatter chatter.axf ALL)
  22 rosserial_add_client_target(chatter flash)
  23 rosserial_add_client_target(chatter size)

Each rosserial_add_client_target will create a specific target for the subproject chatter.

  • rosserial_tivac_tutorials_chatter_chatter.axf: Build the project object file.

  • rosserial_tivac_tutorials_chatter_flash: Creates the binary file and flashes it to the board.

  • rosserial_tivac_tutorials_chatter_size: Prints the binary file size.

  • rosserial_tivac_tutorials_chatter_dumps: Dumps the built object symbol table.

Subproject's CMakeLists.txt

Let's continue developing our application by adding the subproject's CMakeLists.txt.

Create a file chatter/CMakeLists.txt with the content:

   1 cmake_minimum_required(VERSION 2.8.3)
   2 project(chatter)
   3 
   4 # Include rosserial libraries for TivaC
   5 include_directories(${ROS_LIB_DIR})
   6 
   7 # Per project based definitions and options
   8 add_definitions(-DLED_HEARTBEAT)
   9 add_definitions(-DLED_COMM)
  10 add_definitions(-DROSSERIAL_BAUDRATE=57600)
  11 add_definitions(-DTX_BUFFER_SIZE=256)
  12 add_definitions(-DRX_BUFFER_SIZE=256)
  13 
  14 # Generate target for TivaC
  15 generate_tivac_firmware(
  16   SRCS chatter.cpp
  17   BOARD tm4c123gxl
  18 )

CMakeLists.txt explained

   2 project(chatter)

Defines the target's name.

   5 include_directories(${ROS_LIB_DIR})

Includes the generated ros_lib libraries, which are specific for TivaC.

   8 add_definitions(-DLED_HEARTBEAT)
   9 add_definitions(-DLED_COMM)

Optional defines. If you wish to claim the use of the heartbeat LED and communications LED, you can delete these defines.

  10 add_definitions(-DROSSERIAL_BAUDRATE=57600)

Baudrate definition when using communication through the UART over debug USB port. If undefined, 57600 is assumed.

  11 add_definitions(-DTX_BUFFER_SIZE=256)
  12 add_definitions(-DRX_BUFFER_SIZE=256)

Size of UART buffers.

  15 generate_tivac_firmware(
  16   SRCS chatter.cpp
  17   BOARD tm4c123gxl
  18 )

The generate_tivac_firmware function provided by rosserial_tivac package sets all the variables, libraries and build rules for our application.

You need to specify:

  • SRCS: The source files to be compiled on your application.

  • BOARD: tm4c123gxl or tm4c1294xl

Build & upload

Using catkin_make

Now we can build our application when we run catkin.

catkin_make rosserial_tivac_tutorials_chatter_chatter.axf

And also use the catkin target to flash the application.

catkin_make rosserial_tivac_tutorials_chatter_flash

Using catkin tools

Now we can build our application when we run catkin.

catkin build rosserial_tivac_tutorials

And also use the catkin target to flash the application.

catkin build --no-deps rosserial_tivac_tutorials --make-args rosserial_tivac_tutorials_chatter_flash

Test

Let's listen to our newly created topic from TivaC.

Run roscore.

roscore

Run serial_node.py from rosserial_python.

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

Watch the messages from the topic.

rostopic echo /chatter

Addendum

If there's a breakage you don't understand, a good first step is to clean your workspace (delete build and devel trees), and then re-run in verbose mode:

catkin_make VERBOSE=1

Wiki: rosserial_tivac/Tutorials/Hello World (last edited 2017-04-11 08:44:00 by RoboSavvy)