]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
Sensor.msg: use float for pressure
authorErik Andresen <erik@vontaene.de>
Thu, 29 Dec 2016 00:24:23 +0000 (01:24 +0100)
committerErik Andresen <erik@vontaene.de>
Thu, 29 Dec 2016 00:24:23 +0000 (01:24 +0100)
msg/Sensor.msg
scripts/christmas.py
scripts/sensor_board.py

index 72aedff2f8118d5d3d4a1326f615fe8c9ba5ed77..c0204d61fcf8b4795445a212b9133e4e010c342c 100644 (file)
@@ -2,6 +2,6 @@ Header header
 uint16 light
 float32 temp
 uint8 humidity
-int16 pressure
+float32 pressure
 uint16 co
 bool ventilate
index bdfd688272e44fa9df32594ce369fd8edd2ebb29..ae8c18466cfd15bda8c0e8647d17851b8741f9ff 100755 (executable)
@@ -3,21 +3,36 @@
 
 import rospy
 from random import *
-from wild_thumper.msg import LedStripe, Led
+from datetime import datetime
+from wild_thumper.msg import *
 
 max_val = 10
+light = 0
+ldr_thres = 8
+
+def sensorReceived(msg):
+       global light
+       light = msg.light
 
 if __name__ == "__main__":
        rospy.init_node('christmas')
        pub = rospy.Publisher('led_stripe', LedStripe, queue_size=10)
+       rospy.Subscriber("/sensors", Sensor, sensorReceived)
        rate = rospy.Rate(2)
+       val = max_val
        while not rospy.is_shutdown():
-               msg = LedStripe()
-               msg.leds = [
-                               Led(4, randint(0, max_val), randint(0, max_val), randint(0, max_val)),
-                               Led(5, randint(0, max_val), randint(0, max_val), randint(0, max_val)),
-                               Led(6, randint(0, max_val), randint(0, max_val), randint(0, max_val)),
-                               Led(7, randint(0, max_val), randint(0, max_val), randint(0, max_val))
-                               ]
-               pub.publish(msg)
+               if light <= ldr_thres or val != 0:
+                       now = datetime.now()
+                       if light <= ldr_thres and now.hour >= 18 and now.hour <= 22:
+                               val = max_val
+                       else:
+                               val = 0
+                       msg = LedStripe()
+                       msg.leds = [
+                                       Led(4, randint(0, val), randint(0, val), randint(0, val)),
+                                       Led(5, randint(0, val), randint(0, val), randint(0, val)),
+                                       Led(6, randint(0, val), randint(0, val), randint(0, val)),
+                                       Led(7, randint(0, val), randint(0, val), randint(0, val))
+                                       ]
+                       pub.publish(msg)
                rate.sleep()
index 337830ddb4407c9fad4c6b1511fdb81fb9cdd697..bddfb580ead0291735485386e601d5ff99e76909 100755 (executable)
@@ -66,8 +66,6 @@ class SensorBoard:
                                if (datetime.now() - t_last_check).seconds > 900:
                                        ventilate = check_ventilate(temp, humidity)
                                        t_last_check = datetime.now()
-                               if (ventilate > 1.10):
-                                       print "Lüften!"
                                
                                msg = Sensor()
                                msg.header.stamp = rospy.Time.now()
@@ -76,7 +74,7 @@ class SensorBoard:
                                msg.humidity = humidity
                                msg.pressure = pressure
                                msg.co = co
-                               msg.ventilate = ventilate
+                               msg.ventilate = True if ventilate > 1.10 else False
 
                                self.pub.publish(msg)