From ea3b40595902c74a36828559cb10578539e0ba66 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 10 Jan 2013 21:28:07 +1100 Subject: [PATCH] MAVLink: moved CRC table into program this saves 256 bytes of memory --- libraries/GCS_MAVLink/GCS_MAVLink.cpp | 7 +++++++ libraries/GCS_MAVLink/GCS_MAVLink.h | 7 +++++++ 2 files changed, 14 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.cpp b/libraries/GCS_MAVLink/GCS_MAVLink.cpp index d103850f73..ed7aef2006 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.cpp +++ b/libraries/GCS_MAVLink/GCS_MAVLink.cpp @@ -68,3 +68,10 @@ void comm_send_buffer(mavlink_channel_t chan, const uint8_t *buf, uint8_t len) } } +static const uint8_t mavlink_message_crc_progmem[256] PROGMEM = MAVLINK_MESSAGE_CRCS; + +// return CRC byte for a mavlink message ID +uint8_t mavlink_get_message_crc(uint8_t msgid) +{ + return pgm_read_byte(&mavlink_message_crc_progmem[msgid]); +} diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.h b/libraries/GCS_MAVLink/GCS_MAVLink.h index ab66fe51c0..1728b39435 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.h +++ b/libraries/GCS_MAVLink/GCS_MAVLink.h @@ -15,6 +15,10 @@ #define MAVLINK_SEND_UART_BYTES(chan, buf, len) comm_send_buffer(chan, buf, len) +// define our own MAVLINK_MESSAGE_CRC() macro to allow it to be put +// into progmem +#define MAVLINK_MESSAGE_CRC(msgid) mavlink_get_message_crc(msgid) + #if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2 #include #define HAVE_CRC_ACCUMULATE @@ -146,4 +150,7 @@ uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid); // return a MAVLink variable type given a AP_Param type uint8_t mav_var_type(enum ap_var_type t); +// return CRC byte for a mavlink message ID +uint8_t mavlink_get_message_crc(uint8_t msgid); + #endif // GCS_MAVLink_h