diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 6644ba2e940d99..889ffa089dca4c 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -3251,6 +3251,13 @@ function arming:disarm() end -- It provides estimates for the vehicles attitude, and position. 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 ---@return Quaternion_ud|nil function ahrs:get_quaternion() end diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 6868e797d7899b..30b5be0c766ef4 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -61,6 +61,7 @@ singleton AP_AHRS method set_origin boolean Location singleton AP_AHRS method initialised boolean singleton AP_AHRS method get_posvelyaw_source_set uint8_t 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