Skip to content

Commit

Permalink
AP_Scripting: fix remaining luacheck issues
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 committed Dec 23, 2024
1 parent 169d6f6 commit aa2ec19
Show file tree
Hide file tree
Showing 28 changed files with 75 additions and 183 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,9 @@ cmd = 3: rolling circle, arg1 = yaw rate, arg2 = roll rate
cmd = 4: knife edge at any angle, arg1 = roll angle to hold, arg2 = duration
cmd = 5: pause, holding heading and alt to allow stabilization after a move, arg1 = duration in seconds
]]--
-- luacheck: only 0
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: need-check-nil
---@diagnostic disable: cast-local-type
---@diagnostic disable: undefined-global

DO_JUMP = 177
k_throttle = 70
Expand All @@ -29,13 +27,12 @@ local HGT_P = bind_add_param('HGT_P',1,1) -- height P gain
local HGT_I = bind_add_param("HGT_I",2,1) -- height I gain
local HGT_KE_BIAS = bind_add_param("KE_ADD",3,20) -- height knifeedge addition for pitch
local THR_PIT_FF = bind_add_param("PIT_FF",4,80) -- throttle FF from pitch
local SPD_P = bind_add_param("SPD_P",5,5) -- speed P gain
local SPD_I = bind_add_param("SPD_I",6,25) -- speed I gain
-- 5 was "SPD_P" speed P gain
-- 6 was "SPD_I" speed I gain
local TRIM_THROTTLE = Parameter("TRIM_THROTTLE")
local RLL2SRV_TCONST = Parameter("RLL2SRV_TCONST")
local PITCH_TCONST = Parameter("PTCH2SRV_TCONST")

local last_roll_err = 0.0
local last_id = 0
local initial_yaw_deg = 0
local wp_yaw_deg = 0
Expand Down Expand Up @@ -65,10 +62,10 @@ function bind_add_param2(name, idx, default_value)
assert(param:add_param(PARAM_TABLE_KEY2, idx, name, default_value), string.format('could not add param %s', name))
return Parameter(PARAM_TABLE_PREFIX2 .. name)
end
local TRICKS = nil
local TRIK_SEL_FN = nil
local TRIK_ACT_FN = nil
local TRIK_COUNT = nil
local TRICKS
local TRIK_SEL_FN
local TRIK_ACT_FN
local TRIK_COUNT

-- constrain a value between limits
function constrain(v, vmin, vmax)
Expand Down Expand Up @@ -131,7 +128,7 @@ end
--roll controller to keep wings level in earth frame. if arg is 0 then level is at only 0 deg, otherwise its at 180/-180 roll also for loops
function earth_frame_wings_level(arg)
local roll_deg = math.deg(ahrs:get_roll())
local roll_angle_error = 0.0
local roll_angle_error
if (roll_deg > 90 or roll_deg < -90) and arg ~= 0 then
roll_angle_error = 180 - roll_deg
else
Expand Down Expand Up @@ -166,7 +163,6 @@ local function PI_controller(kP,kI,iMax)
-- private fields as locals
local _kP = kP or 0.0
local _kI = kI or 0.0
local _kD = kD or 0.0
local _iMax = iMax
local _last_t = nil
local _I = 0
Expand Down Expand Up @@ -254,7 +250,6 @@ local function height_controller(kP_param,kI_param,KnifeEdge_param,Imax)
end

local height_PI = height_controller(HGT_P, HGT_I, HGT_KE_BIAS, 20.0)
local speed_PI = PI_controller(SPD_P:get(), SPD_I:get(), 100.0)

-- a controller to target a zero pitch angle and zero heading change, used in a roll
-- output is a body frame pitch rate, with convergence over time tconst in seconds
Expand Down Expand Up @@ -305,7 +300,6 @@ function do_axial_roll(arg1, arg2)
gcs:send_text(5, string.format("Starting %d Roll(s)", arg2))
end
local roll_rate = arg1
local pitch_deg = math.deg(ahrs:get_pitch())
local roll_deg = math.deg(ahrs:get_roll())

if trick_stage == 0 then
Expand Down Expand Up @@ -364,7 +358,7 @@ function do_loop(arg1, arg2)
local roll_deg = math.deg(ahrs:get_roll())
local vel = ahrs:get_velocity_NED():length()
local pitch_rate = arg1
local pitch_rate = pitch_rate * (1+ 2*((vel/target_vel)-1)) --increase/decrease rate based on velocity to round loop
pitch_rate = pitch_rate * (1+ 2*((vel/target_vel)-1)) --increase/decrease rate based on velocity to round loop
pitch_rate = constrain(pitch_rate,.5 * arg1, 3 * arg1)

if trick_stage == 0 then
Expand Down Expand Up @@ -400,7 +394,6 @@ function do_loop(arg1, arg2)
return
end
end
throttle = throttle_controller()
if trick_stage == 2 or trick_stage == 0 then
level_type = 0
else
Expand Down Expand Up @@ -430,9 +423,6 @@ function do_rolling_circle(arg1, arg2)
end
local yaw_rate_dps = arg1
local roll_rate_dps = arg2
local pitch_deg = math.deg(ahrs:get_pitch())
local roll_deg = math.deg(ahrs:get_roll())
local yaw_deg = math.deg(ahrs:get_yaw())
local now_ms = millis()
local dt = (now_ms - circle_last_ms):tofloat() * 0.001
circle_last_ms = now_ms
Expand Down Expand Up @@ -474,11 +464,10 @@ function do_knife_edge(arg1,arg2)
if not running then
running = true
height_PI.reset()
knife_edge_s = now
knife_edge_ms = now
gcs:send_text(5, string.format("Starting %d Knife Edge", arg1))
end
local i=0
if (now - knife_edge_s) < arg2 then
if (now - knife_edge_ms) < arg2 then
local roll_deg = math.deg(ahrs:get_roll())
local roll_angle_error = (arg1 - roll_deg)
if math.abs(roll_angle_error) > 180 then
Expand Down Expand Up @@ -506,17 +495,16 @@ function do_knife_edge(arg1,arg2)
end

-- fly level for a time..allows full altitude recovery after trick
function do_pause(arg1,arg2)
function do_pause(arg1,_)
-- arg1 is time of pause in sec, arg2 is unused
local now = millis():tofloat() * 0.001
if not running then
running = true
height_PI.reset()
knife_edge_s = now
knife_edge_ms = now
gcs:send_text(5, string.format("%d sec Pause", arg1))
end
local i=0
if (now - knife_edge_s) < arg1 then
if (now - knife_edge_ms) < arg1 then
roll_rate = earth_frame_wings_level(0)
target_pitch = height_PI.update(initial_height)
pitch_rate, yaw_rate = pitch_controller(target_pitch, wp_yaw_deg, PITCH_TCONST:get())
Expand All @@ -534,11 +522,7 @@ function do_pause(arg1,arg2)
end
end


local circle_yaw = 0
local circle_last_ms = 0

function do_knifedge_circle(arg1, arg2)
function do_knifedge_circle(arg1, _)
-- constant roll angle circle , arg1 yaw rate, positive to right, neg to left, arg2 is not used
if not running then
running = true
Expand All @@ -549,8 +533,6 @@ function do_knifedge_circle(arg1, arg2)
gcs:send_text(5, string.format("Staring KnifeEdge Circle"))
end
local yaw_rate_dps = arg1
local pitch_deg = math.deg(ahrs:get_pitch())
local yaw_deg = math.deg(ahrs:get_yaw())
local now_ms = millis()
local dt = (now_ms - circle_last_ms):tofloat() * 0.001
circle_last_ms = now_ms
Expand Down Expand Up @@ -621,7 +603,6 @@ function do_4point_roll(arg1, arg2)
height_PI.reset()
gcs:send_text(5, string.format("Starting 4pt Roll"))
end
local pitch_deg = math.deg(ahrs:get_pitch())
local roll_deg = math.deg(ahrs:get_roll())

if trick_stage == 0 then
Expand Down Expand Up @@ -844,7 +825,7 @@ function check_trick()
gcs:send_text(0, string.format("No trick selected"))
return 0
end
local id = TRICKS[selection].id:get()
id = TRICKS[selection].id:get()
if action == 1 then
gcs:send_text(5, string.format("Trick %u selected (%s)", id, name[id]))
return 0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: undefined-field
---@diagnostic disable: missing-parameter
---@diagnostic disable: cast-local-type
---@diagnostic disable: need-check-nil
---@diagnostic disable: undefined-global
---@diagnostic disable: inject-field
Expand Down Expand Up @@ -659,8 +658,8 @@ end
--[[
create a class that inherits from a base class
--]]
local function inheritsFrom(baseClass, _name)
local new_class = { name = _name }
local function inheritsFrom(baseClass, name_in)
local new_class = { name = name_in }
local class_mt = { __index = new_class }

function new_class:create()
Expand Down Expand Up @@ -1658,10 +1657,8 @@ end
--[[
perform a rudder over maneuver
--]]
function rudder_over(_direction, _min_speed)
function rudder_over(direction, min_speed)
local self = {}
local direction = _direction
local min_speed = _min_speed
local reached_speed = false
local kick_started = false
local pitch2_done = false
Expand Down Expand Up @@ -1822,12 +1819,10 @@ end
--[[
takeoff controller
--]]
function takeoff_controller(_distance, _thr_slew)
function takeoff_controller(distance, thr_slew)
local self = {}
local start_time = 0
local start_pos = nil
local thr_slew = _thr_slew
local distance = _distance
local all_done = false
local initial_yaw_deg = math.deg(ahrs:get_yaw())
local yaw_correction_tconst = 1.0
Expand Down Expand Up @@ -2245,11 +2240,9 @@ end
milliseconds means we lose accuracy over time. At 9 hours we have
an accuracy of about 1 millisecond
--]]
local function JitterCorrection(_max_lag_ms, _convergence_loops)
local function JitterCorrection(max_lag_ms, convergence_loops)
local self = {}

local max_lag_ms = _max_lag_ms
local convergence_loops = _convergence_loops
local link_offset_ms = 0
local min_sample_ms = 0
local initialised = false
Expand Down
5 changes: 1 addition & 4 deletions libraries/AP_Scripting/applets/Heli_IM_COL_Tune.lua
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,6 @@
-- this pot to adjust the sensitivity of the collective about the collective midstick. The 2nd Pot then controls
-- the value of the 50% point on the curve. This can be used to set the collective position to aid with hovering
-- at the midstick.
-- luacheck: only 0
---@diagnostic disable: cast-local-type

-- Tested and working as of 25th Aug 2020 (Copter Dev)

Expand Down Expand Up @@ -83,8 +81,7 @@ end

-- Get parameter value and perform checks to ensure successful
function get_im_val(param_name,disp)
local value = -1
value = param:get(param_name)
local value = param:get(param_name)

if value >= 0 then
if disp then
Expand Down
8 changes: 3 additions & 5 deletions libraries/AP_Scripting/applets/Script_Controller.lua
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@
a script to select other lua scripts using an auxillary switch from
/1 /2 or /3 subdirectories of the scripts directory
--]]
-- luacheck: only 0
---@diagnostic disable: param-type-mismatch


Expand Down Expand Up @@ -125,7 +124,7 @@ function remove_scripts(subdir)
return false
end
local ret = false
for k,v in ipairs(dlist) do
for _,v in ipairs(dlist) do
local suffix = v:sub(-4)
if compare_strings_ci(suffix,".LUA") and not compare_strings_ci(v,THIS_SCRIPT) then
if not file_exists(subdir .. "/" .. v) then
Expand All @@ -148,7 +147,7 @@ function copy_scripts(subdir)
end
local ret = false
local sdir = get_scripts_dir()
for k, v in ipairs(dlist) do
for _, v in ipairs(dlist) do
local suffix = v:sub(-4)
if compare_strings_ci(suffix,".LUA") and not compare_strings_ci(v,THIS_SCRIPT) then
local src = subdir .. "/" .. v
Expand Down Expand Up @@ -184,12 +183,11 @@ function mission_load(n)
local index = 0
local fail = false
while true and not fail do
local data = {}
local line = file:read()
if not line then
break
end
local ret, _, seq, curr, frame, cmd, p1, p2, p3, p4, x, y, z, autocont = string.find(line, "^(%d+)%s+(%d+)%s+(%d+)%s+(%d+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+(%d+)")
local ret, _, seq, _--[[ curr ]], frame, cmd, p1, p2, p3, p4, x, y, z, _--[[ autocont ]] = string.find(line, "^(%d+)%s+(%d+)%s+(%d+)%s+(%d+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+(%d+)")
if not ret then
fail = true
break
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,6 @@
-- Throttle thresholds also allow automatic enable and disable of stop motors
-- slew up and down times allow to configure how fast the motors are disabled and re-enabled

-- luacheck: only 0
---@diagnostic disable: cast-local-type


-- Config
Expand Down Expand Up @@ -39,12 +37,6 @@ if throttle_off_threshold < 100 then
assert((throttle_off_threshold < throttle_on_threshold) and (throttle_on_threshold < 100), "throttle on and off thresholds not configured correctly")
end

-- clear vars we don't need anymore
slew_down_time = nil
slew_up_time = nil
pwm_range = nil


for i = 1, #stop_motors do
-- Check for a valid motor number
assert(stop_motors[i] >= 1 and stop_motors[i] <= 12, string.format("Lua: motor %i not valid",stop_motors[i]))
Expand Down Expand Up @@ -84,7 +76,7 @@ assert(#stop_motor_chan == #stop_motors, "Lua: could not find all motors to stop
assert(#run_motor_fun > 0, "Lua: cannot stop all motors")

-- keep track of last time in a VTOL mode, this allows to delay switching after a transition/assist
local last_vtol_active = 0
local last_vtol_active = uint32_t(0)

-- current action
local script_enabled = false
Expand Down
4 changes: 1 addition & 3 deletions libraries/AP_Scripting/applets/net_webserver.lua
Original file line number Diff line number Diff line change
Expand Up @@ -435,13 +435,11 @@ end
--[[
client class for open connections
--]]
local function Client(_sock, _idx)
local function Client(sock, idx)
local self = {}

self.closed = false

local sock = _sock
local idx = _idx
local have_header = false
local header = ""
local header_lines = {}
Expand Down
5 changes: 0 additions & 5 deletions libraries/AP_Scripting/applets/plane_package_place.lua
Original file line number Diff line number Diff line change
@@ -1,16 +1,12 @@
--[[
support package place for quadplanes
--]]
-- luacheck: only 0
---@diagnostic disable: param-type-mismatch


local PARAM_TABLE_KEY = 9
local PARAM_TABLE_PREFIX = "PKG_"

local MODE_AUTO = 10

local NAV_TAKEOFF = 22
local NAV_VTOL_PAYLOAD_PLACE = 94

-- add a parameter and bind it to a variable
Expand All @@ -31,7 +27,6 @@ local Q_LAND_FINAL_ALT = Parameter("Q_LAND_FINAL_ALT")

local MAV_SEVERITY_INFO = 6
local MAV_SEVERITY_NOTICE = 5
local MAV_SEVERITY_EMERGENCY = 0

local RNG_ORIENT_DOWN = 25

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/applets/x-quad-cg-allocation.lua
Original file line number Diff line number Diff line change
Expand Up @@ -274,7 +274,7 @@ function protected_wrapper()
gcs:send_text(MAV_SEVERITY.EMERGENCY, "Internal Error: " .. err)
return protected_wrapper, 1000
end
if not (current_state == FSM_STATE.FINISHED) then
if current_state ~= FSM_STATE.FINISHED then
return protected_wrapper, 1000.0/LOOP_RATE_HZ
end
end
Expand Down
Loading

0 comments on commit aa2ec19

Please sign in to comment.