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 PKG = "qualification"
00039 import roslib
00040 roslib.load_manifest(PKG)
00041 import rospy
00042
00043 import sys, os
00044 import subprocess
00045 from optparse import OptionParser
00046 from time import sleep
00047 import string
00048
00049 import traceback
00050
00051 from pr2_self_test_msgs.srv import ConfirmConf, ConfirmConfRequest, ConfirmConfResponse, ScriptDone, ScriptDoneRequest
00052
00053 from wg_invent_client import Invent
00054
00055 prog_path = os.path.join(roslib.packages.get_pkg_dir(PKG), "fwprog")
00056 ECAT_IFACE = "ecat0"
00057 PR2_GRANT = 'pr2_grant'
00058
00059 class MCBProgramConfig:
00060 def __init__(self, expected):
00061 rospy.init_node('mcb_prog_conf')
00062
00063 self.done_service = rospy.ServiceProxy('prestartup_done', ScriptDone)
00064
00065 self.confirm_proxy = rospy.ServiceProxy('mcb_conf_results', ConfirmConf)
00066 self.has_finished = False
00067
00068 username = rospy.get_param('/invent/username', None)
00069 password = rospy.get_param('/invent/password', None)
00070
00071 if username == None or password == None:
00072 self.finished(False, 'Invalid username or password. Cannot check MCB\'s.')
00073 return
00074
00075 self.invent = Invent(username, password)
00076 if not self.invent.login():
00077 self.finished(False, 'Unable to login to invent. Cannot check MCB\'s.')
00078 return
00079
00080 self.expected = expected
00081
00082 self.serials = []
00083
00084
00085 def finished(self, pass_bool, msg = ''):
00086 if self.has_finished:
00087 return
00088
00089 try:
00090 result = ScriptDoneRequest()
00091 if pass_bool:
00092 result.result = 0
00093 else:
00094 result.result = 1
00095
00096 result.failure_msg = msg
00097
00098 rospy.wait_for_service('prestartup_done', 10)
00099 rospy.loginfo('Calling prestartup done service')
00100 self.done_service.call(result)
00101 self.has_finished = True
00102 except Exception, e:
00103 rospy.logerr(traceback.format_exc())
00104
00105
00106
00107
00108 def prompt_user(self, msg, details):
00109 rospy.loginfo('Prompting user: %s' % msg)
00110
00111 conf = ConfirmConfRequest()
00112 conf.message = msg
00113 conf.details = details
00114 resp = self.confirm_proxy.call(conf)
00115
00116 return resp.retry == ConfirmConfResponse.RETRY
00117
00118
00119
00120 def verify_boards(self, check):
00121 if self.has_finished:
00122 return False
00123
00124 try:
00125 rospy.wait_for_service('mcb_conf_results', 15)
00126 except:
00127 msg = "MCB conf results service not available. Unable to configure MCB's"
00128 rospy.logerr(msg)
00129 self.finished(False, msg)
00130 return False
00131
00132 if not self.count_boards():
00133 return False
00134
00135 if not self.check_link():
00136 return False
00137
00138 if not self.get_serials():
00139 return False
00140
00141 if check:
00142 return self.check_boards()
00143
00144 return True
00145
00146
00147 def count_boards(self):
00148 count_cmd = PR2_GRANT + ' ' + os.path.join(prog_path, "eccount") + " -i " + ECAT_IFACE
00149
00150 while not rospy.is_shutdown():
00151 p = subprocess.Popen(count_cmd, stdout =subprocess.PIPE,
00152 stderr = subprocess.PIPE, shell=True)
00153 stdout, stderr = p.communicate()
00154 count = p.returncode
00155 details = 'Ran eccount. Expected %s MCB\'s. Return code %s.\n\n' % (self.expected, count)
00156 details += 'STDOUT:\n' + stdout
00157 if len(stderr) > 3:
00158 details += '\nSTDERR:\n' + stderr
00159
00160
00161 if count == self.expected:
00162 rospy.logdebug("Found %s MCB's, programming" % count)
00163 return True
00164
00165 elif count == 0:
00166 msg = "Found no MCB's! Check cables and power. Retry?"
00167 elif count == 200:
00168 msg = "Unable to initialize interface. Make sure you have root access and the link is connected. Check power to the device. Retry?"
00169 elif count == 203:
00170 msg = "Ethernet interface has link, but no packets are returning. This could mean the etherCAT cable is not plugged into an MCB. Check etherCAT cable. To debug, check that the first device is good. Retry?"
00171 elif count == 204:
00172 msg = "Has no link to device. Check device cable and power. Retry?"
00173 elif count == 205:
00174 msg = "Ethernet interface is not UP. The computer needs to be configured. Run the \"Restart %s\" application and click OK to retry." % ECAT_IFACE
00175 elif count > 199:
00176 msg = "Error counting MCB's. eccount gave error code: %s. Retry?" % count
00177 elif count < self.expected:
00178 msg = "Did not find all MCB's. Found %s, expected %s. Check cables to all MCB's after MCB %s. Click OK to retry." % (count, self.expected, count)
00179 elif count > self.expected:
00180 msg = "Found more MCB's than expected. Found %s, expected %s. Did you scan the right part? Click OK to retry." % (count, self.expected)
00181 else:
00182 msg = "MCB counts don't match. Found %s, expected %s. Retry?" % (count, self.expected)
00183
00184 if not self.prompt_user(msg, details):
00185 self.finished(False, 'Failed to count boards. Operator canceled.\n\n%s\n%s' % (msg, details))
00186 return False
00187
00188 def check_link(self):
00189 emltest_cmd = PR2_GRANT + ' ' + os.path.join(prog_path, "emltest") + " -q -j8 -i %s -T10000,2" % ECAT_IFACE
00190
00191 p = subprocess.Popen(emltest_cmd, stdout = subprocess.PIPE,
00192 stderr = subprocess.PIPE, shell = True)
00193 o, e = p.communicate()
00194 retcode = p.returncode
00195
00196 if retcode != 0:
00197 msg = "Dropped packets to device while checking link. Cables may be damaged."
00198 details = "Ran \"emltest\", found dropped packets when checking link. This is probably a cable problem from the test fixture or between some MCB\'s."
00199
00200 self.finished(False, "%s\n\n%s" % (msg, details))
00201 return False
00202
00203 return True
00204
00205
00206 def get_serials(self):
00207 for board in range(0, self.expected):
00208 check_cmd = PR2_GRANT + ' ' + os.path.join(prog_path, 'device') + ' -i %s -K -p %d' % (ECAT_IFACE, board + 1)
00209 try:
00210 p = subprocess.Popen(check_cmd, stdout = subprocess.PIPE,
00211 stderr = subprocess.PIPE, shell = True)
00212 stdout, stderr = p.communicate()
00213 retcode = p.returncode
00214
00215 if retcode != 0:
00216 self.finished(False, 'Error when checking board %d. "device" returned code %d\n\nOUT: %s\nERROR: %s' % (board, retcode, stdout, stderr))
00217 return False
00218
00219 for ln in stdout.split('\n'):
00220 if ln.startswith('serial :'):
00221 self.serials.append(int(ln[9:].strip()))
00222 except Exception, e:
00223 rospy.logerr(traceback.format_exc())
00224 self.finished(False, 'Error when checking board %d. Caught exception:\n%s' % (board, traceback.format_exc()))
00225 return False
00226
00227 return True
00228
00229
00230 def check_boards(self):
00231
00232 for index, serial in enumerate(self.serials):
00233 rospy.logdebug('Checking serial %s' % serial)
00234 if not self.invent.get_test_status(serial):
00235 self.finished(False, 'Board %d has failed testing. Serial: %s' % (index, serial))
00236 return False
00237
00238 return True
00239
00240
00241
00242 def program_boards(self):
00243 for board in range(0, self.expected):
00244 program_cmd = PR2_GRANT + ' ' + os.path.join(prog_path, "fwprog") + " -i %s -p %s %s/*.bit" % (ECAT_IFACE, (board + 1), prog_path)
00245
00246 while not rospy.is_shutdown():
00247 p = subprocess.Popen(program_cmd, stdout = subprocess.PIPE, stderr = subprocess.PIPE, shell=True)
00248 stdout, stderr = p.communicate()
00249 retcode = p.returncode
00250
00251 details = 'Ran fwprog on MCB %s, returned %s.\n\n' % (board, retcode)
00252 details += 'CMD:\n' + program_cmd + '\n'
00253 details += 'STDOUT:\n' + stdout
00254 if len(stderr) > 5:
00255 details += '\nSTDERR:\n' + stderr
00256
00257 if retcode == 0:
00258 break
00259
00260 msg = "Programming MCB firmware failed for MCB #%s with error %d! Would you like to retry?" %(board, retcode)
00261 retry = self.prompt_user(msg, details)
00262 if not retry:
00263 self.finished(False, '%s\n%s' % (msg, details))
00264 return False
00265
00266
00267 self.finished(True, "Boards programmed. Num. boards: %d. Serials: %s" % (self.expected, str(self.serials)))
00268 return True
00269
00270
00271 def configure_boards(self, mcbs, assembly = False):
00272 path = roslib.packages.get_pkg_dir("ethercat_hardware")
00273 actuator_path = os.path.join(path, "actuators.conf")
00274
00275 for mcb in mcbs:
00276 name, num = mcb.split(',')
00277
00278 cmd = PR2_GRANT + " " + os.path.join(path, "motorconf") + " -i %s -p -n %s -d %s -a %s" % (ECAT_IFACE, name, num, actuator_path)
00279
00280 while not rospy.is_shutdown():
00281 p = subprocess.Popen(cmd, stdout = subprocess.PIPE, stderr = subprocess.PIPE, shell = True)
00282 stdout, stderr = p.communicate()
00283 retcode = p.returncode
00284
00285 details = 'Ran motorconf. Attempted to program MCB %s with actuator name %s. Return code: %s.\n\n' % (num, name, retcode)
00286 details += 'CMD:\n' + cmd + '\n'
00287 details += 'STDOUT:\n' + stdout
00288 if len(stderr) > 5:
00289 details += '\nSTDERR:\n' + stderr
00290
00291 if retcode != 0:
00292 msg = "Programming MCB configuration failed for %s with return code %s." % (name, retcode)
00293 retry = self.prompt_user("%s Retry?" % msg, details)
00294 if not retry:
00295 self.finished(False, '%s\n%s' % (msg, details))
00296 return
00297 else:
00298 break
00299
00300 self.update_conf(mcbs)
00301
00302 if assembly and not self.check_assembly():
00303 self.finished(False, "Mismatch between given MCB's and listed items in inventory system. Component is not properly assembled in inventory. Found MCB serials: %s." % str(self.serials))
00304
00305
00306 self.finished(True, "Boards configured. Num. boards: %d. Serials: %s" % (self.expected, str(self.serials)))
00307 return
00308
00309
00310 def update_conf(self, mcbs):
00311 for index, serial in enumerate(self.serials):
00312 conf_name = mcbs[index].split(',')[0]
00313 self.invent.setKV(serial, 'Configuration', conf_name)
00314
00315
00316 def check_assembly(self):
00317 test_component = rospy.get_param('/qual_item/serial', None)
00318 if test_component is None:
00319 rospy.logerr('Unable to find serial number of test component')
00320 return False
00321
00322 sub_components = self.invent.get_sub_items(test_component, recursive=True)
00323 if len(sub_components) == 0:
00324 rospy.logerr('Unable to find any sub components for item %s' % test_component)
00325 return False
00326
00327 rospy.logdebug('Found sub components: %s' % str(sub_components))
00328
00329 for serial in self.serials:
00330 if not str(serial) in sub_components:
00331 rospy.logerr('MCB serial %s was not listed under component %s in invent. Unit is incorrectly assembled in inventory system.' % (serial, test_component))
00332 return False
00333
00334 return True
00335
00336 if __name__ == '__main__':
00337 parser = OptionParser(usage="./%prog [options]", prog='mcb_prog_conf.py')
00338 parser.add_option("-p", "--program", action="store_true",
00339 dest="program", default=False,
00340 metavar="PROGRAM", help="Program mcbs?")
00341 parser.add_option("-c", "--configure", action="store_true",
00342 dest="configure", default=False,
00343 metavar="CONFIGURE", help="Configure mcbs?")
00344 parser.add_option("-n", "--number", type="int", dest="expected",
00345 default = 0,
00346 metavar="NUMBER", help="Number of MCB's")
00347 parser.add_option("--motor", type="string", dest="mcbs",
00348 action="append", metavar="NAME,NUM",
00349 help="MCB's to configure by name and number")
00350 parser.add_option("-a", "--assembly", action="store_true",
00351 default=False, dest="assembly",
00352 help="Verify that boards are components of qual item")
00353
00354 options, args = parser.parse_args()
00355
00356 if options.program and options.configure:
00357 parser.error("Options \'program\' and \'configure\' are mutually exclusive")
00358
00359 if not options.program and not options.configure:
00360 parser.error("Must choose to program or configure boards")
00361
00362 if options.expected == 0:
00363 parser.error("Must have MCB's to program or configure")
00364
00365 if options.configure and options.expected != len(options.mcbs):
00366 parser.error("Number of boards doesn't match with list given")
00367
00368 prog_conf = MCBProgramConfig(options.expected)
00369
00370 try:
00371 sleep(2)
00372
00373 if not prog_conf.verify_boards(options.program):
00374 sys.exit()
00375
00376 if options.program:
00377 prog_conf.program_boards()
00378 else:
00379 prog_conf.configure_boards(options.mcbs, options.assembly)
00380
00381
00382 rospy.spin()
00383 except KeyboardInterrupt:
00384 pass
00385 except Exception, e:
00386 rospy.logerr(traceback.format_exc())
00387 prog_conf.finished(False, 'Caught exception in prog_conf loop. %s' % traceback.format_exc())
00388
00389