mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: add test for EK3_OGN_HGT_MASK bug
This commit is contained in:
parent
77adb5586d
commit
ee7e8661ed
@ -11377,6 +11377,43 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
self.disarm_vehicle(force=True)
|
||||
self.reboot_sitl()
|
||||
|
||||
def EK3_OGN_HGT_MASK_climbing(self):
|
||||
'''check combination of height bits doesn't cause climb'''
|
||||
self.context_push()
|
||||
self.set_parameters({
|
||||
'EK3_OGN_HGT_MASK': 5,
|
||||
})
|
||||
self.reboot_sitl()
|
||||
|
||||
expected_alt = 10
|
||||
|
||||
self.change_mode('GUIDED')
|
||||
self.wait_ready_to_arm()
|
||||
current_alt = self.get_altitude()
|
||||
|
||||
expected_alt_abs = current_alt + expected_alt
|
||||
|
||||
self.takeoff(expected_alt, mode='GUIDED')
|
||||
self.delay_sim_time(5)
|
||||
|
||||
def check_altitude(mav, m):
|
||||
m_type = m.get_type()
|
||||
epsilon = 10 # in metres
|
||||
if m_type == 'GPS_RAW_INT':
|
||||
got_gps_alt = m.alt * 0.001
|
||||
if abs(expected_alt_abs - got_gps_alt) > epsilon:
|
||||
raise NotAchievedException(f"Bad GPS altitude (got={got_gps_alt} want={expected_alt_abs})")
|
||||
elif m_type == 'GLOBAL_POSITION_INT':
|
||||
if abs(expected_alt - m.relative_alt * 0.001) > epsilon:
|
||||
raise NotAchievedException("Bad canonical altitude")
|
||||
|
||||
self.install_message_hook_context(check_altitude)
|
||||
|
||||
self.delay_sim_time(1500)
|
||||
|
||||
self.context_pop()
|
||||
self.reboot_sitl(force=True)
|
||||
|
||||
def tests2b(self): # this block currently around 9.5mins here
|
||||
'''return list of all tests'''
|
||||
ret = ([
|
||||
@ -11461,6 +11498,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
self.GuidedModeThrust,
|
||||
self.CompassMot,
|
||||
self.AutoRTL,
|
||||
self.EK3_OGN_HGT_MASK_climbing,
|
||||
self.EK3_OGN_HGT_MASK,
|
||||
self.FarOrigin,
|
||||
self.GuidedForceArm,
|
||||
|
Loading…
Reference in New Issue
Block a user