AP_NavEKF: add pred_horiz_pos flags to filter status

This commit is contained in:
Randy Mackay 2015-01-05 14:10:37 +09:00 committed by Andrew Tridgell
parent 54cff29fc2
commit 657afcfe7a
2 changed files with 13 additions and 9 deletions

View File

@ -4503,6 +4503,8 @@ void NavEKF::getFilterStatus(nav_filter_status &status) const
status.flags.vert_pos = !hgtTimeout; // vertical position estimate valid status.flags.vert_pos = !hgtTimeout; // vertical position estimate valid
status.flags.terrain_alt = gndOffsetValid; // terrain height estimate valid status.flags.terrain_alt = gndOffsetValid; // terrain height estimate valid
status.flags.const_pos_mode = constPosMode; // constant position mode status.flags.const_pos_mode = constPosMode; // constant position mode
status.flags.pred_horiz_pos_rel = status.flags.horiz_pos_rel;
status.flags.pred_horiz_pos_abs = status.flags.horiz_pos_abs;
} }
// Check arm status and perform required checks and mode changes // Check arm status and perform required checks and mode changes

View File

@ -21,16 +21,18 @@
union nav_filter_status { union nav_filter_status {
struct { struct {
uint8_t attitude : 1; // 0 - true if attitude estimate is valid uint16_t attitude : 1; // 0 - true if attitude estimate is valid
uint8_t horiz_vel : 1; // 1 - true if horizontal velocity estimate is valid uint16_t horiz_vel : 1; // 1 - true if horizontal velocity estimate is valid
uint8_t vert_vel : 1; // 2 - true if the vertical velocity estimate is valid uint16_t vert_vel : 1; // 2 - true if the vertical velocity estimate is valid
uint8_t horiz_pos_rel : 1; // 3 - true if the relative horizontal position estimate is valid uint16_t horiz_pos_rel : 1; // 3 - true if the relative horizontal position estimate is valid
uint8_t horiz_pos_abs : 1; // 4 - true if the absolute horizontal position estimate is valid uint16_t horiz_pos_abs : 1; // 4 - true if the absolute horizontal position estimate is valid
uint8_t vert_pos : 1; // 5 - true if the vertical position estimate is valid uint16_t vert_pos : 1; // 5 - true if the vertical position estimate is valid
uint8_t terrain_alt : 1; // 6 - true if the terrain height estimate is valid uint16_t terrain_alt : 1; // 6 - true if the terrain height estimate is valid
uint8_t const_pos_mode : 1; // 7 - true if we are in const position mode uint16_t const_pos_mode : 1; // 7 - true if we are in const position mode
uint16_t pred_horiz_pos_rel : 1; // 8 - true if filter expects it can produce a good relative horizontal position estimate - used before takeoff
uint16_t pred_horiz_pos_abs : 1; // 9 - true if filter expects it can produce a good absolute horizontal position estimate - used before takeoff
} flags; } flags;
uint8_t value; uint16_t value;
}; };
#endif // AP_Nav_Common #endif // AP_Nav_Common