Akash Vibhute / mbed_roshydro_test

Dependencies:   rosserial_hydro

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers Temperature.cpp Source File

Temperature.cpp

00001 //#define COMPILE_TEMPERATURE_CODE_ROSSERIAL
00002 #ifdef  COMPILE_TEMPERATURE_CODE_ROSSERIAL
00003 
00004 /*
00005  * rosserial Temperature Sensor Example
00006  *
00007  * This tutorial demonstrates the usage of the
00008  * Sparkfun TMP102 Digital Temperature Breakout board
00009  * http://www.sparkfun.com/products/9418
00010  *
00011  * Source Code Based off of:
00012  * http://wiring.org.co/learning/libraries/tmp102sparkfun.html
00013  */
00014 
00015 #include "mbed.h"
00016 #include <ros.h>
00017 #include <std_msgs/Float32.h>
00018 
00019 ros::NodeHandle  nh;
00020 
00021 std_msgs::Float32 temp_msg;
00022 ros::Publisher pub_temp("temperature", &temp_msg);
00023 
00024 
00025 // From the datasheet the BMP module address LSB distinguishes
00026 // between read (1) and write (0) operations, corresponding to
00027 // address 0x91 (read) and 0x90 (write).
00028 // shift the address 1 bit right (0x91 or 0x90), the Wire library only needs the 7
00029 // most significant bits for the address 0x91 >> 1 = 0x48
00030 // 0x90 >> 1 = 0x48 (72)
00031 
00032  int sensorAddress = 0x91 >>1;  // From datasheet sensor address is 0x91
00033 
00034 // shift the address 1 bit right, the Wire library only needs the 7
00035 // most significant bits for the address
00036 
00037 Timer t;
00038 I2C i2c(p9, p10);        // sda, scl
00039 
00040 int main() {
00041     t.start();
00042 
00043     nh.initNode();
00044     nh.advertise(pub_temp);
00045 
00046     long publisher_timer =0;
00047 
00048     while (1) {
00049 
00050         if (t.read_ms() > publisher_timer) {
00051             // step 1: request reading from sensor
00052             //Wire.requestFrom(sensorAddress,2);
00053             char cmd = 2;
00054             i2c.write(sensorAddress, &cmd, 1);
00055 
00056             wait_ms(50);
00057 
00058             char msb;
00059             char lsb;
00060             int temperature;
00061             i2c.read(sensorAddress, &msb, 1); // receive high byte (full degrees)
00062             i2c.read(sensorAddress, &lsb, 1); // receive low byte (fraction degrees)
00063             
00064             temperature = ((msb) << 4);  // MSB
00065             temperature |= (lsb >> 4);   // LSB
00066 
00067             temp_msg.data = temperature*0.0625;
00068             pub_temp.publish(&temp_msg);
00069 
00070 
00071             publisher_timer = t.read_ms() + 1000;
00072         }
00073 
00074         nh.spinOnce();
00075     }
00076 }
00077 
00078 #endif