Skip to content

Commit

Permalink
AP_Scripting: add handle_external_position_estimate binding
Browse files Browse the repository at this point in the history
can be used for offboard navigation systems
  • Loading branch information
tridge committed Jun 8, 2024
1 parent c783f63 commit d7764c5
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 0 deletions.
7 changes: 7 additions & 0 deletions libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -3136,6 +3136,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 -- estimated location, altitude is ignored
---@param accuracy number -- 1-sigma accuracy in meters
---@param timestamp_ms uint32_t -- 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
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down

0 comments on commit d7764c5

Please sign in to comment.