|
|
|
@ -164,7 +164,7 @@ void NavEKF2_core::setAidingMode()
@@ -164,7 +164,7 @@ void NavEKF2_core::setAidingMode()
|
|
|
|
|
if (!isAiding) { |
|
|
|
|
// Don't allow filter to start position or velocity aiding until the tilt and yaw alignment is complete
|
|
|
|
|
// and IMU gyro bias estimates have stabilised
|
|
|
|
|
bool filterIsStable = tiltAlignComplete && yawAlignComplete && imuCalCompleted(); |
|
|
|
|
bool filterIsStable = tiltAlignComplete && yawAlignComplete && checkGyroCalStatus(); |
|
|
|
|
// If GPS usage has been prohiited then we use flow aiding provided optical flow data is present
|
|
|
|
|
bool useFlowAiding = (frontend->_fusionModeGPS == 3) && optFlowDataPresent(); |
|
|
|
|
// Start aiding if we have a source of aiding data and the filter attitude algnment is complete
|
|
|
|
@ -327,17 +327,15 @@ void NavEKF2_core::recordYawReset()
@@ -327,17 +327,15 @@ void NavEKF2_core::recordYawReset()
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// return true when IMU calibration completed
|
|
|
|
|
bool NavEKF2_core::imuCalCompleted(void) |
|
|
|
|
// return true and set the class variable true if the delta angle bias has been learned
|
|
|
|
|
bool NavEKF2_core::checkGyroCalStatus(void) |
|
|
|
|
{ |
|
|
|
|
// check delta angle bias variances
|
|
|
|
|
const float delAngBiasVarMax = sq(radians(0.1f * dtEkfAvg)); |
|
|
|
|
bool gyroCalComplete = (P[9][9] <= delAngBiasVarMax) && |
|
|
|
|
delAngBiasLearned = (P[9][9] <= delAngBiasVarMax) && |
|
|
|
|
(P[10][10] <= delAngBiasVarMax) && |
|
|
|
|
(P[11][11] <= delAngBiasVarMax); |
|
|
|
|
|
|
|
|
|
return gyroCalComplete; |
|
|
|
|
|
|
|
|
|
return delAngBiasLearned; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// Commands the EKF to not use GPS.
|
|
|
|
|