mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
DataFlash: round baro temp to nearest centi-degree
makes replay logs a tiny bit closer
This commit is contained in:
parent
73d3797a7e
commit
d97074dc9d
@ -824,7 +824,7 @@ void DataFlash_Class::Log_Write_Baro(AP_Baro &baro)
|
||||
time_us : time_us,
|
||||
altitude : baro.get_altitude(0),
|
||||
pressure : baro.get_pressure(0),
|
||||
temperature : (int16_t)(baro.get_temperature(0) * 100),
|
||||
temperature : (int16_t)(baro.get_temperature(0) * 100 + 0.5f),
|
||||
climbrate : baro.get_climb_rate()
|
||||
};
|
||||
WriteBlock(&pkt, sizeof(pkt));
|
||||
@ -835,7 +835,7 @@ void DataFlash_Class::Log_Write_Baro(AP_Baro &baro)
|
||||
time_us : time_us,
|
||||
altitude : baro.get_altitude(1),
|
||||
pressure : baro.get_pressure(1),
|
||||
temperature : (int16_t)(baro.get_temperature(1) * 100),
|
||||
temperature : (int16_t)(baro.get_temperature(1) * 100 + 0.5f),
|
||||
climbrate : baro.get_climb_rate()
|
||||
};
|
||||
WriteBlock(&pkt2, sizeof(pkt2));
|
||||
@ -847,7 +847,7 @@ void DataFlash_Class::Log_Write_Baro(AP_Baro &baro)
|
||||
time_us : time_us,
|
||||
altitude : baro.get_altitude(2),
|
||||
pressure : baro.get_pressure(2),
|
||||
temperature : (int16_t)(baro.get_temperature(2) * 100),
|
||||
temperature : (int16_t)(baro.get_temperature(2) * 100 + 0.5f),
|
||||
climbrate : baro.get_climb_rate()
|
||||
};
|
||||
WriteBlock(&pkt3, sizeof(pkt3));
|
||||
|
Loading…
Reference in New Issue
Block a user