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


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