test_sprofi_modes.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 
18 import time
19 
20 import rospy
21 from std_msgs.msg import ColorRGBA
22 from cob_light.srv import *
23 from cob_light.msg import *
24 
26  rospy.wait_for_service('/light_controller/mode')
27  control_lights = rospy.ServiceProxy('/light_controller/mode', SetLightMode)
28  rospy.init_node('light_test')
29  light_mode = LightMode()
30  #color in rgb color space ranging from 0 to 1
31  red = ColorRGBA()
32  red.r = 1
33  red.g = 0
34  red.b = 0
35  red.a = 0.7
36 
37  light_red = ColorRGBA()
38  light_red.r = 1
39  light_red.g = 0
40  light_red.b = 0
41  light_red.a = 0.3
42 
43  off = ColorRGBA()
44  off.r = 1
45  off.g = 0
46  off.b = 0
47  off.a = 0.01
48 
49  dimm = ColorRGBA()
50  dimm.r = 1
51  dimm.g = 0
52  dimm.b = 0
53  dimm.a = 0.04
54 
55  yellow = ColorRGBA()
56  yellow.r = 1
57  yellow.g = 1
58  yellow.b = 0
59  yellow.a = 1
60 
61  green = ColorRGBA()
62  green.r = 0
63  green.g = 1
64  green.b = 0
65  green.a = 1
66 
67  blue = ColorRGBA()
68  blue.r = 0
69  blue.g = 1
70  blue.b = 0.7
71  blue.a = 0.4
72 
73  white = ColorRGBA()
74  white.r = 0.3
75  white.g = 1
76  white.b = 0.3
77  white.a = 1
78 
79  light_mode.mode = 6
80  light_mode.frequency=100
81  seq1 = Sequence()
82  seq1.color = blue
83  seq1.hold_time = 4;
84  seq1.cross_time = 1;
85  light_mode.sequences.append(seq1);
86 
87  seq2 = Sequence()
88  seq2.color = red;
89  seq2.hold_time = 4;
90  seq2.cross_time = 1;
91  light_mode.sequences.append(seq2);
92 
93  # seq3 = Sequence()
94  # seq3.color = off;
95  # seq3.hold_time = 0.06;
96  # seq3.cross_time = 0.05;
97  # light_mode.sequences.append(seq3);
98 
99  # seq4 = Sequence()
100  # seq4.color = light_red;
101  # seq4.hold_time = 0.08;
102  # seq4.cross_time = 0.05;
103  # light_mode.sequences.append(seq4);
104  #
105  try:
106  resp1 = control_lights(light_mode)
107  print(resp1)
108  except rospy.ServiceException as e:
109  print("Service call failed: %s"%e)
110 
111  time.sleep(6)
112 
113 if __name__ == '__main__':
114  try:
115  rospy.init_node('light_test')
116  changeColor()
117  except rospy.ROSInterruptException:
118  pass
119 


cob_light
Author(s): Benjamin Maidel
autogenerated on Wed Apr 7 2021 02:11:39