autotest: do not assert COMPASS_LEARN value after we set it

the autopilot can instantly reset this back to 0 after we set it, so we never receive the set value:

2025-01-30T06:49:04.2029371Z AT-0931.7: COMPASS_LEARN want=3.000000 autopilot=0.0 (attempt=3/10)
2025-01-30T06:49:04.2029876Z AT-0931.7: Sending set (COMPASS_LEARN) to (3.000000) (old=0.000000)
2025-01-30T06:49:04.2030299Z AT-0931.7: AP: CompassLearn: Initialised
2025-01-30T06:49:04.2030653Z AT-0931.7: AP: CompassLearn: Finished
2025-01-30T06:49:04.2031166Z AT-0931.7: Received wanted PARAM_VALUE COMPASS_LEARN=0.000000
2025-01-30T06:49:04.2031653Z AT-0931.7: Received wanted PARAM_VALUE COMPASS_LEARN=3.000000
2025-01-30T06:49:04.2032117Z AT-0931.7: Received wanted PARAM_VALUE COMPASS_LEARN=0.000000
2025-01-30T06:49:04.2032732Z AT-0931.7: COMPASS_LEARN want=3.000000 autopilot=0.0 (attempt=4/10)
This commit is contained in:
Peter Barker 2025-02-03 12:28:22 +11:00 committed by Peter Barker
parent a1421e7ece
commit e5e3e9a40b

View File

@ -6460,7 +6460,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
self.set_parameters({ self.set_parameters({
"COMPASS_OFS_X": 1100, "COMPASS_OFS_X": 1100,
}) })
self.set_parameter("COMPASS_LEARN", 3) # 3 is in-flight learning self.send_set_parameter("COMPASS_LEARN", 3) # 3 is in-flight learning
self.wait_parameter_value("COMPASS_LEARN", 0) self.wait_parameter_value("COMPASS_LEARN", 0)
self.assert_parameter_value("COMPASS_OFS_X", old_compass_ofs_x, epsilon=30) self.assert_parameter_value("COMPASS_OFS_X", old_compass_ofs_x, epsilon=30)
self.fly_home_land_and_disarm() self.fly_home_land_and_disarm()