mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Scripting: convert ALT_HOLD_RTL to RTL_ALTITUDE
This commit is contained in:
parent
5147ccd4e1
commit
a0c2f5eadb
@ -65,7 +65,7 @@ SHIP_AUTO_OFS = bind_add_param('AUTO_OFS', 3, 0)
|
|||||||
|
|
||||||
-- other parameters
|
-- other parameters
|
||||||
RCMAP_THROTTLE = bind_param("RCMAP_THROTTLE")
|
RCMAP_THROTTLE = bind_param("RCMAP_THROTTLE")
|
||||||
ALT_HOLD_RTL = bind_param("ALT_HOLD_RTL")
|
RTL_ALTITUDE = bind_param("RTL_ALTITUDE")
|
||||||
Q_RTL_ALT = bind_param("Q_RTL_ALT")
|
Q_RTL_ALT = bind_param("Q_RTL_ALT")
|
||||||
AIRSPEED_CRUISE = bind_param("AIRSPEED_CRUISE")
|
AIRSPEED_CRUISE = bind_param("AIRSPEED_CRUISE")
|
||||||
TECS_LAND_ARSPD = bind_param("TECS_LAND_ARSPD")
|
TECS_LAND_ARSPD = bind_param("TECS_LAND_ARSPD")
|
||||||
@ -347,7 +347,7 @@ end
|
|||||||
function get_target_alt()
|
function get_target_alt()
|
||||||
local base_alt = target_pos:alt() * 0.01
|
local base_alt = target_pos:alt() * 0.01
|
||||||
if landing_stage == STAGE_HOLDOFF then
|
if landing_stage == STAGE_HOLDOFF then
|
||||||
return base_alt + ALT_HOLD_RTL:get() * 0.01
|
return base_alt + RTL_ALTITUDE:get()
|
||||||
end
|
end
|
||||||
return base_alt + Q_RTL_ALT:get()
|
return base_alt + Q_RTL_ALT:get()
|
||||||
end
|
end
|
||||||
|
Loading…
Reference in New Issue
Block a user