def __init__(self, ref_only=False): util.kill_processes(['mavproxy.py', GDB]) self.reflog = StringIO() self.testlog = StringIO() self.ref = None self.test = None self.nsh = None self.refmav = None self.testmav = None try: if not ref_only: self.nsh = nsh_console.nsh_console() except Exception as ex: self.close() util.show_error('Connecting to nsh console', ex, self.testlog) try: self.ref = mav_reference.mav_reference(self.reflog) except Exception as ex: self.close() util.show_error('Connecting to reference board1', ex, self.reflog) try: if not ref_only: self.test = mav_test.mav_test(self.testlog) except Exception as ex: self.close() util.show_error('Connecting to test board1', ex, self.testlog) try: logger.info("CONNECTING MAVLINK TO REFERENCE BOARD") self.refmav = mavutil.mavlink_connection('127.0.0.1:14550') util.wait_heartbeat(self.refmav, timeout=30) util.wait_mode(self.refmav, IDLE_MODES) except Exception as ex: self.close() util.show_error('Connecting to reference board2', ex, self.reflog) try: if not ref_only: logger.info("CONNECTING MAVLINK TO TEST BOARD at %s" % time.ctime()) self.testmav = mavutil.mavlink_connection('127.0.0.1:14551') util.wait_heartbeat(self.testmav, timeout=30) logger.info("got heartbeat at %s" % time.ctime()) util.wait_mode(self.testmav, IDLE_MODES) logger.info("Waiting for 'Ready to FLY'") self.test.expect('Ready to FLY', timeout=20) except Exception as ex: self.close() util.show_error('Connecting to test board2 at %s' % time.ctime(), ex, self.testlog) if self.nsh is not None: # log any extra nsh data logger.debug("Draining nsh") try: self.nsh.read_nonblocking(4096, 1) except Exception as ex: pass try: if not ref_only and not ref_gyro_offset_ok(self.refmav): self.close() util.failure("Bad reference gyro - FAILED") except Exception as ex: self.close() util.show_error('testing reference gyros', ex) logger.info("Setting rotation level") try: rotate.set_rotation(self, 'level', wait=False) except Exception as ex: self.close() util.show_error("unable to set safety off", ex)
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 __init__(self, ref_only=False): util.kill_processes(['mavproxy.py', GDB]) self.reflog = StringIO() self.testlog = StringIO() self.ref = None self.test = None self.nsh = None self.refmav = None self.testmav = None try: if not ref_only: self.nsh = nsh_console.nsh_console() except Exception as ex: self.close() util.show_error('Connecting to nsh console', ex, self.testlog) try: self.ref = mav_reference.mav_reference(self.reflog) except Exception as ex: self.close() util.show_error('Connecting to reference board1', ex, self.reflog) try: if not ref_only: self.test = mav_test.mav_test(self.testlog) except Exception as ex: self.close() util.show_error('Connecting to test board1', ex, self.testlog) try: logger.info("CONNECTING MAVLINK TO REFERENCE BOARD") self.refmav = mavutil.mavlink_connection('127.0.0.1:14550') util.wait_heartbeat(self.refmav, timeout=30) util.wait_mode(self.refmav, IDLE_MODES) except Exception as ex: self.close() util.show_error('Connecting to reference board2', ex, self.reflog) try: if not ref_only: logger.info("CONNECTING MAVLINK TO TEST BOARD") self.testmav = mavutil.mavlink_connection('127.0.0.1:14551') util.wait_heartbeat(self.testmav, timeout=30) logger.info("got heartbeat") util.wait_mode(self.testmav, IDLE_MODES) logger.info("Waiting for 'Ready to FLY'") self.fw_version = None self.px4_version = None self.nuttx_version = None self.stm32_serial = None ready = False self.test.send("param fetch\n") # log version information for later reference while (self.fw_version is None or self.px4_version is None or self.nuttx_version is None or self.stm32_serial is None or not ready): i = self.test.expect(['APM: ([^\r\n]*Copter[^\r\n]*)\r\n', 'APM: PX4: ([0-9a-f]+) NuttX: ([0-9a-f]+)\r\n', 'APM: PX4v2 ([0-9A-F]+ [0-9A-F]+ [0-9A-F]+)\r\n', '(Ready to FLY)'], timeout=20) if i == 3: ready = True elif i == 0: self.fw_version = self.test.match.group(1) elif i == 1: self.px4_version = self.test.match.group(1) self.nuttx_version = self.test.match.group(2) elif i == 2: self.stm32_serial = self.test.match.group(1) except Exception as ex: self.close() util.show_error('Connecting to test board2', ex, self.testlog) if self.nsh is not None: # log any extra nsh data logger.debug("Draining nsh") try: self.nsh.read_nonblocking(4096, 1) except Exception as ex: pass try: if not ref_only and not ref_gyro_offset_ok(self.refmav): self.close() util.failure("Bad reference gyro - FAILED") except Exception as ex: self.close() util.show_error('testing reference gyros', ex) logger.info("Setting rotation level") try: rotate.set_rotation(self, 'level', wait=False) except Exception as ex: self.close() util.show_error("unable to set safety off", ex)
def __init__(self, ref_only=False): util.kill_processes(['mavproxy.py', GDB]) self.reflog = StringIO() self.testlog = StringIO() self.ref = None self.test = None self.nsh = None self.refmav = None self.testmav = None try: if not ref_only: self.nsh = nsh_console.nsh_console() except Exception as ex: self.close() util.show_error('Connecting to nsh console', ex, self.testlog) try: self.ref = mav_reference.mav_reference(self.reflog) except Exception as ex: self.close() util.show_error('Connecting to reference board1', ex, self.reflog) try: if not ref_only: self.test = mav_test.mav_test(self.testlog) except Exception as ex: self.close() util.show_error('Connecting to test board1', ex, self.testlog) try: logger.info("CONNECTING MAVLINK TO REFERENCE BOARD") self.refmav = mavutil.mavlink_connection('127.0.0.1:14550') util.wait_heartbeat(self.refmav, timeout=30) util.wait_mode(self.refmav, IDLE_MODES) except Exception as ex: self.close() util.show_error('Connecting to reference board2', ex, self.reflog) try: if not ref_only: logger.info("CONNECTING MAVLINK TO TEST BOARD") self.testmav = mavutil.mavlink_connection('127.0.0.1:14551') util.wait_heartbeat(self.testmav, timeout=30) logger.info("got heartbeat") util.wait_mode(self.testmav, IDLE_MODES) logger.info("Waiting for 'Ready to FLY'") self.fw_version = None self.px4_version = None self.nuttx_version = None self.stm32_serial = None ready = False self.test.send("param fetch\n") # log version information for later reference while (self.fw_version is None or self.px4_version is None or self.nuttx_version is None or self.stm32_serial is None or not ready): i = self.test.expect([ 'APM: ([^\r\n]*Copter[^\r\n]*)\r\n', 'APM: PX4: ([0-9a-f]+) NuttX: ([0-9a-f]+)\r\n', 'APM: PX4v2 ([0-9A-F]+ [0-9A-F]+ [0-9A-F]+)\r\n', '(Ready to FLY)' ], timeout=20) if i == 3: ready = True elif i == 0: self.fw_version = self.test.match.group(1) elif i == 1: self.px4_version = self.test.match.group(1) self.nuttx_version = self.test.match.group(2) elif i == 2: self.stm32_serial = self.test.match.group(1) except Exception as ex: self.close() util.show_error('Connecting to test board2', ex, self.testlog) if self.nsh is not None: # log any extra nsh data logger.debug("Draining nsh") try: self.nsh.read_nonblocking(4096, 1) except Exception as ex: pass try: if not ref_only and not ref_gyro_offset_ok(self.refmav): self.close() util.failure("Bad reference gyro - FAILED") except Exception as ex: self.close() util.show_error('testing reference gyros', ex) logger.info("Setting rotation level") try: rotate.set_rotation(self, 'level', wait=False) except Exception as ex: self.close() util.show_error("unable to set safety off", ex)
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