Replay: adjust lost message threshold

this needs to be a bit higher to cope with truncated logs (if SITL
ends in the middle of an EKF log write then we end up with a mismatch
in log msg counts)
This commit is contained in:
Andrew Tridgell 2020-11-17 14:16:12 +11:00 committed by Peter Barker
parent e830494f0f
commit 70a8853e6a
1 changed files with 1 additions and 1 deletions

View File

@ -69,7 +69,7 @@ def check_log(logfile, progress, ekf2_only=False, ekf3_only=False, verbose=False
if verbose: if verbose:
for mtype in counts.keys(): for mtype in counts.keys():
progress("%s %u/%u %d" % (mtype, counts[mtype], base_counts[mtype], base_counts[mtype]-counts[mtype])) progress("%s %u/%u %d" % (mtype, counts[mtype], base_counts[mtype], base_counts[mtype]-counts[mtype]))
if count == 0 or abs(count - base_count) > 30: if count == 0 or abs(count - base_count) > 100:
failure += 1 failure += 1
if failure != 0 or errors != 0: if failure != 0 or errors != 0:
return False return False