From 3aa21ddef2c657ca29c615369c7a2367bb475408 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 22 Jan 2026 17:27:58 +0000 Subject: [PATCH] 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. --- .../AP_TemperatureSensor_MAX31865.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MAX31865.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MAX31865.cpp index 9fa8738152..89b1acba67 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MAX31865.cpp +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_MAX31865.cpp @@ -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; }