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

Adding Support for New Hardware

Description: This tutorial contains details about the custom code required to get rosserial_client working on your hardware.

Keywords: rosserial, rosserial_client, embedded, microcontroller

Tutorial Level: INTERMEDIATE

Contents

  1. Hardware

rosserial_client contains the generic client-side rosserial implementation. It is designed for microcontrollers and it can run on any processor for which you have an ANSI C++ compiler and a serial port connection to a computer running ROS.

In addition to the components of rosserial_client, you must provide some code that connects rosserial to your hardware platform. This tutorial shows how to create that code. An existing example of integration with a platform is the rosserial_arduino package, which implements a connection from rosserial to the Arduino environment.

Hardware

The first step to using a new piece of hardware is defining the interface between the library and the hardware. The library is templated on a hardware object that must provide the following interface:

   1 class Hardware
   2 {
   3 
   4   Hardware();
   5 
   6   // any initialization code necessary to use the serial port
   7   void init(); 
   8 
   9   // read a byte from the serial port. -1 = failure
  10   int read()
  11 
  12   // write data to the connection to ROS
  13   void write(uint8_t* data, int length);
  14 
  15   // returns milliseconds since start of program
  16   unsigned long time();
  17 
  18 };

To use the Hardware object, you pass it as a template parameter to your node handle.

   1 #include "ros/node_handle.h"
   2 ros::NodeHandle_<Hardware> nh;

For most uses of the library, it is suggested that you simplify the invocation of the NodeHandle_ by creating ros.h header with a typedef of NodeHandle_ with your hardware. This simplifies the use of the library and makes the library look the same for all hardware platforms.

   1 /*
   2  * ros.h
   3  */
   4 
   5 #ifndef _ROS_H_
   6 #define _ROS_H_
   7 
   8 #include "ros/node_handle.h"
   9 #include "HardwareImpl.h"
  10 
  11 namespace ros
  12 {
  13   typedef ros::NodeHandle_<HardwareImpl> NodeHandle;
  14 }
  15 
  16 #endif
  17 

Wiki: rosserial_client/Tutorials/Adding Support for New Hardware (last edited 2011-10-24 22:56:15 by MichaelFerguson)