AP_Scripting: convert remaining uses of TRIM_ARSPD_CM to AIRSPEED_CRUISE

This commit is contained in:
Andrew Tridgell 2024-01-18 16:32:46 +11:00
parent 2a9fe41757
commit 00eeac0551
4 changed files with 7 additions and 8 deletions

View File

@ -28,7 +28,6 @@ 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 TRIM_ARSPD_CM = Parameter("TRIM_ARSPD_CM")
local RLL2SRV_TCONST = Parameter("RLL2SRV_TCONST")
local PITCH_TCONST = Parameter("PTCH2SRV_TCONST")

View File

@ -385,7 +385,7 @@ local DO_JUMP = 177
local k_throttle = 70
local NAME_FLOAT_RATE = 2
local TRIM_ARSPD_CM = Parameter("TRIM_ARSPD_CM")
local AIRSPEED_CRUISE = Parameter("AIRSPEED_CRUISE")
local last_id = 0
local current_task = nil
@ -2010,7 +2010,7 @@ end
velocity at the start of the maneuver
--]]
function target_groundspeed()
return math.max(ahrs:get_EAS2TAS()*TRIM_ARSPD_CM:get()*0.01, ahrs:get_velocity_NED():length())
return math.max(ahrs:get_EAS2TAS()*AIRSPEED_CRUISE:get(), ahrs:get_velocity_NED():length())
end
--[[

View File

@ -67,7 +67,7 @@ SHIP_AUTO_OFS = bind_add_param('AUTO_OFS', 3, 0)
RCMAP_THROTTLE = bind_param("RCMAP_THROTTLE")
ALT_HOLD_RTL = bind_param("ALT_HOLD_RTL")
Q_RTL_ALT = bind_param("Q_RTL_ALT")
TRIM_ARSPD_CM = bind_param("TRIM_ARSPD_CM")
AIRSPEED_CRUISE = bind_param("AIRSPEED_CRUISE")
TECS_LAND_ARSPD = bind_param("TECS_LAND_ARSPD")
Q_TRANS_DECEL = bind_param("Q_TRANS_DECEL")
WP_LOITER_RAD = bind_param("WP_LOITER_RAD")
@ -159,7 +159,7 @@ end
-- get landing airspeed
function get_land_airspeed()
if TECS_LAND_ARSPD:get() < 0 then
return TRIM_ARSPD_CM:get() * 0.01
return AIRSPEED_CRUISE:get()
end
return TECS_LAND_ARSPD:get()
end

View File

@ -30,11 +30,11 @@ local SITL_wind = false
-- Read in required params
local value = param:get('TRIM_ARSPD_CM')
local value = param:get('AIRSPEED_CRUISE')
if value then
air_speed = value / 100
air_speed = value
else
error('LUA: get TRIM_ARSPD_CM failed')
error('LUA: get AIRSPEED_CRUISE failed')
end
value = param:get('ARSPD_FBW_MIN')
if value then