mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: prevent "Starting XXX tune" happening multiple times
when filter setting disabled
This commit is contained in:
parent
c173b3f186
commit
6a8130e8ba
|
@ -288,6 +288,7 @@ end
|
|||
-- setup filter frequencies
|
||||
function setup_filters(axis)
|
||||
if QUIK_AUTO_FILTER:get() <= 0 then
|
||||
filters_done[axis] = true
|
||||
return
|
||||
end
|
||||
local fltd = axis .. "_FLTD"
|
||||
|
|
Loading…
Reference in New Issue