AP_ESC_Telem: update_telem_data to be public

This commit is contained in:
Tom Pittenger 2023-08-09 17:22:33 -07:00 committed by Tom Pittenger
parent 5ddb649ed1
commit dbe0aac73f
1 changed files with 3 additions and 3 deletions

View File

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