mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
autotest: add instant-disarm radio failsafe test
This commit is contained in:
parent
2b24e922a7
commit
b3bfc0bd32
@ -467,7 +467,16 @@ class AutoTestCopter(AutoTest):
|
||||
|
||||
# Tests all actions and logic behind the radio failsafe
|
||||
def fly_throttle_failsafe(self, side=60, timeout=360):
|
||||
# Trigger and RC failure with the failsafe disabled. Verify no action taken.
|
||||
self.start_subtest("If you haven't taken off yet RC failure should be instant disarm")
|
||||
self.change_mode("STABILIZE")
|
||||
self.set_parameter("DISARM_DELAY", 0)
|
||||
self.arm_vehicle()
|
||||
self.set_parameter("SIM_RC_FAIL", 1)
|
||||
self.disarm_wait(timeout=1)
|
||||
self.set_parameter("SIM_RC_FAIL", 0)
|
||||
self.set_parameter("DISARM_DELAY", 10)
|
||||
|
||||
# Trigger an RC failure with the failsafe disabled. Verify no action taken.
|
||||
self.start_subtest("Radio failsafe disabled test: FS_THR_ENABLE=0 should take no failsafe action")
|
||||
self.set_parameter('FS_THR_ENABLE', 0)
|
||||
self.set_parameter('FS_OPTIONS', 0)
|
||||
|
Loading…
Reference in New Issue
Block a user