mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: loosen constraint on achieved angles
apparently within 5 degrees is asking too much....
This commit is contained in:
parent
d1e8cef9b6
commit
23150a0830
@ -4848,7 +4848,7 @@ class AutoTestPlane(AutoTest):
|
||||
self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", {
|
||||
"nav_roll": 0,
|
||||
"nav_pitch": 0,
|
||||
}, epsilon=5)
|
||||
}, epsilon=10)
|
||||
|
||||
def check_altitude(mav, m):
|
||||
global initial_airspeed_threshold_reached
|
||||
@ -4871,7 +4871,7 @@ class AutoTestPlane(AutoTest):
|
||||
self.wait_message_field_values("NAV_CONTROLLER_OUTPUT", {
|
||||
"nav_roll": 0,
|
||||
"nav_pitch": 0,
|
||||
}, epsilon=5)
|
||||
}, epsilon=10)
|
||||
|
||||
self.context_pop() # remove the check_altitude call
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user