AP_Scripting: support precision loiter in quadplanes

and allow for moving landing target
This commit is contained in:
Andrew Tridgell 2024-03-07 18:12:26 +11:00 committed by Randy Mackay
parent efa83d5d6d
commit 252d133110
2 changed files with 53 additions and 12 deletions

View File

@ -11,6 +11,11 @@ local PARAM_TABLE_PREFIX = "PLND_"
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
local MODE_QLAND = 20 local MODE_QLAND = 20
local MODE_QLOITER = 19
local AUX_PRECLOITER = 39
local precloiter_enabled = false
-- bind a parameter to a variable -- bind a parameter to a variable
function bind_param(name) function bind_param(name)
@ -63,7 +68,7 @@ local rangefinder_orient = 25 -- downward
--[[ --[[
update the have_target variable update the have_target variable
--]] --]]
function update_target() local function update_target()
if not precland:healthy() then if not precland:healthy() then
have_target = false have_target = false
return return
@ -88,19 +93,45 @@ function update_target()
end end
--[[ --[[
return true if we are in an automatic landing and should return true if we are in a state where precision landing control should apply
try to use precision landing
--]] --]]
function in_auto_land() local function precision_landing_active()
return quadplane:in_vtol_land_descent() or vehicle:get_mode() == MODE_QLAND local mode = vehicle:get_mode()
if mode == MODE_QLOITER then
-- support precision loiter under pilot control
return precloiter_enabled
end
return quadplane:in_vtol_land_descent() or mode == MODE_QLAND
end
--[[
check for user activating precision loiter
--]]
local function precloiter_check()
local precloiter_pos = rc:get_aux_cached(AUX_PRECLOITER)
if precloiter_pos then
enabled = precloiter_pos == 2
if enabled ~= precloiter_enabled then
precloiter_enabled = enabled
if enabled then
gcs:send_text(MAV_SEVERITY.INFO, "PLND: PrecLoiter enabled")
else
gcs:send_text(MAV_SEVERITY.INFO, "PLND: PrecLoiter disabled")
end
end
end
end end
-- main update function -- main update function
function update() local function update()
if PLND_ENABLED:get() < 1 then if PLND_ENABLED:get() < 1 then
return return
end end
precloiter_check()
--[[ --[[
get the current navigation target. Note that we must get this get the current navigation target. Note that we must get this
before we check if we are in a landing descent to prevent a race condition before we check if we are in a landing descent to prevent a race condition
@ -112,8 +143,8 @@ function update()
return return
end end
-- see if we are landing -- see if we are a precision landing state
if not in_auto_land() then if not precision_landing_active() then
return return
end end
@ -155,7 +186,7 @@ function update()
PLND_OPTIONS then ask vehicle to match PLND_OPTIONS then ask vehicle to match
--]] --]]
local target_vel = precland:get_target_velocity() local target_vel = precland:get_target_velocity()
if target_vel and (PLND_OPTIONS:get():toint() & 1) ~= 0 then if target_vel and (PLND_OPTIONS:get() & 1) ~= 0 then
vehicle:set_velocity_match(target_vel) vehicle:set_velocity_match(target_vel)
end end
if not target_vel then if not target_vel then
@ -196,7 +227,7 @@ gcs:send_text(MAV_SEVERITY.INFO, "PLND: Loaded")
-- wrapper around update(). This calls update() at 20Hz, -- wrapper around update(). This calls update() at 20Hz,
-- and if update faults then an error is displayed, but the script is not -- and if update faults then an error is displayed, but the script is not
-- stopped -- stopped
function protected_wrapper() local function protected_wrapper()
local success, err = pcall(update) local success, err = pcall(update)
if not success then if not success then
gcs:send_text(0, "Internal Error: " .. err) gcs:send_text(0, "Internal Error: " .. err)

View File

@ -1,8 +1,10 @@
# Plane Precision Landing # Plane Precision Landing
This script implements a precision landing system for VTOL fixed wing This script implements a precision landing system for VTOL fixed wing
aircraft (quadplanes). It is a simple script which is intended to be aircraft (quadplanes).
modified by vendors for their specific aircraft.
Precision positioning over a landing sensor is supported in QLOITER,
QLAND, QRTL and AUTO landing.
# Parameters # Parameters
@ -47,3 +49,11 @@ may malfunction.
If the PLND_OPTIONS bit for a moving target is enabled then the If the PLND_OPTIONS bit for a moving target is enabled then the
vehicle will be set to track the estimated target velocity during vehicle will be set to track the estimated target velocity during
descent descent
## Precision QLoiter
To enable precision position hold in QLOITER you will need to use
auxiliary function 39 (PRECISION_LOITER) on an R/C switch or via GCS
auxiliary switch buttons. When enabled the vehicle will position
itself above the landing target. Height control is under user control.