Tools: make C_TO_KELVIN a function macro; create KELVIN_TO_C

These are in celsius
This commit is contained in:
Peter Barker 2022-01-12 23:03:25 +11:00 committed by Peter Barker
parent 9ef959b93b
commit ef11400e13
1 changed files with 5 additions and 5 deletions

View File

@ -1562,7 +1562,7 @@ void AP_Periph_FW::esc_telem_update()
}
int16_t temperature;
if (esc_telem.get_temperature(i, temperature)) {
pkt.temperature = temperature*0.01 + C_TO_KELVIN;
pkt.temperature = C_TO_KELVIN(temperature*0.01);
} else {
pkt.temperature = nan;
}
@ -1736,8 +1736,8 @@ void AP_Periph_FW::can_battery_update(void)
float temperature;
if (battery.lib.get_temperature(temperature, i)) {
// Battery lib reports temperature in Celsius.
// Convert Celsius to Kelvin for tranmission on CAN.
pkt.temperature = temperature + C_TO_KELVIN;
// Convert Celsius to Kelvin for transmission on CAN.
pkt.temperature = C_TO_KELVIN(temperature);
}
pkt.state_of_health_pct = UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN;
@ -2097,7 +2097,7 @@ void AP_Periph_FW::can_baro_update(void)
{
uavcan_equipment_air_data_StaticTemperature pkt {};
pkt.static_temperature = temp + C_TO_KELVIN;
pkt.static_temperature = C_TO_KELVIN(temp);
pkt.static_temperature_variance = 0; // should we make this a parameter?
uint8_t buffer[UAVCAN_EQUIPMENT_AIR_DATA_STATICTEMPERATURE_MAX_SIZE] {};
@ -2148,7 +2148,7 @@ void AP_Periph_FW::can_airspeed_update(void)
if (!airspeed.get_temperature(temp)) {
temp = nanf("");
} else {
temp += C_TO_KELVIN;
temp = C_TO_KELVIN(temp);
}
uavcan_equipment_air_data_RawAirData pkt {};