include_v0.9/checksum.h
Go to the documentation of this file.
1 #ifdef __cplusplus
2 extern "C" {
3 #endif
4 
5 #ifndef _CHECKSUM_H_
6 #define _CHECKSUM_H_
7 
8 // Visual Studio versions before 2010 don't have stdint.h, so we just error out.
9 #if (defined _MSC_VER) && (_MSC_VER < 1600)
10 #error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
11 #endif
12 
13 #include <stdint.h>
14 
21 #define X25_INIT_CRC 0xffff
22 #define X25_VALIDATE_CRC 0xf0b8
23 
33 static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
34 {
35  /*Accumulate one byte of data into the CRC*/
36  uint8_t tmp;
37 
38  tmp = data ^ (uint8_t)(*crcAccum &0xff);
39  tmp ^= (tmp<<4);
40  *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
41 }
42 
48 static inline void crc_init(uint16_t* crcAccum)
49 {
50  *crcAccum = X25_INIT_CRC;
51 }
52 
53 
61 static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
62 {
63  uint16_t crcTmp;
64  crc_init(&crcTmp);
65  while (length--) {
66  crc_accumulate(*pBuffer++, &crcTmp);
67  }
68  return crcTmp;
69 }
70 
80 static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length)
81 {
82  const uint8_t *p = (const uint8_t *)pBuffer;
83  while (length--) {
84  crc_accumulate(*p++, crcAccum);
85  }
86 }
87 
88 
89 
90 
91 #endif /* _CHECKSUM_H_ */
92 
93 #ifdef __cplusplus
94 }
95 #endif
static void crc_init(uint16_t *crcAccum)
Initiliaze the buffer for the X.25 CRC.
#define X25_INIT_CRC
static uint16_t crc_calculate(const uint8_t *pBuffer, uint16_t length)
Calculates the X.25 checksum on a byte buffer.
static void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_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.


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02