mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: added AltResetBadGPS test
this tests the bug in handling a glitching GPS with low accuracy with AHRS alt reset
This commit is contained in:
parent
b397319d6b
commit
4bef9b7164
@ -3945,6 +3945,39 @@ class AutoTestPlane(AutoTest):
|
||||
self.disarm_vehicle(force=True)
|
||||
self.reboot_sitl()
|
||||
|
||||
def AltResetBadGPS(self):
|
||||
'''Tests the handling of poor GPS lock pre-arm alt resets'''
|
||||
self.set_parameters({
|
||||
"SIM_GPS_GLITCH_Z": 0,
|
||||
"SIM_GPS_ACC": 0.3,
|
||||
})
|
||||
self.wait_ready_to_arm()
|
||||
|
||||
m = self.assert_receive_message('GLOBAL_POSITION_INT')
|
||||
relalt = m.relative_alt*0.001
|
||||
if abs(relalt) > 3:
|
||||
raise NotAchievedException("Bad relative alt %.1f" % relalt)
|
||||
|
||||
self.progress("Setting low accuracy, glitching GPS")
|
||||
self.set_parameter("SIM_GPS_ACC", 40)
|
||||
self.set_parameter("SIM_GPS_GLITCH_Z", -47)
|
||||
|
||||
self.progress("Waiting 10s for height update")
|
||||
self.delay_sim_time(10)
|
||||
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
||||
m = self.assert_receive_message('GLOBAL_POSITION_INT')
|
||||
relalt = m.relative_alt*0.001
|
||||
if abs(relalt) > 3:
|
||||
raise NotAchievedException("Bad glitching relative alt %.1f" % relalt)
|
||||
|
||||
self.disarm_vehicle()
|
||||
# reboot to clear potentially bad state
|
||||
self.reboot_sitl()
|
||||
|
||||
|
||||
def tests(self):
|
||||
'''return list of all tests'''
|
||||
ret = super(AutoTestPlane, self).tests()
|
||||
@ -4021,6 +4054,7 @@ class AutoTestPlane(AutoTest):
|
||||
self.GlideSlopeThresh,
|
||||
self.HIGH_LATENCY2,
|
||||
self.MidAirDisarmDisallowed,
|
||||
self.AltResetBadGPS,
|
||||
])
|
||||
return ret
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user