MAVLinkStats.java 4.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151
  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. package com.MAVLink.Messages;
  7. import com.MAVLink.MAVLinkPacket;
  8. import com.MAVLink.common.msg_radio_status;
  9. /**
  10. * Storage for MAVLink Packet and Error statistics
  11. *
  12. */
  13. public class MAVLinkStats /* implements Serializable */{
  14. public int receivedPacketCount; // total recieved packet count for all sources
  15. public int crcErrorCount;
  16. public int lostPacketCount; // total lost packet count for all sources
  17. public boolean ignoreRadioPackets;
  18. // stats are nil for a system id until a packet has been received from a system
  19. public SystemStat[] systemStats; // stats for each system that is known
  20. public MAVLinkStats() {
  21. this(false);
  22. }
  23. public MAVLinkStats(boolean ignoreRadioPackets) {
  24. this.ignoreRadioPackets = ignoreRadioPackets;
  25. resetStats();
  26. }
  27. /**
  28. * Check the new received packet to see if has lost someone between this and
  29. * the last packet
  30. *
  31. * @param packet
  32. * Packet that should be checked
  33. */
  34. public void newPacket(MAVLinkPacket packet) {
  35. if (ignoreRadioPackets && packet.msgid == msg_radio_status.MAVLINK_MSG_ID_RADIO_STATUS) {
  36. return;
  37. }
  38. if (systemStats[packet.sysid] == null) {
  39. // only allocate stats for systems that exsist on the network
  40. systemStats[packet.sysid] = new SystemStat();
  41. }
  42. lostPacketCount += systemStats[packet.sysid].newPacket(packet);
  43. receivedPacketCount++;
  44. }
  45. /**
  46. * Called when a CRC error happens on the parser
  47. */
  48. public void crcError() {
  49. crcErrorCount++;
  50. }
  51. public void resetStats() {
  52. crcErrorCount = 0;
  53. lostPacketCount = 0;
  54. receivedPacketCount = 0;
  55. systemStats = new SystemStat[256];
  56. }
  57. // stat structure for every system id
  58. public static class SystemStat {
  59. public int lostPacketCount; // the lost count for this source
  60. public int receivedPacketCount;
  61. // stats are nil for a component id until a packet has been received from a system
  62. public ComponentStat[] componentStats; // stats for each component that is known
  63. public SystemStat() {
  64. resetStats();
  65. }
  66. public int newPacket(MAVLinkPacket packet) {
  67. int newLostPackets = 0;
  68. if (componentStats[packet.compid] == null) {
  69. // only allocate stats for systems that exsist on the network
  70. componentStats[packet.compid] = new ComponentStat();
  71. }
  72. newLostPackets = componentStats[packet.compid].newPacket(packet);
  73. lostPacketCount += newLostPackets;
  74. receivedPacketCount++;
  75. return newLostPackets;
  76. }
  77. public void resetStats() {
  78. lostPacketCount = 0;
  79. receivedPacketCount = 0;
  80. componentStats = new ComponentStat[256];
  81. }
  82. }
  83. // stat structure for every system id
  84. public static class ComponentStat {
  85. public int lastPacketSeq;
  86. public int lostPacketCount; // the lost count for this source
  87. public int receivedPacketCount;
  88. public ComponentStat() {
  89. resetStats();
  90. }
  91. public int newPacket(MAVLinkPacket packet) {
  92. int newLostPackets = 0;
  93. if (hasLostPackets(packet)) {
  94. newLostPackets = updateLostPacketCount(packet);
  95. }
  96. lastPacketSeq = packet.seq;
  97. advanceLastPacketSequence(packet.seq);
  98. receivedPacketCount++;
  99. return newLostPackets;
  100. }
  101. public void resetStats() {
  102. lastPacketSeq = -1;
  103. lostPacketCount = 0;
  104. receivedPacketCount = 0;
  105. }
  106. private int updateLostPacketCount(MAVLinkPacket packet) {
  107. int lostPackets;
  108. if (packet.seq - lastPacketSeq < 0) {
  109. lostPackets = (packet.seq - lastPacketSeq) + 255;
  110. } else {
  111. lostPackets = (packet.seq - lastPacketSeq);
  112. }
  113. lostPacketCount += lostPackets;
  114. return lostPackets;
  115. }
  116. private void advanceLastPacketSequence(int lastSeq) {
  117. // wrap from 255 to 0 if necessary
  118. lastPacketSeq = (lastSeq + 1) & 0xFF;
  119. }
  120. private boolean hasLostPackets(MAVLinkPacket packet) {
  121. return lastPacketSeq >= 0 && packet.seq != lastPacketSeq;
  122. }
  123. }
  124. }