AP_AHRS: fixed float exception on start in SITL

zero DCM matrix
This commit is contained in:
Andrew Tridgell 2015-12-01 15:19:45 +11:00
parent f19be28e89
commit 1e8c391024

View File

@ -36,6 +36,7 @@ AP_AHRS_NavEKF::AP_AHRS_NavEKF(AP_InertialSensor &ins, AP_Baro &baro, AP_GPS &gp
EKF2(_EKF2),
_flags(flags)
{
_dcm_matrix.identity();
}
// return the smoothed gyro vector corrected for drift