autotest: loosen constraint on achieved angles

apparently within 5 degrees is asking too much....
This commit is contained in:
Peter Barker 2023-09-18 18:04:50 +10:00 committed by Peter Barker
parent d1e8cef9b6
commit 23150a0830

View File

@ -4848,7 +4848,7 @@ class AutoTestPlane(AutoTest):
self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", { self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", {
"nav_roll": 0, "nav_roll": 0,
"nav_pitch": 0, "nav_pitch": 0,
}, epsilon=5) }, epsilon=10)
def check_altitude(mav, m): def check_altitude(mav, m):
global initial_airspeed_threshold_reached global initial_airspeed_threshold_reached
@ -4871,7 +4871,7 @@ class AutoTestPlane(AutoTest):
self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", { self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", {
"nav_roll": 0, "nav_roll": 0,
"nav_pitch": 0, "nav_pitch": 0,
}, epsilon=5) }, epsilon=10)
self.context_pop() # remove the check_altitude call self.context_pop() # remove the check_altitude call