Browse Source

Tools/HIL/run_nsh_cmd.py fail if command failed

master
Daniel Agar 4 years ago
parent
commit
4a0fa08953
  1. 57
      .ci/Jenkinsfile-hardware
  2. 34
      Tools/HIL/monitor_firmware_upload.py
  3. 70
      Tools/HIL/run_nsh_cmd.py
  4. 60
      Tools/HIL/run_tests.py
  5. 3
      platforms/nuttx/Debug/upload_jlink_gdb.sh

57
.ci/Jenkinsfile-hardware

@ -63,6 +63,8 @@ pipeline {
stage("status") { stage("status") {
steps { steps {
statusFTDI() statusFTDI()
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener px4io_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "px4io status" || true'
} }
} }
stage("tests") { stage("tests") {
@ -209,6 +211,8 @@ pipeline {
stage("status") { stage("status") {
steps { steps {
statusFTDI() statusFTDI()
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener px4io_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "px4io status" || true'
} }
} }
stage("tests") { stage("tests") {
@ -355,6 +359,8 @@ pipeline {
stage("status") { stage("status") {
steps { steps {
statusFTDI() statusFTDI()
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener px4io_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "px4io status" || true'
} }
} }
stage("tests") { stage("tests") {
@ -428,6 +434,8 @@ pipeline {
stage("status") { stage("status") {
steps { steps {
statusFTDI() statusFTDI()
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener px4io_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "px4io status" || true'
} }
} }
stage("tests") { stage("tests") {
@ -505,6 +513,8 @@ pipeline {
stage("status") { stage("status") {
steps { steps {
statusFTDI() statusFTDI()
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener px4io_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "px4io status" || true'
} }
} }
stage("tests") { stage("tests") {
@ -578,6 +588,8 @@ pipeline {
stage("status") { stage("status") {
steps { steps {
statusFTDI() statusFTDI()
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener px4io_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "px4io status" || true'
} }
} }
stage("tests") { stage("tests") {
@ -655,6 +667,8 @@ pipeline {
stage("status") { stage("status") {
steps { steps {
statusFTDI() statusFTDI()
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener px4io_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "px4io status" || true'
} }
} }
stage("tests") { stage("tests") {
@ -840,17 +854,17 @@ void statusFTDI() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "free"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "free"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "work_queue status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "work_queue status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "board_adc test"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "board_adc test"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander check"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander check" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate accel quick; sleep 2; param show CAL_ACC*"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate accel quick; sleep 2; param show CAL_ACC*" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate gyro; sleep 2; param show CAL_GYRO*"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate gyro; sleep 2; param show CAL_GYRO*" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate level; sleep 2; param show SENS_BOARD*"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate level; sleep 2; param show SENS_BOARD*" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate mag quick; sleep 2; param show CAL_MAG*"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate mag quick; sleep 2; param show CAL_MAG*" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "dataman status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "dataman status" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "df"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "df"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "dmesg"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "dmesg" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "gps status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "gps status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "gyro_calibration status; param show CAL_GYRO*"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "gyro_calibration status; param show CAL_GYRO*" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener adc_report"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener adc_report"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener battery_status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener battery_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener cpuload"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener cpuload"'
@ -863,7 +877,6 @@ void statusFTDI() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_status_flags"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener estimator_status_flags"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener logger_status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener logger_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener parameter_update"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener parameter_update"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener px4io_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_accel"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_accel"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_accel_fifo"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_accel_fifo"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_baro"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener sensor_baro"'
@ -904,18 +917,18 @@ void statusFTDI() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "perf latency"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "perf latency"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "perf"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "perf"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ps"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ps"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "pwm info -d /dev/pwm_output0"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "pwm info -d /dev/pwm_output0" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "pwm info -d /dev/pwm_output1"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "pwm info -d /dev/pwm_output1" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "pwm_out status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "pwm_out status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "px4io status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_bench -r 2" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_bench -r 2"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sensors status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sensors status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener cpuload; top once; listener cpuload"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "listener cpuload; top once; listener cpuload"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uavcan status" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb top -1 -a"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "uorb top -1 -a"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ver all"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ver all"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "work_queue status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "work_queue status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "gyro_calibration status; param show CAL_GYRO*"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "gyro_calibration status; param show CAL_GYRO*" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ekf2 status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "ekf2 status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "free"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "free"'
// stop logger // stop logger
@ -926,21 +939,21 @@ void cleanupFTDI() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander stop"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander stop"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mavlink stop-all"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mavlink stop-all"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "navigator stop"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "navigator stop"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "dataman stop"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "dataman stop" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "logger off"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "logger off"'
// wipe sdcard // wipe sdcard
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "umount /fs/microsd"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "umount /fs/microsd" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mkfatfs /dev/mmcsd0"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mkfatfs /dev/mmcsd0" || true'
// drop any uncommited hardfaults // drop any uncommited hardfaults
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "hardfault_log rearm"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "hardfault_log rearm" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "hardfault_log reset"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "hardfault_log reset" || true'
// erase mtd // erase mtd
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd readtest"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd readtest" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd rwtest"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd rwtest" || true'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd erase"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "mtd erase" || true'
// disable buzzer and cleanup storage // disable buzzer and cleanup storage
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param reset_all"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param reset_all"'

34
Tools/HIL/monitor_firmware_upload.py

@ -5,46 +5,36 @@ import subprocess
from subprocess import call, Popen from subprocess import call, Popen
from argparse import ArgumentParser from argparse import ArgumentParser
import re import re
import sys
def monitor_firmware_upload(port, baudrate): def monitor_firmware_upload(port, baudrate):
databits = serial.EIGHTBITS ser = serial.Serial(port, baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=1, xonxoff=True, rtscts=False, dsrdtr=False)
stopbits = serial.STOPBITS_ONE
parity = serial.PARITY_NONE
ser = serial.Serial(port, baudrate, databits, parity, stopbits, timeout=1)
finished = 0 timeout = 180 # 3 minutes
timeout = 300 # 5 minutes
timeout_start = time.time() timeout_start = time.time()
timeout_newline = time.time() timeout_newline = time.time()
while finished == 0: while True:
serial_line = ser.readline().decode("ascii", errors='ignore') serial_line = ser.readline().decode("ascii", errors='ignore')
if (len(serial_line) > 0):
print(serial_line.replace('\n', ''))
if "NuttShell (NSH)" in serial_line: if "NuttShell (NSH)" in serial_line:
finished = 1 sys.exit(0)
break elif "nsh>" in serial_line:
sys.exit(0)
if time.time() - timeout_start > 10: else:
if "nsh>" in serial_line: if len(serial_line) > 0:
finished = 1 print(serial_line, end='')
break
if time.time() > timeout_start + timeout: if time.time() > timeout_start + timeout:
print("Error, timeout") print("Error, timeout")
finished = 1 sys.exit(-1)
break
# newline every 10 seconds if still running # newline every 10 seconds if still running
if time.time() - timeout_newline > 10: if time.time() - timeout_newline > 10:
timeout_newline = time.time() timeout_newline = time.time()
ser.write('\n'.encode("ascii")) ser.write("\n".encode("ascii"))
ser.flush() ser.flush()
ser.close()
def main(): def main():
parser = ArgumentParser(description=__doc__) parser = ArgumentParser(description=__doc__)
parser.add_argument('--device', "-d", nargs='?', default=None, help='', required=True) parser.add_argument('--device', "-d", nargs='?', default=None, help='', required=True)

70
Tools/HIL/run_nsh_cmd.py

@ -8,46 +8,50 @@ import re
import sys import sys
def do_nsh_cmd(port, baudrate, cmd): def do_nsh_cmd(port, baudrate, cmd):
databits = serial.EIGHTBITS ser = serial.Serial(port, baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=0.1, xonxoff=True, rtscts=False, dsrdtr=False)
stopbits = serial.STOPBITS_ONE
parity = serial.PARITY_NONE
ser = serial.Serial(port, baudrate, databits, parity, stopbits, timeout=0.1)
# run command
timeout_start = time.time() timeout_start = time.time()
timeout = 10 # 10 seconds timeout = 10 # 10 seconds
# clear # wait for nsh prompt
ser.write("\n".encode("ascii")) while True:
ser.flush() ser.write("\n".encode("ascii"))
ser.readline() ser.flush()
success_cmd = "cmd succeeded!" serial_line = ser.readline().decode("ascii", errors='ignore')
serial_cmd = '{0}; echo "{1}"\n'.format(cmd, success_cmd) if "nsh>" in serial_line:
ser.write(serial_cmd.encode("ascii")) break
ser.flush() else:
ser.readline() if len(serial_line) > 0:
print(serial_line, end='')
# TODO: require successful command echo if time.time() > timeout_start + timeout:
# while True: print("Error, timeout waiting for prompt")
# serial_cmd = '{0}; echo "{1}"\n'.format(cmd, success_cmd) sys.exit(1)
# ser.write(serial_cmd.encode("ascii"))
# ser.flush()
# serial_line = ser.readline().decode("ascii", errors='ignore') # run command
timeout_start = time.time()
timeout = 10 # 10 seconds
# if cmd in serial_line: success_cmd = "cmd succeeded!"
# break
# else:
# print(serial_line, end='')
# if time.time() > timeout_start + timeout: # wait for command echo
# print("Error, timeout") serial_cmd = '{0}; echo "{1}"\r\n'.format(cmd, success_cmd)
# sys.exit(-1) ser.write(serial_cmd.encode("ascii"))
# break ser.flush()
while True:
serial_line = ser.readline().decode("ascii", errors='ignore')
# time.sleep(1) if cmd in serial_line:
break
else:
if len(serial_line) > 0:
print(serial_line, end='')
if time.time() > timeout_start + timeout:
print("Error, timeout waiting for command echo")
break
timeout_start = time.time() timeout_start = time.time()
@ -63,14 +67,12 @@ def do_nsh_cmd(port, baudrate, cmd):
print(serial_line, end='') print(serial_line, end='')
if "nsh>" in serial_line: if "nsh>" in serial_line:
#sys.exit(-1) # error, command didn't complete successfully sys.exit(1) # error, command didn't complete successfully
break # TODO: return error on failure
elif "NuttShell (NSH)" in serial_line: elif "NuttShell (NSH)" in serial_line:
#sys.exit(-1) # error, command didn't complete successfully sys.exit(1) # error, command didn't complete successfully
break # TODO: return error on failure
if len(serial_line) <= 0: if len(serial_line) <= 0:
ser.write("\n".encode("ascii")) ser.write("\r\n".encode("ascii"))
ser.flush() ser.flush()
if time.time() > timeout_start + timeout: if time.time() > timeout_start + timeout:

60
Tools/HIL/run_tests.py

@ -10,10 +10,27 @@ import os
import sys import sys
def do_test(port, baudrate, test_name): def do_test(port, baudrate, test_name):
databits = serial.EIGHTBITS ser = serial.Serial(port, baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=1, xonxoff=True, rtscts=False, dsrdtr=False)
stopbits = serial.STOPBITS_ONE
parity = serial.PARITY_NONE timeout_start = time.time()
ser = serial.Serial(port, baudrate, databits, parity, stopbits, timeout=1) timeout = 10 # 10 seconds
# wait for nsh prompt
while True:
ser.write("\n".encode("ascii"))
ser.flush()
serial_line = ser.readline().decode("ascii", errors='ignore')
if "nsh>" in serial_line:
break
else:
if len(serial_line) > 0:
print(serial_line, end='')
if time.time() > timeout_start + timeout:
print("Error, timeout waiting for prompt")
return False
success = False success = False
@ -22,37 +39,26 @@ def do_test(port, baudrate, test_name):
cmd = 'tests ' + test_name cmd = 'tests ' + test_name
print("| Running:", cmd) print("| Running:", cmd)
print('|======================================================================') print('|======================================================================')
timeout_start = time.time() timeout_start = time.time()
timeout = 10 # 10 seconds timeout = 10 # 10 seconds
# clear # wait for command echo
ser.write("\n".encode("ascii"))
ser.flush()
ser.readline()
serial_cmd = '{0}\n'.format(cmd) serial_cmd = '{0}\n'.format(cmd)
ser.write(serial_cmd.encode("ascii")) ser.write(serial_cmd.encode("ascii"))
ser.flush() ser.flush()
ser.readline() while True:
serial_line = ser.readline().decode("ascii", errors='ignore')
# TODO: retry command
# while True:
# serial_cmd = '{0}\n'.format(cmd)
# ser.write(serial_cmd.encode("ascii"))
# ser.flush()
# serial_line = ser.readline().decode("ascii", errors='ignore')
# if cmd in serial_line:
# break
# else:
# print(serial_line.replace('\n', ''))
# if time.time() > timeout_start + timeout: if cmd in serial_line:
# print("Error, unable to write cmd") break
# return False else:
if len(serial_line) > 0:
print(serial_line, end='')
# time.sleep(1) if time.time() > timeout_start + timeout:
print("Error, timeout waiting for command echo")
break
# print results, wait for final result (PASSED or FAILED) # print results, wait for final result (PASSED or FAILED)

3
platforms/nuttx/Debug/upload_jlink_gdb.sh

@ -32,7 +32,8 @@ do
if [ $gdb_ret -ne 0 ]; then if [ $gdb_ret -ne 0 ]; then
echo "GDB error, retrying" echo "GDB error, retrying"
sleep 3 killall JLinkGDBServerCLExe
sleep 5
else else
exit 0 exit 0
fi fi

Loading…
Cancel
Save