21 MAV_states state = MAV_states.MAVLINK_PARSE_STATE_UNINIT;
24 private MAVLinkPacket
m;
30 public Parser(
boolean ignoreRadioPacketStats) {
49 if (c == MAVLinkPacket.MAVLINK_STX) {
50 state = MAV_states.MAVLINK_PARSE_STATE_GOT_STX;
55 m =
new MAVLinkPacket(c);
56 state = MAV_states.MAVLINK_PARSE_STATE_GOT_LENGTH;
61 state = MAV_states.MAVLINK_PARSE_STATE_GOT_SEQ;
66 state = MAV_states.MAVLINK_PARSE_STATE_GOT_SYSID;
71 state = MAV_states.MAVLINK_PARSE_STATE_GOT_COMPID;
77 state = MAV_states.MAVLINK_PARSE_STATE_GOT_PAYLOAD;
79 state = MAV_states.MAVLINK_PARSE_STATE_GOT_MSGID;
84 m.payload.add((byte) c);
85 if (m.payloadIsFilled()) {
86 state = MAV_states.MAVLINK_PARSE_STATE_GOT_PAYLOAD;
93 if (c != m.crc.getLSB()) {
94 state = MAV_states.MAVLINK_PARSE_STATE_IDLE;
95 if (c == MAVLinkPacket.MAVLINK_STX) {
96 state = MAV_states.MAVLINK_PARSE_STATE_GOT_STX;
97 m.crc.start_checksum();
101 state = MAV_states.MAVLINK_PARSE_STATE_GOT_CRC1;
107 if (c != m.crc.getMSB()) {
108 state = MAV_states.MAVLINK_PARSE_STATE_IDLE;
109 if (c == MAVLinkPacket.MAVLINK_STX) {
110 state = MAV_states.MAVLINK_PARSE_STATE_GOT_STX;
111 m.crc.start_checksum();
116 state = MAV_states.MAVLINK_PARSE_STATE_IDLE;
void newPacket(MAVLinkPacket packet)
MAVLinkPacket mavlink_parse_char(int c)
Parser(boolean ignoreRadioPacketStats)