mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: added get_output_pwm_chan
This commit is contained in:
parent
d6b38f4009
commit
fb3a50096d
|
@ -2550,6 +2550,11 @@ function SRV_Channels:set_output_pwm_chan_timeout(chan, pwm, timeout_ms) end
|
||||||
---@param pwm integer -- pwm value
|
---@param pwm integer -- pwm value
|
||||||
function SRV_Channels:set_output_pwm_chan(chan, pwm) end
|
function SRV_Channels:set_output_pwm_chan(chan, pwm) end
|
||||||
|
|
||||||
|
-- Get the pwm for a given servo output channel
|
||||||
|
---@param chan integer -- servo channel number (zero indexed)
|
||||||
|
---@return integer|nil -- output pwm if available
|
||||||
|
function SRV_Channels:get_output_pwm_chan(chan) end
|
||||||
|
|
||||||
-- Set the pwm for a given servo output function
|
-- Set the pwm for a given servo output function
|
||||||
---@param function_num integer -- servo function number (See SERVOx_FUNCTION parameters)
|
---@param function_num integer -- servo function number (See SERVOx_FUNCTION parameters)
|
||||||
---@param pwm integer -- pwm value
|
---@param pwm integer -- pwm value
|
||||||
|
|
|
@ -377,6 +377,7 @@ singleton SRV_Channels method set_output_pwm_chan_timeout void uint8_t 0 NUM_SER
|
||||||
singleton SRV_Channels method set_output_pwm_chan_timeout depends (!defined(HAL_BUILD_AP_PERIPH))
|
singleton SRV_Channels method set_output_pwm_chan_timeout depends (!defined(HAL_BUILD_AP_PERIPH))
|
||||||
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 float'skip_check
|
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 float'skip_check
|
||||||
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_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_pwm_chan boolean uint8_t 0 NUM_SERVO_CHANNELS-1 uint16_t'Null
|
||||||
singleton SRV_Channels method get_output_scaled float SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1
|
singleton SRV_Channels method get_output_scaled float 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
|
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
|
||||||
singleton SRV_Channels method set_angle void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t'skip_check
|
singleton SRV_Channels method set_angle void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t'skip_check
|
||||||
|
|
Loading…
Reference in New Issue