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