Browse Source

autotest: copter: catch exception on test_gcs_failsafe to reset parameters

c415-sdk
Pierre Kancir 5 years ago committed by Peter Barker
parent
commit
5fe81706bb
  1. 9
      Tools/autotest/arducopter.py

9
Tools/autotest/arducopter.py

@ -672,6 +672,15 @@ class AutoTestCopter(AutoTest): @@ -672,6 +672,15 @@ class AutoTestCopter(AutoTest):
# Tests all actions and logic behind the GCS failsafe
def fly_gcs_failsafe(self, side=60, timeout=360):
try:
self.test_gcs_failsafe(side=side, timeout=timeout)
except Exception as ex:
self.setGCSfailsafe(0)
self.set_parameter('FS_OPTIONS', 0)
self.reboot_sitl()
raise ex
def test_gcs_failsafe(self, side=60, timeout=360):
# Trigger telemety loss with failsafe disabled. Verify no action taken.
self.start_subtest("GCS failsafe disabled test: FS_GCS_ENABLE=0 should take no failsafe action")
self.setGCSfailsafe(0)

Loading…
Cancel
Save