AP_NavEKF: Add public method to report available output data

This commit is contained in:
priseborough 2014-11-14 16:22:16 +11:00 committed by Andrew Tridgell
parent 5532750a99
commit 083e22966c
2 changed files with 37 additions and 0 deletions

View File

@ -4465,4 +4465,27 @@ void NavEKF::getFilterTimeouts(uint8_t &timeouts) const
magTimeout<<3);
}
/*
return filter function status as a bitmasked integer
0 = attitude estimate valid
1 = horizontal velocity estimate valid
2 = vertical velocity estimate valid
3 = relative horizontal position estimate valid
4 = absolute horizontal position estimate valid
5 = vertical position estimate valid
6 = terrain height estimate valid
7 = unassigned
*/
void NavEKF::getFilterStatus(uint8_t &status) const
{
// add code to set bits using private filter data here
status = (!state.quat.is_nan()<<0 |
!(velTimeout && posTimeout)<<1 |
!((velTimeout && hgtTimeout) || (hgtTimeout && _fusionModeGPS > 0))<<2 |
(gpsInhibitMode == 2 && (imuSampleTime_ms - flowMeaTime_ms) < 1000)<<3 |
!posTimeout<<4 |
!hgtTimeout<<5 |
!inhibitGndState<<6);
}
#endif // HAL_CPU_CLASS

View File

@ -197,6 +197,19 @@ public:
*/
void getFilterTimeouts(uint8_t &timeouts) const;
/*
return filter function status as a bitmasked integer
0 = attitude estimate valid
1 = horizontal velocity estimate valid
2 = vertical velocity estimate valid
3 = relative horizontal position estimate valid
4 = absolute horizontal position estimate valid
5 = vertical position estimate valid
6 = terrain height estimate valid
7 = unassigned
*/
void getFilterStatus(uint8_t &status) const;
static const struct AP_Param::GroupInfo var_info[];
private:
@ -546,6 +559,7 @@ private:
float firstArmPosD; // vertical position at the first arming (transition from sttatic mode) after start up
bool firstArmComplete; // true when first transition out of static mode has been performed after start up
bool finalMagYawInit; // true when the final post takeoff initialisation of earth field and yaw angle has been performed
bool flowTimeout; // true when optical flow measurements have time out
// Used by smoothing of state corrections
float gpsIncrStateDelta[10]; // vector of corrections to attitude, velocity and position to be applied over the period between the current and next GPS measurement