before merging master
[inav.git] / lib / main / MAVLink / checksum.h
blob0a899a607719845718b7645777418f00b662d01e
1 #pragma once
3 #if defined(MAVLINK_USE_CXX_NAMESPACE)
4 namespace mavlink {
5 #elif defined(__cplusplus)
6 extern "C" {
7 #endif
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
14 #include <stdint.h>
16 /**
18 * CALCULATE THE CHECKSUM
22 #define X25_INIT_CRC 0xffff
23 #define X25_VALIDATE_CRC 0xf0b8
25 #ifndef HAVE_CRC_ACCUMULATE
26 /**
27 * @brief Accumulate the CRC16_MCRF4XX checksum by adding one char at a time.
29 * The checksum function adds the hash of one char at a time to the
30 * 16 bit checksum (uint16_t).
32 * @param data new char to hash
33 * @param crcAccum the already accumulated checksum
34 **/
35 static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
37 /*Accumulate one byte of data into the CRC*/
38 uint8_t tmp;
40 tmp = data ^ (uint8_t)(*crcAccum &0xff);
41 tmp ^= (tmp<<4);
42 *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
44 #endif
47 /**
48 * @brief Initiliaze the buffer for the MCRF4XX CRC16
50 * @param crcAccum the 16 bit MCRF4XX CRC16
52 static inline void crc_init(uint16_t* crcAccum)
54 *crcAccum = X25_INIT_CRC;
58 /**
59 * @brief Calculates the CRC16_MCRF4XX checksum on a byte buffer
61 * @param pBuffer buffer containing the byte array to hash
62 * @param length length of the byte array
63 * @return the checksum over the buffer bytes
64 **/
65 static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
67 uint16_t crcTmp;
68 crc_init(&crcTmp);
69 while (length--) {
70 crc_accumulate(*pBuffer++, &crcTmp);
72 return crcTmp;
76 /**
77 * @brief Accumulate the MCRF4XX CRC16 by adding an array of bytes
79 * The checksum function adds the hash of one char at a time to the
80 * 16 bit checksum (uint16_t).
82 * @param data new bytes to hash
83 * @param crcAccum the already accumulated checksum
84 **/
85 static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length)
87 const uint8_t *p = (const uint8_t *)pBuffer;
88 while (length--) {
89 crc_accumulate(*p++, crcAccum);
93 #if defined(MAVLINK_USE_CXX_NAMESPACE) || defined(__cplusplus)
95 #endif