Go to the documentation of this file.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 PKG = 'qualification'
00040 NAME = 'confirm_conf'
00041
00042 import roslib
00043 roslib.load_manifest(PKG)
00044 import wx
00045 from wx import xrc
00046 from pr2_self_test_msgs.srv import ConfirmConf, ConfirmConfRequest, ConfirmConfResponse
00047 import rospy
00048 import time
00049 import os
00050
00051 import signal
00052
00053 prev_handler = None
00054
00055
00056 app = wx.PySimpleApp(clearSigInt = True)
00057 process_done = False
00058 prompt_done = False
00059 prompt_click =False
00060 frame=wx.Frame(None)
00061
00062
00063
00064
00065
00066
00067
00068
00069
00070 def msg_detail_prompt(msg, details):
00071
00072 xrc_path = os.path.join(roslib.packages.get_pkg_dir('qualification'), 'xrc/gui.xrc')
00073 xrc_resource = xrc.XmlResource(xrc_path)
00074
00075 dialog = xrc_resource.LoadDialog(None, 'confirm_conf_dialog')
00076
00077 xrc.XRCCTRL(dialog, 'message_text').SetLabel(msg)
00078 xrc.XRCCTRL(dialog, 'message_text').Wrap(400)
00079 xrc.XRCCTRL(dialog, 'detail_text').AppendText(details)
00080
00081 global prompt_click, prompt_done
00082
00083 dialog.Layout()
00084
00085
00086 prompt_click = (dialog.ShowModal() == wx.ID_OK)
00087 prompt_done = True
00088 dialog.Destroy()
00089
00090 def check_w_user(req):
00091 global prompt_done, prompt_click
00092
00093 wx.CallAfter(msg_detail_prompt, req.message, req.details)
00094
00095 while(not prompt_done and not rospy.is_shutdown()):
00096 rospy.loginfo("Waiting for retry prompt . . .")
00097 for i in range(0, 20):
00098 time.sleep(0.5)
00099
00100 resp = ConfirmConfResponse()
00101 if prompt_click:
00102 resp.retry = ConfirmConfResponse.RETRY
00103 else:
00104 resp.retry = ConfirmConfResponse.FAIL
00105
00106 prompt_done = False
00107 prompt_click = False
00108 return resp
00109
00110
00111 def confirm_conf():
00112 rospy.init_node(NAME)
00113 s = rospy.Service('mcb_conf_results', ConfirmConf, check_w_user)
00114
00115
00116 signal.signal(signal.SIGINT, signal.SIG_DFL)
00117
00118 app.MainLoop()
00119
00120 rospy.spin()
00121 time.sleep(1)
00122
00123
00124 if __name__ == "__main__":
00125 confirm_conf()