autotest: tidy wait_disarmed

This commit is contained in:
Peter Barker 2022-06-13 21:20:44 +10:00 committed by Peter Barker
parent b18c597f0b
commit 0697ce19d2

View File

@ -4444,7 +4444,7 @@ class AutoTest(ABC):
0,
0,
timeout=timeout)
return self.wait_disarmed()
self.wait_disarmed()
def disarm_vehicle_expect_fail(self):
'''disarm, checking first that non-forced disarm fails, then doing a forced disarm'''
@ -4481,12 +4481,13 @@ class AutoTest(ABC):
if now - last_print_time > 1:
self.progress("Waiting for disarm (%.2fs so far of allowed %.2f)" % (delta, timeout))
last_print_time = now
self.wait_heartbeat(quiet=True)
# self.progress("Got heartbeat")
if not self.mav.motors_armed():
self.progress("DISARMED after %.2f seconds (allowed=%.2f)" %
(delta, timeout))
return True
msg = self.wait_heartbeat(quiet=True)
if msg.base_mode & mavutil.mavlink.MAV_MODE_FLAG_SAFETY_ARMED:
# still armed
continue
self.progress("DISARMED after %.2f seconds (allowed=%.2f)" %
(delta, timeout))
return
def wait_attitude(self, desroll=None, despitch=None, timeout=2, tolerance=10, message_type='ATTITUDE'):
'''wait for an attitude (degrees)'''
@ -4619,7 +4620,6 @@ class AutoTest(ABC):
self.progress("Disarm motors with MavProxy")
mavproxy.send('disarm\n')
self.wait_disarmed()
return True
def arm_motors_with_rc_input(self, timeout=20):
"""Arm motors with radio."""
@ -8381,15 +8381,14 @@ Also, ignores heartbeats not from our target system'''
if not self.arm_vehicle():
raise NotAchievedException("Failed to ARM")
self.progress("default disarm_vehicle() call")
if not self.disarm_vehicle():
raise NotAchievedException("Failed to DISARM")
self.disarm_vehicle()
self.progress("arm with mavproxy")
mavproxy = self.start_mavproxy()
if not self.mavproxy_arm_vehicle(mavproxy):
raise NotAchievedException("Failed to ARM")
self.progress("disarm with mavproxy")
if not self.mavproxy_disarm_vehicle(mavproxy):
raise NotAchievedException("Failed to DISARM")
self.mavproxy_disarm_vehicle(mavproxy)
self.stop_mavproxy(mavproxy)
if not self.is_sub():
@ -8531,8 +8530,7 @@ Also, ignores heartbeats not from our target system'''
self.progress("Armable mode : %s" % mode)
self.change_mode(mode)
self.arm_vehicle()
if not self.disarm_vehicle():
raise NotAchievedException("Failed to DISARM")
self.disarm_vehicle()
self.progress("PASS arm mode : %s" % mode)
if mode in self.get_not_armable_mode_list():
if mode in self.get_not_disarmed_settable_modes_list():
@ -8563,8 +8561,7 @@ Also, ignores heartbeats not from our target system'''
self.change_mode(mode)
self.arm_vehicle()
self.wait_heartbeat()
if not self.disarm_vehicle():
raise NotAchievedException("Failed to DISARM")
self.disarm_vehicle()
self.progress("PASS arm mode : %s" % mode)
self.progress("Not armable mode without Position : %s" % mode)
self.wait_gps_disable()
@ -8598,8 +8595,7 @@ Also, ignores heartbeats not from our target system'''
self.set_parameter("FOLL_ENABLE", 0)
self.change_mode(self.default_mode())
if self.armed():
if not self.disarm_vehicle():
raise NotAchievedException("Failed to DISARM")
self.disarm_vehicle()
# we should find at least one Armed event and one disarmed
# event, and at least one ARM message for arm and disarm
@ -10915,8 +10911,7 @@ switch value'''
}
self.test_frsky_passthrough_do_wants(frsky, wants)
self.zero_throttle()
if not self.disarm_vehicle():
raise NotAchievedException("Failed to DISARM")
self.disarm_vehicle()
self.progress("Counts of sensor_id polls sent:")
frsky.dump_sensor_id_poll_counts_as_progress_messages()
@ -11370,8 +11365,7 @@ switch value'''
# ok done, stop the engine
if self.is_plane():
self.zero_throttle()
if not self.disarm_vehicle(force=True):
raise NotAchievedException("Failed to DISARM")
self.disarm_vehicle(force=True)
def test_frsky_d(self):
self.set_parameter("SERIAL5_PROTOCOL", 3) # serial5 is FRSky output