2 # -*- coding: iso-8859-15 -*-
7 from datetime import datetime
9 from pyshared.i2c import i2c
10 from pyshared.humidity import *
11 from wild_thumper.msg import Sensor
13 # Board warming offset
14 TEMP_ERROR = -2 # -5 # degree celsius
19 val = [100 285 321 515 636 758 940 1023]
20 lux = [95 34 31 12 11 8 5 0]
25 dev.write(struct.pack(">BB", 0x00, 0x0f))
30 msg = dev.read(11) # for unknown reason need to read one more byte
37 ldr, temp_mess, humidity_mess, pressure, co = struct.unpack(">hhhhh", msg)
41 lux = -3.9338e-07*ldr**3 +0.00083596*ldr**2 -0.58608*ldr +144.96
42 pressure_v = pressure*2.56/1024
43 pressure_kpa = P = (pressure_v/5 + 0.04) / 0.004 + PRESSURE_ERROR # datasheet
45 # fix temperature/humidity
46 temp_real = temp_mess + TEMP_ERROR
47 humidity_abs = calc_humidity_abs(temp_mess, humidity_mess)
48 humidity_real = calc_humidity_rel(temp_real, humidity_abs)
50 return lux, temp_real, humidity_real, pressure_kpa, co
54 rospy.init_node('sensor_board')
55 prctl.set_name("sensor_board")
56 self.pub = rospy.Publisher("sensors", Sensor, queue_size=16)
60 rate = rospy.Rate(1.0)
61 t_last_check = datetime.min
63 while not rospy.is_shutdown():
64 if self.pub.get_num_connections() > 0:
65 ldr, temp, humidity, pressure, co = get()
66 if (datetime.now() - t_last_check).seconds > 900:
67 ventilate = check_ventilate(temp, humidity)
68 t_last_check = datetime.now()
71 msg.header.stamp = rospy.Time.now()
74 msg.humidity = humidity
75 msg.pressure = pressure
77 msg.ventilate = True if ventilate > 1.10 else False
83 if __name__ == "__main__":