Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

LUA : added bindings for extended ESC telem #149

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
22 changes: 20 additions & 2 deletions libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -1245,9 +1245,27 @@ function esc_telem:update_rpm(esc_index, rpm, error_rate) end
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
---@param instance integer (0 is first motor)
---@return uint32_t_ud
function esc_telem:get_last_telem_data_ms(esc_index) end
function esc_telem:get_last_telem_data_ms(instance) end

-- get the input_duty of last telemetry data for an ESC
---@param instance integer (0 is first motor)
---@param input_duty integer
---@return boolean
function esc_telem:get_input_duty(instance, input_duty) end

-- get the output_duty of last telemetry data for an ESC
---@param instance integer (0 is first motor)
---@param output_duty integer
---@return boolean
function esc_telem:get_output_duty(instance, output_duty) end

-- get the status flags of the last telemetry data for an ESC
---@param instance integer (0 is first motor)
---@param flags integer
---@return boolean
function esc_telem:get_flags(instance, flags) end

-- desc
---@class optical_flow
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -315,6 +315,9 @@ singleton AP_ESC_Telem method get_usage_seconds boolean uint8_t 0 NUM_SERVO_CHAN
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 set_rpm_scale void uint8_t 0 NUM_SERVO_CHANNELS float'skip_check
singleton AP_ESC_Telem method get_last_telem_data_ms uint32_t uint8_t 0 NUM_SERVO_CHANNELS
singleton AP_ESC_Telem method get_input_duty boolean uint8_t 0 NUM_SERVO_CHANNELS uint8_t'Null
singleton AP_ESC_Telem method get_output_duty boolean uint8_t 0 NUM_SERVO_CHANNELS uint8_t'Null
singleton AP_ESC_Telem method get_flags boolean uint8_t 0 NUM_SERVO_CHANNELS uint32_t'Null

include AP_Param/AP_Param.h
singleton AP_Param rename param
Expand Down
Loading