AP_NavEKF: Change misnomer (NFC)

This commit is contained in:
murata 2021-03-11 06:43:50 +09:00 committed by Peter Barker
parent a5b6ce9220
commit 0536be1c88
4 changed files with 8 additions and 8 deletions

View File

@ -49,8 +49,8 @@ end
states(1:3) = 0;
states = states - Kfusion * innovation;
% the first 3 states represent the angular misalignment vector. This is
% is used to correct the estimate quaternion
% the first 3 states represent the angular misalignment vector.
% This is used to correct the estimate quaternion
% Convert the error rotation vector to its equivalent quaternion
% error = truth - estimate
rotationMag = sqrt(states(1)^2 + states(2)^2 + states(3)^2);

View File

@ -37,8 +37,8 @@ for obsIndex = 1:3
% Store tilt error estimate for external monitoring
angErrVec = angErrVec + states(1:3);
% the first 3 states represent the angular misalignment vector. This is
% is used to correct the estimated quaternion
% the first 3 states represent the angular misalignment vector.
% This is used to correct the estimated quaternion
% Convert the error rotation vector to its equivalent quaternion
% truth = estimate + error
rotationMag = sqrt(states(1)^2 + states(2)^2 + states(3)^2);

View File

@ -48,8 +48,8 @@ end
states(1:3) = 0;
states = states - Kfusion * innovation;
% the first 3 states represent the angular misalignment vector. This is
% is used to correct the estimate quaternion
% the first 3 states represent the angular misalignment vector.
% This is used to correct the estimate quaternion
% Convert the error rotation vector to its equivalent quaternion
% error = truth - estimate
rotationMag = sqrt(states(1)^2 + states(2)^2 + states(3)^2);

View File

@ -37,8 +37,8 @@ for obsIndex = 1:3
% Store tilt error estimate for external monitoring
angErrVec = angErrVec + states(1:3);
% the first 3 states represent the angular misalignment vector. This is
% is used to correct the estimated quaternion
% the first 3 states represent the angular misalignment vector.
% This is used to correct the estimated quaternion
% Convert the error rotation vector to its equivalent quaternion
% truth = estimate + error
rotationMag = sqrt(states(1)^2 + states(2)^2 + states(3)^2);