mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: use SourceSetSelection enum class
This commit is contained in:
parent
f58d88d144
commit
29b9157a20
|
@ -3285,6 +3285,9 @@ function ahrs:get_vel_innovations_and_variances_for_source(source) end
|
|||
|
||||
-- desc
|
||||
---@param source_set_idx integer
|
||||
---| '0' # PRIMARY
|
||||
---| '1' # SECONDARY
|
||||
---| '2' # TERTIARY
|
||||
function ahrs:set_posvelyaw_source_set(source_set_idx) end
|
||||
|
||||
-- desc
|
||||
|
|
|
@ -53,7 +53,7 @@ singleton AP_AHRS method earth_to_body Vector3f Vector3f
|
|||
singleton AP_AHRS method body_to_earth Vector3f Vector3f
|
||||
singleton AP_AHRS method get_EAS2TAS float
|
||||
singleton AP_AHRS method get_variances boolean float'Null float'Null float'Null Vector3f'Null float'Null
|
||||
singleton AP_AHRS method set_posvelyaw_source_set void uint8_t 0 2
|
||||
singleton AP_AHRS method set_posvelyaw_source_set void AP_NavEKF_Source::SourceSetSelection'enum AP_NavEKF_Source::SourceSetSelection::PRIMARY AP_NavEKF_Source::SourceSetSelection::TERTIARY
|
||||
singleton AP_AHRS method get_vel_innovations_and_variances_for_source boolean uint8_t 3 6 Vector3f'Null Vector3f'Null
|
||||
singleton AP_AHRS method set_home boolean Location
|
||||
singleton AP_AHRS method get_origin boolean Location'Null
|
||||
|
|
Loading…
Reference in New Issue