AP_Scripting: add handle_external_position_estimate binding

can be used for offboard navigation systems
This commit is contained in:
Andrew Tridgell 2024-06-09 08:49:36 +10:00
parent adc147aba3
commit 53a4b5a843
2 changed files with 8 additions and 0 deletions

View File

@ -3251,6 +3251,13 @@ function arming:disarm() end
-- It provides estimates for the vehicles attitude, and position. -- It provides estimates for the vehicles attitude, and position.
ahrs = {} ahrs = {}
-- supply an external position estimate to the AHRS (supported by EKF3)
---@param location Location_ud -- estimated location, altitude is ignored
---@param accuracy number -- 1-sigma accuracy in meters
---@param timestamp_ms uint32_t_ud|integer|number -- timestamp of reading in ms since boot
---@return boolean -- true if call was handled successfully
function ahrs:handle_external_position_estimate(location, accuracy, timestamp_ms) end
-- desc -- desc
---@return Quaternion_ud|nil ---@return Quaternion_ud|nil
function ahrs:get_quaternion() end function ahrs:get_quaternion() end

View File

@ -61,6 +61,7 @@ singleton AP_AHRS method set_origin boolean Location
singleton AP_AHRS method initialised boolean singleton AP_AHRS method initialised boolean
singleton AP_AHRS method get_posvelyaw_source_set uint8_t singleton AP_AHRS method get_posvelyaw_source_set uint8_t
singleton AP_AHRS method get_quaternion boolean Quaternion'Null singleton AP_AHRS method get_quaternion boolean Quaternion'Null
singleton AP_AHRS method handle_external_position_estimate boolean Location float'skip_check uint32_t'skip_check
include AP_Arming/AP_Arming.h include AP_Arming/AP_Arming.h