#include <stdint.h>
Go to the source code of this file.
Defines | |
#define | _CHECKSUM_H_ |
#define | X25_INIT_CRC 0xffff |
#define | X25_VALIDATE_CRC 0xf0b8 |
Functions | |
static void | crc_accumulate (uint8_t data, uint16_t *crcAccum) |
Accumulate the X.25 CRC by adding one char at a time. | |
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 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. |
#define _CHECKSUM_H_ |
Definition at line 6 of file include_v0.9/checksum.h.
#define X25_INIT_CRC 0xffff |
CALCULATE THE CHECKSUM
Definition at line 21 of file include_v0.9/checksum.h.
#define X25_VALIDATE_CRC 0xf0b8 |
Definition at line 22 of file include_v0.9/checksum.h.
static void crc_accumulate | ( | uint8_t | data, |
uint16_t * | crcAccum | ||
) | [inline, static] |
Accumulate the X.25 CRC by adding one char at a time.
The checksum function adds the hash of one char at a time to the 16 bit checksum (uint16_t).
data | new char to hash |
crcAccum | the already accumulated checksum |
Definition at line 33 of file include_v0.9/checksum.h.
static void crc_accumulate_buffer | ( | uint16_t * | crcAccum, |
const char * | pBuffer, | ||
uint8_t | length | ||
) | [inline, static] |
Accumulate the X.25 CRC by adding an array of bytes.
The checksum function adds the hash of one char at a time to the 16 bit checksum (uint16_t).
data | new bytes to hash |
crcAccum | the already accumulated checksum |
Definition at line 80 of file include_v0.9/checksum.h.
static uint16_t crc_calculate | ( | const uint8_t * | pBuffer, |
uint16_t | length | ||
) | [inline, static] |
Calculates the X.25 checksum on a byte buffer.
pBuffer | buffer containing the byte array to hash |
length | length of the byte array |
Definition at line 61 of file include_v0.9/checksum.h.
static void crc_init | ( | uint16_t * | crcAccum | ) | [inline, static] |
Initiliaze the buffer for the X.25 CRC.
crcAccum | the 16 bit X.25 CRC |
Definition at line 48 of file include_v0.9/checksum.h.