diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index e1f33c27fd..5405a1bfcf 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -4145,6 +4145,38 @@ class AutoTestPlane(AutoTest): 0) # button mask self.fly_home_land_and_disarm() + 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() @@ -4225,6 +4257,7 @@ class AutoTestPlane(AutoTest): self.AerobaticsScripting, self.MANUAL_CONTROL, self.WindEstimates, + self.AltResetBadGPS, ]) return ret