Browse Source

AP_NavEKF2: correct comments on getFilterFaults and getFilterTimeouts methods

zr-v5.1
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
081c0bbfe0
  1. 8
      libraries/AP_NavEKF2/AP_NavEKF2.cpp
  2. 8
      libraries/AP_NavEKF2/AP_NavEKF2.h
  3. 8
      libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp
  4. 6
      libraries/AP_NavEKF2/AP_NavEKF2_core.h

8
libraries/AP_NavEKF2/AP_NavEKF2.cpp

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

8
libraries/AP_NavEKF2/AP_NavEKF2.h

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

8
libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp

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

6
libraries/AP_NavEKF2/AP_NavEKF2_core.h

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

Loading…
Cancel
Save