MAVLink: moved CRC table into program

this saves 256 bytes of memory
This commit is contained in:
Andrew Tridgell 2013-01-10 21:28:07 +11:00
parent 0c1912565a
commit c3ae125332
2 changed files with 20 additions and 0 deletions

View File

@ -51,3 +51,11 @@ uint8_t mav_var_type(enum ap_var_type t)
}
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]);
}

View File

@ -12,6 +12,15 @@
// to select MAVLink 1.0 in the arduino GUI build
#define MAVLINK_SEPARATE_HELPERS
// 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 defined( __AVR_ATmega1280__ ) || defined( __AVR_ATmega2560__ )
#include <util/crc16.h>
#define HAVE_CRC_ACCUMULATE
#endif
#include "include/mavlink/v1.0/ardupilotmega/version.h"
// this allows us to make mavlink_message_t much smaller. It means we
@ -124,4 +133,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