mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_GPS: fragments_received is a bitmask not a count
This commit is contained in:
parent
59135b6ea0
commit
d919478bdd
@ -1632,7 +1632,7 @@ void AP_GPS::handle_gps_rtcm_fragment(uint8_t flags, const uint8_t *data, uint8_
|
||||
// we have one or more partial fragments already received
|
||||
// which conflict with the new fragment, discard previous fragments
|
||||
rtcm_buffer->fragment_count = 0;
|
||||
rtcm_stats.fragments_discarded += rtcm_buffer->fragments_received;
|
||||
rtcm_stats.fragments_discarded += __builtin_popcount(rtcm_buffer->fragments_received);
|
||||
rtcm_buffer->fragments_received = 0;
|
||||
}
|
||||
|
||||
@ -1661,7 +1661,7 @@ void AP_GPS::handle_gps_rtcm_fragment(uint8_t flags, const uint8_t *data, uint8_
|
||||
if (rtcm_buffer->fragment_count != 0 &&
|
||||
rtcm_buffer->fragments_received == (1U << rtcm_buffer->fragment_count) - 1) {
|
||||
// we have them all, inject
|
||||
rtcm_stats.fragments_used += rtcm_buffer->fragments_received;
|
||||
rtcm_stats.fragments_used += __builtin_popcount(rtcm_buffer->fragments_received);
|
||||
inject_data(rtcm_buffer->buffer, rtcm_buffer->total_length);
|
||||
rtcm_buffer->fragment_count = 0;
|
||||
rtcm_buffer->fragments_received = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user