Tools: autotest: assume Tracker has AP_Stats

This commit is contained in:
Peter Barker 2019-08-06 17:09:21 +10:00 committed by Randy Mackay
parent e5ea748e7f
commit 05a48928f8
2 changed files with 15 additions and 28 deletions

View File

@ -25,22 +25,6 @@ class AutoTestTracker(AutoTest):
def sitl_start_location(self):
return SITL_START_LOCATION
def start_stream_systemtime(self):
'''AntennaTracker doesn't stream this by default but we need it for get_sim_time'''
try:
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_SYSTEM_TIME, 10)
except Exception:
pass
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_SYSTEM_TIME, 10)
def set_rc_default(self):
'''tracker does not send RC_CHANNELS, so can't set_rc_default'''
'''... however, dodgily hook in here to get system time:'''
self.start_stream_systemtime()
def initialise_after_reboot_sitl(self):
self.start_stream_systemtime()
def default_mode(self):
return "AUTO"
@ -57,18 +41,6 @@ class AutoTestTracker(AutoTest):
def sysid_thismav(self):
return 2
def reboot_sitl(self):
"""Reboot SITL instance and wait it to reconnect."""
self.wait_heartbeat()
if self.armed():
self.disarm_vehicle()
self.mavproxy.send("reboot\n")
self.mavproxy.expect("Init AntennaTracker")
# empty mav to avoid getting old timestamps:
while self.mav.recv_match(blocking=False):
pass
self.initialise_after_reboot_sitl()
def disabled_tests(self):
return {
"ArmFeatures": "See https://github.com/ArduPilot/ardupilot/issues/10652",

View File

@ -339,6 +339,7 @@ class AutoTest(ABC):
def reboot_sitl(self, required_bootcount=None):
"""Reboot SITL instance and wait for it to reconnect."""
self.progress("Rebooting SITL")
self.reboot_sitl_mav(required_bootcount=required_bootcount)
self.assert_simstate_location_is_at_startup_location()
@ -2374,6 +2375,9 @@ class AutoTest(ABC):
if self.distance_to_home() > 1:
raise NotAchievedException("Setting home to current location did not work")
if self.is_tracker():
# tracker starts armed...
self.disarm_vehicle(force=True)
self.reboot_sitl()
def test_dataflash_over_mavlink(self):
@ -2806,6 +2810,12 @@ class AutoTest(ABC):
try:
self.set_parameter("STAT_BOOTCNT", 0)
self.set_parameter("SIM_BARO_COUNT", 0)
if self.is_tracker():
# starts armed...
self.progress("Disarming tracker")
self.disarm_vehicle(force=True)
self.reboot_sitl(required_bootcount=1);
self.progress("Waiting for 'Check BRD_TYPE'")
self.mavproxy.expect("Check BRD_TYPE");
@ -2817,6 +2827,11 @@ class AutoTest(ABC):
self.progress("Resetting SIM_BARO_COUNT")
self.set_parameter("SIM_BARO_COUNT", old_sim_baro_count)
if self.is_tracker():
# starts armed...
self.progress("Disarming tracker")
self.disarm_vehicle(force=True)
self.progress("Calling reboot-sitl ")
self.reboot_sitl(required_bootcount=2);