#include <stdint.h>
Go to the source code of this file.
|  | 
| static void | crc_accumulate (uint8_t data, uint16_t *crcAccum) | 
|  | Accumulate the X.25 CRC by adding one char at a time.  More... 
 | 
|  | 
| 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.  More... 
 | 
|  | 
| static uint16_t | crc_calculate (const uint8_t *pBuffer, uint16_t length) | 
|  | Calculates the X.25 checksum on a byte buffer.  More... 
 | 
|  | 
| static void | crc_init (uint16_t *crcAccum) | 
|  | Initiliaze the buffer for the X.25 CRC.  More... 
 | 
|  | 
      
        
          | #define X25_INIT_CRC   0xffff | 
      
 
 
      
        
          | #define X25_VALIDATE_CRC   0xf0b8 | 
      
 
 
  
  | 
        
          | static void crc_accumulate | ( | uint8_t | data, |  
          |  |  | uint16_t * | crcAccum |  
          |  | ) |  |  |  | inlinestatic | 
 
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).
- Parameters
- 
  
    | data | new char to hash |  | crcAccum | the already accumulated checksum |  
 
Definition at line 35 of file include_v2.0/checksum.h.
 
 
  
  | 
        
          | static void crc_accumulate_buffer | ( | uint16_t * | crcAccum, |  
          |  |  | const char * | pBuffer, |  
          |  |  | uint16_t | length |  
          |  | ) |  |  |  | inlinestatic | 
 
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).
- Parameters
- 
  
    | data | new bytes to hash |  | crcAccum | the already accumulated checksum |  
 
Definition at line 85 of file include_v2.0/checksum.h.
 
 
  
  | 
        
          | static uint16_t crc_calculate | ( | const uint8_t * | pBuffer, |  
          |  |  | uint16_t | length |  
          |  | ) |  |  |  | inlinestatic | 
 
Calculates the X.25 checksum on a byte buffer. 
- Parameters
- 
  
    | pBuffer | buffer containing the byte array to hash |  | length | length of the byte array |  
 
- Returns
- the checksum over the buffer bytes 
Definition at line 65 of file include_v2.0/checksum.h.
 
 
  
  | 
        
          | static void crc_init | ( | uint16_t * | crcAccum | ) |  |  | inlinestatic | 
 
Initiliaze the buffer for the X.25 CRC. 
- Parameters
- 
  
    | crcAccum | the 16 bit X.25 CRC |  
 
Definition at line 52 of file include_v2.0/checksum.h.