diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp index b414893158..14c69c788a 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp @@ -567,7 +567,7 @@ void NavEKF3_core::FuseDragForces() const ftype HK4 = HK0*q1 + HK1*q2 + q3*vd; const ftype HK5 = HK0*q2 - HK1*q1 + q0*vd; const ftype HK6 = -HK0*q3 + HK1*q0 + q1*vd; - const ftype HK7 = powF(q0, 2) + powF(q1, 2) - powF(q2, 2) - powF(q3, 2); + const ftype HK7 = sq(q0) + sq(q1) - sq(q2) - sq(q3); const ftype HK8 = HK7*Kacc; const ftype HK9 = q0*q3 + q1*q2; const ftype HK10 = HK3*HK9; @@ -581,7 +581,7 @@ void NavEKF3_core::FuseDragForces() const ftype HK18 = -HK12*P[0][23] + HK12*P[0][5] - HK13*P[0][6] + HK14*P[0][1] + HK15*P[0][0] - HK16*P[0][2] + HK17*P[0][3] - HK7*P[0][22] + HK7*P[0][4]; const ftype HK19 = HK12*P[5][23]; const ftype HK20 = -HK12*P[23][23] - HK13*P[6][23] + HK14*P[1][23] + HK15*P[0][23] - HK16*P[2][23] + HK17*P[3][23] + HK19 - HK7*P[22][23] + HK7*P[4][23]; - const ftype HK21 = powF(Kacc, 2); + const ftype HK21 = sq(Kacc); const ftype HK22 = HK12*HK21; const ftype HK23 = HK12*P[5][5] - HK13*P[5][6] + HK14*P[1][5] + HK15*P[0][5] - HK16*P[2][5] + HK17*P[3][5] - HK19 + HK7*P[4][5] - HK7*P[5][22]; const ftype HK24 = HK12*P[5][6] - HK12*P[6][23] - HK13*P[6][6] + HK14*P[1][6] + HK15*P[0][6] - HK16*P[2][6] + HK17*P[3][6] + HK7*P[4][6] - HK7*P[6][22]; @@ -652,7 +652,7 @@ void NavEKF3_core::FuseDragForces() const ftype HK6 = HK0*q3 + HK1*q0 - q2*vd; const ftype HK7 = q0*q3 - q1*q2; const ftype HK8 = HK3*HK7; - const ftype HK9 = powF(q0, 2) - powF(q1, 2) + powF(q2, 2) - powF(q3, 2); + const ftype HK9 = sq(q0) - sq(q1) + sq(q2) - sq(q3); const ftype HK10 = HK9*Kacc; const ftype HK11 = q0*q1 + q2*q3; const ftype HK12 = 2*HK11; @@ -662,7 +662,7 @@ void NavEKF3_core::FuseDragForces() const ftype HK16 = 2*HK4; const ftype HK17 = 2*HK6; const ftype HK18 = HK12*P[0][6] + HK13*P[0][22] - HK13*P[0][4] + HK14*P[0][2] + HK15*P[0][0] + HK16*P[0][1] - HK17*P[0][3] - HK9*P[0][23] + HK9*P[0][5]; - const ftype HK19 = powF(Kacc, 2); + const ftype HK19 = sq(Kacc); const ftype HK20 = HK12*P[6][6] - HK13*P[4][6] + HK13*P[6][22] + HK14*P[2][6] + HK15*P[0][6] + HK16*P[1][6] - HK17*P[3][6] + HK9*P[5][6] - HK9*P[6][23]; const ftype HK21 = HK13*P[4][22]; const ftype HK22 = HK12*P[6][22] + HK13*P[22][22] + HK14*P[2][22] + HK15*P[0][22] + HK16*P[1][22] - HK17*P[3][22] - HK21 - HK9*P[22][23] + HK9*P[5][22]; diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp index 52aae85638..a87a0a14f8 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.cpp @@ -1151,11 +1151,11 @@ void NavEKF3_core::CovariancePrediction(Vector3F *rotVarVecPtr) // we calculate the lower diagonal and copy to take advantage of symmetry // intermediate calculations - const ftype PS0 = powF(q1, 2); + const ftype PS0 = sq(q1); const ftype PS1 = 0.25F*daxVar; - const ftype PS2 = powF(q2, 2); + const ftype PS2 = sq(q2); const ftype PS3 = 0.25F*dayVar; - const ftype PS4 = powF(q3, 2); + const ftype PS4 = sq(q3); const ftype PS5 = 0.25F*dazVar; const ftype PS6 = 0.5F*q1; const ftype PS7 = 0.5F*q2; @@ -1193,7 +1193,7 @@ void NavEKF3_core::CovariancePrediction(Vector3F *rotVarVecPtr) const ftype PS39 = q1*q2; const ftype PS40 = q0*q3; const ftype PS41 = -PS2; - const ftype PS42 = powF(q0, 2); + const ftype PS42 = sq(q0); const ftype PS43 = -PS4 + PS42; const ftype PS44 = PS0 + PS41 + PS43; const ftype PS45 = -PS11*P[1][13] - PS12*P[2][13] - PS13*P[3][13] + PS6*P[10][13] + PS7*P[11][13] + PS9*P[12][13] + P[0][13]; @@ -1369,20 +1369,20 @@ void NavEKF3_core::CovariancePrediction(Vector3F *rotVarVecPtr) nextP[1][4] = -PS44*PS93 - PS46*PS95 + PS54*PS97 + PS60*PS82 + PS62*PS92 + PS72*PS80 - PS74*PS89 + PS98; nextP[2][4] = -PS104*PS74 + PS106*PS72 + PS111*PS62 + PS113*PS60 - PS114*PS44 - PS116*PS46 + PS118*PS54 + PS119; nextP[3][4] = PS124*PS62 + PS125*PS72 + PS128*PS60 - PS129*PS74 - PS130*PS44 - PS132*PS46 + PS134*PS54 + PS135; - nextP[4][4] = -PS139*PS142 + PS140*PS146 - PS141*PS44 - PS145*PS74 + PS149*PS72 + PS152*PS60 + PS155*PS62 + PS156*powF(PS54, 2) + PS157*powF(PS46, 2) + PS158 + powF(PS44, 2)*dvxVar; + nextP[4][4] = -PS139*PS142 + PS140*PS146 - PS141*PS44 - PS145*PS74 + PS149*PS72 + PS152*PS60 + PS155*PS62 + PS156*sq(PS54) + PS157*sq(PS46) + PS158 + sq(PS44)*dvxVar; nextP[0][5] = -PS23*PS60 + PS26*PS62 + PS48*PS68 + PS52*PS58 + PS53*PS57 - PS55*PS65 - PS66*PS67 + PS69; nextP[1][5] = PS100 - PS60*PS92 + PS62*PS82 - PS65*PS96 - PS66*PS99 + PS68*PS95 + PS72*PS89 + PS74*PS80; nextP[2][5] = PS104*PS72 + PS106*PS74 - PS111*PS60 + PS113*PS62 + PS116*PS68 - PS117*PS65 - PS120*PS66 + PS121; nextP[3][5] = -PS124*PS60 + PS125*PS74 + PS128*PS62 + PS129*PS72 + PS132*PS68 - PS133*PS65 - PS136*PS66 + PS137; nextP[4][5] = -PS140*PS161 + PS142*PS160 + PS145*PS72 - PS146*PS65 + PS149*PS74 + PS152*PS62 - PS155*PS60 - PS157*PS46*PS68 - PS159*PS66 + PS162*PS163 + PS164; - nextP[5][5] = PS157*powF(PS68, 2) + PS160*PS173 - PS162*PS170 - PS169*PS65 - PS172*PS60 + PS175*PS72 + PS177*PS74 + PS179*PS62 + PS180*powF(PS66, 2) + PS181 + powF(PS65, 2)*dvyVar; + nextP[5][5] = PS157*sq(PS68) + PS160*PS173 - PS162*PS170 - PS169*PS65 - PS172*PS60 + PS175*PS72 + PS177*PS74 + PS179*PS62 + PS180*sq(PS66) + PS181 + sq(PS65)*dvyVar; nextP[0][6] = PS23*PS74 - PS26*PS72 - PS47*PS70 + PS53*PS61 - PS56*PS71 + PS58*PS59 + PS67*PS73 + PS75; nextP[1][6] = PS101 + PS60*PS80 + PS62*PS89 - PS70*PS94 - PS71*PS97 - PS72*PS82 + PS73*PS99 + PS74*PS92; nextP[2][6] = PS104*PS62 + PS106*PS60 + PS111*PS74 - PS113*PS72 - PS115*PS70 - PS118*PS71 + PS120*PS73 + PS122; nextP[3][6] = PS124*PS74 + PS125*PS60 - PS128*PS72 + PS129*PS62 - PS131*PS70 - PS134*PS71 + PS136*PS73 + PS138; nextP[4][6] = PS139*PS167 - PS142*PS70 + PS145*PS62 - PS146*PS165 + PS149*PS60 - PS152*PS72 + PS155*PS74 - PS156*PS54*PS71 + PS159*PS73 - PS163*PS166 + PS168; nextP[5][6] = -PS160*PS167 + PS161*PS165 - PS165*PS169 + PS166*PS170 + PS172*PS74 - PS173*PS70 + PS175*PS62 + PS177*PS60 - PS179*PS72 - PS180*PS66*PS73 + PS182; - nextP[6][6] = PS156*powF(PS71, 2) - PS165*PS184 + PS166*PS185 + PS180*powF(PS73, 2) - PS183*PS70 + PS186 + PS60*(-PS151 - PS165*P[0][14] + PS166*P[0][13] + PS171 + PS60*P[0][0] + PS62*P[0][3] - PS70*P[0][15] + P[0][6]) + PS62*(PS154 - PS165*P[3][14] + PS166*P[3][13] - PS178 + PS60*P[0][3] + PS62*P[3][3] - PS70*P[3][15] + P[3][6]) + powF(PS70, 2)*dvzVar - PS72*(PS147 - PS165*P[2][14] + PS166*P[2][13] + PS174 - PS70*P[2][15] - PS72*P[2][2] + PS74*P[1][2] + P[2][6]) + PS74*(PS143 - PS165*P[1][14] + PS166*P[1][13] + PS176 - PS70*P[1][15] - PS72*P[1][2] + PS74*P[1][1] + P[1][6]); + nextP[6][6] = PS156*sq(PS71) - PS165*PS184 + PS166*PS185 + PS180*sq(PS73) - PS183*PS70 + PS186 + PS60*(-PS151 - PS165*P[0][14] + PS166*P[0][13] + PS171 + PS60*P[0][0] + PS62*P[0][3] - PS70*P[0][15] + P[0][6]) + PS62*(PS154 - PS165*P[3][14] + PS166*P[3][13] - PS178 + PS60*P[0][3] + PS62*P[3][3] - PS70*P[3][15] + P[3][6]) + sq(PS70)*dvzVar - PS72*(PS147 - PS165*P[2][14] + PS166*P[2][13] + PS174 - PS70*P[2][15] - PS72*P[2][2] + PS74*P[1][2] + P[2][6]) + PS74*(PS143 - PS165*P[1][14] + PS166*P[1][13] + PS176 - PS70*P[1][15] - PS72*P[1][2] + PS74*P[1][1] + P[1][6]); nextP[0][7] = -PS11*P[1][7] - PS12*P[2][7] - PS13*P[3][7] + PS6*P[7][10] + PS63*dt + PS7*P[7][11] + PS9*P[7][12] + P[0][7]; nextP[1][7] = PS11*P[0][7] - PS12*P[3][7] + PS13*P[2][7] - PS34*P[7][10] - PS7*P[7][12] + PS9*P[7][11] + PS98*dt + P[1][7]; nextP[2][7] = PS11*P[3][7] + PS119*dt + PS12*P[0][7] - PS13*P[1][7] - PS34*P[7][11] + PS6*P[7][12] - PS9*P[7][10] + P[2][7];