00001 /* 00002 * rosserial Temperature and Humidity Sensor Example 00003 * 00004 * This tutorial demonstrates the usage of the 00005 * Seeedstudio Temperature and Humidity Grove module 00006 * http://www.seeedstudio.com/wiki/Grove_-_Temperature_and_Humidity_Sensor 00007 * 00008 * Source Code Based of: 00009 * https://developer.mbed.org/teams/Seeed/code/Seeed_Grove_Temp_Humidity_Example/ 00010 */ 00011 00012 #include "mbed.h" 00013 #include "DHT.h" 00014 #include <ros.h> 00015 #include <sensor_msgs/Temperature.h> 00016 #include <sensor_msgs/RelativeHumidity.h> 00017 00018 ros::NodeHandle nh; 00019 00020 sensor_msgs::Temperature temp_msg; 00021 sensor_msgs::RelativeHumidity humidity_msg; 00022 ros::Publisher pub_temp("temperature", &temp_msg); 00023 ros::Publisher pub_humidity("humidity", &humidity_msg); 00024 00025 Timer t; 00026 #ifdef TARGET_LPC1768 00027 DHT sensor(p9, AM2302); 00028 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE) 00029 DHT sensor(D6, AM2302); 00030 #elif defined(TARGET_NUCLEO_F401RE) 00031 DHT sensor(A6, AM2302); 00032 #else 00033 #error "You need to specify a pin for the sensor" 00034 #endif 00035 00036 int main() 00037 { 00038 int error = 0; 00039 t.start(); 00040 00041 nh.initNode(); 00042 nh.advertise(pub_temp); 00043 nh.advertise(pub_humidity); 00044 00045 long publisher_timer = 0; 00046 temp_msg.header.frame_id = "/base_link"; 00047 humidity_msg.header.frame_id = "/base_link"; 00048 00049 while (1) 00050 { 00051 00052 if (t.read_ms() > publisher_timer) 00053 { 00054 error = sensor.readData(); 00055 if (0 == error) 00056 { 00057 temp_msg.temperature = sensor.ReadTemperature(CELCIUS); 00058 temp_msg.header.stamp = nh.now(); 00059 pub_temp.publish(&temp_msg); 00060 00061 humidity_msg.relative_humidity = sensor.ReadHumidity(); 00062 humidity_msg.header.stamp = nh.now(); 00063 pub_humidity.publish(&humidity_msg); 00064 } 00065 publisher_timer = t.read_ms() + 1000; 00066 } 00067 nh.spinOnce(); 00068 } 00069 } 00070