Go to the documentation of this file.00001 #ifdef __cplusplus
00002 extern "C" {
00003 #endif
00004
00005 #ifndef _CHECKSUM_H_
00006 #define _CHECKSUM_H_
00007
00008
00009 #if (defined _MSC_VER) && (_MSC_VER < 1600)
00010 #error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
00011 #endif
00012
00013 #include <stdint.h>
00014
00021 #define X25_INIT_CRC 0xffff
00022 #define X25_VALIDATE_CRC 0xf0b8
00023
00024 #ifndef HAVE_CRC_ACCUMULATE
00025
00034 static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
00035 {
00036
00037 uint8_t tmp;
00038
00039 tmp = data ^ (uint8_t)(*crcAccum &0xff);
00040 tmp ^= (tmp<<4);
00041 *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
00042 }
00043 #endif
00044
00045
00051 static inline void crc_init(uint16_t* crcAccum)
00052 {
00053 *crcAccum = X25_INIT_CRC;
00054 }
00055
00056
00064 static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
00065 {
00066 uint16_t crcTmp;
00067 crc_init(&crcTmp);
00068 while (length--) {
00069 crc_accumulate(*pBuffer++, &crcTmp);
00070 }
00071 return crcTmp;
00072 }
00073
00074
00084 static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length)
00085 {
00086 const uint8_t *p = (const uint8_t *)pBuffer;
00087 while (length--) {
00088 crc_accumulate(*p++, crcAccum);
00089 }
00090 }
00091
00092 #endif
00093
00094 #ifdef __cplusplus
00095 }
00096 #endif