mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Scripting: change VTOL-quicktune to use cached aux
makes it possible to use aux buttons in MissionPlanner
This commit is contained in:
parent
8628fd998f
commit
068d1d5413
@ -300,9 +300,6 @@ end
|
|||||||
reset_axes_done()
|
reset_axes_done()
|
||||||
get_all_params()
|
get_all_params()
|
||||||
|
|
||||||
-- 3 position switch
|
|
||||||
local quick_switch = nil
|
|
||||||
|
|
||||||
function axis_enabled(axis)
|
function axis_enabled(axis)
|
||||||
local axes = QUIK_AXES:get()
|
local axes = QUIK_AXES:get()
|
||||||
for i = 1, #axis_names do
|
for i = 1, #axis_names do
|
||||||
@ -455,18 +452,14 @@ end
|
|||||||
-- main update function
|
-- main update function
|
||||||
local last_warning = get_time()
|
local last_warning = get_time()
|
||||||
function update()
|
function update()
|
||||||
if quick_switch == nil then
|
|
||||||
quick_switch = rc:find_channel_for_option(math.floor(QUIK_RC_FUNC:get()))
|
|
||||||
end
|
|
||||||
if quick_switch == nil or QUIK_ENABLE:get() < 1 then
|
|
||||||
return
|
|
||||||
end
|
|
||||||
|
|
||||||
if have_pilot_input() then
|
if have_pilot_input() then
|
||||||
last_pilot_input = get_time()
|
last_pilot_input = get_time()
|
||||||
end
|
end
|
||||||
|
|
||||||
local sw_pos = quick_switch:get_aux_switch_pos()
|
local sw_pos = rc:get_aux_cached(QUIK_RC_FUNC:get())
|
||||||
|
if not sw_pos then
|
||||||
|
return
|
||||||
|
end
|
||||||
if sw_pos == 1 and (not arming:is_armed() or not vehicle:get_likely_flying()) and get_time() > last_warning + 5 then
|
if sw_pos == 1 and (not arming:is_armed() or not vehicle:get_likely_flying()) and get_time() > last_warning + 5 then
|
||||||
gcs:send_text(MAV_SEVERITY_EMERGENCY, string.format("Tuning: Must be flying to tune"))
|
gcs:send_text(MAV_SEVERITY_EMERGENCY, string.format("Tuning: Must be flying to tune"))
|
||||||
last_warning = get_time()
|
last_warning = get_time()
|
||||||
|
Loading…
Reference in New Issue
Block a user