mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
AP_BLHeli: Remove duplicated code, use existing AP_Math CRC function
This commit is contained in:
parent
f3cc661ebd
commit
0dbd05505b
@ -1403,21 +1403,6 @@ void AP_BLHeli::init(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
implement the 8 bit CRC used by the BLHeli ESC telemetry protocol
|
|
||||||
*/
|
|
||||||
uint8_t AP_BLHeli::telem_crc8(uint8_t crc, uint8_t crc_seed) const
|
|
||||||
{
|
|
||||||
uint8_t crc_u = crc;
|
|
||||||
crc_u ^= crc_seed;
|
|
||||||
|
|
||||||
for (uint8_t i=0; i<8; i++) {
|
|
||||||
crc_u = ( crc_u & 0x80 ) ? 0x7 ^ ( crc_u << 1 ) : ( crc_u << 1 );
|
|
||||||
}
|
|
||||||
|
|
||||||
return crc_u;
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
read an ESC telemetry packet
|
read an ESC telemetry packet
|
||||||
*/
|
*/
|
||||||
@ -1432,7 +1417,7 @@ void AP_BLHeli::read_telemetry_packet(void)
|
|||||||
// calculate crc
|
// calculate crc
|
||||||
uint8_t crc = 0;
|
uint8_t crc = 0;
|
||||||
for (uint8_t i=0; i<telem_packet_size-1; i++) {
|
for (uint8_t i=0; i<telem_packet_size-1; i++) {
|
||||||
crc = telem_crc8(buf[i], crc);
|
crc = crc8_dvb(buf[i], crc, 0x07);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (buf[telem_packet_size-1] != crc) {
|
if (buf[telem_packet_size-1] != crc) {
|
||||||
|
@ -285,7 +285,6 @@ private:
|
|||||||
bool BL_VerifyFlash(const uint8_t *buf, uint16_t n);
|
bool BL_VerifyFlash(const uint8_t *buf, uint16_t n);
|
||||||
void blheli_process_command(void);
|
void blheli_process_command(void);
|
||||||
void run_connection_test(uint8_t chan);
|
void run_connection_test(uint8_t chan);
|
||||||
uint8_t telem_crc8(uint8_t crc, uint8_t crc_seed) const;
|
|
||||||
void read_telemetry_packet(void);
|
void read_telemetry_packet(void);
|
||||||
void log_bidir_telemetry(void);
|
void log_bidir_telemetry(void);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user