ros_serial for mbed updated to work with ROS Hydro. Library still needs to be debugged

Dependencies:   rosserial_hydro

Library and program still under development!

Committer:
akashvibhute
Date:
Sun Feb 15 10:56:37 2015 +0000
Revision:
1:225298843679
Parent:
0:cb1dffdc7d05
rosserial_mbed for hydro testing

Who changed what in which revision?

UserRevisionLine numberNew contents of line
akashvibhute 0:cb1dffdc7d05 1 //#define COMPILE_TEMPERATURE_CODE_ROSSERIAL
akashvibhute 0:cb1dffdc7d05 2 #ifdef COMPILE_TEMPERATURE_CODE_ROSSERIAL
akashvibhute 0:cb1dffdc7d05 3
akashvibhute 0:cb1dffdc7d05 4 /*
akashvibhute 0:cb1dffdc7d05 5 * rosserial Temperature Sensor Example
akashvibhute 0:cb1dffdc7d05 6 *
akashvibhute 0:cb1dffdc7d05 7 * This tutorial demonstrates the usage of the
akashvibhute 0:cb1dffdc7d05 8 * Sparkfun TMP102 Digital Temperature Breakout board
akashvibhute 0:cb1dffdc7d05 9 * http://www.sparkfun.com/products/9418
akashvibhute 0:cb1dffdc7d05 10 *
akashvibhute 0:cb1dffdc7d05 11 * Source Code Based off of:
akashvibhute 0:cb1dffdc7d05 12 * http://wiring.org.co/learning/libraries/tmp102sparkfun.html
akashvibhute 0:cb1dffdc7d05 13 */
akashvibhute 0:cb1dffdc7d05 14
akashvibhute 0:cb1dffdc7d05 15 #include "mbed.h"
akashvibhute 0:cb1dffdc7d05 16 #include <ros.h>
akashvibhute 0:cb1dffdc7d05 17 #include <std_msgs/Float32.h>
akashvibhute 0:cb1dffdc7d05 18
akashvibhute 0:cb1dffdc7d05 19 ros::NodeHandle nh;
akashvibhute 0:cb1dffdc7d05 20
akashvibhute 0:cb1dffdc7d05 21 std_msgs::Float32 temp_msg;
akashvibhute 0:cb1dffdc7d05 22 ros::Publisher pub_temp("temperature", &temp_msg);
akashvibhute 0:cb1dffdc7d05 23
akashvibhute 0:cb1dffdc7d05 24
akashvibhute 0:cb1dffdc7d05 25 // From the datasheet the BMP module address LSB distinguishes
akashvibhute 0:cb1dffdc7d05 26 // between read (1) and write (0) operations, corresponding to
akashvibhute 0:cb1dffdc7d05 27 // address 0x91 (read) and 0x90 (write).
akashvibhute 0:cb1dffdc7d05 28 // shift the address 1 bit right (0x91 or 0x90), the Wire library only needs the 7
akashvibhute 0:cb1dffdc7d05 29 // most significant bits for the address 0x91 >> 1 = 0x48
akashvibhute 0:cb1dffdc7d05 30 // 0x90 >> 1 = 0x48 (72)
akashvibhute 0:cb1dffdc7d05 31
akashvibhute 0:cb1dffdc7d05 32 int sensorAddress = 0x91 >>1; // From datasheet sensor address is 0x91
akashvibhute 0:cb1dffdc7d05 33
akashvibhute 0:cb1dffdc7d05 34 // shift the address 1 bit right, the Wire library only needs the 7
akashvibhute 0:cb1dffdc7d05 35 // most significant bits for the address
akashvibhute 0:cb1dffdc7d05 36
akashvibhute 0:cb1dffdc7d05 37 Timer t;
akashvibhute 0:cb1dffdc7d05 38 I2C i2c(p9, p10); // sda, scl
akashvibhute 0:cb1dffdc7d05 39
akashvibhute 0:cb1dffdc7d05 40 int main() {
akashvibhute 0:cb1dffdc7d05 41 t.start();
akashvibhute 0:cb1dffdc7d05 42
akashvibhute 0:cb1dffdc7d05 43 nh.initNode();
akashvibhute 0:cb1dffdc7d05 44 nh.advertise(pub_temp);
akashvibhute 0:cb1dffdc7d05 45
akashvibhute 0:cb1dffdc7d05 46 long publisher_timer =0;
akashvibhute 0:cb1dffdc7d05 47
akashvibhute 0:cb1dffdc7d05 48 while (1) {
akashvibhute 0:cb1dffdc7d05 49
akashvibhute 0:cb1dffdc7d05 50 if (t.read_ms() > publisher_timer) {
akashvibhute 0:cb1dffdc7d05 51 // step 1: request reading from sensor
akashvibhute 0:cb1dffdc7d05 52 //Wire.requestFrom(sensorAddress,2);
akashvibhute 0:cb1dffdc7d05 53 char cmd = 2;
akashvibhute 0:cb1dffdc7d05 54 i2c.write(sensorAddress, &cmd, 1);
akashvibhute 0:cb1dffdc7d05 55
akashvibhute 0:cb1dffdc7d05 56 wait_ms(50);
akashvibhute 0:cb1dffdc7d05 57
akashvibhute 0:cb1dffdc7d05 58 char msb;
akashvibhute 0:cb1dffdc7d05 59 char lsb;
akashvibhute 0:cb1dffdc7d05 60 int temperature;
akashvibhute 0:cb1dffdc7d05 61 i2c.read(sensorAddress, &msb, 1); // receive high byte (full degrees)
akashvibhute 0:cb1dffdc7d05 62 i2c.read(sensorAddress, &lsb, 1); // receive low byte (fraction degrees)
akashvibhute 0:cb1dffdc7d05 63
akashvibhute 0:cb1dffdc7d05 64 temperature = ((msb) << 4); // MSB
akashvibhute 0:cb1dffdc7d05 65 temperature |= (lsb >> 4); // LSB
akashvibhute 0:cb1dffdc7d05 66
akashvibhute 0:cb1dffdc7d05 67 temp_msg.data = temperature*0.0625;
akashvibhute 0:cb1dffdc7d05 68 pub_temp.publish(&temp_msg);
akashvibhute 0:cb1dffdc7d05 69
akashvibhute 0:cb1dffdc7d05 70
akashvibhute 0:cb1dffdc7d05 71 publisher_timer = t.read_ms() + 1000;
akashvibhute 0:cb1dffdc7d05 72 }
akashvibhute 0:cb1dffdc7d05 73
akashvibhute 0:cb1dffdc7d05 74 nh.spinOnce();
akashvibhute 0:cb1dffdc7d05 75 }
akashvibhute 0:cb1dffdc7d05 76 }
akashvibhute 0:cb1dffdc7d05 77
akashvibhute 0:cb1dffdc7d05 78 #endif