smoke_test.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (c) 2013-2015, Rethink Robotics
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions are met:
00008 #
00009 # 1. Redistributions of source code must retain the above copyright notice,
00010 #    this list of conditions and the following disclaimer.
00011 # 2. Redistributions in binary form must reproduce the above copyright
00012 #    notice, this list of conditions and the following disclaimer in the
00013 #    documentation and/or other materials provided with the distribution.
00014 # 3. Neither the name of the Rethink Robotics nor the names of its
00015 #    contributors may be used to endorse or promote products derived from
00016 #    this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028 # POSSIBILITY OF SUCH DAMAGE.
00029 
00030 """
00031 RSDK Smoke Test Execution
00032 """
00033 import sys
00034 import time
00035 import argparse
00036 import re
00037 import socket
00038 import traceback
00039 
00040 import rospy
00041 
00042 from baxter_tools import smoketests
00043 
00044 
00045 def run_test(tname, fname, proceed):
00046     """
00047     Execution of the tests where starting, finishing and error handeling
00048     occurs.
00049     """
00050     try:
00051         cur_test = getattr(smoketests, tname)(tname)
00052     except AttributeError:
00053         print("Exiting: %s is not a valid smoke test." % tname)
00054         sys.exit(1)
00055     except:
00056         print("Exiting: failed during intialization.")
00057         traceback.print_exc()
00058         sys.exit(1)
00059 
00060     cur_test.start_test()
00061     cur_test.finish_test(fname)
00062     if (not proceed and cur_test.result[0] == False or
00063     'KeyboardInterrupt' in cur_test.result[1]):
00064         print("Exiting: Failed Test %s" % tname)
00065         sys.exit(1)
00066 
00067 
00068 def test_help():
00069     """
00070     Help text for argparse describing available sdk tests.
00071     """
00072     return """Specify an individual test for execution
00073     TESTS:
00074     Enable    - Verify ability to enable, check state and disable baxter
00075     Messages  - Verify messages being published and ability to subscribe
00076     Services  - Verify services available and ability to make calls as client
00077     Head      - Move the head pan and tilt, display image to screen
00078     MoveArms  - Move both arms through entire joint range
00079     Grippers  - Calibrate and move grippers using position and velocity control
00080     BlinkLEDs - Blink Navigator LEDs
00081     Cameras   - Verify camera publishing and visualization
00082     """
00083 
00084 
00085 def get_version():
00086     """
00087     Get current software version number from param server.
00088     """
00089     try:
00090         version = rospy.get_param('/rethink/software_version').rsplit('.', 1)[0]
00091     except socket.error:
00092         print("Exiting: Could not communicate with ROS Master to determine " +
00093               "Software version")
00094         sys.exit(1)
00095     except:
00096         print("Exiting: Could not determine SW version from param " +
00097             "'/rethink/software_version'")
00098         sys.exit(1)
00099     return version
00100 
00101 
00102 def ros_init():
00103     """
00104     Initialize rsdk_smoke_test ros node.
00105     """
00106     print("Initializing node 'rsdk_smoke_test'\n")
00107     rospy.init_node('rsdk_smoke_test', disable_signals=True)
00108 
00109 
00110 def main():
00111     format = argparse.RawTextHelpFormatter
00112     parser = argparse.ArgumentParser(formatter_class=format)
00113     parser.add_argument('-p', '--proceed', action='store_true',
00114         help="Continue testing after a failed test until all tests complete")
00115     parser.add_argument('-t', '--test', help=test_help())
00116     args = parser.parse_args(rospy.myargv()[1:])
00117 
00118     test_dict = {
00119         'version': None,
00120         'valid_tests': {
00121             '0.7.0': ['Enable', 'Messages', 'Services', 'Head', 'BlinkLEDs',
00122                       'Cameras'],
00123             '1.0.0': ['Enable', 'Messages', 'Services', 'Head', 'MoveArms',
00124                       'Grippers', 'BlinkLEDs', 'Cameras'],
00125             '1.1.0': ['Enable', 'Messages', 'Services', 'Head', 'MoveArms',
00126                       'Grippers', 'BlinkLEDs', 'Cameras'],
00127             '1.1.1': ['Enable', 'Messages', 'Services', 'Head', 'MoveArms',
00128                       'Grippers', 'BlinkLEDs', 'Cameras'],
00129             }
00130         }
00131 
00132     test_dict['version'] = get_version()
00133     if not test_dict['version'] in test_dict['valid_tests'].keys():
00134         print("Exiting: No tests specified for your software version: %s" %
00135             (test_dict['version']))
00136         return 1
00137 
00138     try:
00139         raw_input("Press <Enter> to Begin Smoke Test\n")
00140     except Exception:
00141         print("\nExiting.")
00142         return 1
00143 
00144     serial = rospy.get_param("manifest/robot_serial")
00145     cur_time = time.localtime()
00146     filename = ("%s-%s.%s.%s-rsdk-%s.smoketest" %
00147                 (serial, cur_time.tm_mon, cur_time.tm_mday,
00148                  cur_time.tm_year, test_dict['version'],)
00149                 )
00150     if args.test == None:
00151         print 'Performing All Tests'
00152         ros_init()
00153         for t in test_dict['valid_tests'][test_dict['version']]:
00154             run_test(t, filename, args.proceed)
00155     elif args.test in test_dict['valid_tests'][test_dict['version']]:
00156         ros_init()
00157         run_test(args.test, filename, args.proceed)
00158     else:
00159         print("Exiting: Invalid test provided: %s for %s version software" %
00160               (args.test, test_dict['version']))
00161         parser.print_help()
00162 
00163     return 0
00164 
00165 if __name__ == '__main__':
00166     sys.exit(main())


baxter_tools
Author(s): Rethink Robotics Inc.
autogenerated on Wed Aug 26 2015 10:50:53