AP_ESC_Telem: for RPM, log NaN instead of 0 when there are no measurements

This commit is contained in:
Maxim Buzdalov 2024-02-18 12:15:33 +00:00 committed by Peter Barker
parent 728d9a9f96
commit 4e280795b2
1 changed files with 2 additions and 2 deletions

View File

@ -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