pr2_test_logger.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright (c) 2010, Willow Garage, Inc.
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 #     * Redistributions of source code must retain the above copyright
00010 #       notice, this list of conditions and the following disclaimer.
00011 #     * 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 #     * Neither the name of the Willow Garage, Inc. 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 ##\author Kevin Watts
00031 ##\brief Logs Results of PR2 burn in test to CSV file, uploads to invent
00032 
00033 from __future__ import with_statement
00034 
00035 PKG = 'life_test'
00036 import roslib; roslib.load_manifest(PKG)
00037 
00038 from life_test.test_param import LifeTest
00039 from life_test.test_record import TestRecord
00040 from pr2_self_test_msgs.msg import TestStatus
00041 
00042 import sys, os
00043 import rospy
00044 
00045 import threading
00046 import getpass
00047 from optparse import OptionParser
00048 from wg_invent_client import Invent
00049 
00050 class PR2TestLogger:
00051     def __init__(self, robot_serial, iv, output_file = None, submit = True, email = True):
00052         my_test = LifeTest(short='PR2', testid='pr2-burn-test', name='PR2 Burn in Test', 
00053                            desc='PR2 Burn in Test', serial='6802967',
00054                            duration=1, launch_script='pr2_test/pr2_burn_in_test.launch', 
00055                            test_type='Burn in', power=False)
00056 
00057         self._out_file = output_file
00058         self._record = TestRecord(my_test, robot_serial, csv_name = self._out_file, send_email = email)
00059 
00060         self._mutex = threading.Lock()
00061 
00062         self._iv = iv
00063         self._serial = robot_serial
00064         self._closed = False
00065         self._submit = submit
00066 
00067         self._record.update(False, False, False, 'Started Logging', '')
00068 
00069         self._status_sub = rospy.Subscriber('test_status', TestStatus, self._status_cb)
00070 
00071     def _status_cb(self, msg):
00072         with self._mutex:
00073             self._record.update(True, msg.test_ok == 0, False, '', msg.message)
00074 
00075     def close(self):
00076         if self._closed:
00077             return 
00078 
00079         # Don't log if we didn't start running
00080         if self._record.get_cum_time() < 1:
00081             print >> sys.stderr, "No robot burn in data record. Unable to send to inventory system"
00082             return
00083 
00084         self._record.update(False, False, False, 'Stopping robot', '')
00085 
00086         if not self._submit:
00087             print "Log recorded: %s. Not submitting to Invent" % self._record.log_file
00088             return
00089 
00090         if self._record.load_attachments(self._iv):
00091             print 'Submitted log to inventory system'
00092         else:
00093             print >> sys.stderr, "Unable to submit log. Load attachments to invent manually"
00094 
00095         self._closed = True
00096     
00097 
00098 if __name__ == '__main__':
00099     parser = OptionParser(usage="%prog -u USERNAME -r ROBOT", prog="pr2_test_logger.py")
00100     parser.add_option('-u', '--username', action="store", dest="username",
00101                       default=None, metavar="USERNAME",
00102                       help="Username for WG inventory system")
00103     parser.add_option('-r', '--robot', action="store", dest="robot",
00104                       default=None, metavar="ROBOT",
00105                       help="Robot SN (10XX) to store data.")
00106     parser.add_option('-o', '--output', action="store", dest="output",
00107                       default=None, metavar="OUTPUT_FILE",
00108                       help="Log file to store data. Appended to existing file")
00109     parser.add_option('-n', '--no-submit', action="store_true", dest="no_submit",
00110                       default=False, help="Don't submit to Inventory system")
00111     parser.add_option('--no-email', action="store_true", dest="no_email",
00112                       default=False, help="Don't email updates")
00113     
00114     options,args = parser.parse_args()
00115     if not options.username and not options.no_submit:
00116         parser.error("Must provide username to WG inverntory system")
00117     if not options.robot:
00118         parser.error("Must provide valid robot SN to log")
00119 
00120     robot = '68029670' + options.robot
00121     
00122     if not options.no_submit:
00123         print 'Enter your password to the Willow Garage Inventory system'
00124         my_pass = getpass.getpass()
00125 
00126         iv = Invent(options.username, my_pass)
00127         if not iv.login():
00128             parser.error("Must provide valid username and password to WG inventory system")
00129         if not iv.check_serial_valid(robot):
00130             parser.error("Robot serial number %s is invalid" % options.robot)
00131     else:
00132         iv = None
00133 
00134     rospy.init_node('pr2_test_logger') # , disable_signals = True)
00135 
00136     pr2_logger = PR2TestLogger(robot, iv, options.output, not options.no_submit, not options.no_email)
00137     rospy.on_shutdown(pr2_logger.close)
00138     
00139     print "Logging PR2 burn in test status..."
00140     try:
00141         rospy.spin()
00142     except KeyboardInterrupt:
00143         print "Shutting down logging, reporting to inventory system"
00144         pr2_logger.close()
00145     except Exception, e:
00146         import traceback
00147         traceback.print_exc()
00148         pr2_logger.close()


life_test
Author(s): Kevin Watts
autogenerated on Sat Dec 28 2013 17:56:37