mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
AP_Scripting: add bindings for ahrs.wind_alignment and ahrs.head_wind
This commit is contained in:
parent
39e7209e33
commit
47fdf2295c
@ -3008,6 +3008,18 @@ function ahrs:groundspeed_vector() end
|
|||||||
---@return Vector3f_ud
|
---@return Vector3f_ud
|
||||||
function ahrs:wind_estimate() end
|
function ahrs:wind_estimate() end
|
||||||
|
|
||||||
|
-- Determine how aligned heading_deg is with the wind. Return result
|
||||||
|
-- is 1.0 when perfectly aligned heading into wind, -1 when perfectly
|
||||||
|
-- aligned with-wind, and zero when perfect cross-wind. There is no
|
||||||
|
-- distinction between a left or right cross-wind. Wind speed is ignored
|
||||||
|
---@param heading_deg number
|
||||||
|
---@return number
|
||||||
|
function ahrs:wind_alignment(heading_deg) end
|
||||||
|
|
||||||
|
-- Forward head-wind component in m/s. Negative means tail-wind
|
||||||
|
---@return number
|
||||||
|
function ahrs:head_wind() end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
---@return number|nil
|
---@return number|nil
|
||||||
function ahrs:get_hagl() end
|
function ahrs:get_hagl() end
|
||||||
|
@ -38,6 +38,8 @@ singleton AP_AHRS method get_gyro Vector3f
|
|||||||
singleton AP_AHRS method get_accel Vector3f
|
singleton AP_AHRS method get_accel Vector3f
|
||||||
singleton AP_AHRS method get_hagl boolean float'Null
|
singleton AP_AHRS method get_hagl boolean float'Null
|
||||||
singleton AP_AHRS method wind_estimate Vector3f
|
singleton AP_AHRS method wind_estimate Vector3f
|
||||||
|
singleton AP_AHRS method wind_alignment float'skip_check float'skip_check
|
||||||
|
singleton AP_AHRS method head_wind float'skip_check
|
||||||
singleton AP_AHRS method groundspeed_vector Vector2f
|
singleton AP_AHRS method groundspeed_vector Vector2f
|
||||||
singleton AP_AHRS method get_velocity_NED boolean Vector3f'Null
|
singleton AP_AHRS method get_velocity_NED boolean Vector3f'Null
|
||||||
singleton AP_AHRS method get_relative_position_NED_home boolean Vector3f'Null
|
singleton AP_AHRS method get_relative_position_NED_home boolean Vector3f'Null
|
||||||
|
Loading…
Reference in New Issue
Block a user