AP_NavEKF2: correct comments on getFilterFaults and getFilterTimeouts methods

This commit is contained in:
Peter Barker 2020-06-29 21:10:41 +10:00 committed by Andrew Tridgell
parent 741520d598
commit 081c0bbfe0
4 changed files with 15 additions and 15 deletions

View File

@ -1333,9 +1333,9 @@ void NavEKF2::setTerrainHgtStable(bool val)
1 = velocities are NaN 1 = velocities are NaN
2 = badly conditioned X magnetometer fusion 2 = badly conditioned X magnetometer fusion
3 = badly conditioned Y magnetometer fusion 3 = badly conditioned Y magnetometer fusion
5 = badly conditioned Z magnetometer fusion 4 = badly conditioned Z magnetometer fusion
6 = badly conditioned airspeed fusion 5 = badly conditioned airspeed fusion
7 = badly conditioned synthetic sideslip fusion 6 = badly conditioned synthetic sideslip fusion
7 = filter is not initialised 7 = filter is not initialised
*/ */
void NavEKF2::getFilterFaults(int8_t instance, uint16_t &faults) const void NavEKF2::getFilterFaults(int8_t instance, uint16_t &faults) const
@ -1354,10 +1354,10 @@ void NavEKF2::getFilterFaults(int8_t instance, uint16_t &faults) const
1 = velocity measurement timeout 1 = velocity measurement timeout
2 = height measurement timeout 2 = height measurement timeout
3 = magnetometer measurement timeout 3 = magnetometer measurement timeout
4 = unassigned
5 = unassigned 5 = unassigned
6 = unassigned 6 = unassigned
7 = unassigned 7 = unassigned
7 = unassigned
*/ */
void NavEKF2::getFilterTimeouts(int8_t instance, uint8_t &timeouts) const void NavEKF2::getFilterTimeouts(int8_t instance, uint8_t &timeouts) const
{ {

View File

@ -256,9 +256,9 @@ public:
1 = velocities are NaN 1 = velocities are NaN
2 = badly conditioned X magnetometer fusion 2 = badly conditioned X magnetometer fusion
3 = badly conditioned Y magnetometer fusion 3 = badly conditioned Y magnetometer fusion
5 = badly conditioned Z magnetometer fusion 4 = badly conditioned Z magnetometer fusion
6 = badly conditioned airspeed fusion 5 = badly conditioned airspeed fusion
7 = badly conditioned synthetic sideslip fusion 6 = badly conditioned synthetic sideslip fusion
7 = filter is not initialised 7 = filter is not initialised
*/ */
void getFilterFaults(int8_t instance, uint16_t &faults) const; void getFilterFaults(int8_t instance, uint16_t &faults) const;
@ -270,10 +270,10 @@ public:
1 = velocity measurement timeout 1 = velocity measurement timeout
2 = height measurement timeout 2 = height measurement timeout
3 = magnetometer measurement timeout 3 = magnetometer measurement timeout
4 = unassigned
5 = unassigned 5 = unassigned
6 = unassigned 6 = unassigned
7 = unassigned 7 = unassigned
7 = unassigned
*/ */
void getFilterTimeouts(int8_t instance, uint8_t &timeouts) const; void getFilterTimeouts(int8_t instance, uint8_t &timeouts) const;

View File

@ -484,9 +484,9 @@ return the filter fault status as a bitmasked integer
1 = velocities are NaN 1 = velocities are NaN
2 = badly conditioned X magnetometer fusion 2 = badly conditioned X magnetometer fusion
3 = badly conditioned Y magnetometer fusion 3 = badly conditioned Y magnetometer fusion
5 = badly conditioned Z magnetometer fusion 4 = badly conditioned Z magnetometer fusion
6 = badly conditioned airspeed fusion 5 = badly conditioned airspeed fusion
7 = badly conditioned synthetic sideslip fusion 6 = badly conditioned synthetic sideslip fusion
7 = filter is not initialised 7 = filter is not initialised
*/ */
void NavEKF2_core::getFilterFaults(uint16_t &faults) const void NavEKF2_core::getFilterFaults(uint16_t &faults) const
@ -645,4 +645,4 @@ bool NavEKF2_core::getDataEKFGSF(float &yaw_composite, float &yaw_composite_vari
return yawEstimator->getLogData(yaw_composite, yaw_composite_variance, yaw, innov_VN, innov_VE, weight); return yawEstimator->getLogData(yaw_composite, yaw_composite_variance, yaw, innov_VN, innov_VE, weight);
} }
return false; return false;
} }

View File

@ -246,9 +246,9 @@ public:
1 = velocities are NaN 1 = velocities are NaN
2 = badly conditioned X magnetometer fusion 2 = badly conditioned X magnetometer fusion
3 = badly conditioned Y magnetometer fusion 3 = badly conditioned Y magnetometer fusion
5 = badly conditioned Z magnetometer fusion 4 = badly conditioned Z magnetometer fusion
6 = badly conditioned airspeed fusion 5 = badly conditioned airspeed fusion
7 = badly conditioned synthetic sideslip fusion 6 = badly conditioned synthetic sideslip fusion
7 = filter is not initialised 7 = filter is not initialised
*/ */
void getFilterFaults(uint16_t &faults) const; void getFilterFaults(uint16_t &faults) const;