mirror of https://github.com/ArduPilot/ardupilot
AP_Beacon: checksum check uses XOR
This commit is contained in:
parent
bcdd836820
commit
292257eaf2
|
@ -111,11 +111,11 @@ void AP_Beacon_Pozyx::parse_buffer()
|
|||
uint8_t checksum = 0;
|
||||
checksum ^= parse_msg_id;
|
||||
checksum ^= parse_msg_len;
|
||||
for (uint8_t i=0; i<linebuf_len-1; i++) {
|
||||
for (uint8_t i=0; i<linebuf_len; i++) {
|
||||
checksum ^= linebuf[i];
|
||||
}
|
||||
// return if failed checksum check
|
||||
if (checksum != linebuf[linebuf_len-1]) {
|
||||
if (checksum != 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue