AP_Scripting: examples: ignore luacheck warnings

This commit is contained in:
Iampete1 2023-02-14 02:45:19 +00:00 committed by Andrew Tridgell
parent 3deaece3b7
commit 03167d41db
32 changed files with 41 additions and 1 deletions

View File

@ -2,6 +2,7 @@
Script to control LED strips based on the roll of the aircraft. This is an example to demonstrate Script to control LED strips based on the roll of the aircraft. This is an example to demonstrate
the LED interface for WS2812 LEDs the LED interface for WS2812 LEDs
--]] --]]
-- luacheck: only 0
--[[ --[[
for this demo we will use a single strip with 30 LEDs for this demo we will use a single strip with 30 LEDs

View File

@ -2,6 +2,7 @@
Script to control LED strips based on the roll of the aircraft. This is an example to demonstrate Script to control LED strips based on the roll of the aircraft. This is an example to demonstrate
the LED interface for WS2812 LEDs the LED interface for WS2812 LEDs
--]] --]]
-- luacheck: only 0
--[[ --[[
for this demo we will use a single strip with 30 LEDs for this demo we will use a single strip with 30 LEDs

View File

@ -2,6 +2,8 @@
Script to control LED strips based on the roll of the aircraft. This is an example to demonstrate Script to control LED strips based on the roll of the aircraft. This is an example to demonstrate
the LED interface for WS2812 LEDs the LED interface for WS2812 LEDs
--]] --]]
-- luacheck: only 0
--[[ --[[
for this demo we will use a single strip with 30 LEDs for this demo we will use a single strip with 30 LEDs

View File

@ -1,4 +1,5 @@
-- Script decodes, checks and prints NMEA messages -- Script decodes, checks and prints NMEA messages
-- luacheck: only 0
-- find the serial first (0) scripting serial port instance -- find the serial first (0) scripting serial port instance
local port = serial:find_serial(0) local port = serial:find_serial(0)

View File

@ -1,4 +1,5 @@
-- this is an example of how to do object oriented programming in Lua -- this is an example of how to do object oriented programming in Lua
-- luacheck: only 0
function constrain(v, minv, maxv) function constrain(v, minv, maxv)
-- constrain a value between two limits -- constrain a value between two limits

View File

@ -1,4 +1,6 @@
-- this script reads data from a serial port and dumps it to a file -- this script reads data from a serial port and dumps it to a file
-- luacheck: only 0
local file_name = 'raw serial dump.txt' local file_name = 'raw serial dump.txt'
local file_name_plain = 'serial dump.txt' local file_name_plain = 'serial dump.txt'
local baud_rate = 9600 local baud_rate = 9600

View File

@ -26,6 +26,7 @@
-- SCR_USER4 holds the threshold for optical flow innovations (about 0.15 is a good choice) -- 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: -- When the 2nd auxiliary switch (300/Scripting1) is pulled high automatic source selection uses these thresholds:
-- luacheck: only 0
local rangefinder_rotation = 25 -- check downward (25) facing lidar local rangefinder_rotation = 25 -- check downward (25) facing lidar
local source_prev = 0 -- previous source, defaults to primary source local source_prev = 0 -- previous source, defaults to primary source

View File

@ -9,6 +9,7 @@
-- SCR_USER3 holds the threshold for GPS innovations (around 0.3 is a good choice) -- 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 -- 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 -- otherwise wheel encoders (secondary source set) will be used
-- luacheck: only 0
local source_prev = 0 -- previous source, defaults to primary source local source_prev = 0 -- previous source, defaults to primary source
local sw_source_prev = -1 -- previous source switch position local sw_source_prev = -1 -- previous source switch position

View File

@ -14,6 +14,7 @@
-- SCR_USER3 holds the threshold for Non-GPS vertical speed innovation (about 0.3 is a good choice) -- SCR_USER3 holds the threshold for Non-GPS vertical speed innovation (about 0.3 is a good choice)
-- if both GPS speed accuracy <= SCR_USER2 and ExternalNav speed variance >= SCR_USER3, source1 will be used -- if both GPS speed accuracy <= SCR_USER2 and ExternalNav speed variance >= SCR_USER3, source1 will be used
-- otherwise source2 (T265) or source3 (optical flow) will be used based on rangefinder distance -- otherwise source2 (T265) or source3 (optical flow) will be used based on rangefinder distance
-- luacheck: only 0
local rangefinder_rotation = 25 -- check downward (25) facing lidar local rangefinder_rotation = 25 -- check downward (25) facing lidar
local source_prev = 0 -- previous source, defaults to primary source local source_prev = 0 -- previous source, defaults to primary source

View File

@ -1,6 +1,8 @@
--[[ --[[
example for getting cached aux function value example for getting cached aux function value
--]] --]]
-- luacheck: only 0
local RATE_HZ = 10 local RATE_HZ = 10

View File

@ -55,6 +55,8 @@
-- a. SIM_WIND_DIR <-- sets direction wind is coming from -- a. SIM_WIND_DIR <-- sets direction wind is coming from
-- b. SIM_WIND_SPD <-- sets wind speed in m/s -- b. SIM_WIND_SPD <-- sets wind speed in m/s
-- --
-- luacheck: only 0
-- create and initialise parameters -- create and initialise parameters
local PARAM_TABLE_KEY = 86 -- parameter table key must be used by only one script on a particular flight controller local PARAM_TABLE_KEY = 86 -- parameter table key must be used by only one script on a particular flight controller

View File

@ -1,6 +1,7 @@
--[[ --[[
An example of using the copy() method on userdata An example of using the copy() method on userdata
--]] --]]
-- luacheck: only 0
local loc1 = Location() local loc1 = Location()

View File

@ -17,6 +17,7 @@
For this test we'll use sensor ID 17 (0x71), For this test we'll use sensor ID 17 (0x71),
Note: 17 is the index, 0x71 is the actual ID Note: 17 is the index, 0x71 is the actual ID
--]] --]]
-- luacheck: only 0
local loop_time = 1000 -- number of ms between runs local loop_time = 1000 -- number of ms between runs

View File

@ -5,6 +5,8 @@
generators. It monitors battery voltage and controls the throttle generators. It monitors battery voltage and controls the throttle
of the generator to maintain a target voltage using a PI controller of the generator to maintain a target voltage using a PI controller
--]] --]]
-- luacheck: only 0
UPDATE_RATE_HZ = 10 UPDATE_RATE_HZ = 10

View File

@ -1,5 +1,7 @@
-- mission editing demo lua script. -- mission editing demo lua script.
-- by Buzz 2020 -- by Buzz 2020
-- luacheck: only 0
current_pos = nil current_pos = nil
home = 0 home = 0
a = {} a = {}

View File

@ -1,5 +1,6 @@
-- Example of loading a mission from the SD card using Scripting -- Example of loading a mission from the SD card using Scripting
-- Would be trivial to select a mission based on scripting params or RC switch -- Would be trivial to select a mission based on scripting params or RC switch
-- luacheck: only 0

View File

@ -18,6 +18,7 @@
-- 9. repeat step 6, 7 and 8 until the test_loc's altitude falls below the terrain altitude -- 9. repeat step 6, 7 and 8 until the test_loc's altitude falls below the terrain altitude
-- 10. interpolate between test_loc and prev_test_loc to find the lat, lon, alt (above sea-level) where alt-above-terrain is zero -- 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 -- 11. display the POI to the user
-- luacheck: only 0
-- global definitions -- global definitions
local ALT_FRAME_ABSOLUTE = 0 local ALT_FRAME_ABSOLUTE = 0

View File

@ -1,5 +1,6 @@
-- demo of waving paw of opendog -- demo of waving paw of opendog
-- -- luacheck: only 0
local flipflop = true local flipflop = true
pwm = { 1500, 1500, 2000, pwm = { 1500, 1500, 2000,

View File

@ -1,4 +1,6 @@
-- This script is a test of param set and get -- This script is a test of param set and get
-- luacheck: only 0
local count = 0 local count = 0
-- for fast param acess it is better to get a param object, -- for fast param acess it is better to get a param object,

View File

@ -7,6 +7,7 @@
-- It is suggested to allow the aircraft to trim for straight, level, unaccelerated flight (SLUF) in FBWB mode before -- It is suggested to allow the aircraft to trim for straight, level, unaccelerated flight (SLUF) in FBWB mode before
-- starting a doublet -- starting a doublet
-- Charlie Johnson, Oklahoma State University 2020 -- 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_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_CHOICE_CHANNEL = 7 -- RCIN channel to choose elevator (low) or rudder (high)

View File

@ -1,6 +1,7 @@
-- warn the user if wind speed exceeds a threshold, failsafe if a second threshold is exceeded -- warn the user if wind speed exceeds a threshold, failsafe if a second threshold is exceeded
-- note that this script is only intended to be run on ArduPlane -- note that this script is only intended to be run on ArduPlane
-- luacheck: only 0
-- tuning parameters -- tuning parameters
local warn_speed = 10 -- metres/second local warn_speed = 10 -- metres/second

View File

@ -2,6 +2,7 @@
-- the average battery consumption, and the wind to decide when to failsafe -- the average battery consumption, and the wind to decide when to failsafe
-- --
-- CAUTION: This script only works for Plane -- CAUTION: This script only works for Plane
-- luacheck: only 0
-- store the batt info as { instance, filtered, capacity, margin_mah } -- store the batt info as { instance, filtered, capacity, margin_mah }
-- instance: the battery monitor instance (zero indexed) -- instance: the battery monitor instance (zero indexed)

View File

@ -1,4 +1,5 @@
-- support follow in GUIDED mode in plane -- support follow in GUIDED mode in plane
-- luacheck: only 0
local PARAM_TABLE_KEY = 11 local PARAM_TABLE_KEY = 11
local PARAM_TABLE_PREFIX = "GFOLL_" local PARAM_TABLE_PREFIX = "GFOLL_"

View File

@ -1,6 +1,7 @@
-- this shows how to protect against faults in your scripts -- this shows how to protect against faults in your scripts
-- you can wrap your update() call (or any other call) in a pcall() -- you can wrap your update() call (or any other call) in a pcall()
-- which catches errors, allowing you to take an appropriate action -- which catches errors, allowing you to take an appropriate action
-- luacheck: only 0
-- example main loop function -- example main loop function

View File

@ -18,6 +18,7 @@
-- Output12: back right tibia (shin) servo -- Output12: back right tibia (shin) servo
-- --
-- CAUTION: This script should only be used with ArduPilot Rover's firmware -- CAUTION: This script should only be used with ArduPilot Rover's firmware
-- luacheck: only 0
local FRAME_LEN = 80 -- frame length in mm local FRAME_LEN = 80 -- frame length in mm

View File

@ -1,4 +1,5 @@
-- This script checks RangeFinder -- This script checks RangeFinder
-- luacheck: only 0
local rotation_downward = 25 local rotation_downward = 25
local rotation_forward = 0 local rotation_forward = 0

View File

@ -11,6 +11,7 @@ of a vehicle. Use this script AT YOUR OWN RISK.
LICENSE - GNU GPLv3 https://www.gnu.org/licenses/gpl-3.0.en.html LICENSE - GNU GPLv3 https://www.gnu.org/licenses/gpl-3.0.en.html
------------------------------------------------------------------------------]] ------------------------------------------------------------------------------]]
-- luacheck: only 0
local SCRIPT_NAME = 'SaveTurns' local SCRIPT_NAME = 'SaveTurns'

View File

@ -5,6 +5,7 @@
-- a) switches to Guided mode -- a) switches to Guided mode
-- b) sets the target location to be 10m above home -- b) sets the target location to be 10m above home
-- c) switches the vehicle to land once it is within a couple of meters of home -- c) switches the vehicle to land once it is within a couple of meters of home
-- luacheck: only 0
local wp_radius = 2 local wp_radius = 2
local target_alt_above_home = 10 local target_alt_above_home = 10

View File

@ -7,6 +7,7 @@
-- 2) switch to GUIDED mode -- 2) switch to GUIDED mode
-- 3) the vehilce will follow a circle in clockwise direction with increasing speed until ramp_up_time_s time has passed. -- 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. -- 4) switch out of and into the GUIDED mode any time to restart the trajectory from the start.
-- luacheck: only 0
-- Edit these variables -- Edit these variables
local rad_xy_m = 10.0 -- circle radius in xy plane in m local rad_xy_m = 10.0 -- circle radius in xy plane in m

View File

@ -1,4 +1,5 @@
-- height above terrain warning script -- height above terrain warning script
-- luacheck: only 0
-- min altitude above terrain, script will warn if lower than this -- min altitude above terrain, script will warn if lower than this
local terrain_min_alt = 20 local terrain_min_alt = 20

View File

@ -7,6 +7,8 @@ gcs:send_text(0,"Testing load() method")
-- a function written as a string. This could come from a file -- a function written as a string. This could come from a file
-- or any other source (eg. mavlink) -- or any other source (eg. mavlink)
-- Note that the [[ xxx ]] syntax is just a multi-line string -- Note that the [[ xxx ]] syntax is just a multi-line string
-- luacheck: only 0
local func_str = [[ local func_str = [[
function TestFunc(x,y) function TestFunc(x,y)
return math.sin(x) + math.cos(y) return math.sin(x) + math.cos(y)

View File

@ -1,4 +1,5 @@
-- Example script for accessing waypoint info -- Example script for accessing waypoint info
-- luacheck: only 0
local wp_index local wp_index
local wp_distance local wp_distance