mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Tools/HIL: explain cmd, use monotonic time
This commit is contained in:
parent
0f6e30599c
commit
b71b908ac7
@ -40,8 +40,8 @@ def monitor_firmware_upload(port, baudrate):
|
||||
ser = serial.Serial(port, baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=1, xonxoff=True, rtscts=False, dsrdtr=False)
|
||||
|
||||
timeout = 180 # 3 minutes
|
||||
timeout_start = time.time()
|
||||
timeout_newline = time.time()
|
||||
timeout_start = time.monotonic()
|
||||
timeout_newline = time.monotonic()
|
||||
|
||||
return_code = 0
|
||||
|
||||
@ -59,13 +59,13 @@ def monitor_firmware_upload(port, baudrate):
|
||||
elif "nsh>" in serial_line:
|
||||
sys.exit(return_code)
|
||||
|
||||
if time.time() > timeout_start + timeout:
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
print("Error, timeout")
|
||||
sys.exit(-1)
|
||||
|
||||
# newline every 10 seconds if still running
|
||||
if time.time() - timeout_newline > 10:
|
||||
timeout_newline = time.time()
|
||||
if time.monotonic() - timeout_newline > 10:
|
||||
timeout_newline = time.monotonic()
|
||||
ser.write("\n".encode("ascii"))
|
||||
ser.flush()
|
||||
|
||||
|
||||
@ -34,7 +34,7 @@ def print_line(line):
|
||||
def do_param_set_cmd(port, baudrate, param_name, param_value):
|
||||
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)
|
||||
|
||||
timeout_start = time.time()
|
||||
timeout_start = time.monotonic()
|
||||
timeout = 30 # 30 seconds
|
||||
|
||||
# wait for nsh prompt
|
||||
@ -50,7 +50,7 @@ def do_param_set_cmd(port, baudrate, param_name, param_value):
|
||||
if len(serial_line) > 0:
|
||||
print_line(serial_line)
|
||||
|
||||
if time.time() > timeout_start + timeout:
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
print("Error, timeout waiting for prompt")
|
||||
sys.exit(1)
|
||||
|
||||
@ -58,12 +58,13 @@ def do_param_set_cmd(port, baudrate, param_name, param_value):
|
||||
ser.readlines()
|
||||
|
||||
# run command
|
||||
timeout_start = time.time()
|
||||
timeout_start = time.monotonic()
|
||||
timeout = 10 # 10 seconds
|
||||
|
||||
cmd = "param set " + param_name + " " + param_value
|
||||
|
||||
# write command (param set) and wait for command echo
|
||||
print("Running command: \'{0}\'".format(cmd))
|
||||
serial_cmd = '{0}\r\n'.format(cmd)
|
||||
ser.write(serial_cmd.encode("ascii"))
|
||||
ser.flush()
|
||||
@ -77,7 +78,7 @@ def do_param_set_cmd(port, baudrate, param_name, param_value):
|
||||
if len(serial_line) > 0:
|
||||
print_line(serial_line)
|
||||
|
||||
if time.time() > timeout_start + timeout:
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
print("Error, timeout waiting for command echo")
|
||||
break
|
||||
|
||||
@ -89,8 +90,8 @@ def do_param_set_cmd(port, baudrate, param_name, param_value):
|
||||
|
||||
param_show_response = param_name + " ["
|
||||
|
||||
timeout_start = time.time()
|
||||
timeout = 2 # 2 seconds
|
||||
timeout_start = time.monotonic()
|
||||
timeout = 3 # 3 seconds
|
||||
|
||||
while True:
|
||||
serial_line = ser.readline().decode("ascii", errors='ignore')
|
||||
@ -107,19 +108,20 @@ def do_param_set_cmd(port, baudrate, param_name, param_value):
|
||||
if len(serial_line) > 0:
|
||||
print_line(serial_line)
|
||||
|
||||
if time.time() > timeout_start + timeout:
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
if "nsh>" in serial_line:
|
||||
sys.exit(1) # error, command didn't complete successfully
|
||||
elif "NuttShell (NSH)" in serial_line:
|
||||
sys.exit(1) # error, command didn't complete successfully
|
||||
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
print("Error, timeout")
|
||||
sys.exit(-1)
|
||||
|
||||
if len(serial_line) <= 0:
|
||||
ser.write("\r\n".encode("ascii"))
|
||||
ser.flush()
|
||||
|
||||
if time.time() > timeout_start + timeout:
|
||||
print("Error, timeout")
|
||||
sys.exit(-1)
|
||||
time.sleep(0.2)
|
||||
|
||||
ser.close()
|
||||
|
||||
|
||||
@ -47,14 +47,14 @@ def monitor_firmware_upload(port, baudrate):
|
||||
|
||||
timeout_reboot_cmd = 30
|
||||
timeout = 300 # 5 minutes
|
||||
timeout_start = time.time()
|
||||
timeout_newline = time.time()
|
||||
timeout_start = time.monotonic()
|
||||
timeout_newline = time.monotonic()
|
||||
time_success = 0
|
||||
|
||||
return_code = 0
|
||||
|
||||
while True:
|
||||
if time.time() > timeout_start + timeout_reboot_cmd:
|
||||
if time.monotonic() > timeout_start + timeout_reboot_cmd:
|
||||
ser.write("reboot\n".encode("ascii"))
|
||||
|
||||
serial_line = ser.readline().decode("ascii", errors='ignore')
|
||||
@ -66,13 +66,13 @@ def monitor_firmware_upload(port, baudrate):
|
||||
print_line(serial_line)
|
||||
|
||||
if "NuttShell (NSH)" in serial_line:
|
||||
time_success = time.time()
|
||||
time_success = time.monotonic()
|
||||
|
||||
# wait at least 2 seconds after seeing prompt to catch potential errors
|
||||
if time_success > 0 and time.time() > time_success + 2:
|
||||
if time_success > 0 and time.monotonic() > time_success + 2:
|
||||
sys.exit(return_code)
|
||||
|
||||
if time.time() > timeout_start + timeout:
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
print("Error, timeout")
|
||||
sys.exit(-1)
|
||||
|
||||
|
||||
@ -40,7 +40,7 @@ def print_line(line):
|
||||
def do_nsh_cmd(port, baudrate, cmd):
|
||||
ser = serial.Serial(port, baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=0.2, xonxoff=True, rtscts=False, dsrdtr=False)
|
||||
|
||||
timeout_start = time.time()
|
||||
timeout_start = time.monotonic()
|
||||
timeout = 30 # 30 seconds
|
||||
|
||||
# wait for nsh prompt
|
||||
@ -56,7 +56,7 @@ def do_nsh_cmd(port, baudrate, cmd):
|
||||
if len(serial_line) > 0:
|
||||
print_line(serial_line)
|
||||
|
||||
if time.time() > timeout_start + timeout:
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
print("Error, timeout waiting for prompt")
|
||||
sys.exit(1)
|
||||
|
||||
@ -64,12 +64,13 @@ def do_nsh_cmd(port, baudrate, cmd):
|
||||
ser.readlines()
|
||||
|
||||
# run command
|
||||
timeout_start = time.time()
|
||||
timeout_start = time.monotonic()
|
||||
timeout = 1 # 1 second
|
||||
|
||||
success_cmd = "cmd succeeded!"
|
||||
|
||||
# wait for command echo
|
||||
print("Running command: \'{0}\'".format(cmd))
|
||||
serial_cmd = '{0}; echo "{1}"; echo "{2}";\r\n'.format(cmd, success_cmd, success_cmd)
|
||||
ser.write(serial_cmd.encode("ascii"))
|
||||
ser.flush()
|
||||
@ -86,12 +87,12 @@ def do_nsh_cmd(port, baudrate, cmd):
|
||||
if len(serial_line) > 0:
|
||||
print_line(serial_line)
|
||||
|
||||
if time.time() > timeout_start + timeout:
|
||||
if (len(serial_line) <= 0) and (time.monotonic() > timeout_start + timeout):
|
||||
print("Error, timeout waiting for command echo")
|
||||
break
|
||||
|
||||
|
||||
timeout_start = time.time()
|
||||
timeout_start = time.monotonic()
|
||||
timeout = 240 # 4 minutes
|
||||
|
||||
return_code = 0
|
||||
@ -114,13 +115,14 @@ def do_nsh_cmd(port, baudrate, cmd):
|
||||
elif "NuttShell (NSH)" in serial_line:
|
||||
sys.exit(1) # error, command didn't complete successfully
|
||||
|
||||
if (len(serial_line) <= 0) and (time.monotonic() > timeout_start + timeout):
|
||||
print("Error, timeout")
|
||||
sys.exit(-1)
|
||||
|
||||
if len(serial_line) <= 0:
|
||||
ser.write("\r\n".encode("ascii"))
|
||||
ser.flush()
|
||||
|
||||
if time.time() > timeout_start + timeout:
|
||||
print("Error, timeout")
|
||||
sys.exit(-1)
|
||||
time.sleep(0.2)
|
||||
|
||||
ser.close()
|
||||
|
||||
|
||||
@ -41,7 +41,7 @@ def print_line(line):
|
||||
def do_test(port, baudrate, test_name):
|
||||
ser = serial.Serial(port, baudrate, bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, stopbits=serial.STOPBITS_ONE, timeout=0.2, xonxoff=True, rtscts=False, dsrdtr=False)
|
||||
|
||||
timeout_start = time.time()
|
||||
timeout_start = time.monotonic()
|
||||
timeout = 30 # 30 seconds
|
||||
|
||||
# wait for nsh prompt
|
||||
@ -57,7 +57,7 @@ def do_test(port, baudrate, test_name):
|
||||
if len(serial_line) > 0:
|
||||
print(serial_line, end='')
|
||||
|
||||
if time.time() > timeout_start + timeout:
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
print("Error, timeout waiting for prompt")
|
||||
return False
|
||||
|
||||
@ -72,10 +72,11 @@ def do_test(port, baudrate, test_name):
|
||||
print("| Running:", cmd)
|
||||
print('|======================================================================')
|
||||
|
||||
timeout_start = time.time()
|
||||
timeout_start = time.monotonic()
|
||||
timeout = 2 # 2 seconds
|
||||
|
||||
# wait for command echo
|
||||
print("Running command: \'{0}\'".format(cmd))
|
||||
serial_cmd = '{0}\n'.format(cmd)
|
||||
ser.write(serial_cmd.encode("ascii"))
|
||||
ser.flush()
|
||||
@ -88,14 +89,14 @@ def do_test(port, baudrate, test_name):
|
||||
if len(serial_line) > 0:
|
||||
print_line(serial_line)
|
||||
|
||||
if time.time() > timeout_start + timeout:
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
print("Error, timeout waiting for command echo")
|
||||
break
|
||||
|
||||
|
||||
# print results, wait for final result (PASSED or FAILED)
|
||||
timeout = 300 # 5 minutes
|
||||
timeout_start = time.time()
|
||||
timeout_start = time.monotonic()
|
||||
timeout_newline = timeout_start
|
||||
|
||||
while True:
|
||||
@ -111,16 +112,16 @@ def do_test(port, baudrate, test_name):
|
||||
success = False
|
||||
break
|
||||
|
||||
if time.time() > timeout_start + timeout:
|
||||
if time.monotonic() > timeout_start + timeout:
|
||||
print("Error, timeout")
|
||||
print(test_name + f" {COLOR_RED}FAILED{COLOR_RESET}")
|
||||
success = False
|
||||
break
|
||||
|
||||
# newline every 10 seconds if still running
|
||||
if time.time() - timeout_newline > 10:
|
||||
if (len(serial_line) <= 0) and (time.monotonic() - timeout_newline > 10):
|
||||
ser.write("\n".encode("ascii"))
|
||||
timeout_newline = time.time()
|
||||
timeout_newline = time.monotonic()
|
||||
|
||||
ser.close()
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user