AP_GPS: fix dataflash logging of blended GPS instance
This commit is contained in:
parent
a12c2a6b87
commit
58f0c34612
@ -1661,6 +1661,7 @@ void AP_GPS::calc_blended_state(void)
|
||||
|
||||
timing[GPS_BLENDED_INSTANCE].last_fix_time_ms = 0;
|
||||
timing[GPS_BLENDED_INSTANCE].last_message_time_ms = 0;
|
||||
bool data_should_be_logged = false;
|
||||
|
||||
// combine the states into a blended solution
|
||||
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
|
||||
@ -1716,6 +1717,7 @@ void AP_GPS::calc_blended_state(void)
|
||||
}
|
||||
if (timing[i].last_message_time_ms > timing[GPS_BLENDED_INSTANCE].last_message_time_ms) {
|
||||
timing[GPS_BLENDED_INSTANCE].last_message_time_ms = timing[i].last_message_time_ms;
|
||||
data_should_be_logged = true;
|
||||
}
|
||||
|
||||
}
|
||||
@ -1801,6 +1803,13 @@ void AP_GPS::calc_blended_state(void)
|
||||
}
|
||||
timing[GPS_BLENDED_INSTANCE].last_fix_time_ms = (uint32_t)temp_time_1;
|
||||
timing[GPS_BLENDED_INSTANCE].last_message_time_ms = (uint32_t)temp_time_2;
|
||||
|
||||
#ifndef HAL_BUILD_AP_PERIPH
|
||||
if (data_should_be_logged &&
|
||||
should_log()) {
|
||||
AP::logger().Write_GPS(GPS_BLENDED_INSTANCE);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
#endif // GPS_BLENDED_INSTANCE
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user