mirror of https://github.com/ArduPilot/ardupilot
autotest: test mag fusion and origin backup
Co-authored-by: Clyde McQueen <clyde@mcqueen.net>
This commit is contained in:
parent
78a7c86bbd
commit
bd27edc9f5
|
@ -821,6 +821,37 @@ class AutoTestSub(vehicle_test_suite.TestSuite):
|
|||
# restart GPS driver
|
||||
self.reboot_sitl()
|
||||
|
||||
def backup_home(self):
|
||||
"""Test ORIGIN_LAT and ORIGIN_LON parameters"""
|
||||
|
||||
self.context_push()
|
||||
self.set_parameters({
|
||||
'GPS1_TYPE': 0, # Disable GPS
|
||||
'EK3_SRC1_POSXY': 0, # Make sure EK3_SRC parameters do not refer to GPS
|
||||
'EK3_SRC1_VELXY': 0, # Make sure EK3_SRC parameters do not refer to GPS
|
||||
'ORIGIN_LAT': 47.607584,
|
||||
'ORIGIN_LON': -122.343911,
|
||||
})
|
||||
self.reboot_sitl()
|
||||
self.context_collect('STATUSTEXT')
|
||||
|
||||
# Wait for the EKF to be happy in constant position mode
|
||||
self.wait_ready_to_arm_const_pos()
|
||||
|
||||
if self.current_onboard_log_contains_message('ORGN'):
|
||||
raise NotAchievedException("Found unexpected ORGN message")
|
||||
|
||||
# This should set the origin and write a record to ORGN
|
||||
self.arm_vehicle()
|
||||
|
||||
self.wait_statustext('Using backup location', check_context=True)
|
||||
|
||||
if not self.current_onboard_log_contains_message('ORGN'):
|
||||
raise NotAchievedException("Did not find expected ORGN message")
|
||||
|
||||
self.disarm_vehicle()
|
||||
self.context_pop()
|
||||
|
||||
def tests(self):
|
||||
'''return list of all tests'''
|
||||
ret = super(AutoTestSub, self).tests()
|
||||
|
@ -848,6 +879,7 @@ class AutoTestSub(vehicle_test_suite.TestSuite):
|
|||
self.MAV_CMD_CONDITION_YAW,
|
||||
self.TerrainMission,
|
||||
self.SetGlobalOrigin,
|
||||
self.backup_home,
|
||||
])
|
||||
|
||||
return ret
|
||||
|
|
Loading…
Reference in New Issue