AP_ESC_Telem: avoid FPE on macos

use floats for rpm in API calls
This commit is contained in:
Andy Piper 2022-05-25 12:26:02 +01:00 committed by Peter Hall
parent 3f96423795
commit 2de992dcf1
4 changed files with 5 additions and 5 deletions

View File

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

View File

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

View File

@ -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);
}

View File

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