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

DHT Humidity and Temperature Sensor

Description: In this tutorial, we will use a Mbed and a DHT Humidity and Temperature Sensor.

Tutorial Level: BEGINNER

Next Tutorial: Motor Shield Example

  Show EOL distros: 

rosserial allows you to easily integrate Mbed-based hardware with ROS. This tutorial will explain how to use a DHT Humidity and Temperature Sensor with an Mbed.

You will need an Mbed, a Humidity and Temperature Sensor, and a way to connect your Sensor to your Mbed to your Mbed such as a breadboard, protoboard or Grove Base Shield.

The Code

Open the Humidity and Temperature Sensor example placed on your previously downloaded rosserial/rosserial_mbed/examples directory, and open the GrovePIRMotionSensor.cpp file in your favorite text editor:

   1 /*
   2  * rosserial Temperature and Humidity Sensor Example
   3  *
   4  * This tutorial demonstrates the usage of the
   5  * Seeedstudio Temperature and Humidity Grove module
   6  * http://www.seeedstudio.com/wiki/Grove_-_Temperature_and_Humidity_Sensor
   7  *
   8  * Source Code Based of:
   9  * https://developer.mbed.org/teams/Seeed/code/Seeed_Grove_Temp_Humidity_Example/
  10  */
  11 
  12 #include "mbed.h"
  13 #include "DHT.h"
  14 #include <ros.h>
  15 #include <sensor_msgs/Temperature.h>
  16 #include <sensor_msgs/RelativeHumidity.h>
  17 
  18 ros::NodeHandle  nh;
  19 
  20 sensor_msgs::Temperature temp_msg;
  21 sensor_msgs::RelativeHumidity humidity_msg;
  22 ros::Publisher pub_temp("temperature", &temp_msg);
  23 ros::Publisher pub_humidity("humidity", &humidity_msg);
  24 
  25 Timer t;
  26 #ifdef TARGET_LPC1768
  27 DHT sensor(p9, AM2302);
  28 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
  29 DHT sensor(D6, AM2302);
  30 #elif defined(TARGET_NUCLEO_F401RE)
  31 DHT sensor(A6, AM2302);
  32 #else
  33 #error "You need to specify a pin for the sensor"
  34 #endif
  35 
  36 int main()
  37 {
  38   int error = 0;
  39   t.start();
  40 
  41   nh.initNode();
  42   nh.advertise(pub_temp);
  43   nh.advertise(pub_humidity);
  44 
  45   long publisher_timer = 0;
  46   temp_msg.header.frame_id = "/base_link";
  47   humidity_msg.header.frame_id = "/base_link";
  48 
  49   while (1)
  50   {
  51 
  52     if (t.read_ms() > publisher_timer)
  53     {
  54       error = sensor.readData();
  55       if (0 == error)
  56       {
  57         temp_msg.temperature = sensor.ReadTemperature(CELCIUS);
  58         temp_msg.header.stamp = nh.now();
  59         pub_temp.publish(&temp_msg);
  60 
  61         humidity_msg.relative_humidity = sensor.ReadHumidity();
  62         humidity_msg.header.stamp = nh.now();
  63         pub_humidity.publish(&humidity_msg);
  64       }
  65       publisher_timer = t.read_ms() + 1000;
  66     }
  67     nh.spinOnce();
  68   }
  69 }

Compiling and uploading the Code

As seen on the previous tutorial, you must compile the source code by using the makefile in order to generate the .bin file that will be uploaded later to your MBED board. This is no different from uploading any other mbed binary.

Launching the App

Launch roscore

$ roscore

Run the serial node with the right serial port corresponding to your MBED board

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

$ rosrun rosserial_python serial_node.py /dev/ttyUSB0

Now watch the sensor's value on the pushed topic

$ rostopic echo /temperature

or

$ rostopic echo /humidity

Wiki: rosserial_mbed/Tutorials/DHT Humidity and Temperature Sensor (last edited 2016-01-04 20:53:56 by AlexisPojomovsky)