00001 /* AUTO-GENERATED FILE. DO NOT MODIFY. 00002 * 00003 * This class was automatically generated by the 00004 * java mavlink generator tool. It should not be modified by hand. 00005 */ 00006 00007 package com.MAVLink.Messages; 00008 00009 import com.MAVLink.MAVLinkPacket; 00010 00015 public class MAVLinkStats /* implements Serializable */{ 00016 00017 public int receivedPacketCount; 00018 00019 public int crcErrorCount; 00020 00021 public int lostPacketCount; 00022 00023 private int lastPacketSeq; 00024 00032 public void newPacket(MAVLinkPacket packet) { 00033 advanceLastPacketSequence(); 00034 if (hasLostPackets(packet)) { 00035 updateLostPacketCount(packet); 00036 } 00037 lastPacketSeq = packet.seq; 00038 receivedPacketCount++; 00039 } 00040 00041 private void updateLostPacketCount(MAVLinkPacket packet) { 00042 int lostPackets; 00043 if (packet.seq - lastPacketSeq < 0) { 00044 lostPackets = (packet.seq - lastPacketSeq) + 255; 00045 } else { 00046 lostPackets = (packet.seq - lastPacketSeq); 00047 } 00048 lostPacketCount += lostPackets; 00049 } 00050 00051 private boolean hasLostPackets(MAVLinkPacket packet) { 00052 return lastPacketSeq > 0 && packet.seq != lastPacketSeq; 00053 } 00054 00055 private void advanceLastPacketSequence() { 00056 // wrap from 255 to 0 if necessary 00057 lastPacketSeq = (lastPacketSeq + 1) & 0xFF; 00058 } 00059 00063 public void crcError() { 00064 crcErrorCount++; 00065 } 00066 00070 public void mavlinkResetStats() { 00071 lastPacketSeq = -1; 00072 lostPacketCount = 0; 00073 crcErrorCount = 0; 00074 receivedPacketCount = 0; 00075 } 00076 00077 }