light_service_test.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 rospy
19 import actionlib
20 import random
21 
22 from cob_light.msg import *
23 
24 from cob_light.srv import SetLightMode
25 from cob_light.srv import SetLightModeRequest
26 from cob_light.srv import SetLightModeResponse
27 
28 from std_msgs.msg import ColorRGBA
29 
30 class ActionTestScript(object):
31  def __init__(self):
32  self.executeMode(0)
33 
34  def executeMode(self, event):
35  rospy.loginfo("setting service mode")
36  mode = self.getLightMode(random.randint(0,14))
37 
38  srv_light = rospy.ServiceProxy('/light_torso/set_light', SetLightMode)
39  srv_light.call(mode)
40 
41  duration = random.uniform(0, 0.5)
42  self.timer = rospy.Timer(rospy.Duration(duration), self.executeMode, True)
43 
44  def getLightMode(self, mode):
45  req = SetLightModeRequest()
46  req.mode.priority = 4
47 
48  if mode == 0:
49  req.mode.mode=LightModes.BREATH
50  req.mode.frequency = 0.3
51  req.mode.pulses = 2
52  req.mode.timeout = 0
53  req.mode.colors.append(ColorRGBA(1.0,1.0,1.0,1.0))
54 
55  elif mode == 1:
56  req.mode.mode=LightModes.FLASH
57  req.mode.frequency = 2
58  req.mode.pulses = 3
59  req.mode.timeout = 0
60  req.mode.colors.append(ColorRGBA(1.0,1.0,1.0,1.0))
61 
62  elif mode == 2:
63  req.mode.mode=LightModes.BREATH
64  req.mode.frequency = 0.4
65  req.mode.pulses = 0
66  req.mode.timeout = 0
67  req.mode.colors.append(ColorRGBA(170.0/255.0, 250.0/255.0, 70.0/255.0, 1.0))
68 
69  elif mode == 3:
70  req.mode.mode=LightModes.BREATH
71  req.mode.frequency = 0.3
72  req.mode.pulses = 0
73  req.mode.timeout = 0
74  req.mode.colors.append(ColorRGBA(70.0/255.0, 140.0/255.0, 250.0/255.0, 1.0))
75 
76  elif mode == 4:
77  req.mode.mode=LightModes.BREATH
78  req.mode.frequency = 0.3
79  req.mode.pulses = 0
80  req.mode.timeout = 0
81  req.mode.colors.append(ColorRGBA(240.0/255.0, 250.0/255.0, 70.0/255.0, 1.0))
82 
83  elif mode == 5:
84  req.mode.mode=LightModes.BREATH
85  req.mode.frequency = 0.3
86  req.mode.pulses = 0
87  req.mode.timeout = 0
88  req.mode.colors.append(ColorRGBA(70.0/255.0, 240.0/255.0, 250.0/255.0, 1.0))
89 
90  elif mode == 6: #static yellow black - barrier tape
91  yellow = ColorRGBA(70.0/255.0, 240.0/255.0, 250.0/255.0, 1.0)
92  black = ColorRGBA()
93  req.mode.mode=LightModes.BREATH
94  req.mode.frequency = 0.3
95  req.mode.pulses = 0
96  req.mode.timeout = 0
97  #58 leds
98  num_segs = 6
99  iterations = int(num_segs/2)
100  seg_div = int(58/num_segs)
101  for i in range(0, iterations):
102  for j in range (0, seg_div):
103  req.mode.colors.append(yellow)
104  for j in range (0, seg_div):
105  req.mode.colors.append(black)
106 
107  elif mode == 7:
108  req.mode.mode=LightModes.BREATH
109  req.mode.frequency = 0.3
110  req.mode.pulses = 0
111  req.mode.timeout = 0
112  req.mode.colors.append(ColorRGBA(250.0/255.0, 70.0/255.0, 70.0/255.0, 1.0))
113 
114  elif mode == 8:
115  req.mode.mode=LightModes.BREATH
116  req.mode.frequency = 0.3
117  req.mode.pulses = 0
118  req.mode.timeout = 0
119  req.mode.colors.append(ColorRGBA(230.0/255.0, 250.0/255.0, 250.0/255.0, 1.0))
120 
121  elif mode == 9:
122  req.mode.mode=LightModes.FADE_COLOR
123  req.mode.frequency = 0.5
124  req.mode.pulses = 0
125  req.mode.timeout = 0
126  req.mode.colors.append(ColorRGBA(1,1,1,1))
127 
128  elif mode == 10:
129  req.mode.mode=LightModes.FLASH
130  req.mode.frequency = 4
131  req.mode.pulses = 0
132  req.mode.timeout = 0
133  req.mode.colors.append(ColorRGBA(230.0/255.0, 250.0/255.0, 250.0/255.0, 1.0))
134 
135  elif mode == 11:
136  req.mode.mode=LightModes.STATIC
137  req.mode.frequency = 1
138  req.mode.pulses = 0
139  req.mode.timeout = 0
140  req.mode.colors.append(ColorRGBA(150.0/255.0, 120.0/255.0, 255.0/255.0, 1.0))
141 
142  elif mode == 12:
143  req.mode.mode=LightModes.STATIC
144  req.mode.frequency = 1
145  req.mode.pulses = 0
146  req.mode.timeout = 0
147  req.mode.colors.append(ColorRGBA(255.0/255.0, 95.0/255.0, 1.0/255.0, 1.0))
148 
149  elif mode == 13: #breath fast in red (error)
150  req.mode.mode=LightModes.BREATH
151  req.mode.frequency = 0.8
152  req.mode.pulses = 0
153  req.mode.timeout = 0
154  req.mode.colors.append(ColorRGBA(1.0, 0.0, 0.0, 1.0))
155 
156  elif mode == 14: #breath fast in red (error)
157  req.mode.mode=LightModes.XMAS
158  req.mode.frequency = 0.8
159  req.mode.pulses = 0
160  req.mode.timeout = 0
161  req.mode.colors.append(ColorRGBA(1.0, 0.0, 0.0, 1.0))
162 
163  return req
164 
165 
166 if __name__ == '__main__':
167  rospy.init_node('light_service_test')
169  rospy.spin()


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