mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: fix remaining luacheck issues
This commit is contained in:
parent
613b835d67
commit
5e5aa13446
|
@ -5,11 +5,9 @@ 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
|
||||
---@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
|
||||
|
@ -29,13 +27,10 @@ local HGT_P = bind_add_param('HGT_P',1,1) -- height P gain
|
|||
local HGT_I = bind_add_param("HGT_I",2,1) -- height I gain
|
||||
local HGT_KE_BIAS = bind_add_param("KE_ADD",3,20) -- height knifeedge addition for pitch
|
||||
local THR_PIT_FF = bind_add_param("PIT_FF",4,80) -- throttle FF from pitch
|
||||
local SPD_P = bind_add_param("SPD_P",5,5) -- speed P gain
|
||||
local SPD_I = bind_add_param("SPD_I",6,25) -- speed I gain
|
||||
local TRIM_THROTTLE = Parameter("TRIM_THROTTLE")
|
||||
local RLL2SRV_TCONST = Parameter("RLL2SRV_TCONST")
|
||||
local PITCH_TCONST = Parameter("PTCH2SRV_TCONST")
|
||||
|
||||
local last_roll_err = 0.0
|
||||
local last_id = 0
|
||||
local initial_yaw_deg = 0
|
||||
local wp_yaw_deg = 0
|
||||
|
@ -65,10 +60,10 @@ function bind_add_param2(name, idx, default_value)
|
|||
assert(param:add_param(PARAM_TABLE_KEY2, idx, name, default_value), string.format('could not add param %s', name))
|
||||
return Parameter(PARAM_TABLE_PREFIX2 .. name)
|
||||
end
|
||||
local TRICKS = nil
|
||||
local TRIK_SEL_FN = nil
|
||||
local TRIK_ACT_FN = nil
|
||||
local TRIK_COUNT = nil
|
||||
local TRICKS
|
||||
local TRIK_SEL_FN
|
||||
local TRIK_ACT_FN
|
||||
local TRIK_COUNT
|
||||
|
||||
-- constrain a value between limits
|
||||
function constrain(v, vmin, vmax)
|
||||
|
@ -131,7 +126,7 @@ end
|
|||
--roll controller to keep wings level in earth frame. if arg is 0 then level is at only 0 deg, otherwise its at 180/-180 roll also for loops
|
||||
function earth_frame_wings_level(arg)
|
||||
local roll_deg = math.deg(ahrs:get_roll())
|
||||
local roll_angle_error = 0.0
|
||||
local roll_angle_error
|
||||
if (roll_deg > 90 or roll_deg < -90) and arg ~= 0 then
|
||||
roll_angle_error = 180 - roll_deg
|
||||
else
|
||||
|
@ -166,7 +161,6 @@ local function PI_controller(kP,kI,iMax)
|
|||
-- private fields as locals
|
||||
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 _I = 0
|
||||
|
@ -254,7 +248,6 @@ local function height_controller(kP_param,kI_param,KnifeEdge_param,Imax)
|
|||
end
|
||||
|
||||
local height_PI = height_controller(HGT_P, HGT_I, HGT_KE_BIAS, 20.0)
|
||||
local speed_PI = PI_controller(SPD_P:get(), SPD_I:get(), 100.0)
|
||||
|
||||
-- a controller to target a zero pitch angle and zero heading change, used in a roll
|
||||
-- output is a body frame pitch rate, with convergence over time tconst in seconds
|
||||
|
@ -305,7 +298,6 @@ function do_axial_roll(arg1, arg2)
|
|||
gcs:send_text(5, string.format("Starting %d Roll(s)", arg2))
|
||||
end
|
||||
local roll_rate = arg1
|
||||
local pitch_deg = math.deg(ahrs:get_pitch())
|
||||
local roll_deg = math.deg(ahrs:get_roll())
|
||||
|
||||
if trick_stage == 0 then
|
||||
|
@ -364,7 +356,7 @@ function do_loop(arg1, arg2)
|
|||
local roll_deg = math.deg(ahrs:get_roll())
|
||||
local vel = ahrs:get_velocity_NED():length()
|
||||
local pitch_rate = arg1
|
||||
local pitch_rate = pitch_rate * (1+ 2*((vel/target_vel)-1)) --increase/decrease rate based on velocity to round loop
|
||||
pitch_rate = pitch_rate * (1+ 2*((vel/target_vel)-1)) --increase/decrease rate based on velocity to round loop
|
||||
pitch_rate = constrain(pitch_rate,.5 * arg1, 3 * arg1)
|
||||
|
||||
if trick_stage == 0 then
|
||||
|
@ -400,7 +392,6 @@ function do_loop(arg1, arg2)
|
|||
return
|
||||
end
|
||||
end
|
||||
throttle = throttle_controller()
|
||||
if trick_stage == 2 or trick_stage == 0 then
|
||||
level_type = 0
|
||||
else
|
||||
|
@ -430,9 +421,6 @@ function do_rolling_circle(arg1, arg2)
|
|||
end
|
||||
local yaw_rate_dps = arg1
|
||||
local roll_rate_dps = arg2
|
||||
local pitch_deg = math.deg(ahrs:get_pitch())
|
||||
local roll_deg = math.deg(ahrs:get_roll())
|
||||
local yaw_deg = math.deg(ahrs:get_yaw())
|
||||
local now_ms = millis()
|
||||
local dt = (now_ms - circle_last_ms):tofloat() * 0.001
|
||||
circle_last_ms = now_ms
|
||||
|
@ -474,11 +462,10 @@ function do_knife_edge(arg1,arg2)
|
|||
if not running then
|
||||
running = true
|
||||
height_PI.reset()
|
||||
knife_edge_s = now
|
||||
knife_edge_ms = now
|
||||
gcs:send_text(5, string.format("Starting %d Knife Edge", arg1))
|
||||
end
|
||||
local i=0
|
||||
if (now - knife_edge_s) < arg2 then
|
||||
if (now - knife_edge_ms) < arg2 then
|
||||
local roll_deg = math.deg(ahrs:get_roll())
|
||||
local roll_angle_error = (arg1 - roll_deg)
|
||||
if math.abs(roll_angle_error) > 180 then
|
||||
|
@ -506,17 +493,16 @@ function do_knife_edge(arg1,arg2)
|
|||
end
|
||||
|
||||
-- fly level for a time..allows full altitude recovery after trick
|
||||
function do_pause(arg1,arg2)
|
||||
function do_pause(arg1,_)
|
||||
-- arg1 is time of pause in sec, arg2 is unused
|
||||
local now = millis():tofloat() * 0.001
|
||||
if not running then
|
||||
running = true
|
||||
height_PI.reset()
|
||||
knife_edge_s = now
|
||||
knife_edge_ms = now
|
||||
gcs:send_text(5, string.format("%d sec Pause", arg1))
|
||||
end
|
||||
local i=0
|
||||
if (now - knife_edge_s) < arg1 then
|
||||
if (now - knife_edge_ms) < arg1 then
|
||||
roll_rate = earth_frame_wings_level(0)
|
||||
target_pitch = height_PI.update(initial_height)
|
||||
pitch_rate, yaw_rate = pitch_controller(target_pitch, wp_yaw_deg, PITCH_TCONST:get())
|
||||
|
@ -534,11 +520,7 @@ function do_pause(arg1,arg2)
|
|||
end
|
||||
end
|
||||
|
||||
|
||||
local circle_yaw = 0
|
||||
local circle_last_ms = 0
|
||||
|
||||
function do_knifedge_circle(arg1, arg2)
|
||||
function do_knifedge_circle(arg1, _)
|
||||
-- constant roll angle circle , arg1 yaw rate, positive to right, neg to left, arg2 is not used
|
||||
if not running then
|
||||
running = true
|
||||
|
@ -549,8 +531,6 @@ function do_knifedge_circle(arg1, arg2)
|
|||
gcs:send_text(5, string.format("Staring KnifeEdge Circle"))
|
||||
end
|
||||
local yaw_rate_dps = arg1
|
||||
local pitch_deg = math.deg(ahrs:get_pitch())
|
||||
local yaw_deg = math.deg(ahrs:get_yaw())
|
||||
local now_ms = millis()
|
||||
local dt = (now_ms - circle_last_ms):tofloat() * 0.001
|
||||
circle_last_ms = now_ms
|
||||
|
@ -621,7 +601,6 @@ function do_4point_roll(arg1, arg2)
|
|||
height_PI.reset()
|
||||
gcs:send_text(5, string.format("Starting 4pt Roll"))
|
||||
end
|
||||
local pitch_deg = math.deg(ahrs:get_pitch())
|
||||
local roll_deg = math.deg(ahrs:get_roll())
|
||||
|
||||
if trick_stage == 0 then
|
||||
|
@ -844,7 +823,7 @@ function check_trick()
|
|||
gcs:send_text(0, string.format("No trick selected"))
|
||||
return 0
|
||||
end
|
||||
local id = TRICKS[selection].id:get()
|
||||
id = TRICKS[selection].id:get()
|
||||
if action == 1 then
|
||||
gcs:send_text(5, string.format("Trick %u selected (%s)", id, name[id]))
|
||||
return 0
|
||||
|
|
|
@ -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
|
||||
|
@ -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()
|
||||
|
@ -1658,10 +1657,10 @@ end
|
|||
--[[
|
||||
perform a rudder over maneuver
|
||||
--]]
|
||||
function rudder_over(_direction, _min_speed)
|
||||
function rudder_over(direction_in, min_speed_in)
|
||||
local self = {}
|
||||
local direction = _direction
|
||||
local min_speed = _min_speed
|
||||
local direction = direction_in
|
||||
local min_speed = min_speed_in
|
||||
local reached_speed = false
|
||||
local kick_started = false
|
||||
local pitch2_done = false
|
||||
|
@ -1822,12 +1821,12 @@ end
|
|||
--[[
|
||||
takeoff controller
|
||||
--]]
|
||||
function takeoff_controller(_distance, _thr_slew)
|
||||
function takeoff_controller(distance_in, thr_slew_in)
|
||||
local self = {}
|
||||
local start_time = 0
|
||||
local start_pos = nil
|
||||
local thr_slew = _thr_slew
|
||||
local distance = _distance
|
||||
local thr_slew = thr_slew_in
|
||||
local distance = distance_in
|
||||
local all_done = false
|
||||
local initial_yaw_deg = math.deg(ahrs:get_yaw())
|
||||
local yaw_correction_tconst = 1.0
|
||||
|
@ -2245,11 +2244,11 @@ 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_in, convergence_loops_in)
|
||||
local self = {}
|
||||
|
||||
local max_lag_ms = _max_lag_ms
|
||||
local convergence_loops = _convergence_loops
|
||||
local max_lag_ms = max_lag_ms_in
|
||||
local convergence_loops = convergence_loops_in
|
||||
local link_offset_ms = 0
|
||||
local min_sample_ms = 0
|
||||
local initialised = false
|
||||
|
|
|
@ -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)
|
||||
|
||||
|
@ -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
|
||||
|
|
|
@ -2,7 +2,6 @@
|
|||
a script to select other lua scripts using an auxillary switch from
|
||||
/1 /2 or /3 subdirectories of the scripts directory
|
||||
--]]
|
||||
-- luacheck: only 0
|
||||
---@diagnostic disable: param-type-mismatch
|
||||
|
||||
|
||||
|
@ -125,7 +124,7 @@ function remove_scripts(subdir)
|
|||
return false
|
||||
end
|
||||
local ret = false
|
||||
for k,v in ipairs(dlist) do
|
||||
for _,v in ipairs(dlist) do
|
||||
local suffix = v:sub(-4)
|
||||
if compare_strings_ci(suffix,".LUA") and not compare_strings_ci(v,THIS_SCRIPT) then
|
||||
if not file_exists(subdir .. "/" .. v) then
|
||||
|
@ -148,7 +147,7 @@ function copy_scripts(subdir)
|
|||
end
|
||||
local ret = false
|
||||
local sdir = get_scripts_dir()
|
||||
for k, v in ipairs(dlist) do
|
||||
for _, v in ipairs(dlist) do
|
||||
local suffix = v:sub(-4)
|
||||
if compare_strings_ci(suffix,".LUA") and not compare_strings_ci(v,THIS_SCRIPT) then
|
||||
local src = subdir .. "/" .. v
|
||||
|
@ -184,12 +183,11 @@ function mission_load(n)
|
|||
local index = 0
|
||||
local fail = false
|
||||
while true and not fail do
|
||||
local data = {}
|
||||
local line = file:read()
|
||||
if not line then
|
||||
break
|
||||
end
|
||||
local ret, _, seq, curr, frame, cmd, p1, p2, p3, p4, x, y, z, autocont = string.find(line, "^(%d+)%s+(%d+)%s+(%d+)%s+(%d+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+(%d+)")
|
||||
local ret, _, seq, _, frame, cmd, p1, p2, p3, p4, x, y, z, _ = string.find(line, "^(%d+)%s+(%d+)%s+(%d+)%s+(%d+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+(%d+)")
|
||||
if not ret then
|
||||
fail = true
|
||||
break
|
||||
|
|
|
@ -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
|
||||
|
@ -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]))
|
||||
|
@ -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
|
||||
|
|
|
@ -435,13 +435,13 @@ end
|
|||
--[[
|
||||
client class for open connections
|
||||
--]]
|
||||
local function Client(_sock, _idx)
|
||||
local function Client(sock_in, idx_in)
|
||||
local self = {}
|
||||
|
||||
self.closed = false
|
||||
|
||||
local sock = _sock
|
||||
local idx = _idx
|
||||
local sock = sock_in
|
||||
local idx = idx_in
|
||||
local have_header = false
|
||||
local header = ""
|
||||
local header_lines = {}
|
||||
|
|
|
@ -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
|
||||
|
@ -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
|
||||
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
@ -98,7 +96,7 @@ local now_s = get_time_sec()
|
|||
--[[
|
||||
EFI Engine Object
|
||||
--]]
|
||||
local function engine_control(_driver)
|
||||
local function engine_control(driver_in)
|
||||
local self = {}
|
||||
|
||||
-- Build up the EFI_State that is passed into the EFI Scripting backend
|
||||
|
@ -109,7 +107,7 @@ local function engine_control(_driver)
|
|||
local rpm = 0
|
||||
local air_pressure = 0
|
||||
local map_ratio = 0.0
|
||||
local driver = _driver
|
||||
local driver = driver_in
|
||||
local last_rpm_t = get_time_sec()
|
||||
local last_state_update_t = get_time_sec()
|
||||
local throttle_pos = 0.0
|
||||
|
@ -123,12 +121,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
|
||||
|
@ -275,9 +267,9 @@ local function engine_control(_driver)
|
|||
|
||||
-- return the instance
|
||||
return self
|
||||
end -- end function engine_control(_driver)
|
||||
end -- end function engine_control(driver_in)
|
||||
|
||||
local engine1 = engine_control(driver1, 1)
|
||||
local engine1 = engine_control(driver1)
|
||||
|
||||
function update()
|
||||
now_s = get_time_sec()
|
||||
|
|
|
@ -243,7 +243,7 @@ end
|
|||
--[[
|
||||
EFI Engine Object
|
||||
--]]
|
||||
local function engine_control(_driver)
|
||||
local function engine_control(driver_in)
|
||||
local self = {}
|
||||
|
||||
-- Build up the EFI_State that is passed into the EFI Scripting backend
|
||||
|
@ -263,7 +263,7 @@ local function engine_control(_driver)
|
|||
local fuel_consumption_lph = 0
|
||||
local fuel_total_l = 0
|
||||
local last_fuel_s = 0
|
||||
local driver = _driver
|
||||
local driver = driver_in
|
||||
local last_rpm_t = get_time_sec()
|
||||
local last_state_update_t = get_time_sec()
|
||||
local last_thr_update = get_time_sec()
|
||||
|
|
|
@ -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
|
||||
|
@ -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] = {}
|
||||
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
@ -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} -- // "
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
||||
|
||||
--[[
|
||||
|
@ -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)
|
||||
|
@ -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
|
||||
|
||||
--[[
|
||||
|
|
|
@ -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)
|
||||
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
@ -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
|
||||
|
||||
|
|
|
@ -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)
|
||||
|
||||
|
@ -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 --
|
||||
|
|
|
@ -14,14 +14,10 @@
|
|||
-- 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
|
||||
-- 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
|
||||
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
|
||||
|
@ -83,9 +79,7 @@ function update()
|
|||
local gps_usable = (gps_speed_accuracy ~= nil) and (gps_speed_accuracy <= gps_usable_accuracy)
|
||||
|
||||
-- get external nav innovations from ahrs
|
||||
local extnav_innov = Vector3f()
|
||||
local extnav_var = Vector3f()
|
||||
extnav_innov, extnav_var = ahrs:get_vel_innovations_and_variances_for_source(6)
|
||||
local extnav_innov = ahrs:get_vel_innovations_and_variances_for_source(6)
|
||||
local extnav_over_threshold = (extnav_innov == nil) or (extnav_innov:z() == 0.0) or (math.abs(extnav_innov:z()) > extnav_innov_thresh)
|
||||
|
||||
-- get rangefinder distance
|
||||
|
|
|
@ -140,7 +140,7 @@ function update()
|
|||
-- first get position offset (cumulative effect of velocity offsets)
|
||||
local pos_offset_NED, _, _ = poscontrol:get_posvelaccel_offset()
|
||||
if pos_offset_NED == nil then
|
||||
print_warning("unable to get position offset")
|
||||
print("unable to get position offset")
|
||||
pos_offset_NED = Vector3f()
|
||||
end
|
||||
-- test velocity offsets in m/s in NED frame
|
||||
|
|
|
@ -5,8 +5,6 @@
|
|||
local PARAM_TABLE_KEY = 72
|
||||
local PARAM_TABLE_PREFIX = "DEPL_"
|
||||
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
|
||||
|
||||
---@diagnostic disable: missing-parameter
|
||||
---@diagnostic disable: param-type-mismatch
|
||||
|
||||
-- bind a parameter to a variable
|
||||
|
@ -69,7 +67,7 @@ function update_state()
|
|||
gcs:send_text(MAV_SEVERITY.INFO, "DEPL: deploying")
|
||||
vehicle:set_mode(MODE_LAND)
|
||||
arming:arm_force()
|
||||
if not vehicle:get_mode() == MODE_LAND or not arming:is_armed() then
|
||||
if (vehicle:get_mode() ~= MODE_LAND) or not arming:is_armed() then
|
||||
gcs:send_text(MAV_SEVERITY.INFO, "DEPL: Arming failed")
|
||||
return
|
||||
end
|
||||
|
|
|
@ -17,8 +17,6 @@
|
|||
For this test we'll use sensor ID 17 (0x71),
|
||||
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
|
||||
|
||||
|
@ -45,7 +43,7 @@ function wrap_360(angle)
|
|||
end
|
||||
|
||||
function prep_5bits(num)
|
||||
local res = 0
|
||||
local res
|
||||
local abs_num = math.floor(math.abs(num) + 0.5)
|
||||
if abs_num < 10 then
|
||||
res = abs_num << 1
|
||||
|
@ -61,7 +59,7 @@ function prep_5bits(num)
|
|||
end
|
||||
|
||||
function wp_pack(index, distance, bearing, xtrack)
|
||||
local wp_dword = uint32_t()
|
||||
local wp_dword
|
||||
wp_dword = math.min(index,WP_LIMIT_COUNT)
|
||||
wp_dword = wp_dword | frsky_sport:prep_number(math.min(math.floor(distance+0.5),WP_LIMIT_DISTANCE),3,2) << WP_OFFSET_DISTANCE
|
||||
wp_dword = wp_dword | prep_5bits(math.min(xtrack,WP_LIMIT_XTRACK)) << WP_OFFSET_XTRACK
|
||||
|
@ -97,16 +95,13 @@ function update_wp_info()
|
|||
end
|
||||
|
||||
function update()
|
||||
local gps_status = gps.status(0,0)
|
||||
|
||||
if not update_wp_info() then
|
||||
return update, loop_time
|
||||
end
|
||||
|
||||
local sensor_id = 0x71
|
||||
local wp_dword = uint32_t()
|
||||
|
||||
wp_dword = wp_pack(wp_index, wp_distance, wp_bearing, wp_xtrack)
|
||||
local wp_dword = wp_pack(wp_index, wp_distance, wp_bearing, wp_xtrack)
|
||||
frsky_sport:sport_telemetry_push(sensor_id, 0x10, 0x5009, wp_dword)
|
||||
|
||||
return update, loop_time
|
||||
|
|
|
@ -5,8 +5,6 @@
|
|||
generators. It monitors battery voltage and controls the throttle
|
||||
of the generator to maintain a target voltage using a PI controller
|
||||
--]]
|
||||
-- luacheck: only 0
|
||||
|
||||
---@diagnostic disable: need-check-nil
|
||||
---@diagnostic disable: param-type-mismatch
|
||||
|
||||
|
@ -63,7 +61,6 @@ GENCTL_VOLT_TARG = bind_add_param('VOLT_TARG', 11, 0)
|
|||
GENCTL_SLEW_RATE = bind_add_param('SLEW_RATE', 12, 100)
|
||||
|
||||
local MAV_SEVERITY_INFO = 6
|
||||
local MAV_SEVERITY_NOTICE = 5
|
||||
local MAV_SEVERITY_EMERGENCY = 0
|
||||
|
||||
local switch = nil
|
||||
|
|
|
@ -1,7 +1,5 @@
|
|||
-- mission editing demo lua script.
|
||||
-- by Buzz 2020
|
||||
-- luacheck: only 0
|
||||
|
||||
---@diagnostic disable: param-type-mismatch
|
||||
---@diagnostic disable: undefined-field
|
||||
|
||||
|
@ -202,7 +200,7 @@ function stage7 ()
|
|||
-- fiurst time in , there's no mission, lets throw a few wps in to play with later..
|
||||
-- change copy of last item slightly, for giggles, and append as a new item
|
||||
if (mission:num_commands() == 1) then
|
||||
for x = 1, 10 do
|
||||
for _ = 1, 10 do
|
||||
m:command(16) -- 16 = normal WAYPOINT
|
||||
m:x(m:x()+math.random(-10000,10000)) -- add something random
|
||||
m:y(m:y()+math.random(-10000,10000))
|
||||
|
|
|
@ -1,6 +1,5 @@
|
|||
-- 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
|
||||
-- luacheck: only 0
|
||||
--Copy this "mission-load.lua" script to the "scripts" directory of the simulation or autopilot's SD card.
|
||||
--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.
|
||||
|
@ -23,12 +22,11 @@ local function read_mission(file_name)
|
|||
local index = 0
|
||||
local fail = false
|
||||
while true and not fail do
|
||||
local data = {}
|
||||
local line = file:read()
|
||||
if not line then
|
||||
break
|
||||
end
|
||||
local ret, _, seq, curr, frame, cmd, p1, p2, p3, p4, x, y, z, autocont = string.find(line, "^(%d+)%s+(%d+)%s+(%d+)%s+(%d+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+(%d+)")
|
||||
local ret, _, seq, _, frame, cmd, p1, p2, p3, p4, x, y, z, _ = string.find(line, "^(%d+)%s+(%d+)%s+(%d+)%s+(%d+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+([-.%d]+)%s+(%d+)")
|
||||
if not ret then
|
||||
fail = true
|
||||
break
|
||||
|
|
|
@ -1,7 +1,6 @@
|
|||
-- 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
|
||||
-- luacheck: only 0
|
||||
|
||||
-- tuning parameters
|
||||
local warn_speed = 10 -- metres/second
|
||||
|
@ -11,26 +10,26 @@ local warning_interval_ms = uint32_t(15000) -- send user message every 15s
|
|||
local warning_last_sent_ms = uint32_t() -- time we last sent a warning message to the user
|
||||
|
||||
function update()
|
||||
local wind = ahrs:wind_estimate() -- get the wind estimate
|
||||
if wind then
|
||||
-- make a 2D wind vector
|
||||
wind_xy = Vector2f()
|
||||
wind_xy:x(wind:x())
|
||||
wind_xy:y(wind:y())
|
||||
speed = wind_xy:length() -- compute the wind speed
|
||||
if speed > failsafe_speed then
|
||||
gcs:send_text(0, "Wind failsafe at " .. speed .. " metres/second")
|
||||
vehicle:set_mode(11) -- FIXME: should be an enum. 11 is RTL.
|
||||
return
|
||||
end
|
||||
if speed > warn_speed then
|
||||
if millis() - warning_last_sent_ms > warning_interval_ms then
|
||||
gcs:send_text(4, "Wind warning at " .. speed .. " metres/second")
|
||||
warning_last_sent_ms = millis()
|
||||
end
|
||||
end
|
||||
end
|
||||
return update, 1000
|
||||
local wind = ahrs:wind_estimate() -- get the wind estimate
|
||||
if wind then
|
||||
-- make a 2D wind vector
|
||||
wind_xy = Vector2f()
|
||||
wind_xy:x(wind:x())
|
||||
wind_xy:y(wind:y())
|
||||
speed = wind_xy:length() -- compute the wind speed
|
||||
if speed > failsafe_speed then
|
||||
gcs:send_text(0, "Wind failsafe at " .. speed .. " metres/second")
|
||||
vehicle:set_mode(11) -- FIXME: should be an enum. 11 is RTL.
|
||||
return
|
||||
end
|
||||
if speed > warn_speed then
|
||||
if millis() - warning_last_sent_ms > warning_interval_ms then
|
||||
gcs:send_text(4, "Wind warning at " .. speed .. " metres/second")
|
||||
warning_last_sent_ms = millis()
|
||||
end
|
||||
end
|
||||
end
|
||||
return update, 1000
|
||||
end
|
||||
|
||||
return update, 1000
|
||||
|
|
|
@ -1,12 +1,8 @@
|
|||
-- 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_"
|
||||
|
||||
local MODE_MANUAL = 0
|
||||
local MODE_GUIDED = 15
|
||||
|
||||
local ALT_FRAME_ABSOLUTE = 0
|
||||
|
@ -29,13 +25,10 @@ assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 3), 'could not add p
|
|||
GFOLL_ENABLE = bind_add_param('ENABLE', 1, 0)
|
||||
|
||||
-- current target
|
||||
local target_pos = Location()
|
||||
local current_pos = Location()
|
||||
local target_velocity = Vector3f()
|
||||
local target_heading = 0.0
|
||||
local target_pos
|
||||
local current_pos
|
||||
|
||||
-- other state
|
||||
local vehicle_mode = MODE_MANUAL
|
||||
local have_target = false
|
||||
|
||||
-- check key parameters
|
||||
|
@ -89,8 +82,7 @@ function update_target()
|
|||
end
|
||||
have_target = true
|
||||
|
||||
target_pos, target_velocity = follow:get_target_location_and_velocity_ofs()
|
||||
target_heading = follow:get_target_heading_deg()
|
||||
target_pos = follow:get_target_location_and_velocity_ofs()
|
||||
end
|
||||
|
||||
-- main update function
|
||||
|
|
|
@ -21,7 +21,7 @@ function update()
|
|||
if pwm7 and pwm7 > 1800 then -- check if RC input 7 has moved high
|
||||
local mode = vehicle:get_mode() -- get current mode
|
||||
if not sent_target then -- if we haven't sent the target yet
|
||||
if not (mode == copter_guided_mode_num) then -- change to guided mode
|
||||
if mode ~= copter_guided_mode_num then -- change to guided mode
|
||||
vehicle:set_mode(copter_guided_mode_num)
|
||||
else
|
||||
local above_home = ahrs:get_home() -- get home location
|
||||
|
@ -33,7 +33,7 @@ function update()
|
|||
else
|
||||
|
||||
-- change to land mode when within 2m of home
|
||||
if not (mode == copter_land_mode_num) then
|
||||
if mode ~= copter_land_mode_num then
|
||||
local home = ahrs:get_home()
|
||||
local curr_loc = ahrs:get_location()
|
||||
if home and curr_loc then
|
||||
|
|
|
@ -6,7 +6,7 @@ local new_target= nil
|
|||
|
||||
function update()
|
||||
|
||||
if not (vehicle:get_mode() == 4) then
|
||||
if vehicle:get_mode() ~= 4 then
|
||||
gcs:send_text(0, "not in Guided")
|
||||
return update, 1000
|
||||
end
|
||||
|
|
Loading…
Reference in New Issue