Skip to content

Commit

Permalink
autotest: add test for EK3_OGN_HGT_MASK bug
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed May 22, 2024
1 parent 24e54da commit 2beb3db
Showing 1 changed file with 38 additions and 0 deletions.
38 changes: 38 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -11345,6 +11345,43 @@ def check_altitude(mav, m):
self.context_pop()
self.reboot_sitl(force=True)

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 = ([
Expand Down Expand Up @@ -11429,6 +11466,7 @@ def tests2b(self): # this block currently around 9.5mins here
self.GuidedModeThrust,
self.CompassMot,
self.AutoRTL,
self.EK3_OGN_HGT_MASK_climbing,
self.EK3_OGN_HGT_MASK,
self.FarOrigin,
])
Expand Down

0 comments on commit 2beb3db

Please sign in to comment.