mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: added set_override method for scripting
useful for test code
This commit is contained in:
parent
19db542111
commit
e8115a99bc
|
@ -679,6 +679,10 @@ local RC_Channel_ud = {}
|
|||
---@return number
|
||||
function RC_Channel_ud:norm_input_ignore_trim() end
|
||||
|
||||
-- desc
|
||||
---@param PWM integer
|
||||
function RC_Channel_ud:set_override(PWM) end
|
||||
|
||||
-- desc
|
||||
---@return integer
|
||||
function RC_Channel_ud:get_aux_switch_pos() end
|
||||
|
|
|
@ -0,0 +1,14 @@
|
|||
-- example of overriding RC inputs
|
||||
|
||||
local RC4 = rc:get_channel(4)
|
||||
|
||||
function update()
|
||||
-- mirror RC1 onto RC4
|
||||
rc1_input = rc:get_pwm(1)
|
||||
RC4:set_override(rc1_input)
|
||||
return update, 10
|
||||
end
|
||||
|
||||
gcs:send_text(0, "RC_override example")
|
||||
|
||||
return update()
|
|
@ -258,6 +258,7 @@ singleton SRV_Channels method set_range void SRV_Channel::Aux_servo_function_t'e
|
|||
ap_object RC_Channel method norm_input 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
|
||||
|
||||
include RC_Channel/RC_Channel.h
|
||||
singleton RC_Channels alias rc
|
||||
|
|
Loading…
Reference in New Issue