diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index 902db738a8..ab5753f95a 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -826,6 +826,7 @@ void DataFlash_Class::Log_Write_Baro(AP_Baro &baro, uint64_t time_us) if (time_us == 0) { time_us = AP_HAL::micros64(); } + float climbrate = baro.get_climb_rate(); float drift_offset = baro.get_baro_drift_offset(); struct log_BARO pkt = { LOG_PACKET_HEADER_INIT(LOG_BARO_MSG), @@ -833,7 +834,7 @@ void DataFlash_Class::Log_Write_Baro(AP_Baro &baro, uint64_t time_us) altitude : baro.get_altitude(0), pressure : baro.get_pressure(0), temperature : (int16_t)(baro.get_temperature(0) * 100 + 0.5f), - climbrate : baro.get_climb_rate(), + climbrate : climbrate, sample_time_ms: baro.get_last_update(0), drift_offset : drift_offset, }; @@ -846,7 +847,7 @@ void DataFlash_Class::Log_Write_Baro(AP_Baro &baro, uint64_t time_us) altitude : baro.get_altitude(1), pressure : baro.get_pressure(1), temperature : (int16_t)(baro.get_temperature(1) * 100 + 0.5f), - climbrate : baro.get_climb_rate(), + climbrate : climbrate, sample_time_ms: baro.get_last_update(1), drift_offset : drift_offset, }; @@ -860,7 +861,7 @@ void DataFlash_Class::Log_Write_Baro(AP_Baro &baro, uint64_t time_us) altitude : baro.get_altitude(2), pressure : baro.get_pressure(2), temperature : (int16_t)(baro.get_temperature(2) * 100 + 0.5f), - climbrate : baro.get_climb_rate(), + climbrate : climbrate, sample_time_ms: baro.get_last_update(2), drift_offset : drift_offset, };