Rover: adjust for changed logging APIs

This commit is contained in:
Andrew Tridgell 2016-05-04 08:26:20 +10:00
parent b31e896ef3
commit ac4da762d1

View File

@ -167,7 +167,6 @@ void Rover::ahrs_update()
if (should_log(MASK_LOG_IMU)) {
DataFlash.Log_Write_IMU(ins);
DataFlash.Log_Write_IMUDT(ins);
}
}
@ -351,7 +350,7 @@ void Rover::update_GPS_50Hz(void)
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)) {
DataFlash.Log_Write_GPS(gps, i, current_loc.alt);
DataFlash.Log_Write_GPS(gps, i);
}
}
}