From 2717470df12af9947c111335b1f2b9a1c110b95f Mon Sep 17 00:00:00 2001 From: George Zogopoulos Date: Thu, 20 Jun 2024 21:08:12 +0200 Subject: [PATCH] AP_Scripting: Misc. small improvements. Typo fix Removed unused variable --- libraries/AP_Scripting/applets/VTOL-quicktune.lua | 2 +- .../AP_Scripting/applets/forward_flight_motor_shutdown.lua | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_Scripting/applets/VTOL-quicktune.lua b/libraries/AP_Scripting/applets/VTOL-quicktune.lua index a04d5ed08e..29c5c3ae26 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 9c2daa97cb..202b3db30a 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")