From 4e280795b2a35522e3c55a977c6dff4687dbdf32 Mon Sep 17 00:00:00 2001 From: Maxim Buzdalov Date: Sun, 18 Feb 2024 12:15:33 +0000 Subject: [PATCH] AP_ESC_Telem: for RPM, log NaN instead of 0 when there are no measurements --- libraries/AP_ESC_Telem/AP_ESC_Telem.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index 4af6e8bd72..837888b94d 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -503,9 +503,9 @@ void AP_ESC_Telem::update() if (_telem_data[i].last_update_ms != _last_telem_log_ms[i] || _rpm_data[i].last_update_us != _last_rpm_log_us[i]) { - float rpm = 0.0f; + float rpm = AP::logger().quiet_nanf(); get_rpm(i, rpm); - float raw_rpm = 0.0f; + float raw_rpm = AP::logger().quiet_nanf(); get_raw_rpm(i, raw_rpm); // Write ESC status messages