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

IR Ranger Tutorial

Description: Using an IR Ranger with rosserial and an MBED

Tutorial Level: BEGINNER

Next Tutorial: SRF08 Ultrasonic Range Finder

  Show EOL distros: 

rosserial allows you to easily integrate mbed-based hardware with ROS. This tutorial will explain how to use a sharp IR ranger with an mbed.

You will need an MBED board. Additionally, you will need a Sharp IR Ranger, Model# GP2D120XJ00F, and a way to connect your IR Ranger to your MBED such as a breadboard or protoboard.

Hardware Setup

To get started, connect your ranger to one of your MBED's "analog" (pwm) pins, the VCC and GND to its respective pins. In the code you can appreciate the different PIN numbers for three different MBED boards.

Software Setup

The Code

Next, open up your favorite plain text editor and copy in the code below.

   1 /*
   2  * rosserial IR Ranger Example
   3  *
   4  * This example is calibrated for the Sharp GP2D120XJ00F.
   5  */
   6 
   7 #include <ros.h>
   8 #include <ros/time.h>
   9 #include <sensor_msgs/Range.h>
  10 
  11 ros::NodeHandle  nh;
  12 
  13 
  14 sensor_msgs::Range range_msg;
  15 ros::Publisher pub_range( "range_data", &range_msg);
  16 
  17 #if defined(TARGET_LPC1768)
  18 PinName analog_pin = p20;
  19 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
  20 PinName analog_pin = A0;
  21 #else
  22 #error "You need to specify a pin for the mic"
  23 #endif
  24 
  25 unsigned long range_timer;
  26 
  27 /*
  28  * getRange() - samples the analog input from the ranger
  29  * and converts it into meters.
  30  */
  31 float getRange(PinName pin_num) {
  32     int sample;
  33     // Get data
  34     sample = AnalogIn(pin_num).read_u16()/4;
  35     // if the ADC reading is too low,
  36     //   then we are really far away from anything
  37     if(sample < 10)
  38         return 254;     // max range
  39     // Magic numbers to get cm
  40     sample= 1309/(sample-3);
  41     return (sample - 1)/100; //convert to meters
  42 }
  43 
  44 char frameid[] = "/ir_ranger";
  45 
  46 Timer t;
  47 int main() {
  48     t.start();
  49     nh.initNode();
  50     nh.advertise(pub_range);
  51 
  52     range_msg.radiation_type = sensor_msgs::Range::INFRARED;
  53     range_msg.header.frame_id =  frameid;
  54     range_msg.field_of_view = 0.01;
  55     range_msg.min_range = 0.03;
  56     range_msg.max_range = 0.4;
  57 
  58     while (1) {
  59         // publish the range value every 50 milliseconds
  60         //   since it takes that long for the sensor to stabilize
  61         if ( (t.read_ms()-range_timer) > 50) {
  62             range_msg.range = getRange(analog_pin);
  63             range_msg.header.stamp = nh.now();
  64             pub_range.publish(&range_msg);
  65             range_timer =  t.read_ms() + 50;
  66         }
  67         nh.spinOnce();
  68     }
  69 }

The Code Explained

Now let's break down the code.

   7 #include <ros.h>
   8 #include <ros/time.h>
   9 #include <sensor_msgs/Range.h>
  10 
  11 ros::NodeHandle  nh;
  12 
  13 
  14 sensor_msgs::Range range_msg;
  15 ros::Publisher pub_range( "range_data", &range_msg);

As always, the code begins by including the appropriate message headers and ros.h from the rosserial library and then instantiating the publisher.

  17 #if defined(TARGET_LPC1768)
  18 PinName analog_pin = p20;
  19 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
  20 PinName analog_pin = A0;
  21 #else
  22 #error "You need to specify a pin for the mic"
  23 #endif
  24 

There are some preprocessor directives for selecting the correct analog pin on three different MBED boards.

  31 float getRange(PinName pin_num) {
  32     int sample;
  33     // Get data
  34     sample = AnalogIn(pin_num).read_u16()/4;
  35     // if the ADC reading is too low,
  36     //   then we are really far away from anything
  37     if(sample < 10)
  38         return 254;     // max range
  39     // Magic numbers to get cm
  40     sample= 1309/(sample-3);
  41     return (sample - 1)/100; //convert to meters
  42 }

Here we define a function that converts the analog signal to a corresponding distance reading in meters.

  44 char frameid[] = "/ir_ranger";

Here, the code creates a global variable for the sensors frame id string. It is important to make this string global so it will be alive for as long as the message will be in use.

  48     t.start();
  49     nh.initNode();
  50     nh.advertise(pub_range);
  51 
  52     range_msg.radiation_type = sensor_msgs::Range::INFRARED;
  53     range_msg.header.frame_id =  frameid;
  54     range_msg.field_of_view = 0.01;
  55     range_msg.min_range = 0.03;
  56     range_msg.max_range = 0.4;

In the mbed's main function, the code initializes the node handle and then fills in the descriptor fields for range_msg.

  61         if ( (t.read_ms()-range_timer) > 50) {
  62             range_msg.range = getRange(analog_pin);
  63             range_msg.header.stamp = nh.now();
  64             pub_range.publish(&range_msg);
  65             range_timer =  t.read_ms() + 50;
  66         }
  67         nh.spinOnce();

Finally, in the main loop, the MBED samples the ranger once every 50 milliseconds and publishes the range data.

Launching the App

After you program your mbed, its time to visualize the sensors measurements using rxplot.

roscore

rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0

rosrun rosserial_python serial_node.py /dev/ttyUSB0

rxplot range_data/range

Wiki: rosserial_mbed/Tutorials/IR Ranger (last edited 2015-11-20 19:08:30 by AlexisPojomovsky)