Parser.java
Go to the documentation of this file.
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;
00008 
00009 import com.MAVLink.MAVLinkPacket;
00010 import com.MAVLink.Messages.MAVLinkStats;
00011 
00012 public class Parser {
00013 
00017     enum MAV_states {
00018         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
00019     }
00020 
00021     MAV_states state = MAV_states.MAVLINK_PARSE_STATE_UNINIT;
00022 
00023     static boolean msg_received;
00024 
00025     public MAVLinkStats stats = new MAVLinkStats();
00026     private MAVLinkPacket m;
00027 
00037     public MAVLinkPacket mavlink_parse_char(int c) {
00038         msg_received = false;
00039 
00040         switch (state) {
00041         case MAVLINK_PARSE_STATE_UNINIT:
00042         case MAVLINK_PARSE_STATE_IDLE:
00043 
00044             if (c == MAVLinkPacket.MAVLINK_STX) {
00045                 state = MAV_states.MAVLINK_PARSE_STATE_GOT_STX;
00046                 m = new MAVLinkPacket();
00047             }
00048             break;
00049 
00050         case MAVLINK_PARSE_STATE_GOT_STX:
00051             if (msg_received) {
00052                 msg_received = false;
00053                 state = MAV_states.MAVLINK_PARSE_STATE_IDLE;
00054             } else {
00055                 m.len = c;
00056                 state = MAV_states.MAVLINK_PARSE_STATE_GOT_LENGTH;
00057             }
00058             break;
00059 
00060         case MAVLINK_PARSE_STATE_GOT_LENGTH:
00061             m.seq = c;
00062             state = MAV_states.MAVLINK_PARSE_STATE_GOT_SEQ;
00063             break;
00064 
00065         case MAVLINK_PARSE_STATE_GOT_SEQ:
00066             m.sysid = c;
00067             state = MAV_states.MAVLINK_PARSE_STATE_GOT_SYSID;
00068             break;
00069 
00070         case MAVLINK_PARSE_STATE_GOT_SYSID:
00071             m.compid = c;
00072             state = MAV_states.MAVLINK_PARSE_STATE_GOT_COMPID;
00073             break;
00074 
00075         case MAVLINK_PARSE_STATE_GOT_COMPID:
00076             m.msgid = c;
00077             if (m.len == 0) {
00078                 state = MAV_states.MAVLINK_PARSE_STATE_GOT_PAYLOAD;
00079             } else {
00080                 state = MAV_states.MAVLINK_PARSE_STATE_GOT_MSGID;
00081             }
00082             break;
00083 
00084         case MAVLINK_PARSE_STATE_GOT_MSGID:
00085             m.payload.add((byte) c);
00086             if (m.payloadIsFilled()) {
00087                 state = MAV_states.MAVLINK_PARSE_STATE_GOT_PAYLOAD;
00088             }
00089             break;
00090 
00091         case MAVLINK_PARSE_STATE_GOT_PAYLOAD:
00092             m.generateCRC();
00093             // Check first checksum byte
00094             if (c != m.crc.getLSB()) {
00095                 msg_received = false;
00096                 state = MAV_states.MAVLINK_PARSE_STATE_IDLE;
00097                 if (c == MAVLinkPacket.MAVLINK_STX) {
00098                     state = MAV_states.MAVLINK_PARSE_STATE_GOT_STX;
00099                     m.crc.start_checksum();
00100                 }
00101                 stats.crcError();
00102             } else {
00103                 state = MAV_states.MAVLINK_PARSE_STATE_GOT_CRC1;
00104             }
00105             break;
00106 
00107         case MAVLINK_PARSE_STATE_GOT_CRC1:
00108             // Check second checksum byte
00109             if (c != m.crc.getMSB()) {
00110                 msg_received = false;
00111                 state = MAV_states.MAVLINK_PARSE_STATE_IDLE;
00112                 if (c == MAVLinkPacket.MAVLINK_STX) {
00113                     state = MAV_states.MAVLINK_PARSE_STATE_GOT_STX;
00114                     m.crc.start_checksum();
00115                 }
00116                 stats.crcError();
00117             } else { // Successfully received the message
00118                 stats.newPacket(m);
00119                 msg_received = true;
00120                 state = MAV_states.MAVLINK_PARSE_STATE_IDLE;
00121             }
00122 
00123             break;
00124 
00125         }
00126         if (msg_received) {
00127             return m;
00128         } else {
00129             return null;
00130         }
00131     }
00132 
00133 }


mavlink
Author(s): Lorenz Meier
autogenerated on Wed Sep 9 2015 18:06:17