mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
autotest: give WindEstimate more time to converge
this was right on the edge
This commit is contained in:
parent
54a4b7a98b
commit
f20769057b
@ -2859,7 +2859,11 @@ class AutoTestPlane(AutoTest):
|
|||||||
for ahrs_type in 0, 2, 3, 10:
|
for ahrs_type in 0, 2, 3, 10:
|
||||||
self.start_subtest("Checking AHRS_EKF_TYPE=%u" % ahrs_type)
|
self.start_subtest("Checking AHRS_EKF_TYPE=%u" % ahrs_type)
|
||||||
self.set_parameter("AHRS_EKF_TYPE", ahrs_type)
|
self.set_parameter("AHRS_EKF_TYPE", ahrs_type)
|
||||||
self.wait_and_maintain_wind_estimate(5, 45, speed_tolerance=1)
|
self.wait_and_maintain_wind_estimate(
|
||||||
|
5, 45,
|
||||||
|
speed_tolerance=1,
|
||||||
|
timeout=20
|
||||||
|
)
|
||||||
self.fly_home_land_and_disarm()
|
self.fly_home_land_and_disarm()
|
||||||
|
|
||||||
def VectorNavEAHRS(self):
|
def VectorNavEAHRS(self):
|
||||||
|
Loading…
Reference in New Issue
Block a user