mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Scripting: add do_aux_function binding and example
This commit is contained in:
parent
acfdf6a38f
commit
15362484bc
@ -2,6 +2,7 @@
|
||||
|
||||
local scripting_rc_1 = rc:find_channel_for_option(300)
|
||||
local scripting_rc_2 = rc:find_channel_for_option(301)
|
||||
local flip_flop = 0
|
||||
|
||||
function update()
|
||||
pwm1 = rc:get_pwm(1)
|
||||
@ -27,6 +28,17 @@ function update()
|
||||
end
|
||||
end
|
||||
|
||||
-- we can also call functions that are available to RC switches
|
||||
-- 28 is Relay one
|
||||
rc:run_aux_function(28, flip_flop)
|
||||
|
||||
if (flip_flop == 0) then
|
||||
flip_flop = 2 -- switch high
|
||||
else
|
||||
flip_flop = 0 -- switch low
|
||||
end
|
||||
|
||||
|
||||
return update, 1000 -- reschedules the loop
|
||||
end
|
||||
|
||||
|
@ -224,8 +224,10 @@ ap_object RC_Channel method norm_input_ignore_trim float
|
||||
|
||||
include RC_Channel/RC_Channel.h
|
||||
singleton RC_Channels alias rc
|
||||
singleton RC_Channels scheduler-semaphore
|
||||
singleton RC_Channels method get_pwm boolean uint8_t 1 NUM_RC_CHANNELS uint16_t'Null
|
||||
singleton RC_Channels method find_channel_for_option RC_Channel RC_Channel::AUX_FUNC'enum 0 UINT16_MAX
|
||||
singleton RC_Channels method run_aux_function boolean RC_Channel::AUX_FUNC'enum 0 UINT16_MAX RC_Channel::AuxSwitchPos'enum RC_Channel::AuxSwitchPos::LOW RC_Channel::AuxSwitchPos::HIGH RC_Channel::AuxFuncTriggerSource::SCRIPTING'literal
|
||||
|
||||
include AP_SerialManager/AP_SerialManager.h
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user