mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_Scripting: bindings: get_alt_frame included
bindings.desc + docs.lua: get_alt_frame included
This commit is contained in:
parent
7f4c12dc28
commit
a7d5f8addc
@ -758,6 +758,14 @@ function Location_ud:lat() end
|
|||||||
---@param value integer
|
---@param value integer
|
||||||
function Location_ud:lat(value) end
|
function Location_ud:lat(value) end
|
||||||
|
|
||||||
|
-- get altitude frame
|
||||||
|
---@return integer
|
||||||
|
---| '0' # ABSOLUTE
|
||||||
|
---| '1' # ABOVE_HOME
|
||||||
|
---| '2' # ABOVE_ORIGIN
|
||||||
|
---| '3' # ABOVE_TERRAIN
|
||||||
|
function Location_ud:get_alt_frame() end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
---@param desired_frame integer
|
---@param desired_frame integer
|
||||||
---| '0' # ABSOLUTE
|
---| '0' # ABSOLUTE
|
||||||
|
@ -18,10 +18,10 @@ userdata Location method get_vector_from_origin_NEU boolean Vector3f'Null
|
|||||||
userdata Location method get_bearing float Location
|
userdata Location method get_bearing float Location
|
||||||
userdata Location method get_distance_NED Vector3f Location
|
userdata Location method get_distance_NED Vector3f Location
|
||||||
userdata Location method get_distance_NE Vector2f Location
|
userdata Location method get_distance_NE Vector2f Location
|
||||||
|
userdata Location method get_alt_frame uint8_t
|
||||||
userdata Location method change_alt_frame boolean Location::AltFrame'enum Location::AltFrame::ABSOLUTE Location::AltFrame::ABOVE_TERRAIN
|
userdata Location method change_alt_frame boolean Location::AltFrame'enum Location::AltFrame::ABSOLUTE Location::AltFrame::ABOVE_TERRAIN
|
||||||
userdata Location method copy Location
|
userdata Location method copy Location
|
||||||
|
|
||||||
|
|
||||||
include AP_AHRS/AP_AHRS.h
|
include AP_AHRS/AP_AHRS.h
|
||||||
|
|
||||||
singleton AP_AHRS rename ahrs
|
singleton AP_AHRS rename ahrs
|
||||||
|
Loading…
Reference in New Issue
Block a user