3 #if defined(MAVLINK_USE_CXX_NAMESPACE) 5 #elif defined(__cplusplus) 10 #if (defined _MSC_VER) && (_MSC_VER < 1600) 11 #error "The C-MAVLink implementation requires Visual Studio 2010 or greater" 22 #define X25_INIT_CRC 0xffff 23 #define X25_VALIDATE_CRC 0xf0b8 25 #ifndef HAVE_CRC_ACCUMULATE 40 tmp = data ^ (uint8_t)(*crcAccum &0xff);
42 *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
52 static inline void crc_init(uint16_t* crcAccum)
65 static inline uint16_t
crc_calculate(
const uint8_t* pBuffer, uint16_t length)
87 const uint8_t *p = (
const uint8_t *)pBuffer;
93 #if defined(MAVLINK_USE_CXX_NAMESPACE) || defined(__cplusplus)
static void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length)
Accumulate the X.25 CRC by adding an array of bytes.
static void crc_accumulate(uint8_t data, uint16_t *crcAccum)
Accumulate the X.25 CRC by adding one char at a time.
static uint16_t crc_calculate(const uint8_t *pBuffer, uint16_t length)
Calculates the X.25 checksum on a byte buffer.
static void crc_init(uint16_t *crcAccum)
Initiliaze the buffer for the X.25 CRC.