Skip to content

Commit

Permalink
check message length in parser
Browse files Browse the repository at this point in the history
  • Loading branch information
Ralph Hartley authored and Andrew Tridgell committed Aug 17, 2012
1 parent da0c5b5 commit 239443d
Show file tree
Hide file tree
Showing 2 changed files with 40 additions and 0 deletions.
20 changes: 20 additions & 0 deletions pymavlink/generator/C/include_v0.9/mavlink_helpers.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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)
Expand Down
20 changes: 20 additions & 0 deletions pymavlink/generator/C/include_v1.0/mavlink_helpers.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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)
Expand Down

0 comments on commit 239443d

Please sign in to comment.