test_numpad.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 ##
00003 # Copyright (C) 2013 TopCoder Inc., All Rights Reserved.
00004 #
00005 # @author KennyAlive
00006 # @version 1.0
00007 #
00008 
00009 ## Tests for numpad
00010 
00011 PKG = 'gazebo_taskboard'
00012 NAME = 'test_numpad'
00013 
00014 import math
00015 import roslib
00016 roslib.load_manifest(PKG)
00017 
00018 import sys, unittest
00019 import os, os.path, threading, time
00020 import rospy, rostest
00021 
00022 from std_msgs.msg import String
00023 from helper import *
00024 from gazebo_taskboard.msg import *
00025 from gazebo_taskboard.srv import *
00026 
00027 button_states = ['UNSEL', 'UNSEL', 'UNSEL', 'UNSEL', 'UNSEL', 'UNSEL', 'UNSEL', 'UNSEL', 'UNSEL']
00028 led_states = ['OFF', 'OFF', 'OFF', 'OFF', 'OFF', 'OFF', 'OFF', 'OFF', 'OFF']
00029 
00030 def onMessage(message):
00031     global button_states
00032     if button_states[0] != message.A02_NUM_PAD_A1:
00033         rospy.loginfo("Num Pad button A1: " + message.A02_NUM_PAD_A1)
00034     button_states[0] = message.A02_NUM_PAD_A1
00035     
00036     if button_states[1] != message.A02_NUM_PAD_A2:
00037         rospy.loginfo("Num Pad button A2: " + message.A02_NUM_PAD_A2)
00038     button_states[1] = message.A02_NUM_PAD_A2
00039     
00040     if button_states[2] != message.A02_NUM_PAD_A3:
00041         rospy.loginfo("Num Pad button A3: " + message.A02_NUM_PAD_A3)
00042     button_states[2] = message.A02_NUM_PAD_A3
00043     
00044     if button_states[3] != message.A02_NUM_PAD_B1:
00045         rospy.loginfo("Num Pad button B1: " + message.A02_NUM_PAD_B1)
00046     button_states[3] = message.A02_NUM_PAD_B1
00047     
00048     if button_states[4] != message.A02_NUM_PAD_B2:
00049         rospy.loginfo("Num Pad button B2: " + message.A02_NUM_PAD_B2)
00050     button_states[4] = message.A02_NUM_PAD_B2
00051     
00052     if button_states[5] != message.A02_NUM_PAD_B3:
00053         rospy.loginfo("Num Pad button B3: " + message.A02_NUM_PAD_B3)
00054     button_states[5] = message.A02_NUM_PAD_B3
00055     
00056     if button_states[6] != message.A02_NUM_PAD_C1:
00057         rospy.loginfo("Num Pad button C1: " + message.A02_NUM_PAD_C1)
00058     button_states[6] = message.A02_NUM_PAD_C1
00059     
00060     if button_states[7] != message.A02_NUM_PAD_C2:
00061         rospy.loginfo("Num Pad button C2: " + message.A02_NUM_PAD_C2)
00062     button_states[7] = message.A02_NUM_PAD_C2
00063     
00064     if button_states[8] != message.A02_NUM_PAD_C3:
00065         rospy.loginfo("Num Pad button C3: " + message.A02_NUM_PAD_C3)
00066     button_states[8] = message.A02_NUM_PAD_C3
00067 
00068     global led_states
00069     if led_states[0] != message.A02_LED_NUM_PAD_A1:
00070         rospy.loginfo("Num Pad led A1: " + message.A02_LED_NUM_PAD_A1)
00071     led_states[0] = message.A02_LED_NUM_PAD_A1
00072 
00073     if led_states[1] != message.A02_LED_NUM_PAD_A2:
00074         rospy.loginfo("Num Pad led A2: " + message.A02_LED_NUM_PAD_A2)
00075     led_states[1] = message.A02_LED_NUM_PAD_A2
00076 
00077     if led_states[2] != message.A02_LED_NUM_PAD_A3:
00078         rospy.loginfo("Num Pad led A3: " + message.A02_LED_NUM_PAD_A3)
00079     led_states[2] = message.A02_LED_NUM_PAD_A3
00080 
00081     if led_states[3] != message.A02_LED_NUM_PAD_B1:
00082         rospy.loginfo("Num Pad led B1: " + message.A02_LED_NUM_PAD_B1)
00083     led_states[3] = message.A02_LED_NUM_PAD_B1
00084 
00085     if led_states[4] != message.A02_LED_NUM_PAD_B2:
00086         rospy.loginfo("Num Pad led B2: " + message.A02_LED_NUM_PAD_B2)
00087     led_states[4] = message.A02_LED_NUM_PAD_B2
00088 
00089     if led_states[5] != message.A02_LED_NUM_PAD_B3:
00090         rospy.loginfo("Num Pad led B3: " + message.A02_LED_NUM_PAD_B3)
00091     led_states[5] = message.A02_LED_NUM_PAD_B3
00092 
00093     if led_states[6] != message.A02_LED_NUM_PAD_C1:
00094         rospy.loginfo("Num Pad led C1: " + message.A02_LED_NUM_PAD_C1)
00095     led_states[6] = message.A02_LED_NUM_PAD_C1
00096 
00097     if led_states[7] != message.A02_LED_NUM_PAD_C2:
00098         rospy.loginfo("Num Pad led C2: " + message.A02_LED_NUM_PAD_C2)
00099     led_states[7] = message.A02_LED_NUM_PAD_C2
00100 
00101     if led_states[8] != message.A02_LED_NUM_PAD_C3:
00102         rospy.loginfo("Num Pad led C3: " + message.A02_LED_NUM_PAD_C3)
00103     led_states[8] = message.A02_LED_NUM_PAD_C3
00104 
00105 class NumPadTest(unittest.TestCase):
00106     def __init__(self, *args):
00107        super(NumPadTest, self).__init__(*args)
00108 
00109     def test_numpad(self):
00110         rospy.init_node(NAME, anonymous=True)
00111 
00112         rospy.Subscriber(TOPIC_NAME, TaskboardPanelA, onMessage)
00113 
00114         rospy.loginfo("Waiting for gazebo ...")
00115         rospy.wait_for_service(SERVICE_MANIPULATE_POWER_COVER)
00116         rospy.wait_for_service(SERVICE_MANIPULATE_POWER_SWITCH)
00117         rospy.wait_for_service(SERVICE_MANIPULATE_NUMPAD)
00118         wait(GUI_WAIT_TIME)
00119         rospy.loginfo("Testing has started")
00120 
00121         try:
00122             manipulatePowerCover = rospy.ServiceProxy(SERVICE_MANIPULATE_POWER_COVER, ManipulatePowerCover)
00123             manipulatePowerSwitch = rospy.ServiceProxy(SERVICE_MANIPULATE_POWER_SWITCH, ManipulatePowerSwitch)
00124             manipulateNumPad = rospy.ServiceProxy(SERVICE_MANIPULATE_NUMPAD, ManipulateNumPad)
00125 
00126             # !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
00127             # Open power cover
00128             manipulatePowerCover(deg2rad(50), 0.5)
00129             wait()
00130             # Turn on power
00131             manipulatePowerSwitch(deg2rad(30), 0.5)
00132             wait()
00133             ## !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
00134 
00135             # Turn on all leds
00136             for i in range(9):
00137                 manipulateNumPad(i, 20.0, 0.25)
00138                 wait(1.5)
00139                 assert led_states[i] == 'ON'
00140                 rospy.loginfo("Case Done.")
00141 
00142             # Turn off some leds
00143             for i in range(1, 9, 2):
00144                 manipulateNumPad(i, 20.0, 0.5)
00145                 wait()
00146                 assert led_states[i-1] == 'ON'
00147                 assert led_states[i] == 'OFF'
00148                 rospy.loginfo("Case Done")
00149 
00150             ## !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
00151             # Turn off the power
00152             manipulatePowerSwitch(deg2rad(-30), 0.5)
00153             wait()
00154             # Close power cover
00155             manipulatePowerCover(deg2rad(-50), 0.5)
00156             wait()
00157             ## !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
00158 
00159             # Check that all leds are off
00160             for i in range(9):
00161                 assert led_states[i] == 'OFF'
00162             rospy.loginfo("Case Done")
00163             
00164             # Without power led is off
00165             manipulateNumPad(0, 20.0, 1.0)
00166             wait()
00167             assert led_states[0] == 'OFF'
00168             rospy.loginfo("Case Done")
00169 
00170             # Press on button long enough and check that it is in SEL state
00171             manipulateNumPad(3, 20.0, 8.0)
00172             wait(1)
00173             assert button_states[3] == 'SEL'
00174             rospy.loginfo("Case Done")
00175 
00176         except rospy.ServiceException, e:
00177             print "Service call failed: %s"%e
00178 
00179         time.sleep(0.5)
00180 
00181 if __name__ == '__main__':
00182     print "Waiting for test to start at time "
00183     rostest.run(PKG, 'test_numpad', NumPadTest)


gazebo_taskboard
Author(s): TCSASSEMBLER
autogenerated on Mon Oct 6 2014 02:45:46