mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_Scripting: restored corrected boolean in height_amsl binding
This commit is contained in:
parent
eac02acef8
commit
262163eb0f
@ -1500,8 +1500,9 @@ function terrain:height_terrain_difference_home(extrapolate) end
|
|||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
---@param loc Location_ud
|
---@param loc Location_ud
|
||||||
|
---@param corrected boolean
|
||||||
---@return number|nil
|
---@return number|nil
|
||||||
function terrain:height_amsl(loc) end
|
function terrain:height_amsl(loc, corrected) end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
---@return integer
|
---@return integer
|
||||||
|
@ -176,7 +176,7 @@ singleton AP_Terrain alias terrain
|
|||||||
singleton AP_Terrain method enabled boolean
|
singleton AP_Terrain method enabled boolean
|
||||||
singleton AP_Terrain enum TerrainStatusDisabled TerrainStatusUnhealthy TerrainStatusOK
|
singleton AP_Terrain enum TerrainStatusDisabled TerrainStatusUnhealthy TerrainStatusOK
|
||||||
singleton AP_Terrain method status uint8_t
|
singleton AP_Terrain method status uint8_t
|
||||||
singleton AP_Terrain method height_amsl boolean Location float'Null
|
singleton AP_Terrain method height_amsl boolean Location float'Null boolean
|
||||||
singleton AP_Terrain method height_terrain_difference_home boolean float'Null boolean
|
singleton AP_Terrain method height_terrain_difference_home boolean float'Null boolean
|
||||||
singleton AP_Terrain method height_above_terrain boolean float'Null boolean
|
singleton AP_Terrain method height_above_terrain boolean float'Null boolean
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user