Skip to content

Commit

Permalink
mavutil: Do not use unknown messages to calculate number of lost packets
Browse files Browse the repository at this point in the history
  • Loading branch information
joshanne authored and tridge committed Dec 20, 2023
1 parent 04375e5 commit 6216586
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion mavutil.py
Original file line number Diff line number Diff line change
Expand Up @@ -399,7 +399,8 @@ def post_message(self, msg):
for s in self.sysid_state.keys():
self.sysid_state[s].messages[type] = msg

if not (src_tuple == radio_tuple or msg.get_type() == 'BAD_DATA'):
if not (src_tuple == radio_tuple or msg.get_msgId() < 0):
# Don't use unknown messages to calculate number of lost packets
if not src_tuple in self.last_seq:
last_seq = -1
else:
Expand Down

0 comments on commit 6216586

Please sign in to comment.