Browse Source

AP_NavEKF2: fixed typos

master
Arjun Vinod 6 years ago committed by Peter Barker
parent
commit
78b165e36f
  1. 8
      libraries/AP_NavEKF2/AP_NavEKF2_AirDataFusion.cpp
  2. 10
      libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp
  3. 4
      libraries/AP_NavEKF2/AP_NavEKF2_OptFlowFusion.cpp
  4. 2
      libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp
  5. 2
      libraries/AP_NavEKF2/AP_NavEKF2_RngBcnFusion.cpp
  6. 2
      libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp
  7. 2
      libraries/AP_NavEKF2/AP_NavEKF2_core.h

8
libraries/AP_NavEKF2/AP_NavEKF2_AirDataFusion.cpp

@ -130,7 +130,7 @@ void NavEKF2_core::FuseAirspeed()
lastTasPassTime_ms = imuSampleTime_ms; lastTasPassTime_ms = imuSampleTime_ms;
// zero the attitude error state - by definition it is assumed to be zero before each observaton fusion // zero the attitude error state - by definition it is assumed to be zero before each observation fusion
stateStruct.angErr.zero(); stateStruct.angErr.zero();
// correct the state vector // correct the state vector
@ -178,7 +178,7 @@ void NavEKF2_core::FuseAirspeed()
} }
} }
// force the covariance matrix to me symmetrical and limit the variances to prevent ill-conditioning. // force the covariance matrix to be symmetrical and limit the variances to prevent ill-conditioning.
ForceSymmetry(); ForceSymmetry();
ConstrainVariances(); ConstrainVariances();
@ -244,7 +244,7 @@ void NavEKF2_core::SelectBetaFusion()
} }
/* /*
* Fuse sythetic sideslip measurement of zero using explicit algebraic equations generated with Matlab symbolic toolbox. * Fuse synthetic sideslip measurement of zero using explicit algebraic equations generated with Matlab symbolic toolbox.
* The script file used to generate these and other equations in this filter can be found here: * The script file used to generate these and other equations in this filter can be found here:
* https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m * https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
*/ */
@ -378,7 +378,7 @@ void NavEKF2_core::FuseSideslip()
return; return;
} }
// zero the attitude error state - by definition it is assumed to be zero before each observaton fusion // zero the attitude error state - by definition it is assumed to be zero before each observation fusion
stateStruct.angErr.zero(); stateStruct.angErr.zero();
// correct the state vector // correct the state vector

10
libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp

@ -232,7 +232,7 @@ void NavEKF2_core::SelectMagFusion()
// start performance timer // start performance timer
hal.util->perf_begin(_perf_FuseMagnetometer); hal.util->perf_begin(_perf_FuseMagnetometer);
// clear the flag that lets other processes know that the expensive magnetometer fusion operation has been perfomred on that time step // clear the flag that lets other processes know that the expensive magnetometer fusion operation has been performed on that time step
// used for load levelling // used for load levelling
magFusePerformed = false; magFusePerformed = false;
@ -717,7 +717,7 @@ void NavEKF2_core::FuseMagnetometer()
ConstrainVariances(); ConstrainVariances();
// update the states // update the states
// zero the attitude error state - by definition it is assumed to be zero before each observaton fusion // zero the attitude error state - by definition it is assumed to be zero before each observation fusion
stateStruct.angErr.zero(); stateStruct.angErr.zero();
// correct the state vector // correct the state vector
@ -821,7 +821,7 @@ void NavEKF2_core::fuseEulerYaw()
measured_yaw = predicted_yaw; measured_yaw = predicted_yaw;
} }
} else { } else {
// calculate observaton jacobian when we are observing a rotation in a 312 sequence // calculate observation jacobian when we are observing a rotation in a 312 sequence
float t2 = q0*q0; float t2 = q0*q0;
float t3 = q1*q1; float t3 = q1*q1;
float t4 = q2*q2; float t4 = q2*q2;
@ -964,7 +964,7 @@ void NavEKF2_core::fuseEulerYaw()
ForceSymmetry(); ForceSymmetry();
ConstrainVariances(); ConstrainVariances();
// zero the attitude error state - by definition it is assumed to be zero before each observaton fusion // zero the attitude error state - by definition it is assumed to be zero before each observation fusion
stateStruct.angErr.zero(); stateStruct.angErr.zero();
// correct the state vector // correct the state vector
@ -1094,7 +1094,7 @@ void NavEKF2_core::FuseDeclination(float declErr)
ForceSymmetry(); ForceSymmetry();
ConstrainVariances(); ConstrainVariances();
// zero the attitude error state - by definition it is assumed to be zero before each observaton fusion // zero the attitude error state - by definition it is assumed to be zero before each observation fusion
stateStruct.angErr.zero(); stateStruct.angErr.zero();
// correct the state vector // correct the state vector

4
libraries/AP_NavEKF2/AP_NavEKF2_OptFlowFusion.cpp

@ -573,7 +573,7 @@ void NavEKF2_core::FuseOptFlow()
float t61 = R_LOS+t28+t39+t44+t55-t70-t79-t86; float t61 = R_LOS+t28+t39+t44+t55-t70-t79-t86;
float t62 = 1.0f/t61; float t62 = 1.0f/t61;
// calculate innovation variance for X axis observation and protect against a badly conditioned calculation // calculate innovation variance for Y axis observation and protect against a badly conditioned calculation
if (t61 > R_LOS) { if (t61 > R_LOS) {
t62 = 1.0f/t61; t62 = 1.0f/t61;
faultStatus.bad_yflow = false; faultStatus.bad_yflow = false;
@ -683,7 +683,7 @@ void NavEKF2_core::FuseOptFlow()
ForceSymmetry(); ForceSymmetry();
ConstrainVariances(); ConstrainVariances();
// zero the attitude error state - by definition it is assumed to be zero before each observaton fusion // zero the attitude error state - by definition it is assumed to be zero before each observation fusion
stateStruct.angErr.zero(); stateStruct.angErr.zero();
// correct the state vector // correct the state vector

2
libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp

@ -714,7 +714,7 @@ void NavEKF2_core::FuseVelPosNED()
ConstrainVariances(); ConstrainVariances();
// update the states // update the states
// zero the attitude error state - by definition it is assumed to be zero before each observaton fusion // zero the attitude error state - by definition it is assumed to be zero before each observation fusion
stateStruct.angErr.zero(); stateStruct.angErr.zero();
// calculate state corrections and re-normalise the quaternions for states predicted using the blended IMU data // calculate state corrections and re-normalise the quaternions for states predicted using the blended IMU data

2
libraries/AP_NavEKF2/AP_NavEKF2_RngBcnFusion.cpp

@ -215,7 +215,7 @@ void NavEKF2_core::FuseRngBcn()
ConstrainVariances(); ConstrainVariances();
// update the states // update the states
// zero the attitude error state - by definition it is assumed to be zero before each observaton fusion // zero the attitude error state - by definition it is assumed to be zero before each observation fusion
stateStruct.angErr.zero(); stateStruct.angErr.zero();
// correct the state vector // correct the state vector

2
libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp

@ -47,7 +47,7 @@ bool NavEKF2_core::calcGpsGoodToAlign(void)
// This check can only be used when the vehicle is stationary // This check can only be used when the vehicle is stationary
const struct Location &gpsloc = gps.location(); // Current location const struct Location &gpsloc = gps.location(); // Current location
const float posFiltTimeConst = 10.0f; // time constant used to decay position drift const float posFiltTimeConst = 10.0f; // time constant used to decay position drift
// calculate time lapsesd since last update and limit to prevent numerical errors // calculate time lapsed since last update and limit to prevent numerical errors
float deltaTime = constrain_float(float(imuDataDelayed.time_ms - lastPreAlignGpsCheckTime_ms)*0.001f,0.01f,posFiltTimeConst); float deltaTime = constrain_float(float(imuDataDelayed.time_ms - lastPreAlignGpsCheckTime_ms)*0.001f,0.01f,posFiltTimeConst);
lastPreAlignGpsCheckTime_ms = imuDataDelayed.time_ms; lastPreAlignGpsCheckTime_ms = imuDataDelayed.time_ms;
// Sum distance moved // Sum distance moved

2
libraries/AP_NavEKF2/AP_NavEKF2_core.h

@ -618,7 +618,7 @@ private:
// force alignment of the yaw angle using GPS velocity data // force alignment of the yaw angle using GPS velocity data
void realignYawGPS(); void realignYawGPS();
// initialise the earth magnetic field states using declination and current attitude and magnetometer meaasurements // initialise the earth magnetic field states using declination and current attitude and magnetometer measurements
// and return attitude quaternion // and return attitude quaternion
Quaternion calcQuatAndFieldStates(float roll, float pitch); Quaternion calcQuatAndFieldStates(float roll, float pitch);

Loading…
Cancel
Save