From 2de992dcf1bd791521a7b4bef9f4d9f83e0af2a2 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 25 May 2022 12:26:02 +0100 Subject: [PATCH] AP_ESC_Telem: avoid FPE on macos use floats for rpm in API calls --- libraries/AP_ESC_Telem/AP_ESC_Telem.cpp | 2 +- libraries/AP_ESC_Telem/AP_ESC_Telem.h | 4 ++-- libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp | 2 +- libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index 5e7fb72a98..cb85e15332 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -436,7 +436,7 @@ void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem // record an update to the RPM together with timestamp, this allows the notch values to be slewed // this should be called by backends when new telemetry values are available -void AP_ESC_Telem::update_rpm(const uint8_t esc_index, const uint16_t new_rpm, const float error_rate) +void AP_ESC_Telem::update_rpm(const uint8_t esc_index, const float new_rpm, const float error_rate) { if (esc_index >= ESC_TELEM_MAX_ESCS) { return; diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.h b/libraries/AP_ESC_Telem/AP_ESC_Telem.h index 29f1787e8c..3537f83187 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.h @@ -99,9 +99,9 @@ public: // callback to update the rpm in the frontend, should be called by the driver when new data is available // can also be called from scripting - void update_rpm(const uint8_t esc_index, const uint16_t new_rpm, const float error_rate); - + void update_rpm(const uint8_t esc_index, const float new_rpm, const float error_rate); private: + // callback to update the data in the frontend, should be called by the driver when new data is available void update_telem_data(const uint8_t esc_index, const AP_ESC_Telem_Backend::TelemetryData& new_data, const uint16_t data_mask); diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp index 7733dc6a09..b104c83562 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp @@ -31,7 +31,7 @@ AP_ESC_Telem_Backend::AP_ESC_Telem_Backend() { } // callback to update the rpm in the frontend, should be called by the driver when new data is available -void AP_ESC_Telem_Backend::update_rpm(const uint8_t esc_index, const uint16_t new_rpm, const float error_rate) { +void AP_ESC_Telem_Backend::update_rpm(const uint8_t esc_index, const float new_rpm, const float error_rate) { _frontend->update_rpm(esc_index, new_rpm, error_rate); } diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h index 1f2d3a4810..769807230f 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h @@ -53,7 +53,7 @@ public: protected: // callback to update the rpm in the frontend, should be called by the driver when new data is available - void update_rpm(const uint8_t esc_index, const uint16_t new_rpm, const float error_rate = 0.0f); + void update_rpm(const uint8_t esc_index, const float new_rpm, const float error_rate = 0.0f); // callback to update the data in the frontend, should be called by the driver when new data is available void update_telem_data(const uint8_t esc_index, const TelemetryData& new_data, const uint16_t data_present_mask);