Tools: add test for ArmingSwitch after reboot

This commit is contained in:
Peter Barker 2024-04-07 12:05:46 +10:00 committed by Peter Barker
parent 021d637edc
commit 1ed388c2e6
1 changed files with 24 additions and 0 deletions

View File

@ -10277,6 +10277,29 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_SET_SAFETY_SWITCH_STATE, mavutil.mavlink.SAFETY_SWITCH_STATE_DANGEROUS)
self.wait_ready_to_arm()
def ArmSwitchAfterReboot(self):
'''test that the arming switch does not trigger after a reboot'''
self.wait_ready_to_arm()
self.set_parameters({
"RC8_OPTION": 153,
})
self.set_rc(8, 2000)
self.wait_armed()
self.disarm_vehicle()
self.context_collect('STATUSTEXT')
self.reboot_sitl()
tstart = self.get_sim_time()
while True:
if self.get_sim_time_cached() - tstart > 60:
break
if self.armed():
raise NotAchievedException("Armed after reboot with switch high")
armmsg = self.statustext_in_collections('Arm: ')
if armmsg is not None:
raise NotAchievedException("statustext(%s) means we tried to arm" % armmsg.text)
self.progress("Did not arm via arming switfch after a reboot")
def GuidedYawRate(self):
'''ensuer guided yaw rate is not affected by rate of sewt-attitude messages'''
self.takeoff(30, mode='GUIDED')
@ -10796,6 +10819,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.GuidedYawRate,
self.NoArmWithoutMissionItems,
self.DO_CHANGE_SPEED_in_guided,
self.ArmSwitchAfterReboot,
self.RPLidarA1,
self.RPLidarA2,
self.SafetySwitch,