Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 import time
00019
00020 import rospy
00021 from std_msgs.msg import ColorRGBA
00022 from cob_light.srv import *
00023 from cob_light.msg import *
00024
00025 def changeColor():
00026 rospy.wait_for_service('/light_controller/mode')
00027 control_lights = rospy.ServiceProxy('/light_controller/mode', SetLightMode)
00028 rospy.init_node('light_test')
00029 light_mode = LightMode()
00030
00031 red = ColorRGBA()
00032 red.r = 1
00033 red.g = 0
00034 red.b = 0
00035 red.a = 0.7
00036
00037 light_red = ColorRGBA()
00038 light_red.r = 1
00039 light_red.g = 0
00040 light_red.b = 0
00041 light_red.a = 0.3
00042
00043 off = ColorRGBA()
00044 off.r = 1
00045 off.g = 0
00046 off.b = 0
00047 off.a = 0.01
00048
00049 dimm = ColorRGBA()
00050 dimm.r = 1
00051 dimm.g = 0
00052 dimm.b = 0
00053 dimm.a = 0.04
00054
00055 yellow = ColorRGBA()
00056 yellow.r = 1
00057 yellow.g = 1
00058 yellow.b = 0
00059 yellow.a = 1
00060
00061 green = ColorRGBA()
00062 green.r = 0
00063 green.g = 1
00064 green.b = 0
00065 green.a = 1
00066
00067 blue = ColorRGBA()
00068 blue.r = 0
00069 blue.g = 1
00070 blue.b = 0.7
00071 blue.a = 0.4
00072
00073 white = ColorRGBA()
00074 white.r = 0.3
00075 white.g = 1
00076 white.b = 0.3
00077 white.a = 1
00078
00079 light_mode.mode = 6
00080 light_mode.frequency=100
00081 seq1 = Sequence()
00082 seq1.color = blue
00083 seq1.hold_time = 4;
00084 seq1.cross_time = 1;
00085 light_mode.sequences.append(seq1);
00086
00087 seq2 = Sequence()
00088 seq2.color = red;
00089 seq2.hold_time = 4;
00090 seq2.cross_time = 1;
00091 light_mode.sequences.append(seq2);
00092
00093
00094
00095
00096
00097
00098
00099
00100
00101
00102
00103
00104
00105 try:
00106 resp1 = control_lights(light_mode)
00107 print resp1
00108 except rospy.ServiceException, e:
00109 print "Service call failed: %s"%e
00110
00111 time.sleep(6)
00112
00113 if __name__ == '__main__':
00114 try:
00115 rospy.init_node('light_test')
00116 changeColor()
00117 except rospy.ROSInterruptException:
00118 pass
00119