Skip to content

Commit

Permalink
autotest: added CommonOrigin test
Browse files Browse the repository at this point in the history
test EK2 and EK3 common origin
  • Loading branch information
tridge committed Sep 9, 2024
1 parent cf45dbf commit ae6376f
Showing 1 changed file with 53 additions and 0 deletions.
53 changes: 53 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -11889,6 +11889,58 @@ def ScriptingAHRSSource(self):
self.set_rc(10, 2000)
self.wait_statustext('Using EKF Source Set 3', check_context=True)

def CommonOrigin(self):
"""Test common origin between EKF2 and EKF3"""
self.context_push()

# start on EKF2
self.set_parameters({
'AHRS_EKF_TYPE': 2,
'EK2_ENABLE': 1,
'EK3_CHECK_SCALE': 1, # make EK3 slow to get origin
})
self.reboot_sitl()

self.context_collect('STATUSTEXT')

self.wait_statustext("EKF2 IMU0 origin set", timeout=60, check_context=True)
self.wait_statustext("EKF2 IMU0 is using GPS", timeout=60, check_context=True)
self.wait_statustext("EKF2 active", timeout=60, check_context=True)

self.context_collect('GPS_GLOBAL_ORIGIN')

# get EKF2 origin
self.run_cmd(mavutil.mavlink.MAV_CMD_GET_HOME_POSITION)
ek2_origin = self.assert_receive_message('GPS_GLOBAL_ORIGIN', check_context=True)

# switch to EKF3
self.set_parameters({
'SIM_GPS_GLITCH_X' : 0.001, # about 100m
'EK3_CHECK_SCALE' : 100,
'AHRS_EKF_TYPE' : 3})

self.wait_statustext("EKF3 IMU0 is using GPS", timeout=60, check_context=True)
self.wait_statustext("EKF3 active", timeout=60, check_context=True)

self.run_cmd(mavutil.mavlink.MAV_CMD_GET_HOME_POSITION)
ek3_origin = self.assert_receive_message('GPS_GLOBAL_ORIGIN', check_context=True)

self.progress("Checking origins")
if ek2_origin.time_usec == ek3_origin.time_usec:
raise NotAchievedException("Did not get a new GPS_GLOBAL_ORIGIN message")

print(ek2_origin, ek3_origin)

if (ek2_origin.latitude != ek3_origin.latitude or
ek2_origin.longitude != ek3_origin.longitude or
ek2_origin.altitude != ek3_origin.altitude):
raise NotAchievedException("Did not get matching EK2 and EK3 origins")

self.context_pop()

# restart GPS driver
self.reboot_sitl()

def tests2b(self): # this block currently around 9.5mins here
'''return list of all tests'''
ret = ([
Expand Down Expand Up @@ -11992,6 +12044,7 @@ def tests2b(self): # this block currently around 9.5mins here
self.BatteryInternalUseOnly,
self.MAV_CMD_MISSION_START_p1_p2,
self.ScriptingAHRSSource,
self.CommonOrigin,
])
return ret

Expand Down

0 comments on commit ae6376f

Please sign in to comment.