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 PKG = 'qualification'
00038 import roslib; roslib.load_manifest(PKG)
00039
00040 import rospy
00041
00042 from pr2_self_test_msgs.srv import ScriptDone, ScriptDoneRequest
00043 from pr2_self_test_msgs.srv import ConfirmConf, ConfirmConfResponse, ConfirmConfRequest
00044
00045 import subprocess, sys
00046
00047
00048 SRV_NAME = 'prestartup_done'
00049 finish = rospy.ServiceProxy(SRV_NAME, ScriptDone)
00050
00051 confirm_proxy = rospy.ServiceProxy('mcb_conf_results', ConfirmConf)
00052
00053
00054 def _report_no_cameras(interface):
00055 conf = ConfirmConfRequest()
00056 conf.message = "No cameras found on interface %s. Check camera lights. Click OK to retry." % interface
00057 conf.details = "No cameras found. This may be a problem with the cables to the camera.\nCamera light codes:\n\tGreen - Power\n\tOrange - Connection\n\nIf lights are on, unplug and plug in camera and retry."
00058
00059 resp = confirm_proxy.call(conf)
00060 return resp.retry == ConfirmConfResponse.RETRY
00061
00062
00063 def check_camera(interface):
00064 while not rospy.is_shutdown():
00065 p = subprocess.Popen('rosrun wge100_camera discover %s' % interface,
00066 stdout=subprocess.PIPE,
00067 stderr=subprocess.PIPE, shell=True)
00068
00069 o,e = p.communicate()
00070 retcode = p.returncode
00071
00072 if retcode != 0:
00073 if _report_no_cameras(interface):
00074 continue
00075 print >> sys.stderr, "Unable to run discover. Camera may not be present"
00076 return False, "Unable to run discover. Camera may not be present"
00077
00078 try_again = False
00079 for ln in e.split('\n'):
00080 if ln.find('No cam') > -1:
00081 if not _report_no_cameras(interface):
00082 print >> sys.stderr, "No cameras found"
00083 return False, "No cameras found"
00084 else:
00085 try_again = True
00086 break
00087 if try_again:
00088 continue
00089
00090 found = 0
00091 for ln in o.split('\n'):
00092 if ln.find('No cam') > -1:
00093 if _report_no_cameras(interface):
00094 continue
00095 print >> sys.stderr, "No cameras found"
00096 return False, "No cameras found"
00097 elif ln.find('Found') == 0:
00098 found += 1
00099 if found > 0:
00100 return True, ''
00101 if not _report_no_cameras(interface):
00102 return False, "No cameras"
00103
00104 return False, 'Rospy shutdown'
00105
00106
00107
00108
00109 if __name__ == '__main__':
00110 rospy.init_node('check_wge100_present')
00111 args = rospy.myargv()
00112 if len(args) > 1:
00113 interface = args[1]
00114 else:
00115 interface = 'lan0'
00116
00117
00118 val, msg = check_camera(interface)
00119 print val, msg
00120
00121 r = ScriptDoneRequest()
00122 r.result = 0
00123 r.failure_msg = 'Found wge100 camera on interface %s' % interface
00124 if not val:
00125 r.result = 1
00126 r.failure_msg = msg
00127
00128 rospy.wait_for_service(SRV_NAME, 5)
00129 finish.call(r)
00130
00131 rospy.spin()