test_power_cover.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 ## Test for power cover
00010 
00011 PKG = 'iss_taskboard_gazebo'
00012 NAME = 'test_power_cover'
00013 
00014 import math
00015 
00016 import sys, unittest
00017 import os, os.path, threading, time
00018 import rospy, rostest
00019 
00020 from std_msgs.msg import String
00021 from helper import *
00022 from iss_taskboard_gazebo.msg import *
00023 from iss_taskboard_gazebo.srv import *
00024 
00025 last_state = 'DOWN'
00026 
00027 def onMessage(msg):
00028     global last_state
00029     if last_state != msg.PANEL_POWER_COVER:
00030         rospy.loginfo("NEW STATE: " + msg.PANEL_POWER_COVER)
00031     last_state = msg.PANEL_POWER_COVER
00032 
00033 class PowerCoverTest(unittest.TestCase):
00034     def __init__(self, *args):
00035        super(PowerCoverTest, self).__init__(*args)
00036        
00037     def test_power_cover(self):
00038         rospy.init_node(NAME, anonymous=True)
00039 
00040         rospy.Subscriber(TOPIC_NAME, TaskboardPanelA, onMessage)
00041 
00042         print "Waiting for gazebo ..."
00043         rospy.wait_for_service(SERVICE_MANIPULATE_POWER_COVER)
00044         wait(GUI_WAIT_TIME)
00045         print "Test started."
00046 
00047         try:
00048             manipulatePowerCover = rospy.ServiceProxy(SERVICE_MANIPULATE_POWER_COVER, ManipulatePowerCover)
00049             print "Test 20, 0.5" 
00050             manipulatePowerCover(deg2rad(20), 0.5)
00051             wait()
00052             assert last_state == 'DOWN'
00053             rospy.loginfo("Case 1 Done.")
00054 
00055             print "Test 40, 0.75"
00056             manipulatePowerCover(deg2rad(40), 0.75)
00057             wait()
00058             assert last_state == 'DOWN'
00059             rospy.loginfo("Case 2 Done.")
00060 
00061             print "Test 50, 1"
00062             manipulatePowerCover(deg2rad(50), 1)
00063             wait()
00064             assert last_state == 'UP'
00065             rospy.loginfo("Case 3 Done.")
00066 
00067             print "Test -25, 0.5"
00068             manipulatePowerCover(deg2rad(-25), 0.5)
00069             wait()
00070             assert last_state == 'UP'
00071             rospy.loginfo("Case 4 Done.")
00072 
00073             print "Test -40, 0.5"
00074             manipulatePowerCover(deg2rad(-40), 0.5)
00075             wait()
00076             assert last_state == 'UP'
00077             rospy.loginfo("Case 5 Done.")
00078 
00079             print "Test -50, 0.5"
00080             manipulatePowerCover(deg2rad(-50), 0.5)
00081             wait()
00082             assert last_state == 'DOWN'
00083             rospy.loginfo("Case 6 Done.")
00084 
00085             rospy.loginfo("Test 70, 0.75")
00086             manipulatePowerCover(deg2rad(70), 0.75)
00087             wait()
00088             assert last_state == 'UP'
00089             rospy.loginfo("Case 7 Done.")
00090 
00091             print "Test -80, 1"
00092             manipulatePowerCover(deg2rad(-80), 1.0)
00093             wait()
00094             assert last_state == 'DOWN'
00095             rospy.loginfo("Case 8 Done.")
00096 
00097         except rospy.ServiceException, e:
00098             print "Service call failed: %s"%e
00099         
00100         time.sleep(2.0)
00101 
00102 if __name__ == '__main__':
00103     print "Waiting for test to start at time "
00104     rostest.run(PKG, NAME, PowerCoverTest, sys.argv)


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