From 2beb3db4c781c3e26f379d23fbf308c03b4439aa Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 29 Apr 2024 14:42:57 +1000 Subject: [PATCH] autotest: add test for EK3_OGN_HGT_MASK bug --- Tools/autotest/arducopter.py | 38 ++++++++++++++++++++++++++++++++++++ 1 file changed, 38 insertions(+) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 7e5e3de3748439..b393516e605eaa 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -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 = ([ @@ -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, ])