7 package com.MAVLink.Messages;
46 if (ignoreRadioPackets && packet.msgid == msg_radio_status.MAVLINK_MSG_ID_RADIO_STATUS) {
50 if (systemStats[packet.sysid] == null) {
54 lostPacketCount += systemStats[packet.sysid].
newPacket(packet);
55 receivedPacketCount++;
68 receivedPacketCount = 0;
85 int newLostPackets = 0;
86 if (componentStats[packet.compid] == null) {
90 newLostPackets = componentStats[packet.compid].
newPacket(packet);
91 lostPacketCount += newLostPackets;
92 receivedPacketCount++;
93 return newLostPackets;
98 receivedPacketCount = 0;
114 int newLostPackets = 0;
115 if (hasLostPackets(packet)) {
116 newLostPackets = updateLostPacketCount(packet);
118 lastPacketSeq = packet.seq;
119 advanceLastPacketSequence(packet.seq);
120 receivedPacketCount++;
121 return newLostPackets;
127 receivedPacketCount = 0;
132 if (packet.seq - lastPacketSeq < 0) {
133 lostPackets = (packet.seq - lastPacketSeq) + 255;
135 lostPackets = (packet.seq - lastPacketSeq);
137 lostPacketCount += lostPackets;
143 lastPacketSeq = (lastSeq + 1) & 0xFF;
147 return lastPacketSeq >= 0 && packet.seq != lastPacketSeq;
void newPacket(MAVLinkPacket packet)
MAVLinkStats(boolean ignoreRadioPackets)
int newPacket(MAVLinkPacket packet)
ComponentStat[] componentStats
boolean ignoreRadioPackets
int newPacket(MAVLinkPacket packet)
boolean hasLostPackets(MAVLinkPacket packet)
int updateLostPacketCount(MAVLinkPacket packet)
void advanceLastPacketSequence(int lastSeq)