diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.h b/libraries/GCS_MAVLink/GCS_MAVLink.h index 03555c1b56..ffa6d37feb 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.h +++ b/libraries/GCS_MAVLink/GCS_MAVLink.h @@ -125,6 +125,15 @@ static inline uint16_t comm_get_txspace(mavlink_channel_t chan) return (uint16_t)ret; } +#ifdef HAVE_CRC_ACCUMULATE +// use the AVR C library implementation. This is a bit over twice as +// fast as the C version +static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) +{ + *crcAccum = _crc_ccitt_update(*crcAccum, data); +} +#endif + #define MAVLINK_USE_CONVENIENCE_FUNCTIONS #include "include/mavlink/v1.0/ardupilotmega/mavlink.h" diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/checksum.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/checksum.h index 4f4cce02fc..5363084f74 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/checksum.h +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/checksum.h @@ -24,6 +24,7 @@ extern "C" { * @param data new char to hash * @param crcAccum the already accumulated checksum **/ +#ifndef HAVE_CRC_ACCUMULATE static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) { /*Accumulate one byte of data into the CRC*/ @@ -33,6 +34,7 @@ static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) tmp ^= (tmp<<4); *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); } +#endif /** * @brief Initiliaze the buffer for the X.25 CRC