]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/christmas.py
gps_follow_waypoints: Increase speeds
[ros_wild_thumper.git] / scripts / christmas.py
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()