include_v2.0/checksum.h
Go to the documentation of this file.
1 #pragma once
2 
3 #if defined(MAVLINK_USE_CXX_NAMESPACE)
4 namespace mavlink {
5 #elif defined(__cplusplus)
6 extern "C" {
7 #endif
8 
9 // Visual Studio versions before 2010 don't have stdint.h, so we just error out.
10 #if (defined _MSC_VER) && (_MSC_VER < 1600)
11 #error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
12 #endif
13 
14 #include <stdint.h>
15 
22 #define X25_INIT_CRC 0xffff
23 #define X25_VALIDATE_CRC 0xf0b8
24 
25 #ifndef HAVE_CRC_ACCUMULATE
26 
35 static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
36 {
37  /*Accumulate one byte of data into the CRC*/
38  uint8_t tmp;
39 
40  tmp = data ^ (uint8_t)(*crcAccum &0xff);
41  tmp ^= (tmp<<4);
42  *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
43 }
44 #endif
45 
46 
52 static inline void crc_init(uint16_t* crcAccum)
53 {
54  *crcAccum = X25_INIT_CRC;
55 }
56 
57 
65 static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
66 {
67  uint16_t crcTmp;
68  crc_init(&crcTmp);
69  while (length--) {
70  crc_accumulate(*pBuffer++, &crcTmp);
71  }
72  return crcTmp;
73 }
74 
75 
85 static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length)
86 {
87  const uint8_t *p = (const uint8_t *)pBuffer;
88  while (length--) {
89  crc_accumulate(*p++, crcAccum);
90  }
91 }
92 
93 #if defined(MAVLINK_USE_CXX_NAMESPACE) || defined(__cplusplus)
94 }
95 #endif
#define X25_INIT_CRC
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.


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