mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
autotest: allow lots of time for GPS rate to recover after simple gyrocal
simple gyro cal makes the GPS units go unhealthy as they are not maintaining their update rate (gyro cal is synchronous in the main loop). Usually ~30 seconds to recover...
This commit is contained in:
parent
0894cfc0c8
commit
0918ddc05a
@ -4795,6 +4795,10 @@ class AutoTestPlane(AutoTest):
|
||||
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
|
||||
p5=4,
|
||||
)
|
||||
# simple gyro cal makes the GPS units go unhealthy as they are
|
||||
# not maintaining their update rate (gyro cal is synchronous
|
||||
# in the main loop). Usually ~30 seconds to recover...
|
||||
self.wait_gps_sys_status_not_present_or_enabled_and_healthy(timeout=60)
|
||||
|
||||
self.start_subtest("force save accels")
|
||||
command(
|
||||
|
Loading…
Reference in New Issue
Block a user