autotest: add new blending test

This commit is contained in:
Peter Barker 2024-03-21 12:08:30 +11:00 committed by Peter Barker
parent 68b58d5435
commit 1bab1a9571

View File

@ -8753,7 +8753,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
print("log difference: %s" % str(log_difference))
return log_difference[0]
def GPSBlending(self):
def GPSBlendingLog(self):
'''Test GPS Blending'''
'''ensure we get dataflash log messages for blended instance'''
@ -8828,6 +8828,67 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
if ex is not None:
raise ex
def GPSBlending(self):
'''Test GPS Blending'''
'''ensure we get dataflash log messages for blended instance'''
self.context_push()
# configure:
self.set_parameters({
"WP_YAW_BEHAVIOR": 0, # do not yaw
"GPS2_TYPE": 1,
"SIM_GPS2_TYPE": 1,
"SIM_GPS2_DISABLE": 0,
"SIM_GPS_POS_X": 1.0,
"SIM_GPS_POS_Y": -1.0,
"SIM_GPS2_POS_X": -1.0,
"SIM_GPS2_POS_Y": 1.0,
"GPS_AUTO_SWITCH": 2,
})
self.reboot_sitl()
alt = 10
self.takeoff(alt, mode='GUIDED')
self.fly_guided_move_local(30, 0, alt)
self.fly_guided_move_local(30, 30, alt)
self.fly_guided_move_local(0, 30, alt)
self.fly_guided_move_local(0, 0, alt)
self.change_mode('LAND')
current_log_file = self.dfreader_for_current_onboard_log()
self.wait_disarmed()
# ensure that the blended solution is always about half-way
# between the two GPSs:
current_ts = None
while True:
m = current_log_file.recv_match(type='GPS')
if m is None:
break
if current_ts is None:
if m.I != 0: # noqa
continue
current_ts = m.TimeUS
measurements = {}
if m.TimeUS != current_ts:
current_ts = None
continue
measurements[m.I] = (m.Lat, m.Lng)
if len(measurements) == 3:
# check lat:
for n in 0, 1:
expected_blended = (measurements[0][n] + measurements[1][n])/2
epsilon = 0.0000002
error = abs(measurements[2][n] - expected_blended)
if error > epsilon:
raise NotAchievedException("Blended diverged")
current_ts = None
self.context_pop()
self.reboot_sitl()
def Callisto(self):
'''Test Callisto'''
self.customise_SITL_commandline(
@ -11091,6 +11152,7 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
self.RTL_TO_RALLY,
self.FlyEachFrame,
self.GPSBlending,
self.GPSBlendingLog,
self.DataFlash,
Test(self.DataFlashErase, attempts=8),
self.Callisto,