mirror of https://github.com/ArduPilot/ardupilot
Tools: Fix AIRSPEED_AUTOCAL test failure
The mission plan for this test causes a lot of overshoot when turning onto final approach with the result that there is still some lateral offset when passing the landing waypoint that is not a measure of estimator accuracy.
This commit is contained in:
parent
344f2d0eb7
commit
e13e888c31
|
@ -1591,7 +1591,7 @@ class AutoTestPlane(AutoTest):
|
||||||
m = self.mav.recv_match(type='AIRSPEED_AUTOCAL',
|
m = self.mav.recv_match(type='AIRSPEED_AUTOCAL',
|
||||||
blocking=True,
|
blocking=True,
|
||||||
timeout=5)
|
timeout=5)
|
||||||
self.wait_waypoint(7, num_wp-1, timeout=500)
|
self.wait_waypoint(7, num_wp-1, max_dist=5, timeout=500)
|
||||||
self.wait_disarmed(timeout=120)
|
self.wait_disarmed(timeout=120)
|
||||||
|
|
||||||
def deadreckoning_main(self, disable_airspeed_sensor=False):
|
def deadreckoning_main(self, disable_airspeed_sensor=False):
|
||||||
|
|
Loading…
Reference in New Issue