From 0c29d4280cec8e89d3f137d2cafc10f92ecf4592 Mon Sep 17 00:00:00 2001 From: Loki077 Date: Thu, 15 Aug 2024 15:35:05 +1000 Subject: [PATCH] AP_Scripting: AP_ESC_Telem method update -Updated AP_ESC_Telem methods to use ESC_TELEM_MAX_ESCS instead of NUM_SERVO_CHANNELS. - the place where the function returns bool adding skip check. --- .../generator/description/bindings.desc | 20 +++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 4d9a81f2fd9f3..a889a46e6e48d 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -440,16 +440,16 @@ userdata AP_ESC_Telem_Backend::TelemetryData field motor_temp_cdeg int16_t'skip_ singleton AP_ESC_Telem depends HAL_WITH_ESC_TELEM == 1 singleton AP_ESC_Telem rename esc_telem -singleton AP_ESC_Telem method get_rpm boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null -singleton AP_ESC_Telem method get_temperature boolean uint8_t 0 NUM_SERVO_CHANNELS int16_t'Null -singleton AP_ESC_Telem method get_motor_temperature boolean uint8_t 0 NUM_SERVO_CHANNELS int16_t'Null -singleton AP_ESC_Telem method get_current boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null -singleton AP_ESC_Telem method get_voltage boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null -singleton AP_ESC_Telem method get_consumption_mah boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null -singleton AP_ESC_Telem method get_usage_seconds boolean uint8_t 0 NUM_SERVO_CHANNELS uint32_t'Null -singleton AP_ESC_Telem method update_rpm void uint8_t 0 NUM_SERVO_CHANNELS uint16_t'skip_check float'skip_check -singleton AP_ESC_Telem method update_telem_data void uint8_t 0 NUM_SERVO_CHANNELS AP_ESC_Telem_Backend::TelemetryData uint16_t'skip_check -singleton AP_ESC_Telem method set_rpm_scale void uint8_t 0 NUM_SERVO_CHANNELS float'skip_check +singleton AP_ESC_Telem method get_rpm boolean uint8_t'skip_check float'Null +singleton AP_ESC_Telem method get_temperature boolean uint8_t'skip_check int16_t'Null +singleton AP_ESC_Telem method get_motor_temperature boolean uint8_t'skip_check int16_t'Null +singleton AP_ESC_Telem method get_current boolean uint8_t'skip_check float'Null +singleton AP_ESC_Telem method get_voltage boolean uint8_t'skip_check float'Null +singleton AP_ESC_Telem method get_consumption_mah boolean uint8_t'skip_check float'Null +singleton AP_ESC_Telem method get_usage_seconds boolean uint8_t'skip_check uint32_t'Null +singleton AP_ESC_Telem method update_rpm void uint8_t 0 ESC_TELEM_MAX_ESCS uint16_t'skip_check float'skip_check +singleton AP_ESC_Telem method update_telem_data void uint8_t 0 ESC_TELEM_MAX_ESCS AP_ESC_Telem_Backend::TelemetryData uint16_t'skip_check +singleton AP_ESC_Telem method set_rpm_scale void uint8_t 0 ESC_TELEM_MAX_ESCS float'skip_check singleton AP_ESC_Telem method get_last_telem_data_ms uint32_t uint8_t 0 ESC_TELEM_MAX_ESCS include AP_Param/AP_Param.h