Revision 23 as of 2016-04-19 20:47:08

Clear message

(!) 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.

rosserial MBED Setup

Description: This tutorial shows how to configure a basic development environment to use rosserial_mbed with an enabled MBED board

Keywords: MBED serial rosserial

Tutorial Level: BEGINNER

Next Tutorial: Hello World (example publisher)

Introduction

MBED is a platform and operating system for devices based on 32-bit ARM Cortex-M microcontrollers. It is a great tool for quickly and easily programming hardware. Using the rosserial_mbed package, you can use ROS directly with your MBED enabled board. rosserial provides a ROS communication protocol that works over your MBED's UART. It allows your MBED to be a full fledged ROS node which can directly publish and subscribe to ROS messages, publish TF transforms, and get the ROS system time.

In order to use the rosserial libraries in your own code, you must first put

  • #include <ros.h>

prior to including any other header files, e.g.

  • #include <std_msgs/String.h>

otherwise the compiler will not be able to locate them.

Using the official online compiler

  Show EOL distros: 

rosserial_mbed is not supported for this distro

You just need to import the rosserial_mbed library to your online compiler account using the following link:

  • $ https://developer.mbed.org/users/garyservin/code/ros_lib_$ROS_DISTRO/

Using the offline compiler

Install gcc4mbed

You need to install gcc4mbed by following the "Quick start" instructions on the Readme.

Cloning the rosserial repo

Clone the rosserial repo on your ros workspace src directory, e.g.: ~/myWorkspace/src/

Generating the ros_lib library

Go to the root of your workspace and execute:

  • $ catkin_make

And then:

  • source devel/setup.bash

Now you are able to generate the ros_lib library, needed to compile a every project using rosserial_mbed:

  • rosrun rosserial_mbed make_libraries.py <ros-lib-dir>

where the last parameter is the output path for the generated 'ros_lib' directory

Exporting path variables

Now, move to your mbed project's directory and set the env var for the gcc4mbed and the ros-lib paths: Example:

  • $ export GCC4MBED_DIR=~/gcc4mbed
    $ export ROS_LIB_DIR=~/ros-lib

You can export this two variables to your .bashr or modify your MBED project's makefile with the desired path for both variables (we are going to cover that later on this document).

Compiling and deploying an mbed project

Once you've finished all the above tasks you must be able to compile and deploy your mbed project into the board:

We are going to base this part of the tutorial on the 'Blink' project that came with the rosserial_mbed repo you've downloaded earlier, you can found it on the following relative path:

  • rosserial/rosserial_mbed/src/examples/Blink/

There you must found a typical source for an mbed project: a c++ source file (Blink.cpp) and a makefile file, that you can use as a base for next projects modifying the things you need.

Then, from your makefile path directory do:

  • $ make

This will generate a compiled binary file, and now you're able to copy it into your mbed device for testing.