GroveTemperatureHumidity.cpp
Go to the documentation of this file.
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 
19 
20 sensor_msgs::Temperature temp_msg;
21 sensor_msgs::RelativeHumidity humidity_msg;
22 ros::Publisher pub_temp("temperature", &temp_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);
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();
60 
61  humidity_msg.relative_humidity = sensor.ReadHumidity();
62  humidity_msg.header.stamp = nh.now();
64  }
65  publisher_timer = t.read_ms() + 1000;
66  }
67  nh.spinOnce();
68  }
69 }
70 
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher pub_temp("temperature",&temp_msg)
Definition: DHT.h:66
ros::Publisher pub_humidity("humidity",&humidity_msg)
Definition: DHT.h:44
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
sensor_msgs::RelativeHumidity humidity_msg
Definition: DHT.h:73
sensor_msgs::Temperature temp_msg
ros::NodeHandle nh


rosserial_mbed
Author(s): Gary Servin
autogenerated on Fri Jun 7 2019 22:02:48