| Note: This tutorial assumes that you have completed the previous tutorials: Arduino IDE Setup. |
IR Ranger Tutorial
Description: Using an IR Ranger with rosserial and an ArduinoTutorial Level: BEGINNER
rosserial allows you to easily integrate Arduino-based hardware with ROS. This tutorial will explain how to use a sharp IR ranger with an Arduino.
You will need an Arduino which you can purchase here for example. Additionally, you will need a Sharp IR Ranger, Model# GP2D120XJ00F, and a way to connect your IR Ranger to your Arduino such as a breadboard or protoboard.
Hardware Setup
To get started, connect your ranger to your Arduino as shown below. Make sure to connect the signal pin of the ranger to analog input 0.
Software Setup
The Code
Next, open up your Arduino IDE and copy in the code below. The code can also be found in the rosserial_arduino_demos package under 'sketches\IrRanger'.
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 sensor_msgs::Range range_msg;
13 ros::Publisher pub_range( "range_data", &range_msg);
14
15 const int analog_pin = 0;
16 unsigned long range_timer;
17
18 /*
19 * getRange() - samples the analog input from the ranger
20 * and converts it into meters.
21 */
22 float getRange(int pin_num){
23 int sample;
24 // Get data
25 sample = analogRead(pin_num)/4;
26 // if the ADC reading is too low,
27 // then we are really far away from anything
28 if(sample < 10)
29 return 254; // max range
30 // Magic numbers to get cm
31 sample= 1309/(sample-3);
32 return (sample - 1)/100; //convert to meters
33 }
34
35 char frameid[] = "/ir_ranger";
36
37 void setup()
38 {
39 nh.initNode();
40 nh.advertise(pub_range);
41
42 range_msg.radiation_type = sensor_msgs::Range::INFRARED;
43 range_msg.header.frame_id = frameid;
44 range_msg.field_of_view = 0.01;
45 range_msg.min_range = 0.03;
46 range_msg.max_range = 0.4;
47
48 }
49
50 void loop()
51 {
52 // publish the range value every 50 milliseconds
53 // since it takes that long for the sensor to stabilize
54 if ( (millis()-range_timer) > 50){
55 range_msg.range = getRange(analog_pin);
56 range_msg.header.stamp = nh.now();
57 pub_range.publish(&range_msg);
58 range_timer = millis();
59 }
60 nh.spinOnce();
61 }
The Code Explained
Now let's break down the code.
As always, the code begins by including the appropriate message headers and ros.h from the rosserial library and then instantiating the publisher.
15 const int analog_pin = 0;
16 unsigned long range_timer;
17
18 /*
19 * getRange() - samples the analog input from the ranger
20 * and converts it into meters.
21 */
22 float getRange(int pin_num){
23 int sample;
24 // Get data
25 sample = analogRead(pin_num)/4;
26 // if the ADC reading is too low,
27 // then we are really far away from anything
28 if(sample < 10)
29 return 254; // max range
30 // Magic numbers to get cm
31 sample= 1309/(sample-3);
32 return (sample - 1)/100; //convert to meters
33 }
We then define the analog_pin that the ranger is attached to, creates a timer variable, and defines a function that converts the analog signal to a corresponding distance reading in meters.
35 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.
In the Arduino's setup function, the code initializes the node handle and then fills in the descriptor fields for range_msg.
50 void loop()
51 {
52 // publish the range value every 50 milliseconds
53 // since it takes that long for the sensor to stabilize
54 if ( (millis()-range_timer) > 50){
55 range_msg.range = getRange(analog_pin);
56 range_msg.header.stamp = nh.now();
57 pub_range.publish(&range_msg);
58 range_timer = millis();
59 }
60 nh.spinOnce();
61 }
Finally, in the publish loop, the Arduino samples the ranger once every 50 milliseconds and publishes the range data.
Launching the App
After you program your Arduino, its time to visualize the sensors measurements using rxplot.
roscore
rosrun rosserial_python serial_node.py /dev/ttyUSB0
rxplot range_data/range






