AP_NavEKF2: update function name

The primary purpose of this function is re-alignment
This commit is contained in:
Paul Riseborough 2016-05-21 11:13:03 +10:00 committed by Andrew Tridgell
parent addd213af0
commit 64a8153b68
2 changed files with 4 additions and 4 deletions

View File

@ -60,7 +60,7 @@ void NavEKF2_core::controlMagYawReset()
// In-Flight reset for vehicles that can use a zero sideslip assumption (Planes)
// this is done to protect against unrecoverable heading alignment errors due to compass faults
if (!firstMagYawInit && assume_zero_sideslip() && inFlight) {
alignYawGPS();
realignYawGPS();
firstMagYawInit = true;
}
@ -74,9 +74,9 @@ void NavEKF2_core::controlMagYawReset()
}
// this function is used to do a forced alignment of the yaw angle to align with the horizontal velocity
// this function is used to do a forced re-alignment of the yaw angle to align with the horizontal velocity
// vector from GPS. It is used to align the yaw angle after launch or takeoff.
void NavEKF2_core::alignYawGPS()
void NavEKF2_core::realignYawGPS()
{
// get quaternion from existing filter states and calculate roll, pitch and yaw angles
Vector3f eulerAngles;

View File

@ -502,7 +502,7 @@ private:
void SelectBetaFusion();
// force alignment of the yaw angle using GPS velocity data
void alignYawGPS();
void realignYawGPS();
// initialise the earth magnetic field states using declination and current attitude and magnetometer meaasurements
// and return attitude quaternion