Plane: ensure we log both GPS at the time we receive a msg

This commit is contained in:
Andrew Tridgell 2014-04-10 10:29:53 +10:00
parent 95304e27c9
commit 4d990fa6c8
2 changed files with 10 additions and 8 deletions

View File

@ -1009,13 +1009,15 @@ static void airspeed_ratio_update(void)
*/
static void update_GPS_50Hz(void)
{
static uint32_t last_gps_reading;
static uint32_t last_gps_reading[GPS_MAX_INSTANCES];
gps.update();
if (gps.last_message_time_ms() != last_gps_reading) {
last_gps_reading = gps.last_message_time_ms();
for (uint8_t i=0; i<gps.num_sensors(); i++) {
if (gps.last_message_time_ms(i) != last_gps_reading[i]) {
last_gps_reading[i] = gps.last_message_time_ms(i);
if (should_log(MASK_LOG_GPS)) {
Log_Write_GPS();
Log_Write_GPS(i);
}
}
}
}

View File

@ -491,9 +491,9 @@ static void Log_Write_Compass()
#endif
}
static void Log_Write_GPS(void)
static void Log_Write_GPS(uint8_t instance)
{
DataFlash.Log_Write_GPS(gps, current_loc.alt - ahrs.get_home().alt);
DataFlash.Log_Write_GPS(gps, instance, current_loc.alt - ahrs.get_home().alt);
}
static void Log_Write_IMU()
@ -612,7 +612,7 @@ static void Log_Write_Control_Tuning() {}
static void Log_Write_Camera() {}
static void Log_Write_Mode(uint8_t mode) {}
static void Log_Write_Compass() {}
static void Log_Write_GPS() {}
static void Log_Write_GPS(uint8_t instance) {}
static void Log_Write_IMU() {}
static void Log_Write_RC() {}
static void Log_Write_Airspeed(void) {}