diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 0663624310588..8f8a5e8860fda 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -392,6 +392,10 @@ efi = {} ---@return EFI_State_ud function efi:get_state() end +-- get last update time in milliseconds +---@return uint32_t_ud +function efi:get_last_update_ms() end + -- desc ---@param instance integer ---@return AP_EFI_Backend_ud|nil @@ -2073,6 +2077,11 @@ function esc_telem:update_rpm(esc_index, rpm, error_rate) end ---@param scale_factor number -- factor function esc_telem:set_rpm_scale(esc_index, scale_factor) end +-- get the timestamp of last telemetry data for an ESC +---@param esc_index integer +---@return uint32_t_ud +function esc_telem:get_last_telem_data_ms(esc_index) end + -- desc optical_flow = {} diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 4da6fca9d8dfd..a889a46e6e48d 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -440,16 +440,17 @@ 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 singleton AP_Param rename param @@ -851,6 +852,7 @@ singleton AP_EFI depends (AP_EFI_SCRIPTING_ENABLED == 1) singleton AP_EFI rename efi singleton AP_EFI method get_backend AP_EFI_Backend uint8_t'skip_check singleton AP_EFI method get_state void EFI_State'Ref +singleton AP_EFI method get_last_update_ms uint32_t -- ----END EFI Library----