AP_TemperatureSensor: fix polynomial calculation

The polynomial calculation was using norm_resistance instead of rpoly
for the higher-order terms, resulting in incorrect temperature values
for sub-zero temperatures. This also fixes the clang
-Wunused-but-set-variable warning.
This commit is contained in:
Andy Piper
2026-01-22 17:27:58 +00:00
committed by Peter Hall
parent 4834caafa4
commit 3aa21ddef2

View File

@@ -153,15 +153,15 @@ float AP_TemperatureSensor_MAX31865::calculate_temperature(const uint16_t raw) c
float rpoly = norm_resistance;
temp = -242.02;
temp += 2.2228 * norm_resistance;
temp += 2.2228 * rpoly;
rpoly *= norm_resistance;
temp += 2.5859e-3 * norm_resistance;
temp += 2.5859e-3 * rpoly;
rpoly *= norm_resistance;
temp -= 4.8260e-6 * norm_resistance;
temp -= 4.8260e-6 * rpoly;
rpoly *= norm_resistance;
temp -= 2.8183e-8 * norm_resistance;
temp -= 2.8183e-8 * rpoly;
rpoly *= norm_resistance;
temp += 1.5243e-10 * norm_resistance;
temp += 1.5243e-10 * rpoly;
return temp;
}