AP_NavEKF: minor comment fix

No functional change
This commit is contained in:
Randy Mackay 2015-09-24 15:23:20 +09:00
parent 51fb13a329
commit b5c49e0792
2 changed files with 11 additions and 10 deletions

View File

@ -4516,8 +4516,9 @@ Quaternion NavEKF::calcQuatAndFieldStates(float roll, float pitch)
// store the yaw change so that it can be retrieved externally for use by the control loops to prevent yaw disturbances following a reset
Vector3f tempEuler;
state.quat.to_euler(tempEuler.x, tempEuler.y, tempEuler.z);
// this check ensures we accumulate the resets that occur within a single iteration of the EKF
if (imuSampleTime_ms != lastYawReset_ms) {
yawResetAngle = 0;
yawResetAngle = 0.0f;
}
yawResetAngle += wrap_PI(yaw - tempEuler.z);
lastYawReset_ms = imuSampleTime_ms;
@ -4877,9 +4878,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 NavEKF::getFilterFaults(uint8_t &faults) const
@ -5400,7 +5401,7 @@ void NavEKF::alignMagStateDeclination()
}
// return the amount of yaw angle change due to the last yaw angle reset in radians
// returns the system time at which the yaw angle was reset
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
uint32_t NavEKF::getLastYawResetAngle(float &yawAng)
{
yawAng = yawResetAngle;

View File

@ -225,9 +225,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(uint8_t &faults) const;
@ -238,10 +238,10 @@ public:
1 = velocity measurement timeout
2 = height measurement timeout
3 = magnetometer measurement timeout
4 = true airspeed measurement timeout
5 = unassigned
6 = unassigned
7 = unassigned
7 = unassigned
*/
void getFilterTimeouts(uint8_t &timeouts) const;
@ -259,7 +259,7 @@ public:
bool getHeightControlLimit(float &height) const;
// return the amount of yaw angle change due to the last yaw angle reset in radians
// returns the system time at which the yaw angle was reset
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
uint32_t getLastYawResetAngle(float &yawAng);
// report any reason for why the backend is refusing to initialise