Skip to content

Commit

Permalink
AP_Scripting: fix some more of the easy luacheck warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and peterbarker committed Dec 13, 2023
1 parent d5cc1d4 commit 452f998
Show file tree
Hide file tree
Showing 6 changed files with 5 additions and 17 deletions.
4 changes: 0 additions & 4 deletions libraries/AP_Scripting/applets/runcam_on_arm.lua
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
-- presses, I want the script to be responsive and start recording as
-- soon as the vehicle arms, so there I use a shorter delay.

-- luacheck: only 0


-- constants
Expand All @@ -46,7 +45,6 @@ function update()
local is_armed = arming:is_armed()

local delay = DELAY_SHORT

if is_armed ~= prev_armed then
-- a state transition has occurred
if is_armed then
Expand All @@ -57,8 +55,6 @@ function update()
rc:run_aux_function(RC_OPTION.RunCamControl, AuxSwitchPos.LOW)
end
delay = DELAY_LONG
else
delay = DELAY_SHORT
end

prev_armed = is_armed
Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_Scripting/examples/OOP_example.lua
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
-- this is an example of how to do object oriented programming in Lua
-- luacheck: only 0

function constrain(v, minv, maxv)
-- constrain a value between two limits
Expand All @@ -25,7 +24,6 @@ local function PIFF(kFF,kP,kI,iMax)
local _kFF = kFF
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 _log_data = {}
Expand Down
6 changes: 1 addition & 5 deletions libraries/AP_Scripting/examples/plane-doublets.lua
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
-- It is suggested to allow the aircraft to trim for straight, level, unaccelerated flight (SLUF) in FBWB mode before
-- starting a doublet
-- Charlie Johnson, Oklahoma State University 2020
-- luacheck: only 0

local DOUBLET_ACTION_CHANNEL = 6 -- RCIN channel to start a doublet when high (>1700)
local DOUBLET_CHOICE_CHANNEL = 7 -- RCIN channel to choose elevator (low) or rudder (high)
Expand All @@ -19,8 +18,6 @@ local DOUBLET_TIME = 500 -- period of doublet signal in ms
-- flight mode numbers for plane https://mavlink.io/en/messages/ardupilotmega.html
local MODE_MANUAL = 0
local MODE_FBWA = 5
local MODE_FBWB = 6
local MODE_RTL = 11
local K_AILERON = 4
local K_ELEVATOR = 19
local K_THROTTLE = 70
Expand All @@ -30,7 +27,6 @@ local K_RUDDER = 21
local start_time = -1
local end_time = -1
local now = -1
local desired_mode = -1

-- store information about the doublet channel
local doublet_srv_chan = SRV_Channels:find_channel(DOUBLET_FUCNTION)
Expand Down Expand Up @@ -65,7 +61,7 @@ function doublet()
pre_doublet_mode = vehicle:get_mode()
-- are we doing a doublet on elevator or rudder? set the other controls to trim
local doublet_choice_pwm = rc:get_pwm(DOUBLET_CHOICE_CHANNEL)
local trim_funcs = {}
local trim_funcs
local pre_doublet_elevator = SRV_Channels:get_output_pwm(K_ELEVATOR)
if doublet_choice_pwm < 1500 then
-- doublet on elevator
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/examples/protected_call.lua
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
-- this shows how to protect against faults in your scripts
-- you can wrap your update() call (or any other call) in a pcall()
-- which catches errors, allowing you to take an appropriate action
-- luacheck: only 0


-- example main loop function
Expand All @@ -12,6 +11,7 @@ function update()
-- deliberately make a bad call to cause a fault, asking for the 6th GPS status
-- as this is done inside a pcall() the error will be caught instead of stopping the script
local status = gps:status(5)
gcs:send_text(0, "GPS status: " .. tostring(status))
end
end

Expand Down
3 changes: 1 addition & 2 deletions libraries/AP_Scripting/examples/quadruped.lua
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
-- Output12: back right tibia (shin) servo
--
-- CAUTION: This script should only be used with ArduPilot Rover's firmware
-- luacheck: only 0


local FRAME_LEN = 80 -- frame length in mm
Expand Down Expand Up @@ -183,7 +182,7 @@ end
-- a) body rotations: body_rot_x, body_rot_y, body_rot_z
-- b) body position: body_pos_x, body_pos_y, body_pos_z
-- c) offset of the center of body
function body_forward_kinematics(X, Y, Z, Xdist, Ydist, Zrot)
function body_forward_kinematics(X, Y, _, Xdist, Ydist, Zrot)
local totaldist_x = X + Xdist + body_pos_x
local totaldist_y = Y + Ydist + body_pos_y
local distBodyCenterFeet = math.sqrt(totaldist_x^2 + totaldist_y^2)
Expand Down
5 changes: 2 additions & 3 deletions libraries/AP_Scripting/examples/test_load.lua
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@ gcs:send_text(0,"Testing load() method")
-- a function written as a string. This could come from a file
-- or any other source (eg. mavlink)
-- Note that the [[ xxx ]] syntax is just a multi-line string
-- luacheck: only 0

local func_str = [[
function TestFunc(x,y)
Expand All @@ -23,9 +22,9 @@ function test_load()
return
end
-- run the code within a protected call to catch any errors
local success, err = pcall(f)
local success, err2 = pcall(f)
if not success then
gcs:send_text(0, string.format("Failed to load TestFunc: %s", err))
gcs:send_text(0, string.format("Failed to load TestFunc: %s", err2))
return
end

Expand Down

0 comments on commit 452f998

Please sign in to comment.