mirror of https://github.com/ArduPilot/ardupilot
Tools: relax req accuracy for plane dead reckoning when not using airspeed
This commit is contained in:
parent
9d2b05840b
commit
19f6b2d6d6
|
@ -2155,7 +2155,10 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||||
if self.simstate is None:
|
if self.simstate is None:
|
||||||
return
|
return
|
||||||
divergence = self.get_distance_int(self.gpi, self.simstate)
|
divergence = self.get_distance_int(self.gpi, self.simstate)
|
||||||
max_allowed_divergence = 200
|
if disable_airspeed_sensor:
|
||||||
|
max_allowed_divergence = 300
|
||||||
|
else:
|
||||||
|
max_allowed_divergence = 150
|
||||||
if (time.time() - self.last_print > 1 or
|
if (time.time() - self.last_print > 1 or
|
||||||
divergence > self.max_divergence):
|
divergence > self.max_divergence):
|
||||||
self.progress("position-estimate-divergence=%fm" % (divergence,))
|
self.progress("position-estimate-divergence=%fm" % (divergence,))
|
||||||
|
|
Loading…
Reference in New Issue