Class X25Checksum
java.lang.Object
de.wuespace.telestion.extension.mavlink.security.X25Checksum
This class is handling the creation of the X.25 (CRC-16-CCITT) custom checksum for MAVLink.
Apart from only hashing the message itself a CRC_EXTRA byte must be added which is unique for each message. Only 2 bytes (last 2 bytes) of the final hash will then be used.
Implementation is based on the official c implementation for MAVLink.
Apart from only hashing the message itself a CRC_EXTRA byte must be added which is unique for each message. Only 2 bytes (last 2 bytes) of the final hash will then be used.
Implementation is based on the official c implementation for MAVLink.
-
Field Summary
Modifier and TypeFieldDescriptionstatic int
Initial value for the CRC-Calculation.
This is needed because for each byte of the message the current-checksum gets "reused". -
Method Summary
Modifier and TypeMethodDescriptionstatic int
calculate(byte[] buffer)
Calculates the CRC X.25-checksum for a whole byte[] array.
Must contain the CRC_EXTRA byte which must be added for each message.static int
calculate(byte[] payload, int crc)
Calculates the CRC X.25-checksum for a given payload array and the right crc-extra extra byte.static int
calculate(int data, int currentCrc)
Calculates the CRC X.25-checksum for one byte with regards to the current-checksum.
-
Field Details
-
INIT_CRC
public static final int INIT_CRCInitial value for the CRC-Calculation.
This is needed because for each byte of the message the current-checksum gets "reused".- See Also:
- Constant Field Values
-
-
Method Details
-
calculate
public static int calculate(int data, int currentCrc)Calculates the CRC X.25-checksum for one byte with regards to the current-checksum.- Parameters:
data
- byte which should be added to the checksumcurrentCrc
- current checksum which should be extended- Returns:
- checksum composed from a prior checksum and a byte of data
-
calculate
public static int calculate(byte[] buffer)Calculates the CRC X.25-checksum for a whole byte[] array.
Must contain the CRC_EXTRA byte which must be added for each message.- Parameters:
buffer
- of data to calculate a checksum for- Returns:
- checksum for the whole buffer
-
calculate
public static int calculate(byte[] payload, int crc)Calculates the CRC X.25-checksum for a given payload array and the right crc-extra extra byte.- Parameters:
payload
- data to calculate the checksum forcrc
- crc-byte which must be added- Returns:
- checksum for the payload
-