test_rocker_switch_a01.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 rocker switch A01
00010 
00011 PKG = 'iss_taskboard_gazebo'
00012 NAME = 'test_rocker_switch_a01'
00013 
00014 import math
00015 import roslib
00016 roslib.load_manifest(PKG)
00017 
00018 import sys
00019 import unittest
00020 import os
00021 import os.path
00022 import threading
00023 import time
00024 import rospy
00025 import rostest
00026 
00027 from std_msgs.msg import String
00028 from helper import *
00029 from iss_taskboard_gazebo.msg import *
00030 from iss_taskboard_gazebo.srv import *
00031 
00032 rocker_switch_state = 'CENTER'
00033 led_top_state = 'OFF'
00034 led_bottom_state = 'OFF'
00035 
00036 
00037 def onMessage(message):
00038     global rocker_switch_state
00039     if rocker_switch_state != message.A01_ROCKER_SWITCH:
00040         rospy.loginfo("Rocker switch A01: " + message.A01_ROCKER_SWITCH)
00041     rocker_switch_state = message.A01_ROCKER_SWITCH
00042 
00043     global led_top_state
00044     if led_top_state != message.A01_ROCKER_LED_TOP:
00045         rospy.loginfo("Rocker LED TOP: " + message.A01_ROCKER_LED_TOP)
00046     led_top_state = message.A01_ROCKER_LED_TOP
00047 
00048     global led_bottom_state
00049     if led_bottom_state != message.A01_ROCKER_LED_BOTTOM:
00050         rospy.loginfo("Rocker LED BOTTOM: " + message.A01_ROCKER_LED_BOTTOM)
00051     led_bottom_state = message.A01_ROCKER_LED_BOTTOM
00052 
00053 
00054 class RockerSwitchA01Test(unittest.TestCase):
00055 
00056     def __init__(self, *args):
00057         super(RockerSwitchA01Test, self).__init__(*args)
00058 
00059     def test_rocker_switch_a01(self):
00060         rospy.init_node(NAME, anonymous=True)
00061 
00062         rospy.Subscriber(TOPIC_NAME, TaskboardPanelA, onMessage)
00063 
00064         rospy.loginfo("Waiting for gazebo ...")
00065         rospy.wait_for_service(SERVICE_MANIPULATE_POWER_COVER)
00066         rospy.wait_for_service(SERVICE_MANIPULATE_POWER_SWITCH)
00067         rospy.wait_for_service(SERVICE_MANIPULATE_ROCKER_SWITCH)
00068         wait(GUI_WAIT_TIME)
00069         rospy.loginfo("Testing has started")
00070 
00071         try:
00072             manipulatePowerCover = rospy.ServiceProxy(SERVICE_MANIPULATE_POWER_COVER, ManipulatePowerCover)
00073             manipulatePowerSwitch = rospy.ServiceProxy(SERVICE_MANIPULATE_POWER_SWITCH, ManipulatePowerSwitch)
00074             manipulateRockerSwitchA01 = rospy.ServiceProxy(SERVICE_MANIPULATE_ROCKER_SWITCH, ManipulateRockerSwitch)
00075 
00076             # !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
00077             # Open power cover
00078             manipulatePowerCover(deg2rad(50), 1)
00079             wait()
00080             # Turn on power
00081             manipulatePowerSwitch(deg2rad(30), 1)
00082             wait()
00083             # !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
00084 
00085             # Apply force and put rocker switch to UP position but do not stay in UP for too long
00086             manipulateRockerSwitchA01(10, 1)
00087             wait(4)
00088             assert rocker_switch_state == 'CENTER'
00089             assert led_top_state == 'OFF'
00090             assert led_bottom_state == 'OFF'
00091             rospy.loginfo("Case 1 Done.")
00092 
00093             # Apply force and put rocker switch to UP position and stay in UP for some time (apply force long enough)
00094             manipulateRockerSwitchA01(10, 8)
00095             wait(1)
00096             assert rocker_switch_state == 'UP'
00097             assert led_top_state == 'ON'
00098             assert led_bottom_state == 'OFF'
00099             rospy.loginfo("Case 2 Done.")
00100 
00101             # Apply force and put rocker switch to DOWN position but do not stay in DOWN for too long
00102             manipulateRockerSwitchA01(-10, 1)
00103             wait(4)
00104             assert rocker_switch_state == 'CENTER'
00105             assert led_top_state == 'OFF'
00106             assert led_bottom_state == 'OFF'
00107             rospy.loginfo("Case 3 Done.")
00108 
00109             # Apply force and put rocker switch to DOWN position and stay in DOWN for some time (apply force long enough)
00110             manipulateRockerSwitchA01(-10, 8)
00111             wait(1)
00112             assert rocker_switch_state == 'DOWN'
00113             assert led_top_state == 'OFF'
00114             assert led_bottom_state == 'ON'
00115             rospy.loginfo("Case 4 Done.")
00116 
00117             # !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
00118             # Turn off the power
00119             manipulatePowerSwitch(deg2rad(-30), 1)
00120             wait()
00121             # Close power cover
00122             manipulatePowerCover(deg2rad(-50), 1)
00123             wait()
00124             # !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
00125 
00126             # Apply force and put rocker switch to UP position and stay in UP for some time (apply force long enough)
00127             manipulateRockerSwitchA01(10, 8)
00128             wait(1)
00129             assert rocker_switch_state == 'UP'
00130             assert led_top_state == 'OFF'
00131             assert led_bottom_state == 'OFF'
00132             rospy.loginfo("Case 5 Done.")
00133 
00134             # Apply force and put rocker switch to DOWN position and stay in DOWN for some time (apply force long enough)
00135             manipulateRockerSwitchA01(-10, 8)
00136             wait(1)
00137             assert rocker_switch_state == 'DOWN'
00138             assert led_top_state == 'OFF'
00139             assert led_bottom_state == 'OFF'
00140             rospy.loginfo("Case 6 Done.")
00141 
00142             # Check the final state
00143             wait(9)
00144             assert rocker_switch_state == 'CENTER'
00145             assert led_top_state == 'OFF'
00146             assert led_bottom_state == 'OFF'
00147             rospy.loginfo("Case 7 Done.")
00148 
00149         except rospy.ServiceException, e:
00150             print "Service call failed: %s" % e
00151 
00152         time.sleep(1.0)
00153 
00154 if __name__ == '__main__':
00155     print "Waiting for test to start at time "
00156     rostest.run(PKG, 'test_rocker_switch_a01', RockerSwitchA01Test)


iss_taskboard_gazebo
Author(s):
autogenerated on Sat Jun 8 2019 19:20:28