## For instruction on writing tutorials
## http://www.ros.org/wiki/WritingTutorials
####################################
##FILL ME IN
####################################
## for a custom note with links:
## note =
## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links
## note.0=[[rosserial_tivac/Tutorials/TivaWare Setup|Tivaware and toolchain setup]]
## descriptive title for the tutorial
## title = Hello world publisher on TM4C123GXL
## multi-line description to be displayed in search
## description = Chatter publisher for the EK-TM4C123GXL board using UART over debug USB port.
## the next tutorial description (optional)
## next =
## links to next tutorial (optional)
## next.0.link= [[rosserial_tivac/Tutorials/Hello World129|Hello world publisher on TM4C1294XL]]
## next.1.link=
## what level user is this tutorial for
## level= IntermediateCategory
## keywords =
####################################
<<IncludeCSTemplate(TutorialCSHeaderTemplate)>>

<<TableOfContents(4)>>

##startpage
== 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 [[https://github.com/robosavvy/rosserial_tivac_tutorials|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:
{{{#!xml
<?xml version="1.0"?>
<package>
  <name>rosserial_tivac_tutorials</name>
  <version>0.0.0</version>
  <description>The rosserial_tivac_tutorials package</description>
  <maintainer email="todo@todo.todo">todo</maintainer>
  <license>TODO</license>

  <buildtool_depend>catkin</buildtool_depend>
  
  <build_depend>rosserial_client</build_depend>
  <build_depend>rosserial_tivac</build_depend>  
  <build_depend>std_msgs</build_depend>
  
  <run_depend>rosserial_client</run_depend>
  <run_depend>rosserial_tivac</run_depend>
  <run_depend>std_msgs</run_depend>
</package>
}}}

'''CMakeLists.txt'''

And your `CMakeLists.txt` file ought to contain the minimal dependency definitions by now.
{{{#!cplusplus
cmake_minimum_required(VERSION 2.8.3)
project(rosserial_tivac_tutorials)

find_package(catkin REQUIRED COMPONENTS
  message_generation
  rosserial_client
  rosserial_tivac
  std_msgs
)
}}}

== Write your code ==
Create a new directory 'chatter' and a new file inside called `chatter.cpp` with the following code:
{{{
#!cplusplus block=srccode
#include <stdbool.h>
#include <stdint.h>
// TivaC specific includes
extern "C"
{
  #include <driverlib/sysctl.h>
  #include <driverlib/gpio.h>
}
// ROS includes
#include <ros.h>
#include <std_msgs/String.h>

// ROS nodehandle
ros::NodeHandle nh;

std_msgs::String str_msg;
ros::Publisher chatter("chatter", &str_msg);
char hello[13] = "Hello world!";

int main(void)
{
  // TivaC application specific code
  MAP_FPUEnable();
  MAP_FPULazyStackingEnable();
  // TivaC system clock configuration. Set to 80MHz.
  MAP_SysCtlClockSet(SYSCTL_SYSDIV_2_5 | SYSCTL_USE_PLL | SYSCTL_XTAL_16MHZ | SYSCTL_OSC_MAIN);

  // ROS nodehandle initialization and topic registration
  nh.initNode();
  nh.advertise(chatter);

  while (1)
  {
    // Publish message to be transmitted.
    str_msg.data = hello;
    chatter.publish(&str_msg);

    // Handle all communications and callbacks.
    nh.spinOnce();

    // Delay for a bit.
    nh.getHardware()->delay(100);
  }
}
}}}

=== 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.
<<CodeRef(srccode,4,8)>>
But we are now compiling a C++ application with use Tivaware C libraries.
<<CodeRef(srccode,9,11)>>
Like a typical ROS application, we include the required headers.
<<CodeRef(srccode,13,18)>>
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.
<<CodeRef(srccode,23,26)>>
These are MCU specific instructions to set up and configure the system.
<<CodeRef(srccode,29,30)>>
Then the node is initialized, and any publisher, subscriber and service should be added to the callback queue.
<<CodeRef(srccode,32,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.
{{{
#!cplusplus block=newcmake
cmake_minimum_required(VERSION 2.8.3)
project(rosserial_tivac_tutorials)

find_package(catkin REQUIRED COMPONENTS
  message_generation
  rosserial_client
  rosserial_tivac
  std_msgs
)

rosserial_generate_ros_lib(
  PACKAGE rosserial_tivac
  SCRIPT make_libraries_tiva
)

# Chatter tutorial
rosserial_configure_client(
  DIRECTORY chatter
  TOOLCHAIN_FILE ${ROSSERIAL_TIVAC_TOOLCHAIN}
)
rosserial_add_client_target(chatter chatter.axf ALL)
rosserial_add_client_target(chatter flash)
rosserial_add_client_target(chatter size)
rosserial_add_client_target(chatter dump)
}}}

<<CodeRef(newcmake,11,13)>>
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`.
<<CodeRef(newcmake,16,19)>>
`rosserial_configure_client` will configure a new client subproject `chatter` with the specified toolchain file, provided by the package `rosserial_tivac`.
<<CodeRef(newcmake,20,23)>>
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:
{{{
#!cplusplus block=subcmake
cmake_minimum_required(VERSION 2.8.3)
project(chatter)

# Include rosserial libraries for TivaC
include_directories(${ROS_LIB_DIR})

# Per project based definitions and options
add_definitions(-DLED_HEARTBEAT)
add_definitions(-DLED_COMM)
add_definitions(-DROSSERIAL_BAUDRATE=57600)
add_definitions(-DTX_BUFFER_SIZE=256)
add_definitions(-DRX_BUFFER_SIZE=256)

# Generate target for TivaC
generate_tivac_firmware(
  SRCS chatter.cpp
  BOARD tm4c123gxl
)
}}}

=== CMakeLists.txt explained ===

<<CodeRef(subcmake,2,2)>>
Defines the target's name.
<<CodeRef(subcmake,5,5)>>
Includes the generated `ros_lib` libraries, which are specific for TivaC.
<<CodeRef(subcmake,8,9)>>
Optional defines. If you wish to claim the use of the heartbeat LED and communications LED, you can delete these defines.
<<CodeRef(subcmake,10,10)>>
Baudrate definition when using communication through the UART over debug USB port. If undefined, 57600 is assumed.
<<CodeRef(subcmake,11,12)>>
Size of UART buffers.
<<CodeRef(subcmake,15,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
}}}



##endpage
## AUTOGENERATED DO NOT DELETE
## TutorialCategory
## FILL IN THE STACK TUTORIAL CATEGORY HERE