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 import roslib; roslib.load_manifest('qualification')
00038 import rospy
00039 import rospy.client
00040 from wg_invent_client import Invent;
00041 from wge100_camera.srv import BoardConfig
00042 import sys
00043 import os
00044
00045 myargv = rospy.client.myargv()
00046
00047 if len(myargv) != 2:
00048 print "WARNING! This script can only be run once per camera."
00049 print "Make sure you enter the right barcode!"
00050 print
00051 print "Enter barcode:"
00052 barcode = raw_input()
00053 else:
00054 barcode = myargv[1]
00055 print "Preparing to configure forearm camera",barcode
00056
00057 rospy.init_node('forearm_config')
00058
00059
00060 if len(barcode) != 12 or not barcode.isdigit():
00061 print "The item id", barcode, "should be 12 numeric digits."
00062 exit(-1)
00063 if not barcode[0:7] in [ "6805018", "6805027", "6805030"]:
00064 print "Part number", barcode[0:7], "is not a forearm camera."
00065 exit(-1)
00066 serial = int(barcode[5:12])
00067
00068 if serial >= 1800000 and serial <= 1800015:
00069 serial = serial - 1800000
00070
00071 if serial == 2701004:
00072 serial = 1002701004
00073
00074 url = "serial://%i"%serial
00075
00076 print "Camera url is:", url
00077
00078
00079 username = rospy.get_param('/invent/username', None)
00080 password = rospy.get_param('/invent/password', None)
00081
00082
00083 i = Invent(username, password)
00084 if not i.login():
00085 print "Could not connect to invent."
00086 exit(-1)
00087
00088
00089
00090 try:
00091 prevserial = i.get_item_references(barcode)["camera_url"]
00092 if not prevserial in [ url, '']:
00093 print "This part was already stored in invent with a different serial '%s'. This should never happen."%prevserial
00094 exit(-1)
00095 except KeyError:
00096 prevserial = ''
00097 pass
00098
00099 if prevserial != url:
00100 print "Writing camera_url to invent"
00101 i.addItemReference(barcode, "camera_url", url)
00102 else:
00103 print "camera_url already in invent"
00104
00105
00106 i.generateWGMacaddr(barcode, "lan0")
00107 refs = i.get_item_references(barcode)
00108 macstr = refs["lan0"]
00109 print "Camera MAC is:", macstr
00110 mac = []
00111 if len(macstr.rstrip("1234567890abcdefABCDEF")) != 0 or len(macstr) != 12:
00112 print "The MAC should be 12 hex digits."
00113 exit(-1)
00114 for j in range(0, 6):
00115 mac.append(int(macstr[2*j:2*j+2], 16))
00116
00117 if i.getKV(barcode, 'board_configured') == 'yes':
00118 print "This board has already been configured."
00119 exit(0)
00120
00121 i.setKV(barcode, 'board_configured', 'unknown')
00122
00123
00124 print "Waiting for board_config service."
00125 rospy.wait_for_service('board_config', 10)
00126 board_config = rospy.ServiceProxy('board_config', BoardConfig)
00127 rslt = board_config(serial, "".join([chr(x) for x in mac]) );
00128 print "Result is", rslt.success
00129 if rslt.success == 1:
00130 i.setKV(barcode, 'board_configured', 'yes')
00131
00132 os.system("rosrun wge100_camera reconfigure_cam serial://0@10.68.0.2")
00133
00134 exit(rslt == 1)