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 authored and tpwrules committed Dec 24, 2024
1 parent 95d4dc1 commit 0dbbb87
Show file tree
Hide file tree
Showing 26 changed files with 57 additions and 144 deletions.
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
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
15 changes: 3 additions & 12 deletions libraries/AP_Scripting/drivers/EFI_HFE.lua
Original file line number Diff line number Diff line change
@@ -1,9 +1,7 @@
--[[
EFI Scripting backend driver for HFE based on HFEDCN0191 Rev E
--]]
-- luacheck: only 0
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: redundant-parameter
---@diagnostic disable: undefined-field
---@diagnostic disable: missing-parameter
---@diagnostic disable: need-check-nil
Expand Down Expand Up @@ -98,7 +96,7 @@ local now_s = get_time_sec()
--[[
EFI Engine Object
--]]
local function engine_control(_driver)
local function engine_control(driver)
local self = {}

-- Build up the EFI_State that is passed into the EFI Scripting backend
Expand All @@ -109,7 +107,6 @@ local function engine_control(_driver)
local rpm = 0
local air_pressure = 0
local map_ratio = 0.0
local driver = _driver
local last_rpm_t = get_time_sec()
local last_state_update_t = get_time_sec()
local throttle_pos = 0.0
Expand All @@ -123,12 +120,6 @@ local function engine_control(_driver)
local injector_duty = 0.0
local ignition_angle = 0.0

-- Generator Data Structure
local gen = {}
gen.amps = 0.0
gen.rpm = 0.0
gen.batt_current = 0.0

-- Temperature Data Structure
local temps = {}
temps.egt = 0.0 -- Engine Gas Temperature
Expand Down Expand Up @@ -275,9 +266,9 @@ local function engine_control(_driver)

-- return the instance
return self
end -- end function engine_control(_driver)
end -- end function engine_control(driver)

local engine1 = engine_control(driver1, 1)
local engine1 = engine_control(driver1)

function update()
now_s = get_time_sec()
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/drivers/EFI_Halo6000.lua
Original file line number Diff line number Diff line change
Expand Up @@ -338,7 +338,7 @@ local function engine_control()

-- return the instance
return self
end -- end function engine_control(_driver)
end -- end function engine_control()

local engine1 = engine_control()

Expand Down
3 changes: 1 addition & 2 deletions libraries/AP_Scripting/drivers/EFI_SkyPower.lua
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,7 @@ end
--[[
EFI Engine Object
--]]
local function engine_control(_driver)
local function engine_control(driver)
local self = {}

-- Build up the EFI_State that is passed into the EFI Scripting backend
Expand All @@ -263,7 +263,6 @@ local function engine_control(_driver)
local fuel_consumption_lph = 0
local fuel_total_l = 0
local last_fuel_s = 0
local driver = _driver
local last_rpm_t = get_time_sec()
local last_state_update_t = get_time_sec()
local last_thr_update = get_time_sec()
Expand Down
6 changes: 1 addition & 5 deletions libraries/AP_Scripting/examples/LED_matrix_image.lua
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@
Script to control LED strips based on the roll of the aircraft. This is an example to demonstrate
the LED interface for WS2812 LEDs
--]]
-- luacheck: only 0

--[[
for this demo we will use a single strip with 30 LEDs
Expand Down Expand Up @@ -77,7 +76,7 @@ id[7][6] = 28
id[7][7] = 27

-- ArduPilot logo 7 x 48, RGB
image = {}
local image = {}
image[1] = {}
image[2] = {}
image[3] = {}
Expand Down Expand Up @@ -502,9 +501,6 @@ local function display_image(image_in,offset_in,brightness_in)
brightness = brightness_in
end

local i
local j

for i = 1, 48 do
local x_index = i + im_offset
if x_index >= 1 and x_index <= matrix_x then
Expand Down
7 changes: 1 addition & 6 deletions libraries/AP_Scripting/examples/LED_matrix_text.lua
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@
Script to control LED strips based on the roll of the aircraft. This is an example to demonstrate
the LED interface for WS2812 LEDs
--]]
-- luacheck: only 0

--[[
for this demo we will use a single strip with 30 LEDs
Expand Down Expand Up @@ -77,7 +76,7 @@ id[7][6] = 28
id[7][7] = 27

-- https://github.com/noopkat/oled-font-5x7/blob/master/oled-font-5x7.js
font = {}
local font = {}
font[' '] = {0x00, 0x00, 0x00, 0x00, 0x00} -- // space
font['!'] = {0x00, 0x00, 0x5F, 0x00, 0x00} -- // !
font['"'] = {0x00, 0x07, 0x00, 0x07, 0x00} -- // "
Expand Down Expand Up @@ -205,9 +204,6 @@ if char_offset < 1 - 5 then
return
end

local i
local j

for i = 1, 5 do
local x_index = i + char_offset
if x_index >= 1 and x_index <= matrix_x then
Expand All @@ -225,7 +221,6 @@ end

local function display_string(string,r,g,b,offset_in)
local str_offset = 0
local i
for i = 1, string:len() do
display_char(string:sub(i,i),r,g,b,str_offset + offset_in)
str_offset = str_offset + 6
Expand Down
5 changes: 2 additions & 3 deletions libraries/AP_Scripting/examples/LED_roll.lua
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@
Script to control LED strips based on the roll of the aircraft. This is an example to demonstrate
the LED interface for WS2812 LEDs
--]]
-- luacheck: only 0


--[[
Expand Down Expand Up @@ -57,7 +56,7 @@ local rainbow = {
--[[
Function to set a LED to a color on a classic rainbow spectrum, with v=0 giving red
--]]
function set_Rainbow(chan, led, v)
local function set_Rainbow(channel, led, v)
local num_rows = #rainbow
local row = math.floor(constrain(v * (num_rows-1)+1, 1, num_rows-1))
local v0 = (row-1) / (num_rows-1)
Expand All @@ -66,7 +65,7 @@ function set_Rainbow(chan, led, v)
r = math.floor(rainbow[row][1] + p * (rainbow[row+1][1] - rainbow[row][1]))
g = math.floor(rainbow[row][2] + p * (rainbow[row+1][2] - rainbow[row][2]))
b = math.floor(rainbow[row][3] + p * (rainbow[row+1][3] - rainbow[row][3]))
serialLED:set_RGB(chan, led, r, g, b)
serialLED:set_RGB(channel, led, r, g, b)
end

--[[
Expand Down
5 changes: 2 additions & 3 deletions libraries/AP_Scripting/examples/NMEA-decode.lua
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
-- Script decodes, checks and prints NMEA messages
-- luacheck: only 0

-- find the serial first (0) scripting serial port instance
local port = serial:find_serial(0)
Expand Down Expand Up @@ -40,8 +39,8 @@ local function decode_NMEA(byte)
-- test the checksum
string_complete = true
return checksum == tonumber(term[term_number],16)
else
-- we could further decode the message data here

-- else -- we could further decode the message data here
end

if char == '*' then
Expand Down
10 changes: 2 additions & 8 deletions libraries/AP_Scripting/examples/ahrs-source-gps-optflow.lua
Original file line number Diff line number Diff line change
Expand Up @@ -26,13 +26,10 @@
-- SCR_USER4 holds the threshold for optical flow innovations (about 0.15 is a good choice)
--
-- When the 2nd auxiliary switch (300/Scripting1) is pulled high automatic source selection uses these thresholds:
-- luacheck: only 0
---@diagnostic disable: cast-local-type
---@diagnostic disable: need-check-nil

local rangefinder_rotation = 25 -- check downward (25) facing lidar
local source_prev = 0 -- previous source, defaults to primary source
local sw_source_prev = -1 -- previous source switch position
local sw_auto_pos_prev = -1 -- previous auto source switch position
local auto_switch = false -- true when auto switching between sources is active
local gps_usable_accuracy = 1.0 -- GPS is usable if speed accuracy is at or below this value
Expand Down Expand Up @@ -115,12 +112,9 @@ function update()

-- get opticalflow innovations from ahrs (only x and y values are valid)
local opticalflow_over_threshold = true
local opticalflow_xy_innov = 0
local opticalflow_innov = Vector3f()
local opticalflow_var = Vector3f()
opticalflow_innov, opticalflow_var = ahrs:get_vel_innovations_and_variances_for_source(5)
local opticalflow_innov = ahrs:get_vel_innovations_and_variances_for_source(5)
if (opticalflow_innov) then
opticalflow_xy_innov = math.sqrt(opticalflow_innov:x() * opticalflow_innov:x() + opticalflow_innov:y() * opticalflow_innov:y())
local opticalflow_xy_innov = math.sqrt(opticalflow_innov:x() * opticalflow_innov:x() + opticalflow_innov:y() * opticalflow_innov:y())
opticalflow_over_threshold = (opticalflow_xy_innov == 0.0) or (opticalflow_xy_innov > opticalflow_innov_thresh)
end

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,15 +9,11 @@
-- SCR_USER3 holds the threshold for GPS innovations (around 0.3 is a good choice)
-- if GPS speed accuracy <= SCR_USER2 and GPS innovations <= SRC_USER3 then the GPS (primary source set) will be used
-- otherwise wheel encoders (secondary source set) will be used
-- luacheck: only 0
---@diagnostic disable: cast-local-type
---@diagnostic disable: need-check-nil

local source_prev = 0 -- previous source, defaults to primary source
local sw_source_prev = -1 -- previous source switch position
local sw_auto_pos_prev = -1 -- previous auto source switch position
local auto_switch = false -- true when auto switching between sources is active
local gps_usable_accuracy = 1.0 -- GPS is usable if speed accuracy is at or below this value
local vote_counter_max = 20 -- when a vote counter reaches this number (i.e. 2sec) source may be switched
local gps_vs_nongps_vote = 0 -- vote counter for GPS vs NonGPS (-20 = GPS, +20 = NonGPS)

Expand Down Expand Up @@ -67,9 +63,7 @@ function update()
local gps_over_threshold = (gps_speed_accuracy == nil) or (gps:speed_accuracy(gps:primary_sensor()) > gps_speedaccuracy_thresh)

-- get GPS innovations from ahrs
local gps_innov = Vector3f()
local gps_var = Vector3f()
gps_innov, gps_var = ahrs:get_vel_innovations_and_variances_for_source(3)
local gps_innov = ahrs:get_vel_innovations_and_variances_for_source(3)
local gps_innov_over_threshold = (gps_innov == nil) or (gps_innov:z() == 0.0) or (math.abs(gps_innov:z()) > gps_innov_thresh)

-- automatic selection logic --
Expand Down
Loading

0 comments on commit 0dbbb87

Please sign in to comment.