AP_Scripting: added bindings for telemetry data for ESCs

allows more complete ESC protocol implementation in scripting
This commit is contained in:
Andrew Tridgell 2023-11-01 15:16:22 +11:00 committed by Randy Mackay
parent eab86de50f
commit 9366422b82
2 changed files with 44 additions and 1 deletions

View File

@ -1514,12 +1514,45 @@ function param:add_table(table_key, prefix, num_params) end
---@return boolean
function param:add_param(table_key, param_num, name, default_value) end
-- desc
---@class ESCTelemetryData_ud
local ESCTelemetryData_ud = {}
---@return ESCTelemetryData_ud
function ESCTelemetryData() end
-- set field
---@param value integer
function ESCTelemetryData_ud:motor_temp_cdeg(value) end
-- set field
---@param value number
function ESCTelemetryData_ud:consumption_mah(value) end
-- set field
---@param value number
function ESCTelemetryData_ud:current(value) end
-- set field
---@param value number
function ESCTelemetryData_ud:voltage(value) end
-- set field
---@param value integer
function ESCTelemetryData_ud:temperature_cdeg(value) end
-- desc
---@class esc_telem
esc_telem = {}
-- desc
-- update telemetry data for an ESC instance
---@param instance integer
---@param telemdata ESCTelemetryData_ud
---@param data_mask integer
function esc_telem:update_telem_data(instance, telemdata, data_mask) end
-- desc
---@param param1 integer
---@return uint32_t_ud|nil
function esc_telem:get_usage_seconds(instance) end

View File

@ -343,6 +343,15 @@ singleton AP_OpticalFlow method healthy boolean
singleton AP_OpticalFlow method quality uint8_t
include AP_ESC_Telem/AP_ESC_Telem.h
userdata AP_ESC_Telem_Backend::TelemetryData depends (HAL_WITH_ESC_TELEM == 1)
userdata AP_ESC_Telem_Backend::TelemetryData rename ESCTelemetryData
userdata AP_ESC_Telem_Backend::TelemetryData field temperature_cdeg int16_t'skip_check write
userdata AP_ESC_Telem_Backend::TelemetryData field voltage float'skip_check write
userdata AP_ESC_Telem_Backend::TelemetryData field current float'skip_check write
userdata AP_ESC_Telem_Backend::TelemetryData field consumption_mah float'skip_check write
userdata AP_ESC_Telem_Backend::TelemetryData field motor_temp_cdeg int16_t'skip_check write
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
@ -353,6 +362,7 @@ singleton AP_ESC_Telem method get_voltage boolean uint8_t 0 NUM_SERVO_CHANNELS f
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
include AP_Param/AP_Param.h