AP_Scripting: ignore lua-language-server-errors

This commit is contained in:
Iampete1 2024-05-03 19:22:25 +01:00 committed by Andrew Tridgell
parent 07c854db57
commit 5bb5f442e1
77 changed files with 212 additions and 5 deletions

View File

@ -6,6 +6,10 @@ 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

View File

@ -5,6 +5,13 @@
assistance from Paul Riseborough, testing by Henry Wurzburg
]]--
-- luacheck: ignore 212 (Unused argument)
---@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
-- setup param block for aerobatics, reserving 35 params beginning with AERO_
local PARAM_TABLE_KEY = 70

View File

@ -4,6 +4,9 @@
See Tools/scripts/battery_fit.py for a tool to calculate the coefficients from a log
--]]
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: cast-local-type
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
local PARAM_TABLE_KEY = 14

View File

@ -5,6 +5,7 @@
-- 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)

View File

@ -1,4 +1,6 @@
-- idle_control.lua: a closed loop control throttle control while on ground idle (trad-heli)
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: need-check-nil
local PARAM_TABLE_KEY = 73
local PARAM_TABLE_PREFIX = 'IDLE_'

View File

@ -3,6 +3,8 @@
-- but also on the disarm to arm transition, it will load (if file exists) a file in the root named
-- missionH.txt, missionM.txt, or missionH.txt corresponding to the the Mission Reset switch position of High/Mid/Low
-- luacheck: only 0
---@diagnostic disable: need-check-nil
local mission_loaded = false
local rc_switch = rc:find_channel_for_option(24) --AUX FUNC sw for mission restart

View File

@ -24,12 +24,14 @@ The param SCR_VM_I_COUNT may need to be increased in some circumstances
Written by Stephen Dade (stephen_dade@hotmail.com)
]]--
---@diagnostic disable: cast-local-type
local PARAM_TABLE_KEY = 10
local PARAM_TABLE_PREFIX = "RCK_"
local port = serial:find_serial(0)
if not port or baud == 0 then
if not port then
gcs:send_text(0, "Rockblock: No Scripting Serial Port")
return
end

View File

@ -3,6 +3,8 @@
/1 /2 or /3 subdirectories of the scripts directory
--]]
-- luacheck: only 0
---@diagnostic disable: param-type-mismatch
local THIS_SCRIPT = "Script_Controller.lua"
local sel_ch = Parameter("SCR_USER6")

View File

@ -20,6 +20,9 @@
---------and set to -1 for unchanged, 0 (PitMode),1,2,3, or 4 for power level (1 lowest,4 maximum)
-- 3. Attach the UART's TX for the Serial port chosen above to the VTX's SmartAudio input
---@diagnostic disable: need-check-nil
-- init local variables
local startup_pwr = param:get('SCR_USER1')
local scripting_rc = rc:find_channel_for_option(300)

View File

@ -6,6 +6,9 @@
--]]
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: need-check-nil
---@diagnostic disable: missing-parameter
--[[
- TODO:

View File

@ -56,6 +56,9 @@
-- b. SIM_WIND_SPD <-- sets wind speed in m/s
--
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: cast-local-type
-- create and initialise parameters
local PARAM_TABLE_KEY = 86 -- parameter table key must be used by only one script on a particular flight controller
assert(param:add_table(PARAM_TABLE_KEY, "DR_", 9), 'could not add param table')

View File

@ -5,6 +5,8 @@
-- 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

View File

@ -1,6 +1,8 @@
-- leds_on_a_switch.lua: control led brightness with a radio switch
--
---@diagnostic disable: cast-local-type
-- constants
local AuxSwitchPos = {LOW=0, MIDDLE=1, HIGH=2}
local NTF_LED_BRIGHT = Parameter("NTF_LED_BRIGHT")

View File

@ -19,6 +19,10 @@
-- 10. interpolate between test_loc and prev_test_loc to find the lat, lon, alt (above sea-level) where alt-above-terrain is zero
-- 11. display the POI to the user
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: cast-local-type
---@diagnostic disable: missing-parameter
-- global definitions
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
local ALT_FRAME_ABSOLUTE = 0

View File

@ -1,6 +1,10 @@
--[[
example script to test lua socket API
--]]
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: undefined-field
---@diagnostic disable: need-check-nil
---@diagnostic disable: redundant-parameter
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}

View File

@ -2,6 +2,7 @@
support package place for quadplanes
--]]
-- luacheck: only 0
---@diagnostic disable: param-type-mismatch
local PARAM_TABLE_KEY = 9

View File

@ -5,6 +5,8 @@
for development of a custom solution
--]]
---@diagnostic disable: param-type-mismatch
local PARAM_TABLE_KEY = 12
local PARAM_TABLE_PREFIX = "PLND_"

View File

@ -4,6 +4,10 @@
See this post for details: https://discuss.ardupilot.org/t/ship-landing-support
--]]
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: cast-local-type
---@diagnostic disable: need-check-nil
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
local PARAM_TABLE_KEY = 7

View File

@ -2,6 +2,10 @@
parameter reversion utility. This helps with manual tuning
in-flight by giving a way to instantly revert parameters to the startup parameters
--]]
---@diagnostic disable: param-type-mismatch
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
local PARAM_TABLE_KEY = 31

View File

@ -18,6 +18,9 @@ See the accompanying rover-quiktune.md file for instructions on how to use
--]]
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: need-check-nil
-- global definitions
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}

View File

@ -10,6 +10,9 @@
-- Alternatively Mission Planner's Aux Function screen can be used in place of an actual RC switch
--
---@diagnostic disable: param-type-mismatch
-- global definitions
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
local PARAM_TABLE_KEY = 80

View File

@ -2,6 +2,9 @@
device driver for ANX CAN battery monitor
--]]
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: missing-parameter
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
local PARAM_TABLE_KEY = 45

View File

@ -2,6 +2,11 @@
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
-- Check Script uses a miniumum firmware version

View File

@ -2,6 +2,11 @@
EFI Scripting backend driver for Halo6000 generator
--]]
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: undefined-field
---@diagnostic disable: missing-parameter
---@diagnostic disable: need-check-nil
-- Check Script uses a miniumum firmware version
local SCRIPT_AP_VERSION = 4.3
local SCRIPT_NAME = "EFI: Halo6000 CAN"

View File

@ -12,6 +12,12 @@ CAN_D1_BITRATE 500000 (500 kbit/s)
--]]
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: need-check-nil
---@diagnostic disable: undefined-field
---@diagnostic disable: missing-parameter
-- Check Script uses a miniumum firmware version
local SCRIPT_AP_VERSION = 4.3
local SCRIPT_NAME = "EFI: Skypower CAN"

View File

@ -3,6 +3,9 @@
See http://www.svffi.com/en/
--]]
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: missing-parameter
local PARAM_TABLE_KEY = 42
local PARAM_TABLE_PREFIX = "EFI_SVF_"

View File

@ -2,6 +2,8 @@
driver for HobbyWing DataLink ESC telemetry
--]]
---@diagnostic disable: param-type-mismatch
local PARAM_TABLE_KEY = 44
local PARAM_TABLE_PREFIX = "ESC_HW_"

View File

@ -2,6 +2,9 @@
Driver for NoopLoop TOFSense-M CAN Version. Can be used as a 1-D RangeFidner or 3-D proximity sensor. Upto 3 CAN devices supported in this script although its easy to extend.
--]]
---@diagnostic disable: undefined-field
---@diagnostic disable: undefined-global
local update_rate_ms = 10 -- update rate (in ms) of the driver. 10ms was found to be appropriate
-- Global variables (DO NOT CHANGE)

View File

@ -2,6 +2,10 @@
Upto 3 CAN devices supported in this script although its easy to extend.
--]]
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: cast-local-type
---@diagnostic disable: undefined-global
local sensor_no = 1 -- Sensor ID. Upload a copy of this script to the flight controller with this variable changed if you would like to use multiple of these sensors as serial. Switching to CAN highly recommended in that case
local update_rate_ms = 10 -- update rate (in ms) of the driver. 10ms was found to be appropriate
local bytes_to_parse = 100 -- serial bytes to parse in one interation of lua script. Reduce this if script is not able to complete in time

View File

@ -71,6 +71,9 @@
--]]
---@diagnostic disable: cast-local-type
-- global definitions
local INIT_INTERVAL_MS = 3000 -- attempt to initialise the gimbal at this interval
local UPDATE_INTERVAL_MS = 1 -- update interval in millis

View File

@ -31,6 +31,9 @@
n+2 checksum XOR of byte3 to n+1 (inclusive)
--]]
---@diagnostic disable: cast-local-type
---@diagnostic disable: undefined-global
-- parameters
local PARAM_TABLE_KEY = 39
assert(param:add_table(PARAM_TABLE_KEY, "VIEP_", 6), "could not add param table")

View File

@ -1,5 +1,7 @@
-- switch between DCM and EKF3 on a switch
---@diagnostic disable: need-check-nil
local scripting_rc1 = rc:find_channel_for_option(300)
local EKF_TYPE = Parameter('AHRS_EKF_TYPE')

View File

@ -1,6 +1,8 @@
-- Control MiniCheetah motor driver over CAN
-- https://os.mbed.com/users/benkatz/code/HKC_MiniCheetah/docs/tip/CAN__com_8cpp_source.html
---@diagnostic disable: param-type-mismatch
-- Load CAN driver with a buffer size of 20
local driver = CAN:get_device(20)

View File

@ -4,6 +4,8 @@
Also need LOG_DISARMED set to 1 if running this while disarmed.
--]]
---@diagnostic disable: param-type-mismatch
local can_driver = CAN:get_device(25)
if not can_driver then

View File

@ -3,6 +3,10 @@
this can be used with a loopback cable between CAN1 and CAN2 to test CAN EFI Drivers
--]]
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: missing-parameter
local driver2 = CAN.get_device2(25)
if not driver2 then
gcs:send_text(0,string.format("EFISIM: Failed to load CAN driver"))

View File

@ -17,9 +17,14 @@ Caveats:
Written by Stephen Dade (stephen_dade@hotmail.com)
--]]
---@diagnostic disable: need-check-nil
---@diagnostic disable: cast-local-type
local port = serial:find_serial(0)
if not port or baud == 0 then
if not port then
gcs:send_text(0, "No Scripting Serial Port")
return
end

View File

@ -1,5 +1,8 @@
-- example of overriding RC inputs
---@diagnostic disable: need-check-nil
---@diagnostic disable: param-type-mismatch
local RC4 = rc:get_channel(4)
function update()

View File

@ -8,6 +8,9 @@
https://github.com/sparkfun/SparkFun_Particle_Sensor_SN-GCJA5_Arduino_Library
]]--
---@diagnostic disable: need-check-nil
---@diagnostic disable: undefined-global
-- search for a index without a file, this stops us overwriting from a previous run
local index = 0
local file_name

View File

@ -1,5 +1,9 @@
-- this script reads data from a serial port and dumps it to a file
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: need-check-nil
---@diagnostic disable: cast-local-type
local file_name = 'raw serial dump.txt'
local file_name_plain = 'serial dump.txt'
local baud_rate = 9600

View File

@ -3,7 +3,7 @@
-- find the serial first (0) scripting serial port instance
local port = serial:find_serial(0)
if not port or baud == 0 then
if not port then
gcs:send_text(0, "No Scripting Serial Port")
return
end

View File

@ -1,6 +1,8 @@
-- example script for using "set_home()"
-- sets the home location to the current vehicle location every 5 seconds
---@diagnostic disable: param-type-mismatch
function update ()
if ahrs:home_is_set() then

View File

@ -27,6 +27,8 @@
--
-- 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

View File

@ -10,6 +10,8 @@
-- 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

View File

@ -16,6 +16,9 @@
-- otherwise source2 (T265) or source3 (optical flow) will be used based on rangefinder distance
-- luacheck: only 0
---@diagnostic disable: need-check-nil
---@diagnostic disable: cast-local-type
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

View File

@ -2,6 +2,8 @@
-- for these examples BRD_PWM_COUNT must be 0
---@diagnostic disable: need-check-nil
-- load the analog pin, there are only 16 of these available
-- some are used by the main AP code, ie battery monitors
-- assign them like this in the init, not in the main loop

View File

@ -1,5 +1,7 @@
-- Lua Can Driver for Benewake CAN Rangefinder
---@diagnostic disable: undefined-global
-- User settable parameters
local update_rate_ms = 10 -- update rate (in ms) of the driver
local debug_enable = false -- true to enable debug messages

View File

@ -1,5 +1,7 @@
-- camera-test.lua. Tests triggering taking pictures at regular intervals
---@diagnostic disable: cast-local-type
-- global definitions
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
local TAKE_PIC_INTERVAL_MS = 5000 -- take pictures at this interval

View File

@ -2,6 +2,8 @@
script implementing pre-arm check that batteries are well balanced
--]]
---@diagnostic disable: param-type-mismatch
local MAX_CELL_DEVIATION = 0.2
local auth_id = arming:get_aux_auth_id()

View File

@ -6,6 +6,10 @@
-- b) slows the spiral and stops at the preset altitude
-- c) switches to RTL
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: cast-local-type
---@diagnostic disable: need-check-nil
-- constants
local copter_guided_mode_num = 4 -- Guided mode is 4 on copter
local copter_rtl_mode_num = 6 -- RTL is 6 on copter

View File

@ -12,6 +12,9 @@
-- "arg2" specifies the height (e.g. North-South) in meters
-- Once the vehicle completes the square or the timeout expires the mission will continue and the vehicle should RTL home
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: need-check-nil
local running = false
local last_id = -1 -- unique id used to detect if a new NAV_SCRIPT_TIME command has started
local start_loc -- vehicle's location when command starts (South-West corner of square)

View File

@ -18,6 +18,7 @@
Note: 17 is the index, 0x71 is the actual ID
--]]
-- luacheck: only 0
---@diagnostic disable: param-type-mismatch
local loop_time = 1000 -- number of ms between runs

View File

@ -8,6 +8,8 @@
-- If the aircraft drops below a predetermined minimum altitude, QLAND mode is engaged and the aircraft lands at its current position.
-- If the aircraft arrives within Q_FW_LND_APR_RAD of the return point before dropping below the minimum altitude, it should loiter down to the minimum altitude before switching to QRTL and landing.
---@diagnostic disable: cast-local-type
-- setup param block for VTOL failsafe params
local PARAM_TABLE_KEY = 77
local PARAM_TABLE_PREFIX = "VTFS_"

View File

@ -7,6 +7,8 @@
--]]
-- luacheck: only 0
---@diagnostic disable: need-check-nil
---@diagnostic disable: param-type-mismatch
UPDATE_RATE_HZ = 10

View File

@ -1,4 +1,7 @@
-- This script scans for devices on the i2c bus
---@diagnostic disable: need-check-nil
local address = 0
local found = 0

View File

@ -2,6 +2,9 @@
-- by Buzz 2020
-- luacheck: only 0
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: undefined-field
current_pos = nil
home = 0
a = {}

View File

@ -5,7 +5,7 @@
--The "mission1.txt" file containing the mission items should be placed in the directory above the "scripts" directory.
--In case of placing it on SD Card, mission1.txt file should be placed in the APM directory root.
---@diagnostic disable: param-type-mismatch
local function read_mission(file_name)

View File

@ -1,5 +1,7 @@
-- Example of saving the current mission to a file on the SD card on arming
---@diagnostic disable: need-check-nil
local function save_to_SD()
-- check if there is a mission to save

View File

@ -12,6 +12,8 @@
-- stage 9: point North and Down
-- stage 10: move angle to neutral position
---@diagnostic disable: cast-local-type
local stage = 0
local stage_time_ms = 5000
local stage_start_time_ms = 0

View File

@ -2,6 +2,8 @@
example script to test lua socket API
--]]
---@diagnostic disable: param-type-mismatch
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
PARAM_TABLE_KEY = 46

View File

@ -8,6 +8,9 @@
-- starting a doublet
-- Charlie Johnson, Oklahoma State University 2020
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: cast-local-type
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)
local DOUBLET_FUCNTION = 19 -- which control surface (SERVOx_FUNCTION) number will have a doublet happen

View File

@ -3,6 +3,9 @@
--
-- CAUTION: This script only works for Plane
---@diagnostic disable: cast-local-type
---@diagnostic disable: undefined-global
-- store the batt info as { instance, filtered, capacity, margin_mah }
-- instance: the battery monitor instance (zero indexed)
-- filtered: internal variable for current draw

View File

@ -1,5 +1,7 @@
-- support follow in GUIDED mode in plane
-- luacheck: only 0
---@diagnostic disable: cast-local-type
local PARAM_TABLE_KEY = 11
local PARAM_TABLE_PREFIX = "GFOLL_"

View File

@ -19,6 +19,8 @@
--
-- CAUTION: This script should only be used with ArduPilot Rover's firmware
---@diagnostic disable: cast-local-type
local FRAME_LEN = 80 -- frame length in mm
local FRAME_WIDTH = 150 -- frame width in mm

View File

@ -10,6 +10,9 @@
-- "RNGFND1_MIN_CM": 10,
-- "RNGFND1_MAX_CM": 5000,
---@diagnostic disable: cast-local-type
-- UPDATE_PERIOD_MS is the time between when a distance is set and
-- when it is read. There is a periodic task that copies the set distance to
-- the state structure that it is read from. If UPDATE_PERIOD_MS is too short this periodic

View File

@ -13,6 +13,8 @@ of a vehicle. Use this script AT YOUR OWN RISK.
LICENSE - GNU GPLv3 https://www.gnu.org/licenses/gpl-3.0.en.html
------------------------------------------------------------------------------]]
---@diagnostic disable: param-type-mismatch
local SCRIPT_NAME = 'MinFixType'
-------- MAVLINK/AUTOPILOT 'CONSTANTS' --------

View File

@ -12,6 +12,9 @@ of a vehicle. Use this script AT YOUR OWN RISK.
LICENSE - GNU GPLv3 https://www.gnu.org/licenses/gpl-3.0.en.html
------------------------------------------------------------------------------]]
---@diagnostic disable: cast-local-type
---@diagnostic disable: need-check-nil
local SCRIPT_NAME = 'SaveTurns'
-------- USER EDITABLE GLOBALS --------

View File

@ -28,6 +28,8 @@ https://www.youtube.com/watch?v=UdXGXjigxAo&t=7155s
Credit to @ktrussell for the idea and discussion!
------------------------------------------------------------------------------]]
---@diagnostic disable: param-type-mismatch
local SCRIPT_NAME = 'TerrainDetector'
local RUN_INTERVAL_MS = 25 -- needs to be pretty fast for good detection
local SBY_INTERVAL_MS = 500 -- slower interval when detection is disabled

View File

@ -1,5 +1,7 @@
-- Lua script to write and read from a serial
---@diagnostic disable: need-check-nil
local port = serial:find_serial(0)
port:begin(115200)

View File

@ -5,7 +5,7 @@
local flipflop = true
local K_AILERON = 4
local aileron_channel = SRV_Channels:find_channel(K_AILERON)
local aileron_channel = assert(SRV_Channels:find_channel(K_AILERON))
function update()
if flipflop then

View File

@ -8,6 +8,9 @@
-- 3) the vehilce will follow a circle in clockwise direction with increasing speed until ramp_up_time_s time has passed.
-- 4) switch out of and into the GUIDED mode any time to restart the trajectory from the start.
---@diagnostic disable: cast-local-type
---@diagnostic disable: redundant-parameter
-- Edit these variables
local rad_xy_m = 10.0 -- circle radius in xy plane in m
local target_speed_xy_mps = 5.0 -- maximum target speed in m/s

View File

@ -1,5 +1,7 @@
-- support takeoff with velocity matching for quadplanes
---@diagnostic disable: need-check-nil
local PARAM_TABLE_KEY = 35
local PARAM_TABLE_PREFIX = "SHIPV_"

View File

@ -13,6 +13,8 @@
-- SCR_USER3 is a bit field that controls driver logging.
--
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: cast-local-type
local UPDATE_PERIOD_MS = 50

View File

@ -1,6 +1,7 @@
--[[
test the load function for loading new code from strings
--]]
---@diagnostic disable: undefined-global
gcs:send_text(0,"Testing load() method")

View File

@ -8,6 +8,8 @@ a script to test handling of 32 bit micros timer wrap with BDShot
- BRD_SAFETY_DFLT must be 0
- BDShot must be enabled on outputs 9-12
--]]
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: cast-local-type
local PARAM_TABLE_KEY = 138
local PARAM_TABLE_PREFIX = "WRAP32_"

View File

@ -33,6 +33,9 @@
-- luacheck: ignore 421 (Shadowing a local variable)
-- luacheck: ignore 581 (Negation of a relational operator - operator can be flipped)
---@diagnostic disable: cast-local-type
---@diagnostic disable: undefined-global
gcs:send_text(6, "testing numbers and math lib")
local minint = math.mininteger

View File

@ -1,3 +1,6 @@
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: missing-parameter
local mavlink_msgs = require("mavlink/mavlink_msgs")
local msg_map = {}

View File

@ -29,6 +29,11 @@
-- luacheck: ignore 581 (Negation of a relational operator - operator can be flipped)
---@diagnostic disable: param-type-mismatch
---@diagnostic disable: missing-parameter
---@diagnostic disable: undefined-global
gcs:send_text(6, 'testing strings and string library')
local maxi, mini = math.maxinteger, math.mininteger