diff --git a/libraries/AP_Scripting/applets/VTOL-quicktune.lua b/libraries/AP_Scripting/applets/VTOL-quicktune.lua index a04d5ed08ebfa..29c5c3ae2646e 100644 --- a/libraries/AP_Scripting/applets/VTOL-quicktune.lua +++ b/libraries/AP_Scripting/applets/VTOL-quicktune.lua @@ -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 diff --git a/libraries/AP_Scripting/applets/forward_flight_motor_shutdown.lua b/libraries/AP_Scripting/applets/forward_flight_motor_shutdown.lua index 9c2daa97cbaeb..202b3db30abb2 100644 --- a/libraries/AP_Scripting/applets/forward_flight_motor_shutdown.lua +++ b/libraries/AP_Scripting/applets/forward_flight_motor_shutdown.lua @@ -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")