## 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_arduino/Tutorials/Hello World|Hello World Publisher]] ## descriptive title for the tutorial ## title = CMake with rosserial_arduino ## multi-line description to be displayed in search ## description = This tutorial shows how to use the CMake build system with rosserial_arduino. ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link=[[rosserial_arduino/Tutorials/Servo Controller|Servo Controller]] ## next.1.link= ## what level user is this tutorial for ## level= AdvancedCategory ## keywords = #################################### <> 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. <> {{{{{#!wiki buildsystem catkin <> <> 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 [[http://packages.ubuntu.com/trusty/arduino-core|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 <> 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. {{{ #!cplusplus block=helloworld #include #include #include ros::NodeHandle nh; std_msgs::String str_msg; ros::Publisher chatter("chatter", &str_msg); char hello[13] = "hello world!"; void setup() { nh.initNode(); nh.advertise(chatter); } void loop() { str_msg.data = hello; chatter.publish( &str_msg ); nh.spinOnce(); delay(1000); } }}} This program is almost exactly the same as the hello world covered in the [[rosserial_arduino/Tutorials/Hello World|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: {{{ #!cplusplus block=cmakelist cmake_minimum_required(VERSION 2.8.3) project(helloworld) ## Compile as C++11, supported in ROS Kinetic and newer add_compile_options(-std=c++11) find_package(catkin REQUIRED COMPONENTS rosserial_arduino rosserial_client ) catkin_package() rosserial_generate_ros_lib( PACKAGE rosserial_arduino SCRIPT make_libraries.py ) rosserial_configure_client( DIRECTORY firmware TOOLCHAIN_FILE ${ROSSERIAL_ARDUINO_TOOLCHAIN} ) rosserial_add_client_target(firmware hello ALL) 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: {{{ #!cplusplus block=cmakelist cmake_minimum_required(VERSION 2.8.3) ## Compile as C++11, supported in ROS Kinetic and newer add_compile_options(-std=c++11) include_directories(${ROS_LIB_DIR}) # Remove this if using an Arduino without native USB (eg, other than Leonardo) add_definitions(-DUSB_CON) generate_arduino_firmware(hello SRCS chatter.cpp ${ROS_LIB_DIR}/time.cpp BOARD leonardo PORT /dev/ttyACM0 ) }}} The `generate_arduino_firmware` function is provided by the [[https://github.com/queezythegreat/arduino-cmake|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 [[https://github.com/ros-drivers/rosserial/blob/indigo-devel/rosserial_client/cmake/rosserial_client-extras.cmake|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 buildsystem rosbuild <> {{{#!wiki caution '''Warning''' Although we wont be using the Arduino IDE directly, you must have it installed. This CMake build system uses the libraries and tools from the Arduino IDE installation. Follow the [[rosserial_arduino/Tutorials/Arduino IDE Setup | Arduino IDE Setup Tutorial]] before continuing. }}} == Making Your Project == Making your rosserial_arduino project is just like making any other ROS package. You create a package on your ROS_PACKAGE_PATH: {{{ roscreate-pkg helloworld rosserial_arduino std_msgs }}} As usual, use roscreate-pkg to create a package named helloworld which depends on rosserial_arduino and std_msgs. You must depend on rosserial_arduino and since we are going to use std_msgs/String messages, the package depends on std_msgs. == Source Code == Copy the the source code below and make a file called src/chatter.cpp in your helloworld package. {{{ #!cplusplus block=helloworld /* * rosserial Publisher Example * Prints "hello world!" */ #include #include #include ros::NodeHandle nh; std_msgs::String str_msg; ros::Publisher chatter("chatter", &str_msg); char hello[] = "hello world!"; void setup() { nh.initNode(); nh.advertise(chatter); } void loop() { str_msg.data = hello; chatter.publish( &str_msg ); nh.spinOnce(); delay(1000); } }}} This program is almost exactly the same as the hello world covered in the [[rosserial_arduino/Tutorials/Hello World|Publisher Tutorial]]. The only difference is <> 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 compare it to the CMakeList below. {{{ #!cplusplus block=cmakelist cmake_minimum_required(VERSION 2.4.6) include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) rosbuild_find_ros_package(rosserial_arduino) include(${rosserial_arduino_PACKAGE_PATH}/cmake_scripts/rosserial.cmake) #====================================================================# # Chatter # #====================================================================# set(FIRMWARE_NAME chatter) set(${FIRMWARE_NAME}_BOARD atmega328) # Arduino Target board set(${FIRMWARE_NAME}_SRCS src/chatter.cpp ) set(${FIRMWARE_NAME}_PORT /dev/ttyUSB0) # Serial upload port generate_ros_firmware(${FIRMWARE_NAME}) }}} With rosserial_arduino, we are cross compiling our source code for the AVR processor. As a result, we cannot use the standard ROS CMake file directly. We take ROS's standard first two lines, delete the rest, and then include the special rosserial_arduino cmake functions. <> The included rosserial.cmake will setup the compiler, create the generate_ros_firmware function, and attempt to find your Arduino installation. Next, the CMakeLists generates the ROS firmware. It does so using the generate generate_ros_firmware function. This function uses a declarative programming style. You describe your function in variables named ${FIRMWARE}_${SUFFIX}. The cpp files are stored in chatter_SRCS. The Arduino's serial port is stored in chatter_PORT. The arduino board type, atmega328, is stored chatter_BOARD. The board type can be any type defined in hardware/arduino/boards.txt of your Arduino installation. Typically this would be uno, mega2560, or atmega328. generate_ros_firmware access these variables and creates your targets. This setup is shown in <> Once you set up the variables describing the firmware, it generates the targets for compiling and programming that target. You can have as many targets as you would like in a project. The compile target is always the name of the firmware and the upload target is always the TARGET_NAME-upload. We will be able to compile chatter by entering {{{ make chatter }}} and program an atmega328 type Arduino like the Duemilanove using {{{ make chatter-upload }}} Now, copy the above CMakeLists into your package CMakeLists.txt file and then in the package directory run {{{ cmake . }}} If you have you Arduino installation in a non-standard location, you will receive the errors {{{ -- The arduino sdk path is ARDUINO_SDK_PATH-NOTFOUND -- REQUIRED_VARS (missing: ARDUINO_SDK_PATH ARDUINO_SDK_VERSION) }}} when you go to generate your Makefile. ARDUINO_SDK_PATH is the path to your Arduino IDE folder. To fix the problem, you can either set the ARDUINO_SDK_PATH before including rosserial.cmake {{{ set(ARDUINO_SDK_PATH ) include(${rosserial_arduino_PACKAGE_PATH}/cmake_scripts/rosserial.cmake) }}} or move the installation to a folder on your application path. == Testing == Connect your Arduino and make sure that the chatter_PORT corresponds to the serial port of your Arduino. Program your Arduino using {{{ make chatter-upload }}} Now you can use the Arduino! Start up the roscore ,the rosserial_python serial_node.py , and rostopic echo to see it in action. {{{ roscore }}} {{{ rosrun rosserial_python serial_node.py /dev/ttyUSB0 }}} {{{ rostopic echo chatter }}} == Additional Info == === generate_ros_firmware === The generate_ros_firmware macro takes care of all of the heavy lifting necessary for your rosserial_arduino project. Make sure to define any additional variables that you need. {{{ # - Generate firmware for rosserial_arduino Devices # generate_ros_firmware(TARGET_NAME) # TARGET_NAME - Name of target # Creates a Arduino firmware target. # # The target options can be configured by setting options of # the following format: # ${TARGET_NAME}${SUFFIX} # The following suffixes are availabe: # _SRCS # Sources # _HDRS # Headers # _LIBS # Libraries to linked in # _BOARD # Board name (such as uno, mega2560, atmega328 ...) # _PORT # Serial port, for upload and serial targets [OPTIONAL] # _AFLAGS # Override global Avrdude flags for target # _SERIAL # Serial command for serial target [OPTIONAL] # _NO_AUTOLIBS # Disables Arduino library detection # _NO_DEFAULT_COM # Disables a default communication implementation }}} === Using Arduino Libraries === generate_ros_firmware will automatically link to any Arduino library like Wire or Servo that is found in your Arduino IDE libraries folder. It does not know about libraries in your sketchbook. === Finding rosserial_arduino cmake === rosserial_arduino CMake implementation is found under rosserial_arduino/cmake_scripts. It is based on the [[https://github.com/queezythegreat/arduino-cmake | arduino-cmake project]]. You should never need to edit these files. You just need to include them into your CMakeLists.txt. }}}}} ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE