Note: This tutorial assumes that you have completed the previous tutorials: Hello World Publisher.
(!) 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.

CMake with rosserial_arduino

Description: This tutorial shows how to use the CMake build system with rosserial_arduino.

Tutorial Level: ADVANCED

Next Tutorial: Servo Controller

When you are doing large software projects, the Arduino IDE quickly becomes unwieldy. You often want to be able to compile your project from the command line or use a different IDE like Eclipse where you can use autocompletion. Finally, by using rosserial_client CMake infrastructure, you can build and distribute firmwares using the ROS buildfarm.

For this tutorial, we are going to create a simple hello world firmware.

New in Indigo You can now again build rosserial firmwares and other clients inside your regular ROS packages. This functionality is available from Indigo onward. The installation of the rosserial_arduino package now also installs arduino-core, so there's nothing additional needed to make this work.

Making Your Project

Starting your rosserial_arduino project is just like creating any other package. In your catkin workspace's src folder:

catkin_create_pkg helloworld rosserial_arduino rosserial_client std_msgs

As usual, use catkin_create_pkg to create a package named helloworld. You must depend on rosserial_arduino for the Arduino toolchain, and on rosserial_client for client library generation macros. And finally, since we are going to use std_msgs/String messages, you must depend on std_msgs.

Source Code

Copy the the source code below and make a file called firmware/chatter.cpp in your helloworld package.

Toggle line numbers
   1 #include <ros.h>
   2 #include <std_msgs/String.h>
   3 
   4 #include <Arduino.h>
   5 
   6 ros::NodeHandle nh;
   7 
   8 std_msgs::String str_msg;
   9 ros::Publisher chatter("chatter", &str_msg);
  10 
  11 char hello[13] = "hello world!";
  12 
  13 void setup()
  14 {
  15   nh.initNode();
  16   nh.advertise(chatter);
  17 }
  18 
  19 void loop()
  20 {
  21   str_msg.data = hello;
  22   chatter.publish( &str_msg );
  23   nh.spinOnce();
  24   delay(1000);
  25 }

This program is almost exactly the same as the hello world covered in the Publisher Tutorial.

When you are compiling a cpp file outside of the Arduino IDE, you need to explicitly include a header file which contains all of the Arduino functions (digitalRead, analogRead, delay, etc.).

If you are unsure if you are going to be using a file with the Arduino IDE versus CMake, just add this line at the top of your file. It never hurts and it makes sure your file is always compatible with non-Arduino IDE build systems.

CMakeLists.txt

Open the CMakeLists.txt in your package directory and replace the contents with the below:

Toggle line numbers
   1 cmake_minimum_required(VERSION 2.8.3)
   2 project(helloworld)
   3 
   4 ## Compile as C++11, supported in ROS Kinetic and newer
   5 add_compile_options(-std=c++11)
   6 
   7 find_package(catkin REQUIRED COMPONENTS
   8   rosserial_arduino
   9   rosserial_client
  10 )
  11 
  12 catkin_package()
  13 
  14 rosserial_generate_ros_lib(
  15   PACKAGE rosserial_arduino
  16   SCRIPT make_libraries.py
  17 )
  18 
  19 rosserial_configure_client(
  20   DIRECTORY firmware
  21   TOOLCHAIN_FILE ${ROSSERIAL_ARDUINO_TOOLCHAIN}
  22 )
  23 
  24 rosserial_add_client_target(firmware hello ALL)
  25 rosserial_add_client_target(firmware hello-upload)

With rosserial_client's CMake scripts, we are not actually building the firmware directly, but configuring a separate CMake project, and passing through targets from the catkin package to the sub-project.

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

The rosserial_configure_client function creates a target which will configure the CMake project in the specified subdirectory, optionally using the supplied toolchain. In this case, we use the Arduino toolchain, helpfully provided by rosserial_arduino.

Finally, the rosserial_add_client_target calls each pass through targets, so that when you run make the helloworld_firmware_hello catkin target, it will configure the firmware directory and build the hello target therein.

Now, we actually need a second CMakeLists.txt, and that's the one for the firmware subproject. Create the file firmware/CMakeLists.txt in your package, with the following contents:

Toggle line numbers
   1 cmake_minimum_required(VERSION 2.8.3)
   2 
   3 ## Compile as C++11, supported in ROS Kinetic and newer
   4 add_compile_options(-std=c++11)
   5 
   6 include_directories(${ROS_LIB_DIR})
   7 
   8 # Remove this if using an Arduino without native USB (eg, other than Leonardo)
   9 add_definitions(-DUSB_CON)
  10 
  11 generate_arduino_firmware(hello
  12   SRCS chatter.cpp ${ROS_LIB_DIR}/time.cpp
  13   BOARD leonardo
  14   PORT /dev/ttyACM0
  15 )

The generate_arduino_firmware function is provided by the arduino-cmake toolchain, which this uses. It handles the intricacies of locating Arduino, linking any libraries you use, and so on.

You should be done!

Build & Test

Using catkin_make

The firmware should build by default when you run catkin_make, but you can also specify it explicitly:

catkin_make helloworld_firmware_hello

Now connect an Arduino Leonardo, confirm that it comes up as /dev/ttyACM0 (or change the firmware's CMakeLists.txt accordingly), and program it:

catkin_make helloworld_firmware_hello-upload

You might need to press the reset button to reboot the Leonardo to allow code to be uploaded, and the port might change after reset.

Using catkin tools

The firmware should build by default when you run catkin build, but you can also specify it explicitly:

catkin build helloworld

Now connect an Arduino Leonardo, confirm that it comes up as /dev/ttyACM0 (or change the firmware's CMakeLists.txt accordingly), and program it:

catkin build --no-deps  helloworld --make-args helloworld_firmware_hello-upload

You might need to press the reset button to reboot the Leonardo to allow code to be uploaded, and the port might change after reset.

Testing

Now you can use the Arduino! Launch the following in separate terminals to see it in action:

roscore

rosrun rosserial_python serial_node.py /dev/ttyACM0

rostopic echo chatter

Additional Info

The CMake script which supplies these functions lives here, if you want to inspect it to understand better what is going on.

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_arduino/Tutorials/CMake (last edited 2023-05-12 22:47:09 by ChristianBauer)