Skip to content

Commit

Permalink
AP_Scripting: added bindings for telemetry data for ESCs
Browse files Browse the repository at this point in the history
allows more complete ESC protocol implementation in scripting
  • Loading branch information
tridge committed Nov 1, 2023
1 parent 69beea6 commit 2c1ea3d
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 1 deletion.
13 changes: 12 additions & 1 deletion libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -1737,8 +1737,19 @@ function param:add_param(table_key, param_num, name, default_value) end
---@class esc_telem
esc_telem = {}

-- desc
-- set RPM scaling factor for an ESC instance
---@param instance integer
---@param rpm_scale number
function esc_telem:set_rpm_scale(instance, rpm_scale) end

-- 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

Expand Down
10 changes: 10 additions & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -380,6 +380,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
Expand All @@ -390,6 +399,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
Expand Down

0 comments on commit 2c1ea3d

Please sign in to comment.