From dbe0aac73f34271ee8e4c267329e7cab9879d58e Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Wed, 9 Aug 2023 17:22:33 -0700 Subject: [PATCH] AP_ESC_Telem: update_telem_data to be public --- libraries/AP_ESC_Telem/AP_ESC_Telem.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.h b/libraries/AP_ESC_Telem/AP_ESC_Telem.h index bf62542da8..a639e2607e 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.h @@ -97,6 +97,9 @@ public: // can also be called from scripting void update_rpm(const uint8_t esc_index, const float new_rpm, const float error_rate); + // 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); + #if AP_SCRIPTING_ENABLED /* set RPM scale factor from script @@ -106,9 +109,6 @@ public: 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); - // helper that validates RPM data static bool rpm_data_within_timeout (const volatile AP_ESC_Telem_Backend::RpmData &instance, const uint32_t now_us, const uint32_t timeout_us); static bool was_rpm_data_ever_reported (const volatile AP_ESC_Telem_Backend::RpmData &instance);