mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-18 00:08:22 +08:00
msg: Add EKF solution status flags to estimator status message
This commit is contained in:
committed by
Lorenz Meier
parent
b6d69ca3aa
commit
fa47569aa5
@@ -65,3 +65,16 @@ float32 pos_test_ratio # ratio of the largest horizontal position innovation com
|
||||
float32 hgt_test_ratio # ratio of the vertical position innovation to the innovation test limit
|
||||
float32 tas_test_ratio # ratio of the true airspeed innovation to the innovation test limit
|
||||
float32 hagl_test_ratio # ratio of the height above ground innovation to the innovation test limit
|
||||
uint16 solution_status_flags # Bitmask indicating which filter kinematic state outputs are valid for flight control use.
|
||||
# 0 - True if the attitude estimate is good
|
||||
# 1 - True if the horizontal velocity estimate is good
|
||||
# 2 - True if the vertical velocity estimate is good
|
||||
# 3 - True if the horizontal position (relative) estimate is good
|
||||
# 4 - True if the horizontal position (absolute) estimate is good
|
||||
# 5 - True if the vertical position (absolute) estimate is good
|
||||
# 6 - True if the vertical position (above ground) estimate is good
|
||||
# 7 - True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)
|
||||
# 8 - True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate
|
||||
# 9 - True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate
|
||||
# 10 - True if the EKF has detected a GPS glitch
|
||||
|
||||
|
||||
Reference in New Issue
Block a user