MAVLinkStats.java
Go to the documentation of this file.
1 /* AUTO-GENERATED FILE. DO NOT MODIFY.
2  *
3  * This class was automatically generated by the
4  * java mavlink generator tool. It should not be modified by hand.
5  */
6 
7 package com.MAVLink.Messages;
8 
10 import com.MAVLink.common.msg_radio_status;
11 
16 public class MAVLinkStats /* implements Serializable */{
17 
18  public int receivedPacketCount; // total recieved packet count for all sources
19 
20  public int crcErrorCount;
21 
22  public int lostPacketCount; // total lost packet count for all sources
23 
24  public boolean ignoreRadioPackets;
25 
26  // stats are nil for a system id until a packet has been received from a system
27  public SystemStat[] systemStats; // stats for each system that is known
28 
29  public MAVLinkStats() {
30  this(false);
31  }
32 
33  public MAVLinkStats(boolean ignoreRadioPackets) {
34  this.ignoreRadioPackets = ignoreRadioPackets;
35  resetStats();
36  }
37 
45  public void newPacket(MAVLinkPacket packet) {
46  if (ignoreRadioPackets && packet.msgid == msg_radio_status.MAVLINK_MSG_ID_RADIO_STATUS) {
47  return;
48  }
49 
50  if (systemStats[packet.sysid] == null) {
51  // only allocate stats for systems that exsist on the network
52  systemStats[packet.sysid] = new SystemStat();
53  }
54  lostPacketCount += systemStats[packet.sysid].newPacket(packet);
55  receivedPacketCount++;
56  }
57 
61  public void crcError() {
62  crcErrorCount++;
63  }
64 
65  public void resetStats() {
66  crcErrorCount = 0;
67  lostPacketCount = 0;
68  receivedPacketCount = 0;
69  systemStats = new SystemStat[256];
70  }
71 
72  // stat structure for every system id
73  public static class SystemStat {
74  public int lostPacketCount; // the lost count for this source
75  public int receivedPacketCount;
76 
77  // stats are nil for a component id until a packet has been received from a system
78  public ComponentStat[] componentStats; // stats for each component that is known
79 
80  public SystemStat() {
81  resetStats();
82  }
83 
84  public int newPacket(MAVLinkPacket packet) {
85  int newLostPackets = 0;
86  if (componentStats[packet.compid] == null) {
87  // only allocate stats for systems that exsist on the network
88  componentStats[packet.compid] = new ComponentStat();
89  }
90  newLostPackets = componentStats[packet.compid].newPacket(packet);
91  lostPacketCount += newLostPackets;
92  receivedPacketCount++;
93  return newLostPackets;
94  }
95 
96  public void resetStats() {
97  lostPacketCount = 0;
98  receivedPacketCount = 0;
99  componentStats = new ComponentStat[256];
100  }
101  }
102 
103  // stat structure for every system id
104  public static class ComponentStat {
105  public int lastPacketSeq;
106  public int lostPacketCount; // the lost count for this source
108 
109  public ComponentStat() {
110  resetStats();
111  }
112 
113  public int newPacket(MAVLinkPacket packet) {
114  int newLostPackets = 0;
115  if (hasLostPackets(packet)) {
116  newLostPackets = updateLostPacketCount(packet);
117  }
118  lastPacketSeq = packet.seq;
119  advanceLastPacketSequence(packet.seq);
120  receivedPacketCount++;
121  return newLostPackets;
122  }
123 
124  public void resetStats() {
125  lastPacketSeq = -1;
126  lostPacketCount = 0;
127  receivedPacketCount = 0;
128  }
129 
130  private int updateLostPacketCount(MAVLinkPacket packet) {
131  int lostPackets;
132  if (packet.seq - lastPacketSeq < 0) {
133  lostPackets = (packet.seq - lastPacketSeq) + 255;
134  } else {
135  lostPackets = (packet.seq - lastPacketSeq);
136  }
137  lostPacketCount += lostPackets;
138  return lostPackets;
139  }
140 
141  private void advanceLastPacketSequence(int lastSeq) {
142  // wrap from 255 to 0 if necessary
143  lastPacketSeq = (lastSeq + 1) & 0xFF;
144  }
145 
146  private boolean hasLostPackets(MAVLinkPacket packet) {
147  return lastPacketSeq >= 0 && packet.seq != lastPacketSeq;
148  }
149  }
150 
151 }


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02