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 import os
00033 import sys
00034
00035 WXVER = '2.8'
00036 import wxversion
00037 if wxversion.checkInstalled(WXVER):
00038 wxversion.select(WXVER)
00039 else:
00040 print >> sys.stderr, "This application requires wxPython version %s"%(WXVER)
00041 sys.exit(1)
00042
00043 import wx
00044
00045 PKG = 'qualification'
00046 import roslib
00047 roslib.load_manifest(PKG)
00048
00049 from optparse import OptionParser
00050
00051
00052 import traceback
00053
00054 import rospy
00055
00056 import rviz
00057 import ogre_tools
00058
00059 from pr2_self_test_msgs.srv import ScriptDone, ScriptDoneRequest
00060
00061 from time import sleep
00062
00063 import threading
00064
00065 SRV_NAME = 'visual_check'
00066 def call_done_service(result, msg):
00067 result_service = rospy.ServiceProxy(SRV_NAME, ScriptDone)
00068 r = ScriptDoneRequest()
00069 r.result = result
00070 r.failure_msg = msg
00071 try:
00072 rospy.wait_for_service(SRV_NAME, 5)
00073 result_service.call(r)
00074 except Exception, e:
00075 print >> sys.stderr, "Unable to call %s service. Make sure the service is up" % SRV_NAME
00076
00077
00078
00079 class VisualRunner(threading.Thread):
00080 def __init__(self, app, timeout = None):
00081 threading.Thread.__init__(self)
00082 self.app = app
00083
00084 def run(self):
00085 start = rospy.get_time()
00086 if timeout is None or timeout < 0:
00087 return
00088 while not rospy.is_shutdown():
00089 if rospy.get_time() - start > timeout:
00090 wx.CallAfter(self.app.frame.Close)
00091 call_done_service(ScriptDoneRequest.RESULT_OK, 'Visual check passed by automatic runner.')
00092 break
00093 sleep(1.0)
00094
00095
00096 class VisualizerFrame(wx.Frame):
00097 def __init__(self, parent, id=wx.ID_ANY, title='Qualification Visualizer', pos=wx.DefaultPosition, size=(800, 600), style=wx.DEFAULT_FRAME_STYLE):
00098 wx.Frame.__init__(self, parent, id, title, pos, size, style)
00099
00100 ogre_tools.initializeOgre()
00101
00102 visualizer_panel = rviz.VisualizationPanel(self)
00103
00104 self._visualizer_panel = visualizer_panel
00105 manager = visualizer_panel.getManager()
00106
00107 self.Bind(wx.EVT_CLOSE, self.on_close)
00108
00109 main_sizer = wx.BoxSizer(wx.VERTICAL)
00110
00111 top_sizer = wx.BoxSizer(wx.VERTICAL)
00112 main_sizer.Add(top_sizer, 1, wx.EXPAND, 5)
00113
00114 bottom_sizer = wx.BoxSizer(wx.HORIZONTAL)
00115 main_sizer.Add(bottom_sizer, 0, wx.ALIGN_RIGHT|wx.EXPAND, 5)
00116
00117 top_sizer.Add(visualizer_panel, 1, wx.EXPAND, 5)
00118
00119 self._instructions_ctrl = wx.TextCtrl(self, wx.ID_ANY, wx.EmptyString, wx.DefaultPosition, wx.DefaultSize, wx.TE_MULTILINE|wx.TE_READONLY );
00120 self._pass_button = wx.Button(self, wx.ID_ANY, "Pass")
00121 self._fail_button = wx.Button(self, wx.ID_ANY, "Fail")
00122 bottom_sizer.Add(self._instructions_ctrl, 1, wx.ALL, 5)
00123 bottom_sizer.Add(self._pass_button, 0, wx.ALL|wx.ALIGN_BOTTOM, 5)
00124 bottom_sizer.Add(self._fail_button, 0, wx.ALL|wx.ALIGN_BOTTOM, 5)
00125
00126 self.SetSizer(main_sizer)
00127 self.Layout()
00128
00129 self._pass_button.Bind(wx.EVT_BUTTON, self.on_pass)
00130 self._fail_button.Bind(wx.EVT_BUTTON, self.on_fail)
00131
00132 self._shutdown_timer = wx.Timer()
00133 self._shutdown_timer.Bind(wx.EVT_TIMER, self._on_shutdown_timer)
00134 self._shutdown_timer.Start(100)
00135
00136 def _on_shutdown_timer(self, event):
00137 if (rospy.is_shutdown()):
00138 self.Close(True)
00139
00140 def on_close(self, event):
00141 self.Destroy()
00142
00143 def on_pass(self, event):
00144 call_done_service(ScriptDoneRequest.RESULT_OK, 'Visual check passed by operator.')
00145 self.Destroy()
00146
00147 def on_fail(self, event):
00148 call_done_service(ScriptDoneRequest.RESULT_FAIL, 'Visual check failed by operator.')
00149 self.Destroy()
00150
00151 def load_config_from_path(self, path):
00152 manager = self._visualizer_panel.getManager()
00153 manager.removeAllDisplays()
00154 self._visualizer_panel.loadGeneralConfig(path)
00155 self._visualizer_panel.loadDisplayConfig(path)
00156
00157 def set_instructions(self, instructions):
00158 self._instructions_ctrl.SetValue(instructions)
00159
00160 class VisualizerApp(wx.App):
00161 def __init__(self, file):
00162 self._filepath = file
00163 self._instructions = 'Move joints and verify robot is OK.'
00164
00165 wx.App.__init__(self, clearSigInt = False)
00166
00167 def OnInit(self):
00168 try:
00169 self.frame = VisualizerFrame(None, wx.ID_ANY, "Visual Verifier", wx.DefaultPosition, wx.Size( 800, 600 ) )
00170
00171 if (not os.path.exists(self._filepath)):
00172 call_done_service(ScriptDoneRequest.RESULT_ERROR, 'Visual check recorded error, file does not exist!')
00173 rospy.logerr('Visual check recorded error, file does not exist!')
00174 return False
00175
00176 self.frame.load_config_from_path(self._filepath)
00177 self.frame.set_instructions(self._instructions)
00178 self.frame.Show(True)
00179 return True
00180 except:
00181 traceback.print_exc()
00182 rospy.logerr('Error initializing rviz: %s' % traceback.format_exc())
00183 call_done_service(ScriptDoneRequest.RESULT_ERROR, 'Visual check recorded error on initialization: %s' % traceback.format_exc())
00184 return False
00185
00186 def OnExit(self):
00187 ogre_tools.cleanupOgre()
00188
00189 if __name__ == "__main__":
00190 if (len(sys.argv) < 2):
00191 call_done_service(ScriptDoneRequest.RESULT_ERROR, "Visual verifier not given path to config file.\nusage: visual_verifier.py 'path to config file'")
00192 print >> sys.stderr, 'Usage: visual_verifier.py \'path to config file\''
00193 sys.exit(1)
00194
00195 if not os.path.exists(sys.argv[1]):
00196 call_done_service(ScriptDoneRequest.RESULT_ERROR, "Visual verifier not given path to actual config file.\nusage: visual_verifier.py 'path to config file'\nFile %s does not exist" % sys.argv[1])
00197 print >> sys.stderr, 'Usage: visual_verifier.py \'path to config file\'.\nGiven file does not exist'
00198 sys.exit(1)
00199
00200 try:
00201 app = VisualizerApp(sys.argv[1])
00202 rospy.init_node('visual_verifier')
00203
00204
00205
00206 timeout = rospy.get_param('visual_runner_timeout', -1)
00207 if timeout > 0:
00208 runner = VisualRunner(app, timeout)
00209 runner.start()
00210
00211 app.MainLoop()
00212
00213 rospy.spin()
00214 except KeyboardInterrupt:
00215 pass
00216 except Exception, e:
00217 call_done_service(ScriptDoneRequest.RESULT_ERROR, 'Visual check recorded error: %s' % traceback.format_exc())
00218 rospy.logerr(traceback.format_exc())