Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 PKG = 'iss_taskboard_gazebo'
00012 NAME = 'test_power_switch'
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 power_cover_state = 'DOWN'
00033 power_switch_state = 'DOWN'
00034 power_led_state = 'OFF'
00035
00036
00037 def onMessage(msg):
00038 global power_cover_state
00039 power_cover_state = msg.PANEL_POWER_COVER
00040
00041 global power_switch_state
00042 if power_switch_state != msg.PANEL_POWER_SWITCH:
00043 rospy.loginfo("Power switch state: " + msg.PANEL_POWER_SWITCH)
00044 power_switch_state = msg.PANEL_POWER_SWITCH
00045
00046 global power_led_state
00047 if power_led_state != msg.PANEL_POWER_LED:
00048 rospy.loginfo("Power LED state: " + msg.PANEL_POWER_LED)
00049 power_led_state = msg.PANEL_POWER_LED
00050
00051
00052 class PowerSwitchTest(unittest.TestCase):
00053
00054 def __init__(self, *args):
00055 super(PowerSwitchTest, self).__init__(*args)
00056
00057 def test_power_switch(self):
00058 rospy.init_node(NAME, anonymous=True)
00059
00060 rospy.Subscriber(TOPIC_NAME, TaskboardPanelA, onMessage)
00061
00062 rospy.loginfo("Waiting for gazebo ...")
00063 rospy.wait_for_service(SERVICE_MANIPULATE_POWER_COVER)
00064 rospy.wait_for_service(SERVICE_MANIPULATE_POWER_SWITCH)
00065 wait(GUI_WAIT_TIME)
00066 rospy.loginfo("Testing has started")
00067
00068 try:
00069 manipulatePowerCover = rospy.ServiceProxy(SERVICE_MANIPULATE_POWER_COVER, ManipulatePowerCover)
00070 manipulatePowerSwitch = rospy.ServiceProxy(SERVICE_MANIPULATE_POWER_SWITCH, ManipulatePowerSwitch)
00071
00072 manipulatePowerCover(deg2rad(50), 1)
00073 wait()
00074 assert power_cover_state == 'UP'
00075 rospy.loginfo("Case 1 Done.")
00076
00077 manipulatePowerSwitch(deg2rad(30), 1)
00078 wait()
00079 assert power_switch_state == 'UP'
00080 rospy.loginfo("Case 2 Done.")
00081
00082 manipulatePowerSwitch(deg2rad(-10), 0.5)
00083 wait()
00084 assert power_switch_state == 'UP'
00085 rospy.loginfo("Case 3 Done.")
00086
00087 manipulatePowerSwitch(deg2rad(-20), 0.5)
00088 wait()
00089 assert power_switch_state == 'UP'
00090 rospy.loginfo("Case 4 Done.")
00091
00092 manipulatePowerSwitch(deg2rad(-27), 0.75)
00093 wait()
00094 assert power_switch_state == 'DOWN'
00095 rospy.loginfo("Case 5 Done.")
00096
00097 manipulatePowerSwitch(deg2rad(15), 0.3)
00098 wait()
00099 assert power_switch_state == 'DOWN'
00100 rospy.loginfo("Case 6 Done.")
00101
00102 manipulatePowerSwitch(deg2rad(35), 0.75)
00103 wait()
00104 assert power_switch_state == 'UP'
00105 rospy.loginfo("Case 7 Done.")
00106
00107 manipulatePowerSwitch(deg2rad(-35), 0.75)
00108 wait()
00109 assert power_switch_state == 'DOWN'
00110 rospy.loginfo("Case 8 Done.")
00111
00112 except rospy.ServiceException, e:
00113 print "Service call failed: %s" % e
00114
00115 time.sleep(3.0)
00116
00117 if __name__ == '__main__':
00118 print "Waiting for test to start at time "
00119 rostest.run(PKG, 'test_power_switch', PowerSwitchTest)