diff --git a/pymavlink/generator/C/include_v0.9/mavlink_helpers.h b/pymavlink/generator/C/include_v0.9/mavlink_helpers.h index b53a5ee34d..3e2058feae 100644 --- a/pymavlink/generator/C/include_v0.9/mavlink_helpers.h +++ b/pymavlink/generator/C/include_v0.9/mavlink_helpers.h @@ -227,6 +227,13 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; #define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid] #endif +#endif + +#if MAVLINK_CHECK_MESSAGE_LENGTH +#ifndef MAVLINK_MESSAGE_LENGTH + static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS; +#define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid] +#endif #endif mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); ///< The currently decoded message @@ -291,6 +298,19 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa break; case MAVLINK_PARSE_STATE_GOT_COMPID: +#if MAVLINK_CHECK_MESSAGE_LENGTH + if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c)) + { + status->parse_error++; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + break; + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + mavlink_start_checksum(rxmsg); + } + } +#endif rxmsg->msgid = c; mavlink_update_checksum(rxmsg, c); if (rxmsg->len == 0) diff --git a/pymavlink/generator/C/include_v1.0/mavlink_helpers.h b/pymavlink/generator/C/include_v1.0/mavlink_helpers.h index b53a5ee34d..3e2058feae 100644 --- a/pymavlink/generator/C/include_v1.0/mavlink_helpers.h +++ b/pymavlink/generator/C/include_v1.0/mavlink_helpers.h @@ -227,6 +227,13 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; #define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid] #endif +#endif + +#if MAVLINK_CHECK_MESSAGE_LENGTH +#ifndef MAVLINK_MESSAGE_LENGTH + static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS; +#define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid] +#endif #endif mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); ///< The currently decoded message @@ -291,6 +298,19 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa break; case MAVLINK_PARSE_STATE_GOT_COMPID: +#if MAVLINK_CHECK_MESSAGE_LENGTH + if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c)) + { + status->parse_error++; + status->parse_state = MAVLINK_PARSE_STATE_IDLE; + break; + if (c == MAVLINK_STX) + { + status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; + mavlink_start_checksum(rxmsg); + } + } +#endif rxmsg->msgid = c; mavlink_update_checksum(rxmsg, c); if (rxmsg->len == 0)