AP_Scripting: added norm_input_dz binding

This commit is contained in:
Andrew Tridgell 2022-05-03 21:59:37 +10:00
parent 8aba79b8a0
commit 8320b90a01
2 changed files with 6 additions and 1 deletions

View File

@ -687,10 +687,14 @@ function RC_Channel_ud:set_override(PWM) end
---@return integer
function RC_Channel_ud:get_aux_switch_pos() end
-- desc
-- desc return input on a channel from -1 to 1, centered on the trim. Ignores the deadzone
---@return number
function RC_Channel_ud:norm_input() end
-- desc return input on a channel from -1 to 1, centered on the trim. Returns zero when within deadzone of the trim
---@return number
function RC_Channel_ud:norm_input_dz() end
-- desc
---@class motors

View File

@ -259,6 +259,7 @@ singleton SRV_Channels method set_angle void SRV_Channel::Aux_servo_function_t'e
singleton SRV_Channels method set_range void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t 0 UINT16_MAX
ap_object RC_Channel method norm_input float
ap_object RC_Channel method norm_input_dz float
ap_object RC_Channel method get_aux_switch_pos uint8_t
ap_object RC_Channel method norm_input_ignore_trim float
ap_object RC_Channel method set_override void uint16_t 0 2200 0'literal