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

Temperature Sensor

Description: Measuring Temperature using the TMP102

Tutorial Level: BEGINNER

Next Tutorial: Push Button

  Show EOL distros: 

In this tutorial, we will use an Arduino and a TMP102 temperature sensor to measure the ambient temperature in a room. The tutorial's goals are two fold. The first is to show an example temperature sensing node. The second is to demonstrate the Arduino as an I2C interface for ROS. The TMP102 is one of many pieces of hardware that use I2C to communicate. You can now interface SPI/I2C to ROS with ease using an Arduino.

Hardware

For this tutorial, you will need an Arduino and a TMP102 Breakout board from Sparkfun. This board is a great little temperature sensor that can measure temperature with a 0.625 degree C resolution. Connecting it to an Arduino is very straightforward. It is a 3.3V sensor communication over I2C so it connects to the Arduino's 3.3V output, GND, SDA, SCL pins. SDA and SCL are the I2C data line and I2C clock line respectively. They are exposed on the Arduino board as analog pins 4 and 5.

tmp102.png

Diagram from here

Code

   1 #include <Wire.h>
   2 #include <ros.h>
   3 #include <std_msgs/Float32.h>
   4 
   5 
   6 //Set up the ros node and publisher
   7 std_msgs::Float32 temp_msg;
   8 ros::Publisher pub_temp("temperature", &temp_msg);
   9 ros::NodeHandle nh;
  10 
  11 int sensorAddress = 0x91 >> 1;  // From datasheet sensor address is 0x91
  12                                 // shift the address 1 bit right,
  13                                  //the Wire library only needs the 7
  14                                 // most significant bits for the address
  15 
  16 void setup()
  17 {
  18   Wire.begin();        // join i2c bus (address optional for master)
  19 
  20   nh.initNode();
  21   nh.advertise(pub_temp);
  22 
  23 }
  24 
  25 long publisher_timer;
  26 
  27 void loop()
  28 {
  29 
  30   if (millis() > publisher_timer) {
  31   // step 1: request reading from sensor
  32     Wire.requestFrom(sensorAddress,2);
  33     delay(10);
  34     if (2 <= Wire.available())  // if two bytes were received
  35     {
  36       byte msb;
  37       byte lsb;
  38       int temperature;
  39 
  40       msb = Wire.read();  // receive high byte (full degrees)
  41       lsb = Wire.read();  // receive low byte (fraction degrees)
  42       temperature = ((msb) << 4);  // MSB
  43       temperature |= (lsb >> 4);   // LSB
  44 
  45       temp_msg.data = temperature*0.0625;
  46       pub_temp.publish(&temp_msg);
  47     }
  48 
  49   publisher_timer = millis() + 1000; //publish once a second
  50   }
  51 
  52   nh.spinOnce();
  53 }

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.

Testing

roscore

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

rosrun rosserial_python serial_node.py /dev/ttyUSB0

rostopic echo temperature

Wiki: rosserial_arduino/Tutorials/Measuring Temperature (last edited 2014-09-22 16:29:52 by AustinHendrix)