mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Scripting: add set_output_norm binding
This commit is contained in:
parent
a3b435e912
commit
94b2381399
@ -201,7 +201,7 @@ singleton SRV_Channels method set_output_pwm_chan_timeout void uint8_t 0 NUM_SER
|
||||
singleton SRV_Channels method set_output_scaled void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 int16_t INT16_MIN INT16_MAX
|
||||
singleton SRV_Channels method get_output_pwm boolean SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t'Null
|
||||
singleton SRV_Channels method get_output_scaled int16_t SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1
|
||||
|
||||
singleton SRV_Channels method set_output_norm void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 float -1 1
|
||||
|
||||
ap_object RC_Channel method norm_input float
|
||||
ap_object RC_Channel method get_aux_switch_pos uint8_t
|
||||
|
Loading…
Reference in New Issue
Block a user