test_loader.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2010, Willow Garage, Inc.
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without
00009 # modification, are permitted provided that the following conditions
00010 # are met:
00011 #
00012 #  * Redistributions of source code must retain the above copyright
00013 #    notice, this list of conditions and the following disclaimer.
00014 #  * Redistributions in binary form must reproduce the above
00015 #    copyright notice, this list of conditions and the following
00016 #    disclaimer in the documentation and/or other materials provided
00017 #    with the distribution.
00018 #  * Neither the name of the Willow Garage nor the names of its
00019 #    contributors may be used to endorse or promote products derived
00020 #    from this software without specific prior written permission.
00021 #
00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 # POSSIBILITY OF SUCH DAMAGE.
00034 
00035 ##\author Kevin Watts
00036 
00037 PKG = 'qualification'
00038 import roslib; roslib.load_manifest(PKG)
00039 
00040 import os, sys
00041 from xml.dom import minidom
00042 
00043 from test import Test
00044 from wg_station import WGTestStation
00045 
00046 TESTS_DIR = os.path.join(roslib.packages.get_pkg_dir(PKG), 'tests')
00047 CONFIG_DIR = os.path.join(roslib.packages.get_pkg_dir(PKG), 'config')
00048 QUAL_DIR = roslib.packages.get_pkg_dir(PKG)
00049 
00050 def load_tests_from_map(tests, debugs = []):
00051   """
00052   Loads tests from tests/tests.xml configuration file
00053 
00054   \param tests {} : Test by serial. { str: [ Test ] }
00055   \return True if loaded successfully and all tests validated
00056   """
00057   # Load test directory
00058   tests_xml_path = os.path.join(TESTS_DIR, 'tests.xml')
00059   try:
00060     doc = minidom.parse(tests_xml_path)
00061   except IOError:
00062     print >> sys.stderr, "Could not load tests description from '%s'. IOError, file may be invalid."%(tests_xml_path)
00063     return False  
00064   except Exception:
00065     print >> sys.stderr, "Could not load tests description from '%s'. Unknown exception."%(tests_xml_path)
00066     import traceback
00067     traceback.print_exc()
00068     return False  
00069   
00070   # Loads tests by serial number of part
00071   test_elements = doc.getElementsByTagName('test')
00072   for tst in test_elements:
00073     if not tst.attributes.has_key('serial'):
00074       print >> sys.stderr, "Tst XML element does not have attribute \"serial\". Unable to load. XML: %s" % str(tst)
00075       return False
00076     serial = tst.attributes['serial'].value
00077     if not len(serial) == 7: 
00078       print >> sys.stderr, "Serial number is invalid: %s" % serial
00079       return False
00080 
00081     if not tst.attributes.has_key('file'):
00082       print >> sys.stderr, "Test XML element does not have attribute \"file\". Unable to load. XML: %s" % str(tst)
00083       return False
00084     test_file = tst.attributes['file'].value
00085 
00086     if not tst.attributes.has_key('descrip'):
00087       print >> sys.stderr, "Test XML element does not have attribute \"descrip\". Unable to load. XML: %s" % str(tst)
00088       return False
00089     descrip = tst.attributes['descrip'].value
00090 
00091     # Mark as debug test, which allows us to run outside debug mode
00092     debug_test = tst.attributes.has_key('debug') and tst.attributes['debug'].value.lower() == "true"
00093     if debug_test:
00094       debugs.append(serial)
00095 
00096     test_path = os.path.join(os.path.join(TESTS_DIR, test_file))
00097     test_dir = os.path.dirname(test_path)
00098     test_str = open(test_path).read()
00099 
00100     my_test = Test(descrip, serial[3:7])
00101     try:
00102       if not my_test.load(test_str, test_dir):
00103         print >> sys.stderr, "Unable to load test %s" % descrip
00104         return False
00105     except Exception, e:
00106       print >> sys.stderr, "Unable to load test %s" % descrip
00107       import traceback
00108       traceback.print_exc()
00109       return False
00110 
00111     my_test.debug_ok = debug_test
00112 
00113     tests.setdefault(serial, []).append(my_test)
00114     
00115   return True
00116 
00117 def load_configs_from_map(config_files):
00118   """
00119   Loads configuration scripts from config/configs.xml configuration file
00120 
00121   \param tests {} : Configs by serial. { str: [ Test ] }
00122   \return True if loaded successfully and all tests validated
00123   """
00124   # Load part configuration scripts
00125   config_xml_path = os.path.join(CONFIG_DIR, 'configs.xml')
00126   try:
00127     doc = minidom.parse(config_xml_path)
00128   except IOError:
00129     print >> sys.stderr, "Could not load configuation scripts from '%s'. IOError, file may be invalid."%(config_xml_path)
00130     return False
00131   except Exception:
00132     print >> sys.stderr, "Could not load tests description from '%s'. Unknown exception."%(tests_xml_path)
00133     import traceback
00134     traceback.print_exc()
00135     return False  
00136     
00137   config_elements = doc.getElementsByTagName('config')
00138   for conf in config_elements:
00139     if not conf.attributes.has_key('serial'):
00140       print >> sys.stderr, "Test XML element does not have attribute \"serial\". Unable to load. XML: %s" % str(conf)
00141       return False
00142     serial = conf.attributes['serial'].value
00143     if not len(serial) == 7: 
00144       print >> sys.stderr, "Serial number is invalid: %s" % serial
00145       return False
00146 
00147     if not conf.attributes.has_key('file'):
00148       print >> sys.stderr, "Test XML element does not have attribute \"file\". Unable to load. XML: %s" % str(conf)
00149       return False
00150     test_file = conf.attributes['file'].value
00151 
00152     if not conf.attributes.has_key('descrip'):
00153       print >> sys.stderr, "Test XML element does not have attribute \"descrip\". Unable to load. XML: %s" % str(conf)
00154       return False
00155     descrip = conf.attributes['descrip'].value
00156       
00157     powerboard = True
00158     if conf.attributes.has_key('powerboard'):
00159       powerboard = conf.attributes['powerboard'].value.lower() == "true"
00160       
00161     timeout = 600
00162     if conf.attributes.has_key('timeout'):
00163       timeout = int(conf.attributes['timeout'].value)
00164 
00165     # Generate test XML. If we need power board, add prestartup/shutdown
00166     # to turn on/off power
00167     tst = ['<test name="%s" id="%s" >' % (descrip, serial)]
00168     if powerboard:
00169       tst.append('<pre_startup name="Power On" timeout="30">scripts/power_cycle.launch</pre_startup>')
00170     tst.append('<pre_startup name="%s" timeout="%d">config/%s</pre_startup>' % (descrip, timeout, test_file))
00171     tst.append('<subtest name="%s Test" timeout="30">config/subtest_conf.launch</subtest>' % (descrip))
00172     if powerboard:
00173       tst.append('<shutdown name="Shutdown" timeout="30">scripts/power_board_disable.launch</shutdown>')
00174     tst.append('</test>')
00175 
00176     test_str = '\n'.join(tst)
00177 
00178     my_conf = Test(descrip, serial[3:7])
00179     if not my_conf.load(test_str, QUAL_DIR):
00180       print >> sys.stderr, "Unable to load test %s" % descrip
00181       print >> sys.stderr, "Test XML: %s" % tst
00182       return False
00183   
00184     my_conf.debug_ok = conf.attributes.has_key('debug') and conf.attributes['debug'].value.lower() == "true"
00185   
00186     config_files.setdefault(serial, []).append(my_conf)
00187 
00188   return True
00189 
00190 
00191 def load_wg_station_map(wg_teststations):
00192   """
00193   Loads "map" of WG test stations. Each station has a GUI, a remote host
00194   and a power board.
00195   \param wg_teststations { str : WGTestStation } : Output dictionary of test stations
00196   \return True if loaded successfully
00197   """
00198   map_xml_path = os.path.join(roslib.packages.get_pkg_dir(PKG), 'wg_map.xml')
00199   
00200   try:
00201     doc = minidom.parse(map_xml_path)
00202   except IOError:
00203     print >> sys.stderr, "Could not load test map from '%s'"%(map_xml_path)
00204     return False
00205 
00206   stations = doc.getElementsByTagName('station')
00207 
00208   for st in stations:
00209     my_station = WGTestStation()
00210 
00211     if not my_station.xmlLoad(st):
00212       return False
00213     wg_teststations[my_station.gui_host] = my_station
00214 
00215   return True


qualification
Author(s): Kevin Watts (watts@willowgarage.com), Josh Faust (jfaust@willowgarage.com)
autogenerated on Sat Dec 28 2013 17:57:34