ros_serial for mbed updated to work with ROS Hydro. Library still needs to be debugged
Library and program still under development!
examples/Temperature.cpp
- Committer:
- akashvibhute
- Date:
- 2015-02-15
- Revision:
- 1:225298843679
- Parent:
- 0:cb1dffdc7d05
File content as of revision 1:225298843679:
//#define COMPILE_TEMPERATURE_CODE_ROSSERIAL #ifdef COMPILE_TEMPERATURE_CODE_ROSSERIAL /* * rosserial Temperature Sensor Example * * This tutorial demonstrates the usage of the * Sparkfun TMP102 Digital Temperature Breakout board * http://www.sparkfun.com/products/9418 * * Source Code Based off of: * http://wiring.org.co/learning/libraries/tmp102sparkfun.html */ #include "mbed.h" #include <ros.h> #include <std_msgs/Float32.h> ros::NodeHandle nh; std_msgs::Float32 temp_msg; ros::Publisher pub_temp("temperature", &temp_msg); // From the datasheet the BMP module address LSB distinguishes // between read (1) and write (0) operations, corresponding to // address 0x91 (read) and 0x90 (write). // shift the address 1 bit right (0x91 or 0x90), the Wire library only needs the 7 // most significant bits for the address 0x91 >> 1 = 0x48 // 0x90 >> 1 = 0x48 (72) int sensorAddress = 0x91 >>1; // From datasheet sensor address is 0x91 // shift the address 1 bit right, the Wire library only needs the 7 // most significant bits for the address Timer t; I2C i2c(p9, p10); // sda, scl int main() { t.start(); nh.initNode(); nh.advertise(pub_temp); long publisher_timer =0; while (1) { if (t.read_ms() > publisher_timer) { // step 1: request reading from sensor //Wire.requestFrom(sensorAddress,2); char cmd = 2; i2c.write(sensorAddress, &cmd, 1); wait_ms(50); char msb; char lsb; int temperature; i2c.read(sensorAddress, &msb, 1); // receive high byte (full degrees) i2c.read(sensorAddress, &lsb, 1); // receive low byte (fraction degrees) temperature = ((msb) << 4); // MSB temperature |= (lsb >> 4); // LSB temp_msg.data = temperature*0.0625; pub_temp.publish(&temp_msg); publisher_timer = t.read_ms() + 1000; } nh.spinOnce(); } } #endif