From 295c34395975cb332b19164c20b2192f85e5f604 Mon Sep 17 00:00:00 2001 From: murata Date: Wed, 24 Apr 2019 15:52:34 +0900 Subject: [PATCH] AP_Airspeed: Commonize the CRC4 method --- libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp | 23 ++------------------ 1 file changed, 2 insertions(+), 21 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp b/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp index 135911e27a..e972899c76 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp @@ -26,6 +26,7 @@ #include #include #include +#include extern const AP_HAL::HAL &hal; @@ -113,27 +114,7 @@ bool AP_Airspeed_MS5525::init() */ uint16_t AP_Airspeed_MS5525::crc4_prom(void) { - uint16_t n_rem = 0; - uint8_t n_bit; - - for (uint8_t cnt = 0; cnt < sizeof(prom); cnt++) { - /* uneven bytes */ - if (cnt & 1) { - n_rem ^= (uint8_t)((prom[cnt >> 1]) & 0x00FF); - } else { - n_rem ^= (uint8_t)(prom[cnt >> 1] >> 8); - } - - for (n_bit = 8; n_bit > 0; n_bit--) { - if (n_rem & 0x8000) { - n_rem = (n_rem << 1) ^ 0x3000; - } else { - n_rem = (n_rem << 1); - } - } - } - - return (n_rem >> 12) & 0xF; + return crc_crc4(prom); } bool AP_Airspeed_MS5525::read_prom(void)