Skip to content

Commit

Permalink
Tools: relax req accuracy for plane dead reckoning when not using air…
Browse files Browse the repository at this point in the history
…speed
  • Loading branch information
priseborough authored and tridge committed Dec 1, 2023
1 parent 6145d83 commit a107018
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -2210,7 +2210,10 @@ def validate_global_position_int_against_simstate(mav, m):
if self.simstate is None:
return
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
divergence > self.max_divergence):
self.progress("position-estimate-divergence=%fm" % (divergence,))
Expand Down

0 comments on commit a107018

Please sign in to comment.