Parser.java 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125
  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;
  7. import com.MAVLink.MAVLinkPacket;
  8. import com.MAVLink.Messages.MAVLinkStats;
  9. public class Parser {
  10. /**
  11. * States from the parsing state machine
  12. */
  13. enum MAV_states {
  14. MAVLINK_PARSE_STATE_UNINIT, MAVLINK_PARSE_STATE_IDLE, MAVLINK_PARSE_STATE_GOT_STX, MAVLINK_PARSE_STATE_GOT_LENGTH, MAVLINK_PARSE_STATE_GOT_SEQ, MAVLINK_PARSE_STATE_GOT_SYSID, MAVLINK_PARSE_STATE_GOT_COMPID, MAVLINK_PARSE_STATE_GOT_MSGID, MAVLINK_PARSE_STATE_GOT_CRC1, MAVLINK_PARSE_STATE_GOT_PAYLOAD
  15. }
  16. MAV_states state = MAV_states.MAVLINK_PARSE_STATE_UNINIT;
  17. public MAVLinkStats stats;
  18. private MAVLinkPacket m;
  19. public Parser() {
  20. this(false);
  21. }
  22. public Parser(boolean ignoreRadioPacketStats) {
  23. stats = new MAVLinkStats(ignoreRadioPacketStats);
  24. }
  25. /**
  26. * This is a convenience function which handles the complete MAVLink
  27. * parsing. the function will parse one byte at a time and return the
  28. * complete packet once it could be successfully decoded. Checksum and other
  29. * failures will be silently ignored.
  30. *
  31. * @param c
  32. * The char to parse
  33. */
  34. public MAVLinkPacket mavlink_parse_char(int c) {
  35. switch (state) {
  36. case MAVLINK_PARSE_STATE_UNINIT:
  37. case MAVLINK_PARSE_STATE_IDLE:
  38. if (c == MAVLinkPacket.MAVLINK_STX) {
  39. state = MAV_states.MAVLINK_PARSE_STATE_GOT_STX;
  40. }
  41. break;
  42. case MAVLINK_PARSE_STATE_GOT_STX:
  43. m = new MAVLinkPacket(c);
  44. state = MAV_states.MAVLINK_PARSE_STATE_GOT_LENGTH;
  45. break;
  46. case MAVLINK_PARSE_STATE_GOT_LENGTH:
  47. m.seq = c;
  48. state = MAV_states.MAVLINK_PARSE_STATE_GOT_SEQ;
  49. break;
  50. case MAVLINK_PARSE_STATE_GOT_SEQ:
  51. m.sysid = c;
  52. state = MAV_states.MAVLINK_PARSE_STATE_GOT_SYSID;
  53. break;
  54. case MAVLINK_PARSE_STATE_GOT_SYSID:
  55. m.compid = c;
  56. state = MAV_states.MAVLINK_PARSE_STATE_GOT_COMPID;
  57. break;
  58. case MAVLINK_PARSE_STATE_GOT_COMPID:
  59. m.msgid = c;
  60. if (m.len == 0) {
  61. state = MAV_states.MAVLINK_PARSE_STATE_GOT_PAYLOAD;
  62. } else {
  63. state = MAV_states.MAVLINK_PARSE_STATE_GOT_MSGID;
  64. }
  65. break;
  66. case MAVLINK_PARSE_STATE_GOT_MSGID:
  67. m.payload.add((byte) c);
  68. if (m.payloadIsFilled()) {
  69. state = MAV_states.MAVLINK_PARSE_STATE_GOT_PAYLOAD;
  70. }
  71. break;
  72. case MAVLINK_PARSE_STATE_GOT_PAYLOAD:
  73. m.generateCRC();
  74. // Check first checksum byte
  75. if (c != m.crc.getLSB()) {
  76. state = MAV_states.MAVLINK_PARSE_STATE_IDLE;
  77. if (c == MAVLinkPacket.MAVLINK_STX) {
  78. state = MAV_states.MAVLINK_PARSE_STATE_GOT_STX;
  79. m.crc.start_checksum();
  80. }
  81. stats.crcError();
  82. } else {
  83. state = MAV_states.MAVLINK_PARSE_STATE_GOT_CRC1;
  84. }
  85. break;
  86. case MAVLINK_PARSE_STATE_GOT_CRC1:
  87. // Check second checksum byte
  88. if (c != m.crc.getMSB()) {
  89. state = MAV_states.MAVLINK_PARSE_STATE_IDLE;
  90. if (c == MAVLinkPacket.MAVLINK_STX) {
  91. state = MAV_states.MAVLINK_PARSE_STATE_GOT_STX;
  92. m.crc.start_checksum();
  93. }
  94. stats.crcError();
  95. } else { // Successfully received the message
  96. stats.newPacket(m);
  97. state = MAV_states.MAVLINK_PARSE_STATE_IDLE;
  98. return m;
  99. }
  100. break;
  101. }
  102. return null;
  103. }
  104. }