def factory_install(device_barcode): '''main factory installer''' start_time = time.time() if not args.test: colour_text.clear_screen() # start a new log directory on each run logger.new_log_dir() logger.reopen_logfile() logdir = logger.get_log_dir() logger.info("Logging to %s" % logdir) logger.info("Device barcode %s" % device_barcode) colour_text.print_blue(''' ================================================== | Starting installation. Barcode is %s ================================================== ''' % device_barcode) logger.info(time.ctime()) if args.erase: if not jtag.erase_firmwares(): colour_text.print_fail(''' ====================================== | FAILED: JTAG firmware erase failed ====================================== ''') logger.critical("JTAG firmware erase failed") return False if not args.nofw and not jtag.load_all_firmwares(retries=3): colour_text.print_fail(''' ====================================== | FAILED: JTAG firmware install failed ====================================== ''') logger.critical("JTAG firmware install failed") return False if args.erase: if not connection.erase_parameters(): colour_text.print_fail(''' ========================================== | FAILED: Failed to erase parameters ========================================== ''') logger.critical("Failed to erase parameters") return False if not accelcal.accel_calibrate_retries(retries=4): colour_text.print_fail(''' ========================================== | FAILED: Accelerometer calibration failed ========================================== ''') logger.critical("Accelerometer calibration failed") return False # all OK colour_text.print_green(''' ================================================ | Device: %s | PASSED: Factory install complete (%u seconds) ================================================ ''' % (device_barcode, (time.time() - start_time))) logger.info("Factory install complete (%u seconds)" % (time.time() - start_time)) return True
def load_all_firmwares(retries=3): '''load 4 firmwares. Return True on success, False on failure''' while retries > 0: retries -= 1 if not util.wait_devices([IO_JTAG, FMU_JTAG, FMU_DEBUG]): if retries == 1: logger.info("RETRIES=1 - POWER CYCLING") power_control.power_cycle(down_time=4) continue try: load_firmware(IO_JTAG, FW_IO, CPUID_IO) load_firmware(IO_JTAG, BL_IO, CPUID_IO) load_firmware(FMU_JTAG, BL_FMU, CPUID_FMU) load_firmware(FMU_JTAG, FW_FMU, CPUID_FMU) except Exception as ex: logger.error("error loading firmwares %s" % ex) continue # power cycle after loading to ensure the boards can come up cleanly power_retries = 6 while power_retries > 0: power_retries -= 1 power_control.power_cycle(down_time=4) if util.wait_devices([FMU_DEBUG], timeout=5): break logger.info("Retrying power cycle - tries left %u" % power_retries) if not util.wait_devices([FMU_DEBUG], timeout=10): logger.info("Failed to find nsh console device") continue logger.debug("Checking nsh console") nsh = nsh_console.nsh_console() failure = None i = -1 try: i = nsh.expect([ 'No MPU6000 external', 'l3gd20: driver start failed', 'Error in startup', 'ArduPilot started OK', 'format failed', 'Opening USB nsh', 'no RGB led', 'rgbled: init failed' ]) except Exception as ex: failure = "******* Failed to get data from NSH console *******" pass try: nsh.send("\nver all\n") nsh.expect("UID:") nsh.expect("nsh>") nsh.close() except Exception as ex: if i == 3: failure = "******* failed to get version from nsh *******" pass if failure is None: if i == 0: failure = "******* No external mpu6000 found - is IMU board connected? *****" if i == 1: failure = "******* No external l3gd20 found - is IMU board connected? *****" if i == 2: failure = "******* Failed to startup ArduPilot - is IMU board connected? *****" if i == 4: failure = "******* microSD card failure ********" if i == 5: failure = "****** ArduPilot failed to start - general failure ******" if i == 6: failure = "****** RGB LED not found on I2C ******" if i == 7: failure = "****** RGB LED initialisation failed on I2C ******" if failure is not None: logger.info(failure) colour_text.print_fail(failure) continue if util.wait_devices([USB_DEV_TEST, USB_DEV_REFERENCE]): break logger.info("Failed to find USB devices") if retries > 0: logger.info("RETRIES %u - TRYING AGAIN" % retries) if retries == 0: logger.error("FAILED TO LOAD FIRMWARES") return False logger.info("All firmwares loaded OK") return True
# wait for the power to be switched off, disable serial logging logger.info("waiting for power off") util.wait_no_device([FMU_JTAG, IO_JTAG], timeout=600) device_barcode = args.barcode if not args.test and device_barcode is None: colour_text.print_blue(''' ========================================== | PLEASE SWIPE DEVICE BARCODE ========================================== ''') device_barcode = barcode.barcode_read() if device_barcode is None: colour_text.print_fail(''' ========================================== | FAILED: Barcode not detected ========================================== ''') logger.critical("Barcode not detected") time.sleep(2) continue # log the barcode logger.info("Barcode detected: %s" % device_barcode) # wait for the power to come on again while not util.wait_devices([FMU_JTAG, IO_JTAG, FMU_DEBUG]): logger.info("waiting for power up....") ret = factory_install(device_barcode)
def factory_install(device_barcode): '''main factory installer''' start_time = time.time() script_dir = os.path.dirname(os.path.abspath(__file__)) ete.command_bytes('test_work') if not args.test: colour_text.clear_screen() # start a new log directory on each run logger.new_log_dir() logger.reopen_logfile() logdir = logger.get_log_dir() logger.info("Logging to %s" % logdir) #logger.info("Device barcode %s" % device_barcode) colour_text.print_blue(''' ================================================== | Starting installation. Barcode is %s ================================================== ''' % device_barcode) logger.info(time.ctime()) if args.erase: if not jtag.erase_firmwares(): colour_text.print_fail(''' ====================================== | FAILED: JTAG firmware erase failed ====================================== ''') logger.critical("JTAG firmware erase failed") ete.command_bytes('test_fail') ete.command_bytes('reset') ete.accel(10000) ete.yawspeed(5000) ete.rollspeed(10000) return False if not args.nofw and not jtag.load_all_firmwares(retries=3): colour_text.print_fail(''' ====================================== | FAILED: JTAG firmware install failed ====================================== ''') logger.critical("JTAG firmware install failed") ete.command_bytes('test_fail') ete.command_bytes('reset') ete.accel(100000) ete.yawspeed(5000) ete.rollspeed(10000) try: conn = connection.Connection(ref_only=True) rotate.center_servos(conn) except Exception as ex: print("Failed to center servos: %s" % ex) pass return False if args.erase: if not connection.erase_parameters(): colour_text.print_fail(''' ========================================== | FAILED: Failed to erase parameters ========================================== ''') logger.critical("Failed to erase parameters") ete.command_bytes('test_fail') ete.position(0, 0) ete.command_bytes('reset') ete.accel(100000) ete.yawspeed(5000) ete.rollspeed(10000) return False if not accelcal.accel_calibrate_retries(retries=4): colour_text.print_fail(''' ========================================== | FAILED: Accelerometer calibration failed ========================================== ''') logger.critical("Accelerometer calibration failed") ete.command_bytes('test_fail') ete.position(0, 0) ete.command_bytes('reset') ete.accel(100000) ete.yawspeed(5000) ete.rollspeed(10000) return False # all OK logger.info("Writting OTP region in STM32") #Add OTP HERE script_dir = os.path.dirname(os.path.abspath(__file__)) if args.otp_show: p1 = Popen(['python', script_dir + '/otp_program.py', '--port', FMU_DEBUG,'--only-display',"abc"], stdin=PIPE, stdout=PIPE, stderr=PIPE) output, err = p1.communicate() logger.info(output) time.sleep(1) #conn = connection.Connection(ref_only=False) #otp_program_mod.Display_OTP(conn) def getMacAddress(): if sys.platform == 'win32': for line in os.popen("ipconfig /all"): if line.lstrip().startswith('Physical Address'): mac = line.split(':')[1].strip().replace('-',':') break else: for line in os.popen("/sbin/ifconfig"): if line.find('Ether') > -1: mac = line.split()[4] break return mac print("Manufacturer info : Hex Technology, \xA9 ProfiCNC 2016") print "MAC Address:",getMacAddress() #.join(['{:02x}'.format((uuid.getnode() >> i) & 0xff) for i in range(0,8*6,8)][::-1]) colour_text.print_blue('''Barcode is %s''' % device_barcode) print("date of testing :" + time.strftime("%x")) print("time of testing :" + time.strftime("%X")) accel_data0 = "%f,%f,%f,%f,%f,%f" % (test_sensors.offset[0][0] ,test_sensors.offset[0][1] ,test_sensors.offset[0][2],test_sensors.scale_factor[0][0],test_sensors.scale_factor[0][1],test_sensors.scale_factor[0][2]) accel_data2 = "%f,%f,%f,%f,%f,%f" % (test_sensors.offset[2][0] ,test_sensors.offset[2][1] ,test_sensors.offset[2][2],test_sensors.scale_factor[2][0],test_sensors.scale_factor[2][1],test_sensors.scale_factor[2][2]) print "Accel :", accel_data0 print "Accel :", accel_data2 if True:#args.otp_write: #Manufacturing Info p2 = Popen(['python', script_dir + '/otp_program.py', '--port', FMU_DEBUG,'Hex Technology, \xA9 ProfiCNC 2016',getMacAddress(),device_barcode,time.strftime("%x"),time.strftime("%X"),'--',str(accel_data0),str(accel_data2)], stdin=PIPE, stdout=PIPE, stderr=PIPE) output, err = p2.communicate() logger.info(output) logger.info(err) time.sleep(1) #Display #p3 = Popen(['python', script_dir + '/otp_program.py', '--port', FMU_DEBUG,'--only-display',"abc"], stdin=PIPE, stdout=PIPE, stderr=PIPE) #output, err = p3.communicate() #logger.info(output) colour_text.print_green(''' ================================================ | Device: %s | PASSED: Factory install complete (%u seconds) ================================================ ''' % (device_barcode, (time.time() - start_time))) logger.info("Factory install complete (%u seconds)" % (time.time() - start_time)) ete.command_bytes('test_pass') ete.position(0, 0) ete.command_bytes('reset') ete.accel(100000) ete.yawspeed(5000) ete.rollspeed(10000) return True
def load_all_firmwares(retries=3): '''load 4 firmwares. Return True on success, False on failure''' while retries > 0: retries -= 1 if not util.wait_devices([IO_JTAG, FMU_JTAG, FMU_DEBUG]): if retries == 1: logger.info("RETRIES=1 - POWER CYCLING") power_control.power_cycle(down_time=4) continue try: load_firmware(IO_JTAG, FW_IO, CPUID_IO) load_firmware(IO_JTAG, BL_IO, CPUID_IO) load_firmware(FMU_JTAG, BL_FMU, CPUID_FMU) load_firmware(FMU_JTAG, FW_FMU, CPUID_FMU) except Exception as ex: logger.error("error loading firmwares %s" % ex) continue # power cycle after loading to ensure the boards can come up cleanly power_retries = 6 while power_retries > 0: power_retries -= 1 power_control.power_cycle(down_time=4) if util.wait_devices([FMU_DEBUG], timeout=5): break logger.info("Retrying power cycle - tries left %u" % power_retries) if not util.wait_devices([FMU_DEBUG], timeout=10): logger.info("Failed to find nsh console device") continue logger.debug("Checking nsh console") nsh = nsh_console.nsh_console() failure = None i = -1 try: i = nsh.expect(['No MPU6000 external', 'l3gd20: driver start failed', 'Error in startup', 'ArduPilot started OK', 'format failed', 'Opening USB nsh', 'no RGB led', 'rgbled: init failed']) except Exception as ex: failure = "******* Failed to get data from NSH console *******" pass try: nsh.send("\nver all\n") nsh.expect("UID:") nsh.expect("nsh>") nsh.close() except Exception as ex: if i == 3: failure = "******* failed to get version from nsh *******" pass if failure is None: if i == 0: failure = "******* No external mpu6000 found - is IMU board connected? *****" if i == 1: failure = "******* No external l3gd20 found - is IMU board connected? *****" if i == 2: failure = "******* Failed to startup ArduPilot - is IMU board connected? *****" if i == 4: failure = "******* microSD card failure ********" if i == 5: failure = "****** ArduPilot failed to start - general failure ******" if i == 6: failure = "****** RGB LED not found on I2C ******" if i == 7: failure = "****** RGB LED initialisation failed on I2C ******" if failure is not None: logger.info(failure) colour_text.print_fail(failure) continue if util.wait_devices([USB_DEV_TEST, USB_DEV_REFERENCE]): break logger.info("Failed to find USB devices") if retries > 0: logger.info("RETRIES %u - TRYING AGAIN" % retries) if retries == 0: logger.error("FAILED TO LOAD FIRMWARES") return False logger.info("All firmwares loaded OK") return True
def factory_install(device_barcode): '''main factory installer''' start_time = time.time() script_dir = os.path.dirname(os.path.abspath(__file__)) ete.command_bytes('test_work') if not args.test: colour_text.clear_screen() # start a new log directory on each run logger.new_log_dir() logger.reopen_logfile() logdir = logger.get_log_dir() logger.info("Logging to %s" % logdir) #logger.info("Device barcode %s" % device_barcode) colour_text.print_blue(''' ================================================== | Starting installation. Barcode is %s ================================================== ''' % device_barcode) logger.info(time.ctime()) if args.erase: if not jtag.erase_firmwares(): colour_text.print_fail(''' ====================================== | FAILED: JTAG firmware erase failed ====================================== ''') logger.critical("JTAG firmware erase failed") ete.command_bytes('test_fail') ete.command_bytes('reset') ete.accel(10000) ete.yawspeed(5000) ete.rollspeed(10000) return False if not args.nofw and not jtag.load_all_firmwares(retries=3): colour_text.print_fail(''' ====================================== | FAILED: JTAG firmware install failed ====================================== ''') logger.critical("JTAG firmware install failed") ete.command_bytes('test_fail') ete.command_bytes('reset') ete.accel(100000) ete.yawspeed(5000) ete.rollspeed(10000) try: conn = connection.Connection(ref_only=True) rotate.center_servos(conn) except Exception as ex: print("Failed to center servos: %s" % ex) pass return False if args.erase: if not connection.erase_parameters(): colour_text.print_fail(''' ========================================== | FAILED: Failed to erase parameters ========================================== ''') logger.critical("Failed to erase parameters") ete.command_bytes('test_fail') ete.position(0, 0) ete.command_bytes('reset') ete.accel(100000) ete.yawspeed(5000) ete.rollspeed(10000) return False if not accelcal.accel_calibrate_retries(retries=4): colour_text.print_fail(''' ========================================== | FAILED: Accelerometer calibration failed ========================================== ''') logger.critical("Accelerometer calibration failed") ete.command_bytes('test_fail') ete.position(0, 0) ete.command_bytes('reset') ete.accel(100000) ete.yawspeed(5000) ete.rollspeed(10000) return False # all OK logger.info("Writting OTP region in STM32") #Add OTP HERE script_dir = os.path.dirname(os.path.abspath(__file__)) if args.otp_show: p1 = Popen([ 'python', script_dir + '/otp_program.py', '--port', FMU_DEBUG, '--only-display', "abc" ], stdin=PIPE, stdout=PIPE, stderr=PIPE) output, err = p1.communicate() logger.info(output) time.sleep(1) #conn = connection.Connection(ref_only=False) #otp_program_mod.Display_OTP(conn) def getMacAddress(): if sys.platform == 'win32': for line in os.popen("ipconfig /all"): if line.lstrip().startswith('Physical Address'): mac = line.split(':')[1].strip().replace('-', ':') break else: for line in os.popen("/sbin/ifconfig"): if line.find('Ether') > -1: mac = line.split()[4] break return mac print("Manufacturer info : Hex Technology, \xA9 ProfiCNC 2016") print "MAC Address:", getMacAddress( ) #.join(['{:02x}'.format((uuid.getnode() >> i) & 0xff) for i in range(0,8*6,8)][::-1]) colour_text.print_blue('''Barcode is %s''' % device_barcode) print("date of testing :" + time.strftime("%x")) print("time of testing :" + time.strftime("%X")) accel_data0 = "%f,%f,%f,%f,%f,%f" % ( test_sensors.offset[0][0], test_sensors.offset[0][1], test_sensors.offset[0][2], test_sensors.scale_factor[0][0], test_sensors.scale_factor[0][1], test_sensors.scale_factor[0][2]) accel_data2 = "%f,%f,%f,%f,%f,%f" % ( test_sensors.offset[2][0], test_sensors.offset[2][1], test_sensors.offset[2][2], test_sensors.scale_factor[2][0], test_sensors.scale_factor[2][1], test_sensors.scale_factor[2][2]) print "Accel :", accel_data0 print "Accel :", accel_data2 if True: #args.otp_write: #Manufacturing Info p2 = Popen([ 'python', script_dir + '/otp_program.py', '--port', FMU_DEBUG, 'Hex Technology, \xA9 ProfiCNC 2016', getMacAddress(), device_barcode, time.strftime("%x"), time.strftime("%X"), '--', str(accel_data0), str(accel_data2) ], stdin=PIPE, stdout=PIPE, stderr=PIPE) output, err = p2.communicate() logger.info(output) logger.info(err) time.sleep(1) #Display #p3 = Popen(['python', script_dir + '/otp_program.py', '--port', FMU_DEBUG,'--only-display',"abc"], stdin=PIPE, stdout=PIPE, stderr=PIPE) #output, err = p3.communicate() #logger.info(output) colour_text.print_green(''' ================================================ | Device: %s | PASSED: Factory install complete (%u seconds) ================================================ ''' % (device_barcode, (time.time() - start_time))) logger.info("Factory install complete (%u seconds)" % (time.time() - start_time)) ete.command_bytes('test_pass') ete.position(0, 0) ete.command_bytes('reset') ete.accel(100000) ete.yawspeed(5000) ete.rollspeed(10000) return True
logger.info("waiting for power off") util.wait_no_device([FMU_JTAG, IO_JTAG], timeout=600) device_barcode = args.barcode if not args.test and device_barcode is None: ete.command_bytes('test_wait') colour_text.print_blue(''' ========================================== | PLEASE SWIPE DEVICE BARCODE ========================================== ''') device_barcode = barcode.barcode_read() if device_barcode is None: colour_text.print_fail(''' ========================================== | FAILED: Barcode not detected ========================================== ''') logger.critical("Barcode not detected") time.sleep(2) continue # we don't use logger for the barcode here as we are still on the previous # boards log print("Got barcode: %s" % device_barcode) logger.info("Barcode detected") # wait for the power to come on again while not util.wait_devices([FMU_JTAG, IO_JTAG, FMU_DEBUG]): logger.info("waiting for power up....")