00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 SHOULDER_PNS = ['6804204', '6804338']
00040
00041 PKG = 'qualification'
00042 import roslib; roslib.load_manifest(PKG)
00043
00044
00045 import wx
00046 import sys
00047
00048 from pr2_self_test_msgs.srv import ScriptDone, ScriptDoneRequest
00049 import rospy
00050
00051 from wg_invent_client import Invent
00052
00053 def _report_invalid_id():
00054 dlg = wx.MessageDialog(None, "Invalid Shoulder Serial number. Press Cancel to abort, OK to retry", "Invalid ID", wx.OK|wx.CANCEL)
00055 return dlg.ShowModal() == wx.ID_OK
00056
00057 def _check_pn(serial):
00058 for part in SHOULDER_PNS:
00059 if serial.startswith(part):
00060 return True
00061 return False
00062
00063 def get_sn_from_user(iv):
00064 while not rospy.is_shutdown():
00065 sn = str(wx.GetTextFromUser("Enter the shoulder serial number by scanning the shoulder barcode", "Enter Shoulder SN"))
00066 if not unicode(sn).isnumeric() or not len(sn) == 12 or \
00067 not _check_pn(sn) or not iv.check_serial_valid(sn):
00068 if _report_invalid_id():
00069 continue
00070 return None
00071
00072 return sn
00073 return None
00074
00075 def check_shoulder_ok(iv, shoulder_sn):
00076 if not iv.login():
00077 wx.MessageBox("Unable to login to invent", "Unable to login", wx.OK|wx.ICON_ERROR, None)
00078 return False
00079
00080 if not iv.get_test_status(shoulder_sn):
00081 wx.MessageBox("Shoulder has not passed qualification. Qualify shoulder and retry", "Shoulder Not Qualified", wx.OK|wx.ICON_ERROR, None)
00082 return False
00083 return True
00084
00085 def set_note_to_shoulder(iv, shoulder_sn):
00086 ua_sn = rospy.get_param('/qual_item/serial', None)
00087 ua_test_name = rospy.get_param('/qual_item/name', None)
00088
00089 if ua_sn is None or ua_test_name is None:
00090 wx.MessageBox("Unable to recover upperarm SN or test name from qual system", "Qual System Error", wx.OK|wx.ICON_ERROR, None)
00091 return False
00092
00093 note = "Shoulder was qualified with upperarm %s using qual test \"%s\"" % (ua_sn, ua_test_name)
00094 iv.setNote(shoulder_sn, note)
00095
00096 return True
00097
00098
00099 if __name__ == '__main__':
00100 rospy.init_node('shoulder_sn_getter')
00101 done_srv = rospy.ServiceProxy('prestartup_done', ScriptDone)
00102 rospy.wait_for_service('prestartup_done')
00103
00104 app = wx.PySimpleApp()
00105
00106 username = rospy.get_param('/invent/username', '')
00107 password = rospy.get_param('/invent/password', '')
00108
00109 iv = Invent(username, password)
00110 if not iv.login():
00111 wx.MessageBox("Unable to login to invent", "Qual System Error", wx.OK|wx.ICON_ERROR, None)
00112 done_srv.call(result = ScriptDoneRequest.RESULT_FAIL, failure_msg = "Unable to login to invent")
00113 rospy.spin()
00114 sys.exit()
00115
00116 sn = get_sn_from_user(iv)
00117 if sn is None:
00118 done_srv.call(result = ScriptDoneRequest.RESULT_FAIL, failure_msg = "User was unable to get shoulder SN")
00119 rospy.spin()
00120 sys.exit()
00121
00122 if not check_shoulder_ok(iv, sn):
00123 done_srv.call(result = ScriptDoneRequest.RESULT_FAIL, failure_msg = "Shoulder %s had not passed qualification. Unable to complete." % sn)
00124 rospy.spin()
00125 sys.exit()
00126
00127 if not set_note_to_shoulder(iv, sn):
00128 done_srv.call(result = ScriptDoneRequest.RESULT_FAIL, failure_msg = "Unable to load note into inventory system for shoulder %s" % sn)
00129 rospy.spin()
00130 sys.exit()
00131
00132 done_srv.call(result = ScriptDoneRequest.RESULT_OK, failure_msg = "Qualifying with shoulder %s" % sn)
00133
00134 rospy.spin()
00135
00136 sys.exit(0)
00137