checksum.h
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 // Visual Studio versions before 2010 don't have stdint.h, so we just error out.
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 
00033 static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
00034 {
00035         /*Accumulate one byte of data into the CRC*/
00036         uint8_t tmp;
00037 
00038         tmp = data ^ (uint8_t)(*crcAccum &0xff);
00039         tmp ^= (tmp<<4);
00040         *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
00041 }
00042 
00048 static inline void crc_init(uint16_t* crcAccum)
00049 {
00050         *crcAccum = X25_INIT_CRC;
00051 }
00052 
00053 
00061 static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
00062 {
00063         uint16_t crcTmp;
00064         crc_init(&crcTmp);
00065         while (length--) {
00066                 crc_accumulate(*pBuffer++, &crcTmp);
00067         }
00068         return crcTmp;
00069 }
00070 
00080 static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length)
00081 {
00082         const uint8_t *p = (const uint8_t *)pBuffer;
00083         while (length--) {
00084                 crc_accumulate(*p++, crcAccum);
00085         }
00086 }
00087 
00088 
00089 
00090 
00091 #endif /* _CHECKSUM_H_ */
00092 
00093 #ifdef __cplusplus
00094 }
00095 #endif


mavlink
Author(s): Lorenz Meier
autogenerated on Thu Jun 6 2019 19:01:57