light_service_test.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #   http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 
00018 import rospy
00019 import actionlib
00020 import random
00021 
00022 from cob_light.msg import *
00023 
00024 from cob_light.srv import SetLightMode
00025 from cob_light.srv import SetLightModeRequest
00026 from cob_light.srv import SetLightModeResponse
00027 
00028 from std_msgs.msg import ColorRGBA
00029 
00030 class ActionTestScript(object):
00031     def __init__(self):
00032         self.executeMode(0)
00033 
00034     def executeMode(self, event):
00035         rospy.loginfo("setting service mode")
00036         mode = self.getLightMode(random.randint(0,14))
00037 
00038         srv_light = rospy.ServiceProxy('/light_torso/set_light', SetLightMode)
00039         srv_light.call(mode)
00040 
00041         duration = random.uniform(0, 0.5)
00042         self.timer = rospy.Timer(rospy.Duration(duration), self.executeMode, True)
00043 
00044     def getLightMode(self, mode):
00045         req = SetLightModeRequest()
00046         req.mode.priority = 4
00047 
00048         if mode == 0:
00049             req.mode.mode=LightModes.BREATH
00050             req.mode.frequency = 0.3
00051             req.mode.pulses = 2
00052             req.mode.timeout = 0
00053             req.mode.colors.append(ColorRGBA(1.0,1.0,1.0,1.0))
00054 
00055         elif mode == 1:
00056             req.mode.mode=LightModes.FLASH
00057             req.mode.frequency = 2
00058             req.mode.pulses = 3
00059             req.mode.timeout = 0
00060             req.mode.colors.append(ColorRGBA(1.0,1.0,1.0,1.0))
00061 
00062         elif mode == 2:
00063             req.mode.mode=LightModes.BREATH
00064             req.mode.frequency = 0.4
00065             req.mode.pulses = 0
00066             req.mode.timeout = 0
00067             req.mode.colors.append(ColorRGBA(170.0/255.0, 250.0/255.0, 70.0/255.0, 1.0))
00068 
00069         elif mode == 3:
00070             req.mode.mode=LightModes.BREATH
00071             req.mode.frequency = 0.3
00072             req.mode.pulses = 0
00073             req.mode.timeout = 0
00074             req.mode.colors.append(ColorRGBA(70.0/255.0, 140.0/255.0, 250.0/255.0, 1.0))
00075 
00076         elif mode == 4:
00077             req.mode.mode=LightModes.BREATH
00078             req.mode.frequency = 0.3
00079             req.mode.pulses = 0
00080             req.mode.timeout = 0
00081             req.mode.colors.append(ColorRGBA(240.0/255.0, 250.0/255.0, 70.0/255.0, 1.0))
00082 
00083         elif mode == 5:
00084             req.mode.mode=LightModes.BREATH
00085             req.mode.frequency = 0.3
00086             req.mode.pulses = 0
00087             req.mode.timeout = 0
00088             req.mode.colors.append(ColorRGBA(70.0/255.0, 240.0/255.0, 250.0/255.0, 1.0))
00089 
00090         elif mode == 6: #static yellow black - barrier tape
00091             yellow = ColorRGBA(70.0/255.0, 240.0/255.0, 250.0/255.0, 1.0)
00092             black = ColorRGBA()
00093             req.mode.mode=LightModes.BREATH
00094             req.mode.frequency = 0.3
00095             req.mode.pulses = 0
00096             req.mode.timeout = 0
00097             #58 leds
00098             num_segs = 6
00099             iterations = int(num_segs/2)
00100             seg_div = int(58/num_segs)
00101             for i in range(0, iterations):
00102                 for j in range (0, seg_div):
00103                     req.mode.colors.append(yellow)
00104                 for j in range (0, seg_div):
00105                     req.mode.colors.append(black)
00106 
00107         elif mode == 7:
00108             req.mode.mode=LightModes.BREATH
00109             req.mode.frequency = 0.3
00110             req.mode.pulses = 0
00111             req.mode.timeout = 0
00112             req.mode.colors.append(ColorRGBA(250.0/255.0, 70.0/255.0, 70.0/255.0, 1.0))
00113 
00114         elif mode == 8:
00115             req.mode.mode=LightModes.BREATH
00116             req.mode.frequency = 0.3
00117             req.mode.pulses = 0
00118             req.mode.timeout = 0
00119             req.mode.colors.append(ColorRGBA(230.0/255.0, 250.0/255.0, 250.0/255.0, 1.0))
00120 
00121         elif mode == 9:
00122             req.mode.mode=LightModes.FADE_COLOR
00123             req.mode.frequency = 0.5
00124             req.mode.pulses = 0
00125             req.mode.timeout = 0
00126             req.mode.colors.append(ColorRGBA(1,1,1,1))
00127 
00128         elif mode == 10:
00129             req.mode.mode=LightModes.FLASH
00130             req.mode.frequency = 4
00131             req.mode.pulses = 0
00132             req.mode.timeout = 0
00133             req.mode.colors.append(ColorRGBA(230.0/255.0, 250.0/255.0, 250.0/255.0, 1.0))
00134 
00135         elif mode == 11:
00136             req.mode.mode=LightModes.STATIC
00137             req.mode.frequency = 1
00138             req.mode.pulses = 0
00139             req.mode.timeout = 0
00140             req.mode.colors.append(ColorRGBA(150.0/255.0, 120.0/255.0, 255.0/255.0, 1.0))
00141 
00142         elif mode == 12:
00143             req.mode.mode=LightModes.STATIC
00144             req.mode.frequency = 1
00145             req.mode.pulses = 0
00146             req.mode.timeout = 0
00147             req.mode.colors.append(ColorRGBA(255.0/255.0, 95.0/255.0, 1.0/255.0, 1.0))
00148 
00149         elif mode == 13: #breath fast in red (error)
00150             req.mode.mode=LightModes.BREATH
00151             req.mode.frequency = 0.8
00152             req.mode.pulses = 0
00153             req.mode.timeout = 0
00154             req.mode.colors.append(ColorRGBA(1.0, 0.0, 0.0, 1.0))
00155 
00156         elif mode == 14: #breath fast in red (error)
00157             req.mode.mode=LightModes.XMAS
00158             req.mode.frequency = 0.8
00159             req.mode.pulses = 0
00160             req.mode.timeout = 0
00161             req.mode.colors.append(ColorRGBA(1.0, 0.0, 0.0, 1.0))
00162 
00163         return req
00164 
00165 
00166 if __name__ == '__main__':
00167   rospy.init_node('light_service_test')
00168   ActionTestScript()
00169   rospy.spin()


cob_light
Author(s): Benjamin Maidel
autogenerated on Sat Jun 8 2019 21:02:07