mirror of https://github.com/ArduPilot/ardupilot
autotest: use BATTERY_STATUS to detect sub reboot
Sub doesn't implement AP_Stats so we have custom reboot detection for it. The current look-for-string strategy is flawed - we're missing the string on reboot
This commit is contained in:
parent
e86e3333a5
commit
f65bee80dc
|
@ -3,6 +3,7 @@
|
||||||
# Dive ArduSub in SITL
|
# Dive ArduSub in SITL
|
||||||
from __future__ import print_function
|
from __future__ import print_function
|
||||||
import os
|
import os
|
||||||
|
import time
|
||||||
|
|
||||||
from pymavlink import mavutil
|
from pymavlink import mavutil
|
||||||
|
|
||||||
|
@ -326,16 +327,43 @@ class AutoTestSub(AutoTest):
|
||||||
|
|
||||||
def reboot_sitl(self):
|
def reboot_sitl(self):
|
||||||
"""Reboot SITL instance and wait it to reconnect."""
|
"""Reboot SITL instance and wait it to reconnect."""
|
||||||
self.context_push()
|
# out battery is reset to full on reboot. So reduce it to 10%
|
||||||
self.context_collect("STATUSTEXT")
|
# and wait for it to go above 50.
|
||||||
self.send_reboot_command()
|
self.run_cmd(mavutil.mavlink.MAV_CMD_BATTERY_RESET,
|
||||||
# "Init ArduSub" comes out as raw text, not a statustext
|
255, # battery mask
|
||||||
for i in range(2):
|
10, # percentage
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0)
|
||||||
|
self.run_cmd_reboot()
|
||||||
|
tstart = time.time()
|
||||||
|
while True:
|
||||||
|
if time.time() - tstart > 30:
|
||||||
|
raise NotAchievedException("Did not detect reboot")
|
||||||
|
# ask for the message:
|
||||||
|
batt = None
|
||||||
try:
|
try:
|
||||||
self.wait_statustext("ArduPilot Ready", check_context=True, wallclock_timeout=True)
|
self.send_cmd(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,
|
||||||
|
mavutil.mavlink.MAVLINK_MSG_ID_BATTERY_STATUS,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0)
|
||||||
|
batt = self.mav.recv_match(type='BATTERY_STATUS',
|
||||||
|
blocking=True,
|
||||||
|
timeout=1)
|
||||||
except ConnectionResetError as e:
|
except ConnectionResetError as e:
|
||||||
pass
|
pass
|
||||||
self.context_pop()
|
self.progress("Battery: %s" % str(batt))
|
||||||
|
if batt is None:
|
||||||
|
continue
|
||||||
|
if batt.battery_remaining > 50:
|
||||||
|
break
|
||||||
self.initialise_after_reboot_sitl()
|
self.initialise_after_reboot_sitl()
|
||||||
|
|
||||||
def apply_defaultfile_parameters(self):
|
def apply_defaultfile_parameters(self):
|
||||||
|
|
|
@ -1488,6 +1488,17 @@ class AutoTest(ABC):
|
||||||
backup_valgrind_log = ("%s-%s" % (str(int(time.time())), valgrind_log))
|
backup_valgrind_log = ("%s-%s" % (str(int(time.time())), valgrind_log))
|
||||||
shutil.move(valgrind_log, backup_valgrind_log)
|
shutil.move(valgrind_log, backup_valgrind_log)
|
||||||
|
|
||||||
|
def run_cmd_reboot(self):
|
||||||
|
self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
|
||||||
|
1, # confirmation
|
||||||
|
1, # reboot autopilot
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0,
|
||||||
|
0)
|
||||||
|
|
||||||
def reboot_sitl_mav(self, required_bootcount=None):
|
def reboot_sitl_mav(self, required_bootcount=None):
|
||||||
"""Reboot SITL instance using mavlink and wait for it to reconnect."""
|
"""Reboot SITL instance using mavlink and wait for it to reconnect."""
|
||||||
old_bootcount = self.get_parameter('STAT_BOOTCNT')
|
old_bootcount = self.get_parameter('STAT_BOOTCNT')
|
||||||
|
@ -1500,15 +1511,7 @@ class AutoTest(ABC):
|
||||||
self.start_SITL(wipe=False)
|
self.start_SITL(wipe=False)
|
||||||
else:
|
else:
|
||||||
self.progress("Executing reboot command")
|
self.progress("Executing reboot command")
|
||||||
self.run_cmd(mavutil.mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN,
|
self.run_cmd_reboot()
|
||||||
1, # confirmation
|
|
||||||
1, # reboot autopilot
|
|
||||||
0,
|
|
||||||
0,
|
|
||||||
0,
|
|
||||||
0,
|
|
||||||
0,
|
|
||||||
0)
|
|
||||||
self.detect_and_handle_reboot(old_bootcount, required_bootcount=required_bootcount)
|
self.detect_and_handle_reboot(old_bootcount, required_bootcount=required_bootcount)
|
||||||
|
|
||||||
def send_cmd_enter_cpu_lockup(self):
|
def send_cmd_enter_cpu_lockup(self):
|
||||||
|
|
Loading…
Reference in New Issue