Browse Source

AP_Scripting: added update_rpm() scripting binding

apm_2208
Andrew Tridgell 3 years ago
parent
commit
1995dbf47c
  1. 6
      libraries/AP_Scripting/docs/docs.lua
  2. 1
      libraries/AP_Scripting/generator/description/bindings.desc

6
libraries/AP_Scripting/docs/docs.lua

@ -1113,6 +1113,12 @@ function esc_telem:get_temperature(instance) end @@ -1113,6 +1113,12 @@ function esc_telem:get_temperature(instance) end
---@return number|nil
function esc_telem:get_rpm(instance) end
-- update RPM for an ESC
---@param param1 integer -- ESC number
---@param param2 integer -- RPM
---@param param3 number -- error rate
function esc_telem:update_rpm(esc_index, rpm, error_rate) end
-- desc
---@class optical_flow

1
libraries/AP_Scripting/generator/description/bindings.desc

@ -309,6 +309,7 @@ singleton AP_ESC_Telem method get_current boolean uint8_t 0 NUM_SERVO_CHANNELS f @@ -309,6 +309,7 @@ singleton AP_ESC_Telem method get_current boolean uint8_t 0 NUM_SERVO_CHANNELS f
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
include AP_Param/AP_Param.h
singleton AP_Param rename param

Loading…
Cancel
Save