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 import roslib
00036 roslib.load_manifest('qualification')
00037 import wx
00038 import sys
00039 import os
00040
00041 from pr2_self_test_msgs.srv import ScriptDone, ScriptDoneRequest
00042
00043 import rospy
00044
00045 def getparam(name):
00046 val = rospy.get_param(name, None)
00047 if val == None:
00048 print >> sys.stderr, "Parameter %s not set"%name
00049 exit(-1)
00050 return val
00051
00052 rospy.init_node("wge100_set_mac_dialog")
00053 barcode = getparam('qual_item/serial')
00054 camera_path = getparam('~camera_path')+"/board_config"
00055
00056 app = wx.PySimpleApp()
00057 ret = wx.MessageBox("Are you sure you've plugged in camera \"%s\"? Check camera's power light is on." % barcode,
00058 "Set MAC and Serial Number",
00059 wx.YES_NO)
00060 done = ScriptDoneRequest()
00061 if (ret == wx.NO):
00062 done.result = ScriptDoneRequest.RESULT_FAIL
00063 done.failure_msg = 'User pressed NO.'
00064 else:
00065 if os.system("rosrun qualification wge100_board_config.py board_config:=%s %s"%(camera_path, barcode)) == 0:
00066 done.result = ScriptDoneRequest.RESULT_OK
00067 done.failure_msg = ''
00068 else:
00069 done.result = ScriptDoneRequest.RESULT_FAIL
00070 done.failure_msg = 'Board configuration failed.'
00071
00072 try:
00073 finish = rospy.ServiceProxy('prestartup_done', ScriptDone)
00074 rospy.wait_for_service('prestartup_done', 2)
00075 finish.call(done)
00076 sys.exit(0)
00077 except:
00078
00079 sys.exit(0)