mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 10:43:58 -04:00
GCS_MAVLink: use AVR assembler CRC function if available
This commit is contained in:
parent
82b036282b
commit
d6ac02139f
@ -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"
|
||||
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user