Skip to content

Commit

Permalink
AP_NavEKF: add enumeration to document EKF SolutionStatus
Browse files Browse the repository at this point in the history
this isn't used for anything but documenting the solution status field, which can be used in the Wiki and in various log analysis tools
  • Loading branch information
peterbarker authored and tridge committed Nov 4, 2024
1 parent 44375f2 commit de0f3dd
Showing 1 changed file with 24 additions and 0 deletions.
24 changes: 24 additions & 0 deletions libraries/AP_NavEKF/AP_Nav_Common.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,30 @@
#include <stdint.h>
#include <AP_Math/AP_Math.h>

// enumeration corresponding to buts within nav_filter_status union.
// Only used for documentation purposes.
enum class NavFilterStatusBit {
ATTITUDE = 1, // attitude estimate valid
HORIZ_VEL = 2, // horizontal velocity estimate valid
VERT_VEL = 4, // vertical velocity estimate valid
HORIZ_POS_REL = 8, // relative horizontal position estimate valid
HORIZ_POS_ABS = 16, // absolute horizontal position estimate valid
VERT_POS = 32, // vertical position estimate valid
TERRAIN_ALT = 64, // terrain height estimate valid
CONST_POS_MODE = 128, // in constant position mode
PRED_HORIZ_POS_REL = 256, // expected good relative horizontal position estimate - used before takeoff
PRED_HORIZ_POS_ABS = 512, // expected good absolute horizontal position estimate - used before takeoff
TAKEOFF_DETECTED = 1024, // optical flow takeoff has been detected
TAKEOFF_EXPECTED = 2048, // compensating for baro errors during takeoff
TOUCHDOWN_EXPECTED = 4096, // compensating for baro errors during touchdown
USING_GPS = 8192, // using GPS position
GPS_GLITCHING = 16384, // GPS glitching is affecting navigation accuracy
GPS_QUALITY_GOOD = 32768, // can use GPS for navigation
INITALIZED = 65536, // has ever been healthy
REJECTING_AIRSPEED = 131072, // rejecting airspeed data
DEAD_RECKONING = 262144, // dead reckoning (e.g. no position or velocity source)
};

union nav_filter_status {
struct {
bool attitude : 1; // 0 - true if attitude estimate is valid
Expand Down

0 comments on commit de0f3dd

Please sign in to comment.