|
|
|
@ -223,16 +223,8 @@ void Ekf::fuseMag()
@@ -223,16 +223,8 @@ void Ekf::fuseMag()
|
|
|
|
|
Kfusion[19] = SK_MX[0]*(P[19][19] + P[19][1]*SH_MAG[0] - P[19][2]*SH_MAG[1] + P[19][3]*SH_MAG[2] + P[19][0]*SK_MX[2] - P[19][16]*SK_MX[1] + P[19][17]*SK_MX[4] - P[19][18]*SK_MX[3]); |
|
|
|
|
Kfusion[20] = SK_MX[0]*(P[20][19] + P[20][1]*SH_MAG[0] - P[20][2]*SH_MAG[1] + P[20][3]*SH_MAG[2] + P[20][0]*SK_MX[2] - P[20][16]*SK_MX[1] + P[20][17]*SK_MX[4] - P[20][18]*SK_MX[3]); |
|
|
|
|
Kfusion[21] = SK_MX[0]*(P[21][19] + P[21][1]*SH_MAG[0] - P[21][2]*SH_MAG[1] + P[21][3]*SH_MAG[2] + P[21][0]*SK_MX[2] - P[21][16]*SK_MX[1] + P[21][17]*SK_MX[4] - P[21][18]*SK_MX[3]); |
|
|
|
|
|
|
|
|
|
// Don't update wind states unless we are doing wind estimation
|
|
|
|
|
if (_control_status.flags.wind) { |
|
|
|
|
Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][1]*SH_MAG[0] - P[22][2]*SH_MAG[1] + P[22][3]*SH_MAG[2] + P[22][0]*SK_MX[2] - P[22][16]*SK_MX[1] + P[22][17]*SK_MX[4] - P[22][18]*SK_MX[3]); |
|
|
|
|
Kfusion[23] = SK_MX[0]*(P[23][19] + P[23][1]*SH_MAG[0] - P[23][2]*SH_MAG[1] + P[23][3]*SH_MAG[2] + P[23][0]*SK_MX[2] - P[23][16]*SK_MX[1] + P[23][17]*SK_MX[4] - P[23][18]*SK_MX[3]); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
Kfusion[22] = 0.0f; |
|
|
|
|
Kfusion[23] = 0.0f; |
|
|
|
|
} |
|
|
|
|
Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][1]*SH_MAG[0] - P[22][2]*SH_MAG[1] + P[22][3]*SH_MAG[2] + P[22][0]*SK_MX[2] - P[22][16]*SK_MX[1] + P[22][17]*SK_MX[4] - P[22][18]*SK_MX[3]); |
|
|
|
|
Kfusion[23] = SK_MX[0]*(P[23][19] + P[23][1]*SH_MAG[0] - P[23][2]*SH_MAG[1] + P[23][3]*SH_MAG[2] + P[23][0]*SK_MX[2] - P[23][16]*SK_MX[1] + P[23][17]*SK_MX[4] - P[23][18]*SK_MX[3]); |
|
|
|
|
|
|
|
|
|
} else if (index == 1) { |
|
|
|
|
// Calculate Y axis Kalman gains
|
|
|
|
@ -264,16 +256,8 @@ void Ekf::fuseMag()
@@ -264,16 +256,8 @@ void Ekf::fuseMag()
|
|
|
|
|
Kfusion[19] = SK_MY[0]*(P[19][20] + P[19][0]*SH_MAG[2] + P[19][1]*SH_MAG[1] + P[19][2]*SH_MAG[0] - P[19][3]*SK_MY[2] - P[19][17]*SK_MY[1] - P[19][16]*SK_MY[3] + P[19][18]*SK_MY[4]); |
|
|
|
|
Kfusion[20] = SK_MY[0]*(P[20][20] + P[20][0]*SH_MAG[2] + P[20][1]*SH_MAG[1] + P[20][2]*SH_MAG[0] - P[20][3]*SK_MY[2] - P[20][17]*SK_MY[1] - P[20][16]*SK_MY[3] + P[20][18]*SK_MY[4]); |
|
|
|
|
Kfusion[21] = SK_MY[0]*(P[21][20] + P[21][0]*SH_MAG[2] + P[21][1]*SH_MAG[1] + P[21][2]*SH_MAG[0] - P[21][3]*SK_MY[2] - P[21][17]*SK_MY[1] - P[21][16]*SK_MY[3] + P[21][18]*SK_MY[4]); |
|
|
|
|
|
|
|
|
|
// Don't update wind states unless we are doing wind estimation
|
|
|
|
|
if (_control_status.flags.wind) { |
|
|
|
|
Kfusion[22] = SK_MY[0]*(P[22][20] + P[22][0]*SH_MAG[2] + P[22][1]*SH_MAG[1] + P[22][2]*SH_MAG[0] - P[22][3]*SK_MY[2] - P[22][17]*SK_MY[1] - P[22][16]*SK_MY[3] + P[22][18]*SK_MY[4]); |
|
|
|
|
Kfusion[23] = SK_MY[0]*(P[23][20] + P[23][0]*SH_MAG[2] + P[23][1]*SH_MAG[1] + P[23][2]*SH_MAG[0] - P[23][3]*SK_MY[2] - P[23][17]*SK_MY[1] - P[23][16]*SK_MY[3] + P[23][18]*SK_MY[4]); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
Kfusion[22] = 0.0f; |
|
|
|
|
Kfusion[23] = 0.0f; |
|
|
|
|
} |
|
|
|
|
Kfusion[22] = SK_MY[0]*(P[22][20] + P[22][0]*SH_MAG[2] + P[22][1]*SH_MAG[1] + P[22][2]*SH_MAG[0] - P[22][3]*SK_MY[2] - P[22][17]*SK_MY[1] - P[22][16]*SK_MY[3] + P[22][18]*SK_MY[4]); |
|
|
|
|
Kfusion[23] = SK_MY[0]*(P[23][20] + P[23][0]*SH_MAG[2] + P[23][1]*SH_MAG[1] + P[23][2]*SH_MAG[0] - P[23][3]*SK_MY[2] - P[23][17]*SK_MY[1] - P[23][16]*SK_MY[3] + P[23][18]*SK_MY[4]); |
|
|
|
|
|
|
|
|
|
} else if (index == 2) { |
|
|
|
|
// Calculate Z axis Kalman gains
|
|
|
|
@ -305,16 +289,8 @@ void Ekf::fuseMag()
@@ -305,16 +289,8 @@ void Ekf::fuseMag()
|
|
|
|
|
Kfusion[19] = SK_MZ[0]*(P[19][21] + P[19][0]*SH_MAG[1] - P[19][1]*SH_MAG[2] + P[19][3]*SH_MAG[0] + P[19][2]*SK_MZ[2] + P[19][18]*SK_MZ[1] + P[19][16]*SK_MZ[4] - P[19][17]*SK_MZ[3]); |
|
|
|
|
Kfusion[20] = SK_MZ[0]*(P[20][21] + P[20][0]*SH_MAG[1] - P[20][1]*SH_MAG[2] + P[20][3]*SH_MAG[0] + P[20][2]*SK_MZ[2] + P[20][18]*SK_MZ[1] + P[20][16]*SK_MZ[4] - P[20][17]*SK_MZ[3]); |
|
|
|
|
Kfusion[21] = SK_MZ[0]*(P[21][21] + P[21][0]*SH_MAG[1] - P[21][1]*SH_MAG[2] + P[21][3]*SH_MAG[0] + P[21][2]*SK_MZ[2] + P[21][18]*SK_MZ[1] + P[21][16]*SK_MZ[4] - P[21][17]*SK_MZ[3]); |
|
|
|
|
|
|
|
|
|
// Don't update wind states unless we are doing wind estimation
|
|
|
|
|
if (_control_status.flags.wind) { |
|
|
|
|
Kfusion[22] = SK_MZ[0]*(P[22][21] + P[22][0]*SH_MAG[1] - P[22][1]*SH_MAG[2] + P[22][3]*SH_MAG[0] + P[22][2]*SK_MZ[2] + P[22][18]*SK_MZ[1] + P[22][16]*SK_MZ[4] - P[22][17]*SK_MZ[3]); |
|
|
|
|
Kfusion[23] = SK_MZ[0]*(P[23][21] + P[23][0]*SH_MAG[1] - P[23][1]*SH_MAG[2] + P[23][3]*SH_MAG[0] + P[23][2]*SK_MZ[2] + P[23][18]*SK_MZ[1] + P[23][16]*SK_MZ[4] - P[23][17]*SK_MZ[3]); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
Kfusion[22] = 0.0f; |
|
|
|
|
Kfusion[23] = 0.0f; |
|
|
|
|
} |
|
|
|
|
Kfusion[22] = SK_MZ[0]*(P[22][21] + P[22][0]*SH_MAG[1] - P[22][1]*SH_MAG[2] + P[22][3]*SH_MAG[0] + P[22][2]*SK_MZ[2] + P[22][18]*SK_MZ[1] + P[22][16]*SK_MZ[4] - P[22][17]*SK_MZ[3]); |
|
|
|
|
Kfusion[23] = SK_MZ[0]*(P[23][21] + P[23][0]*SH_MAG[1] - P[23][1]*SH_MAG[2] + P[23][3]*SH_MAG[0] + P[23][2]*SK_MZ[2] + P[23][18]*SK_MZ[1] + P[23][16]*SK_MZ[4] - P[23][17]*SK_MZ[3]); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
return; |
|
|
|
@ -682,24 +658,14 @@ void Ekf::fuseDeclination()
@@ -682,24 +658,14 @@ void Ekf::fuseDeclination()
|
|
|
|
|
Kfusion[13] = -t4*t13*(P[13][16]*magE-P[13][17]*magN); |
|
|
|
|
Kfusion[14] = -t4*t13*(P[14][16]*magE-P[14][17]*magN); |
|
|
|
|
Kfusion[15] = -t4*t13*(P[15][16]*magE-P[15][17]*magN); |
|
|
|
|
|
|
|
|
|
// We only do declination fusion when we are using all the field states, so no logic required here
|
|
|
|
|
Kfusion[16] = -t4*t13*(P[16][16]*magE-P[16][17]*magN); |
|
|
|
|
Kfusion[17] = -t4*t13*(P[17][16]*magE-P[17][17]*magN); |
|
|
|
|
Kfusion[18] = -t4*t13*(P[18][16]*magE-P[18][17]*magN); |
|
|
|
|
Kfusion[19] = -t4*t13*(P[19][16]*magE-P[19][17]*magN); |
|
|
|
|
Kfusion[20] = -t4*t13*(P[20][16]*magE-P[20][17]*magN); |
|
|
|
|
Kfusion[21] = -t4*t13*(P[21][16]*magE-P[21][17]*magN); |
|
|
|
|
|
|
|
|
|
// Don't update wind states unless we are doing wind estimation
|
|
|
|
|
if (_control_status.flags.wind) { |
|
|
|
|
Kfusion[22] = -t4*t13*(P[22][16]*magE-P[22][17]*magN); |
|
|
|
|
Kfusion[23] = -t4*t13*(P[23][16]*magE-P[23][17]*magN); |
|
|
|
|
|
|
|
|
|
} else { |
|
|
|
|
Kfusion[22] = 0.0f; |
|
|
|
|
Kfusion[23] = 0.0f; |
|
|
|
|
} |
|
|
|
|
Kfusion[22] = -t4*t13*(P[22][16]*magE-P[22][17]*magN); |
|
|
|
|
Kfusion[23] = -t4*t13*(P[23][16]*magE-P[23][17]*magN); |
|
|
|
|
|
|
|
|
|
// calculate innovation and constrain
|
|
|
|
|
float innovation = atanf(magE / magN) - _mag_declination; |
|
|
|
|