mirror of https://github.com/ArduPilot/ardupilot
AP_RCProtocol: Change to shared CRC16 method
This commit is contained in:
parent
428d4d4574
commit
987966a6d7
|
@ -21,32 +21,11 @@
|
|||
*/
|
||||
|
||||
#include "AP_RCProtocol_SRXL.h"
|
||||
#include <AP_Math/crc.h>
|
||||
|
||||
// #define SUMD_DEBUG
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
/**
|
||||
* This function calculates the 16bit crc as used throughout the srxl protocol variants
|
||||
*
|
||||
* This function is intended to be called whenever a new byte shall be added to the crc.
|
||||
* Simply provide the old crc and the new data byte and the function return the new crc value.
|
||||
*
|
||||
* To start a new crc calculation for a new srxl frame, provide parameter crc=0 and the first byte of the frame.
|
||||
*
|
||||
* @param[in] crc - start value for crc
|
||||
* @param[in] new_byte - byte that shall be included in crc calculation
|
||||
* @return calculated crc
|
||||
*/
|
||||
uint16_t AP_RCProtocol_SRXL::srxl_crc16(uint16_t crc, uint8_t new_byte)
|
||||
{
|
||||
uint8_t loop;
|
||||
crc = crc ^ (uint16_t)new_byte << 8;
|
||||
for (loop = 0; loop < 8; loop++) {
|
||||
crc = (crc & 0x8000) ? (crc << 1) ^ 0x1021 : (crc << 1);
|
||||
}
|
||||
return crc;
|
||||
}
|
||||
|
||||
void AP_RCProtocol_SRXL::process_pulse(uint32_t width_s0, uint32_t width_s1)
|
||||
{
|
||||
uint8_t b;
|
||||
|
@ -229,7 +208,7 @@ void AP_RCProtocol_SRXL::_process_byte(uint32_t timestamp_us, uint8_t byte)
|
|||
switch (decode_state) {
|
||||
case STATE_NEW: /* buffer header byte and prepare for frame reception and decoding */
|
||||
buffer[0U]=byte;
|
||||
crc_fmu = srxl_crc16(0U,byte);
|
||||
crc_fmu = crc_xmodem_update(0U,byte);
|
||||
buflen = 1U;
|
||||
decode_state_next = STATE_COLLECT;
|
||||
break;
|
||||
|
@ -247,7 +226,7 @@ void AP_RCProtocol_SRXL::_process_byte(uint32_t timestamp_us, uint8_t byte)
|
|||
buflen++;
|
||||
/* CRC not over last 2 frame bytes as these bytes inhabitate the crc */
|
||||
if (buflen <= (frame_len_full-2)) {
|
||||
crc_fmu = srxl_crc16(crc_fmu,byte);
|
||||
crc_fmu = crc_xmodem_update(crc_fmu,byte);
|
||||
}
|
||||
if (buflen == frame_len_full) {
|
||||
/* CRC check here */
|
||||
|
|
|
@ -43,7 +43,6 @@ public:
|
|||
void process_byte(uint8_t byte, uint32_t baudrate) override;
|
||||
private:
|
||||
void _process_byte(uint32_t timestamp_us, uint8_t byte);
|
||||
static uint16_t srxl_crc16(uint16_t crc, uint8_t new_byte);
|
||||
int srxl_channels_get_v1v2(uint16_t max_values, uint8_t *num_values, uint16_t *values, bool *failsafe_state);
|
||||
int srxl_channels_get_v5(uint16_t max_values, uint8_t *num_values, uint16_t *values, bool *failsafe_state);
|
||||
uint8_t buffer[SRXL_FRAMELEN_MAX]; /* buffer for raw srxl frame data in correct order --> buffer[0]=byte0 buffer[1]=byte1 */
|
||||
|
|
|
@ -43,6 +43,7 @@
|
|||
* @author Marco Bauer <marco@wtns.de>
|
||||
*/
|
||||
#include "AP_RCProtocol_SUMD.h"
|
||||
#include <AP_Math/crc.h>
|
||||
|
||||
#define SUMD_HEADER_LENGTH 3
|
||||
#define SUMD_HEADER_ID 0xA8
|
||||
|
@ -64,18 +65,6 @@
|
|||
// #define SUMD_DEBUG
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
uint16_t AP_RCProtocol_SUMD::sumd_crc16(uint16_t crc, uint8_t value)
|
||||
{
|
||||
int i;
|
||||
crc ^= (uint16_t)value << 8;
|
||||
|
||||
for (i = 0; i < 8; i++) {
|
||||
crc = (crc & 0x8000) ? (crc << 1) ^ 0x1021 : (crc << 1);
|
||||
}
|
||||
|
||||
return crc;
|
||||
}
|
||||
|
||||
uint8_t AP_RCProtocol_SUMD::sumd_crc8(uint8_t crc, uint8_t value)
|
||||
{
|
||||
crc += value;
|
||||
|
@ -107,7 +96,7 @@ void AP_RCProtocol_SUMD::_process_byte(uint32_t timestamp_us, uint8_t byte)
|
|||
_crc16 = 0x0000;
|
||||
_crc8 = 0x00;
|
||||
_crcOK = false;
|
||||
_crc16 = sumd_crc16(_crc16, byte);
|
||||
_crc16 = crc_xmodem_update(_crc16, byte);
|
||||
_crc8 = sumd_crc8(_crc8, byte);
|
||||
_decode_state = SUMD_DECODE_STATE_GOT_HEADER;
|
||||
|
||||
|
@ -127,7 +116,7 @@ void AP_RCProtocol_SUMD::_process_byte(uint32_t timestamp_us, uint8_t byte)
|
|||
}
|
||||
|
||||
if (_sumd) {
|
||||
_crc16 = sumd_crc16(_crc16, byte);
|
||||
_crc16 = crc_xmodem_update(_crc16, byte);
|
||||
|
||||
} else {
|
||||
_crc8 = sumd_crc8(_crc8, byte);
|
||||
|
@ -150,7 +139,7 @@ void AP_RCProtocol_SUMD::_process_byte(uint32_t timestamp_us, uint8_t byte)
|
|||
_rxpacket.length = byte;
|
||||
|
||||
if (_sumd) {
|
||||
_crc16 = sumd_crc16(_crc16, byte);
|
||||
_crc16 = crc_xmodem_update(_crc16, byte);
|
||||
|
||||
} else {
|
||||
_crc8 = sumd_crc8(_crc8, byte);
|
||||
|
@ -173,7 +162,7 @@ void AP_RCProtocol_SUMD::_process_byte(uint32_t timestamp_us, uint8_t byte)
|
|||
_rxpacket.sumd_data[_rxlen] = byte;
|
||||
|
||||
if (_sumd) {
|
||||
_crc16 = sumd_crc16(_crc16, byte);
|
||||
_crc16 = crc_xmodem_update(_crc16, byte);
|
||||
|
||||
} else {
|
||||
_crc8 = sumd_crc8(_crc8, byte);
|
||||
|
@ -341,4 +330,3 @@ void AP_RCProtocol_SUMD::process_byte(uint8_t byte, uint32_t baudrate)
|
|||
}
|
||||
_process_byte(AP_HAL::micros(), byte);
|
||||
}
|
||||
|
||||
|
|
|
@ -30,7 +30,6 @@ public:
|
|||
|
||||
private:
|
||||
void _process_byte(uint32_t timestamp_us, uint8_t byte);
|
||||
static uint16_t sumd_crc16(uint16_t crc, uint8_t value);
|
||||
static uint8_t sumd_crc8(uint8_t crc, uint8_t value);
|
||||
|
||||
#pragma pack(push, 1)
|
||||
|
|
Loading…
Reference in New Issue