mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_Scripting: applets: ignore luacheck warnings
This commit is contained in:
parent
068328f2df
commit
3deaece3b7
@ -5,6 +5,7 @@ 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
|
||||
|
||||
DO_JUMP = 177
|
||||
k_throttle = 70
|
||||
|
@ -4,6 +4,7 @@
|
||||
Written by Matthew Hampsey, Andy Palmer and Andrew Tridgell, with controller
|
||||
assistance from Paul Riseborough, testing by Henry Wurzburg
|
||||
]]--
|
||||
-- luacheck: only 0
|
||||
|
||||
-- setup param block for aerobatics, reserving 30 params beginning with AERO_
|
||||
local PARAM_TABLE_KEY = 70
|
||||
|
@ -4,6 +4,7 @@
|
||||
-- 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
|
||||
|
||||
-- Tested and working as of 25th Aug 2020 (Copter Dev)
|
||||
|
||||
|
@ -25,6 +25,7 @@ LEDs should now work!, if not try swapping AUX 5 and 6, either by physically swa
|
||||
To get colours to match either change the ordering in "local led_map =" below or swap headers round on the LED distribution board
|
||||
If using 6 les add two extra colours to "local led_map =" e.g: "local led_map = {red, red, red, green, green, green}"
|
||||
--]]
|
||||
-- luacheck: only 0
|
||||
|
||||
-- helper colours, red, green, blue values from 0 to 255
|
||||
local red = {255, 0, 0}
|
||||
|
@ -2,6 +2,7 @@
|
||||
-- Must have Mission Reset switch assigned, it will function normally when armed or disarmed
|
||||
-- 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
|
||||
|
||||
local mission_loaded = false
|
||||
local rc_switch = rc:find_channel_for_option(24) --AUX FUNC sw for mission restart
|
||||
|
@ -2,6 +2,7 @@
|
||||
a script to select other lua scripts using an auxillary switch from
|
||||
/1 /2 or /3 subdirectories of the scripts directory
|
||||
--]]
|
||||
-- luacheck: only 0
|
||||
|
||||
local THIS_SCRIPT = "Script_Controller.lua"
|
||||
local sel_ch = Parameter("SCR_USER6")
|
||||
|
@ -5,6 +5,8 @@
|
||||
for copters, although it will work in other VTOL modes
|
||||
|
||||
--]]
|
||||
-- luacheck: only 0
|
||||
|
||||
|
||||
--[[
|
||||
- TODO:
|
||||
|
@ -4,6 +4,8 @@
|
||||
-- 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
|
||||
|
||||
-- Config
|
||||
|
||||
-- Motors numbers to stop
|
||||
|
@ -1,6 +1,8 @@
|
||||
--[[
|
||||
support package place for quadplanes
|
||||
--]]
|
||||
-- luacheck: only 0
|
||||
|
||||
|
||||
local PARAM_TABLE_KEY = 9
|
||||
local PARAM_TABLE_PREFIX = "PKG_"
|
||||
|
@ -1,4 +1,5 @@
|
||||
-- support takeoff and landing on moving platforms for VTOL planes
|
||||
-- luacheck: only 0
|
||||
|
||||
local PARAM_TABLE_KEY = 7
|
||||
local PARAM_TABLE_PREFIX = "SHIP_"
|
||||
|
@ -19,6 +19,8 @@
|
||||
-- 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
|
||||
local RC_OPTION = {RunCamControl=78}
|
||||
|
Loading…
Reference in New Issue
Block a user