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. |
SRF08 Ultrasonic Ranger
Description: In this tutorial, we will use an Arduino and a SRF08 Ultrasonic Ranger as a Range Finder.The SRF08 communicates with an Arduino over SPI/I2C.Tutorial Level: BEGINNER
Next Tutorial: BlinkM
Show EOL distros:
Contents
rosserial allows you to easily integrate Arduino-based hardware with ROS. This tutorial will explain how to use a SRF08 Ultrasonic ranger with an Arduino.
You will need an Arduino ,a SRF08 Ultrasonic Ranger, and a way to connect your Ranger to your Arduino such as a breadboard or protoboard.The SRF08 Arduino library can be downloaded fromSonar_srf08.zip
Hardware Setup
Below is the diagram for setting up the SRF08 sensor for a typical Arduino. The only additional circuitry necessary are two 1.8kOhm pullup resistors as seen below.
The Code
Next, open up your Arduino IDE and copy in the code below.
1 /*
2 * rosserial SRF08 Ultrasonic Ranger Example
3 *
4 * This example is calibrated for the SRF08 Ultrasonic Ranger.
5 */
6 #include <Sonar_srf08.h> //SRF08 specific library
7 #include <WProgram.h>
8 #include <Wire.h>
9 #include <ros.h>
10 #include <std_msgs/Float32.h>
11
12
13 //Set up the ros node and publisher
14 std_msgs::Float32 sonar_msg;
15 ros::Publisher pub_sonar("sonar", &sonar_msg);
16 ros::NodeHandle nh;
17
18
19 Sonar_srf08 MySonar; //create MySonar object
20
21 #define CommandRegister 0x00
22 int New_Address = 248; //0xF8
23 #define ResultRegister 0x02
24
25 float sensorReading =0;
26
27 char unit = 'i'; // 'i' for inches , 'c' for centimeters
28
29
30 void setup()
31 {
32 MySonar.connect();
33 MySonar.changeAddress(CommandRegister, New_Address);
34 New_Address += 4;
35 nh.initNode();
36 nh.advertise(pub_sonar);
37
38 }
39
40
41 long publisher_timer;
42
43 void loop()
44 {
45
46 if (millis() > publisher_timer) {
47
48 // step 1: request reading from sensor
49 MySonar.setUnit(CommandRegister, New_Address, unit);
50
51 //pause
52 delay(70);
53
54 // set register for reading
55 MySonar.setRegister(New_Address, ResultRegister);
56
57 // read data from result register
58 sensorReading = MySonar.readData(New_Address, 2);
59
60 sonar_msg.data = sensorReading;
61 pub_sonar.publish(&sonar_msg);
62
63 publisher_timer = millis() + 4000; //publish once a second
64
65 }
66
67 nh.spinOnce();
68 }
The special bit of code in this example is the use of Arduino's Wire library. Wire is a I2C library that simplifies reading and writing to the I2C bus.
Launching the App
roscore
rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0
rosrun rosserial_python serial_node.py /dev/ttyUSB0
rostopic echo sonar