mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_ESC_Telem: expose update_rpm() for scripting
This commit is contained in:
parent
19bc7ebebe
commit
ec31a13275
@ -91,9 +91,11 @@ public:
|
|||||||
// udpate at 10Hz to log telemetry
|
// udpate at 10Hz to log telemetry
|
||||||
void update();
|
void update();
|
||||||
|
|
||||||
private:
|
|
||||||
// callback to update the rpm in the frontend, should be called by the driver when new data is available
|
// 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 uint16_t 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
|
// 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);
|
void update_telem_data(const uint8_t esc_index, const AP_ESC_Telem_Backend::TelemetryData& new_data, const uint16_t data_mask);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user