mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: Change misnomer (NFC)
This commit is contained in:
parent
9abf91c86e
commit
a5b6ce9220
|
@ -128,8 +128,8 @@ void NavEKF2_core::FuseAirspeed()
|
||||||
statesArray[j] = statesArray[j] - Kfusion[j] * innovVtas;
|
statesArray[j] = statesArray[j] - Kfusion[j] * innovVtas;
|
||||||
}
|
}
|
||||||
|
|
||||||
// the first 3 states represent the angular misalignment vector. This is
|
// the first 3 states represent the angular misalignment vector.
|
||||||
// is used to correct the estimated quaternion on the current time step
|
// This is used to correct the estimated quaternion on the current time step
|
||||||
stateStruct.quat.rotate(stateStruct.angErr);
|
stateStruct.quat.rotate(stateStruct.angErr);
|
||||||
|
|
||||||
// correct the covariance P = (I - K*H)*P
|
// correct the covariance P = (I - K*H)*P
|
||||||
|
@ -370,8 +370,8 @@ void NavEKF2_core::FuseSideslip()
|
||||||
statesArray[j] = statesArray[j] - Kfusion[j] * innovBeta;
|
statesArray[j] = statesArray[j] - Kfusion[j] * innovBeta;
|
||||||
}
|
}
|
||||||
|
|
||||||
// the first 3 states represent the angular misalignment vector. This is
|
// the first 3 states represent the angular misalignment vector.
|
||||||
// is used to correct the estimated quaternion on the current time step
|
// This is used to correct the estimated quaternion on the current time step
|
||||||
stateStruct.quat.rotate(stateStruct.angErr);
|
stateStruct.quat.rotate(stateStruct.angErr);
|
||||||
|
|
||||||
// correct the covariance P = (I - K*H)*P
|
// correct the covariance P = (I - K*H)*P
|
||||||
|
|
|
@ -689,8 +689,8 @@ void NavEKF2_core::FuseMagnetometer()
|
||||||
MagTableConstrain();
|
MagTableConstrain();
|
||||||
}
|
}
|
||||||
|
|
||||||
// the first 3 states represent the angular misalignment vector. This is
|
// the first 3 states represent the angular misalignment vector.
|
||||||
// is used to correct the estimated quaternion on the current time step
|
// This is used to correct the estimated quaternion on the current time step
|
||||||
stateStruct.quat.rotate(stateStruct.angErr);
|
stateStruct.quat.rotate(stateStruct.angErr);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
|
@ -964,8 +964,8 @@ void NavEKF2_core::fuseEulerYaw()
|
||||||
statesArray[i] -= Kfusion[i] * innovation;
|
statesArray[i] -= Kfusion[i] * innovation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// the first 3 states represent the angular misalignment vector. This is
|
// the first 3 states represent the angular misalignment vector.
|
||||||
// is used to correct the estimated quaternion on the current time step
|
// This is used to correct the estimated quaternion on the current time step
|
||||||
stateStruct.quat.rotate(stateStruct.angErr);
|
stateStruct.quat.rotate(stateStruct.angErr);
|
||||||
|
|
||||||
// record fusion event
|
// record fusion event
|
||||||
|
@ -1095,8 +1095,8 @@ void NavEKF2_core::FuseDeclination(float declErr)
|
||||||
statesArray[j] = statesArray[j] - Kfusion[j] * innovation;
|
statesArray[j] = statesArray[j] - Kfusion[j] * innovation;
|
||||||
}
|
}
|
||||||
|
|
||||||
// the first 3 states represent the angular misalignment vector. This is
|
// the first 3 states represent the angular misalignment vector.
|
||||||
// is used to correct the estimated quaternion on the current time step
|
// This is used to correct the estimated quaternion on the current time step
|
||||||
stateStruct.quat.rotate(stateStruct.angErr);
|
stateStruct.quat.rotate(stateStruct.angErr);
|
||||||
|
|
||||||
// record fusion health status
|
// record fusion health status
|
||||||
|
|
|
@ -697,8 +697,8 @@ void NavEKF2_core::FuseOptFlow()
|
||||||
statesArray[j] = statesArray[j] - Kfusion[j] * innovOptFlow[obsIndex];
|
statesArray[j] = statesArray[j] - Kfusion[j] * innovOptFlow[obsIndex];
|
||||||
}
|
}
|
||||||
|
|
||||||
// the first 3 states represent the angular misalignment vector. This is
|
// the first 3 states represent the angular misalignment vector.
|
||||||
// is used to correct the estimated quaternion on the current time step
|
// This is used to correct the estimated quaternion on the current time step
|
||||||
stateStruct.quat.rotate(stateStruct.angErr);
|
stateStruct.quat.rotate(stateStruct.angErr);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
|
|
|
@ -891,8 +891,8 @@ void NavEKF2_core::FuseVelPosNED()
|
||||||
statesArray[i] = statesArray[i] - Kfusion[i] * innovVelPos[obsIndex];
|
statesArray[i] = statesArray[i] - Kfusion[i] * innovVelPos[obsIndex];
|
||||||
}
|
}
|
||||||
|
|
||||||
// the first 3 states represent the angular misalignment vector. This is
|
// the first 3 states represent the angular misalignment vector.
|
||||||
// is used to correct the estimated quaternion
|
// This is used to correct the estimated quaternion
|
||||||
stateStruct.quat.rotate(stateStruct.angErr);
|
stateStruct.quat.rotate(stateStruct.angErr);
|
||||||
|
|
||||||
// sum the attitude error from velocity and position fusion only
|
// sum the attitude error from velocity and position fusion only
|
||||||
|
|
|
@ -214,8 +214,8 @@ void NavEKF2_core::FuseRngBcn()
|
||||||
statesArray[j] = statesArray[j] - Kfusion[j] * innovRngBcn;
|
statesArray[j] = statesArray[j] - Kfusion[j] * innovRngBcn;
|
||||||
}
|
}
|
||||||
|
|
||||||
// the first 3 states represent the angular misalignment vector. This is
|
// the first 3 states represent the angular misalignment vector.
|
||||||
// is used to correct the estimated quaternion on the current time step
|
// This is used to correct the estimated quaternion on the current time step
|
||||||
stateStruct.quat.rotate(stateStruct.angErr);
|
stateStruct.quat.rotate(stateStruct.angErr);
|
||||||
|
|
||||||
// record healthy fusion
|
// record healthy fusion
|
||||||
|
|
Loading…
Reference in New Issue