mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: Misc. small improvements.
Typo fix Removed unused variable
This commit is contained in:
parent
12de0d85dd
commit
2717470df1
|
@ -401,7 +401,7 @@ function adjust_gain(pname, value)
|
|||
local FF = params[ffname]
|
||||
if FF:get() > 0 then
|
||||
-- if we have any FF on an axis then we don't couple I to P,
|
||||
-- usually we want I = FF for a one sectond time constant for trim
|
||||
-- usually we want I = FF for a one second time constant for trim
|
||||
return
|
||||
end
|
||||
param_changed[iname] = true
|
||||
|
|
|
@ -93,7 +93,6 @@ local slew
|
|||
local slew_pwm
|
||||
function update()
|
||||
|
||||
local switch_pos = switch:get_aux_switch_pos()
|
||||
if switch:get_aux_switch_pos() == 2 then
|
||||
if not script_enabled then
|
||||
gcs:send_text(0, "Lua: Forward flight motor shutdown enabled")
|
||||
|
|
Loading…
Reference in New Issue