Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012 #include "mbed.h"
00013 #include <ros.h>
00014 #include <std_msgs/Float32.h>
00015
00016 ros::NodeHandle nh;
00017
00018 std_msgs::Float32 temp_msg;
00019 ros::Publisher pub_temp("temperature", &temp_msg);
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 int sensorAddress = 0x91 >>1;
00030
00031
00032
00033 Timer t;
00034 #ifdef TARGET_LPC1768
00035 I2C i2c(p9, p10);
00036 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
00037 I2C i2c(D14, D15);
00038 #else
00039 #error "You need to specify a pin for the sensor"
00040 #endif
00041
00042 int main() {
00043 t.start();
00044
00045 nh.initNode();
00046 nh.advertise(pub_temp);
00047
00048 long publisher_timer =0;
00049
00050 while (1) {
00051
00052 if (t.read_ms() > publisher_timer) {
00053
00054
00055 char cmd = 2;
00056 i2c.write(sensorAddress, &cmd, 1);
00057
00058 wait_ms(50);
00059
00060 char msb;
00061 char lsb;
00062 int temperature;
00063 i2c.read(sensorAddress, &msb, 1);
00064 i2c.read(sensorAddress, &lsb, 1);
00065
00066 temperature = ((msb) << 4);
00067 temperature |= (lsb >> 4);
00068
00069 temp_msg.data = temperature*0.0625;
00070 pub_temp.publish(&temp_msg);
00071
00072 publisher_timer = t.read_ms() + 1000;
00073 }
00074
00075 nh.spinOnce();
00076 }
00077 }
00078