Browse Source

AP_Beacon: checksum check uses XOR

master
murata 8 years ago committed by Randy Mackay
parent
commit
292257eaf2
  1. 4
      libraries/AP_Beacon/AP_Beacon_Pozyx.cpp

4
libraries/AP_Beacon/AP_Beacon_Pozyx.cpp

@ -111,11 +111,11 @@ void AP_Beacon_Pozyx::parse_buffer() @@ -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…
Cancel
Save