forked from Archive/PX4-Autopilot
268 lines
12 KiB
Plaintext
268 lines
12 KiB
Plaintext
// Auto code for fusion of line of sight rate massurements from a optical flow camera aligned with the Z body axis
|
|
// Conversion from Matlab symbolic toolbox objects to c-code made using custom scripts and auto-coder from the InertialNav repo
|
|
// Observations are body modtion compensated optica flow rates about the X and Y body axis
|
|
// Sequential fusion is used (observation errors about each axis are assumed to be uncorrelated)
|
|
|
|
float H_LOS[2][24]; // Optical flow observation Jacobians
|
|
float Kfusion[24][2]; // Optical flow Kalman gains
|
|
|
|
// calculate X axis observation Jacobian
|
|
float t2 = 1.0f / range;
|
|
H_LOS[0][0] = t2*(q1*vd*2.0f+q0*ve*2.0f-q3*vn*2.0f);
|
|
H_LOS[0][1] = t2*(q0*vd*2.0f-q1*ve*2.0f+q2*vn*2.0f);
|
|
H_LOS[0][2] = t2*(q3*vd*2.0f+q2*ve*2.0f+q1*vn*2.0f);
|
|
H_LOS[0][3] = -t2*(q2*vd*-2.0f+q3*ve*2.0f+q0*vn*2.0f);
|
|
H_LOS[0][4] = -t2*(q0*q3*2.0f-q1*q2*2.0f);
|
|
H_LOS[0][5] = t2*(q0*q0-q1*q1+q2*q2-q3*q3);
|
|
H_LOS[0][6] = t2*(q0*q1*2.0f+q2*q3*2.0f);
|
|
|
|
// calculate intermediate variables for the X observaton innovatoin variance and Kalman gains
|
|
float t3 = q1*vd*2.0f;
|
|
float t4 = q0*ve*2.0f;
|
|
float t11 = q3*vn*2.0f;
|
|
float t5 = t3+t4-t11;
|
|
float t6 = q0*q3*2.0f;
|
|
float t29 = q1*q2*2.0f;
|
|
float t7 = t6-t29;
|
|
float t8 = q0*q1*2.0f;
|
|
float t9 = q2*q3*2.0f;
|
|
float t10 = t8+t9;
|
|
float t12 = P[0][0]*t2*t5;
|
|
float t13 = q0*vd*2.0f;
|
|
float t14 = q2*vn*2.0f;
|
|
float t28 = q1*ve*2.0f;
|
|
float t15 = t13+t14-t28;
|
|
float t16 = q3*vd*2.0f;
|
|
float t17 = q2*ve*2.0f;
|
|
float t18 = q1*vn*2.0f;
|
|
float t19 = t16+t17+t18;
|
|
float t20 = q3*ve*2.0f;
|
|
float t21 = q0*vn*2.0f;
|
|
float t30 = q2*vd*2.0f;
|
|
float t22 = t20+t21-t30;
|
|
float t23 = q0*q0;
|
|
float t24 = q1*q1;
|
|
float t25 = q2*q2;
|
|
float t26 = q3*q3;
|
|
float t27 = t23-t24+t25-t26;
|
|
float t31 = P[1][1]*t2*t15;
|
|
float t32 = P[6][0]*t2*t10;
|
|
float t33 = P[1][0]*t2*t15;
|
|
float t34 = P[2][0]*t2*t19;
|
|
float t35 = P[5][0]*t2*t27;
|
|
float t79 = P[4][0]*t2*t7;
|
|
float t80 = P[3][0]*t2*t22;
|
|
float t36 = t12+t32+t33+t34+t35-t79-t80;
|
|
float t37 = t2*t5*t36;
|
|
float t38 = P[6][1]*t2*t10;
|
|
float t39 = P[0][1]*t2*t5;
|
|
float t40 = P[2][1]*t2*t19;
|
|
float t41 = P[5][1]*t2*t27;
|
|
float t81 = P[4][1]*t2*t7;
|
|
float t82 = P[3][1]*t2*t22;
|
|
float t42 = t31+t38+t39+t40+t41-t81-t82;
|
|
float t43 = t2*t15*t42;
|
|
float t44 = P[6][2]*t2*t10;
|
|
float t45 = P[0][2]*t2*t5;
|
|
float t46 = P[1][2]*t2*t15;
|
|
float t47 = P[2][2]*t2*t19;
|
|
float t48 = P[5][2]*t2*t27;
|
|
float t83 = P[4][2]*t2*t7;
|
|
float t84 = P[3][2]*t2*t22;
|
|
float t49 = t44+t45+t46+t47+t48-t83-t84;
|
|
float t50 = t2*t19*t49;
|
|
float t51 = P[6][3]*t2*t10;
|
|
float t52 = P[0][3]*t2*t5;
|
|
float t53 = P[1][3]*t2*t15;
|
|
float t54 = P[2][3]*t2*t19;
|
|
float t55 = P[5][3]*t2*t27;
|
|
float t85 = P[4][3]*t2*t7;
|
|
float t86 = P[3][3]*t2*t22;
|
|
float t56 = t51+t52+t53+t54+t55-t85-t86;
|
|
float t57 = P[6][5]*t2*t10;
|
|
float t58 = P[0][5]*t2*t5;
|
|
float t59 = P[1][5]*t2*t15;
|
|
float t60 = P[2][5]*t2*t19;
|
|
float t61 = P[5][5]*t2*t27;
|
|
float t88 = P[4][5]*t2*t7;
|
|
float t89 = P[3][5]*t2*t22;
|
|
float t62 = t57+t58+t59+t60+t61-t88-t89;
|
|
float t63 = t2*t27*t62;
|
|
float t64 = P[6][4]*t2*t10;
|
|
float t65 = P[0][4]*t2*t5;
|
|
float t66 = P[1][4]*t2*t15;
|
|
float t67 = P[2][4]*t2*t19;
|
|
float t68 = P[5][4]*t2*t27;
|
|
float t90 = P[4][4]*t2*t7;
|
|
float t91 = P[3][4]*t2*t22;
|
|
float t69 = t64+t65+t66+t67+t68-t90-t91;
|
|
float t70 = P[6][6]*t2*t10;
|
|
float t71 = P[0][6]*t2*t5;
|
|
float t72 = P[1][6]*t2*t15;
|
|
float t73 = P[2][6]*t2*t19;
|
|
float t74 = P[5][6]*t2*t27;
|
|
float t93 = P[4][6]*t2*t7;
|
|
float t94 = P[3][6]*t2*t22;
|
|
float t75 = t70+t71+t72+t73+t74-t93-t94;
|
|
float t76 = t2*t10*t75;
|
|
float t87 = t2*t22*t56;
|
|
float t92 = t2*t7*t69;
|
|
float t77 = R_LOS+t37+t43+t50+t63+t76-t87-t92;
|
|
float t78 = 1.0f / t77;
|
|
|
|
// calculate Kalman gains for X-axis observation
|
|
Kfusion[0][0] = t78*(t12-P[0][4]*t2*t7+P[0][1]*t2*t15+P[0][6]*t2*t10+P[0][2]*t2*t19-P[0][3]*t2*t22+P[0][5]*t2*t27);
|
|
Kfusion[1][0] = t78*(t31+P[1][0]*t2*t5-P[1][4]*t2*t7+P[1][6]*t2*t10+P[1][2]*t2*t19-P[1][3]*t2*t22+P[1][5]*t2*t27);
|
|
Kfusion[2][0] = t78*(t47+P[2][0]*t2*t5-P[2][4]*t2*t7+P[2][1]*t2*t15+P[2][6]*t2*t10-P[2][3]*t2*t22+P[2][5]*t2*t27);
|
|
Kfusion[3][0] = t78*(-t86+P[3][0]*t2*t5-P[3][4]*t2*t7+P[3][1]*t2*t15+P[3][6]*t2*t10+P[3][2]*t2*t19+P[3][5]*t2*t27);
|
|
Kfusion[4][0] = t78*(-t90+P[4][0]*t2*t5+P[4][1]*t2*t15+P[4][6]*t2*t10+P[4][2]*t2*t19-P[4][3]*t2*t22+P[4][5]*t2*t27);
|
|
Kfusion[5][0] = t78*(t61+P[5][0]*t2*t5-P[5][4]*t2*t7+P[5][1]*t2*t15+P[5][6]*t2*t10+P[5][2]*t2*t19-P[5][3]*t2*t22);
|
|
Kfusion[6][0] = t78*(t70+P[6][0]*t2*t5-P[6][4]*t2*t7+P[6][1]*t2*t15+P[6][2]*t2*t19-P[6][3]*t2*t22+P[6][5]*t2*t27);
|
|
Kfusion[7][0] = t78*(P[7][0]*t2*t5-P[7][4]*t2*t7+P[7][1]*t2*t15+P[7][6]*t2*t10+P[7][2]*t2*t19-P[7][3]*t2*t22+P[7][5]*t2*t27);
|
|
Kfusion[8][0] = t78*(P[8][0]*t2*t5-P[8][4]*t2*t7+P[8][1]*t2*t15+P[8][6]*t2*t10+P[8][2]*t2*t19-P[8][3]*t2*t22+P[8][5]*t2*t27);
|
|
Kfusion[9][0] = t78*(P[9][0]*t2*t5-P[9][4]*t2*t7+P[9][1]*t2*t15+P[9][6]*t2*t10+P[9][2]*t2*t19-P[9][3]*t2*t22+P[9][5]*t2*t27);
|
|
Kfusion[10][0] = t78*(P[10][0]*t2*t5-P[10][4]*t2*t7+P[10][1]*t2*t15+P[10][6]*t2*t10+P[10][2]*t2*t19-P[10][3]*t2*t22+P[10][5]*t2*t27);
|
|
Kfusion[11][0] = t78*(P[11][0]*t2*t5-P[11][4]*t2*t7+P[11][1]*t2*t15+P[11][6]*t2*t10+P[11][2]*t2*t19-P[11][3]*t2*t22+P[11][5]*t2*t27);
|
|
Kfusion[12][0] = t78*(P[12][0]*t2*t5-P[12][4]*t2*t7+P[12][1]*t2*t15+P[12][6]*t2*t10+P[12][2]*t2*t19-P[12][3]*t2*t22+P[12][5]*t2*t27);
|
|
Kfusion[13][0] = t78*(P[13][0]*t2*t5-P[13][4]*t2*t7+P[13][1]*t2*t15+P[13][6]*t2*t10+P[13][2]*t2*t19-P[13][3]*t2*t22+P[13][5]*t2*t27);
|
|
Kfusion[14][0] = t78*(P[14][0]*t2*t5-P[14][4]*t2*t7+P[14][1]*t2*t15+P[14][6]*t2*t10+P[14][2]*t2*t19-P[14][3]*t2*t22+P[14][5]*t2*t27);
|
|
Kfusion[15][0] = t78*(P[15][0]*t2*t5-P[15][4]*t2*t7+P[15][1]*t2*t15+P[15][6]*t2*t10+P[15][2]*t2*t19-P[15][3]*t2*t22+P[15][5]*t2*t27);
|
|
Kfusion[16][0] = t78*(P[16][0]*t2*t5-P[16][4]*t2*t7+P[16][1]*t2*t15+P[16][6]*t2*t10+P[16][2]*t2*t19-P[16][3]*t2*t22+P[16][5]*t2*t27);
|
|
Kfusion[17][0] = t78*(P[17][0]*t2*t5-P[17][4]*t2*t7+P[17][1]*t2*t15+P[17][6]*t2*t10+P[17][2]*t2*t19-P[17][3]*t2*t22+P[17][5]*t2*t27);
|
|
Kfusion[18][0] = t78*(P[18][0]*t2*t5-P[18][4]*t2*t7+P[18][1]*t2*t15+P[18][6]*t2*t10+P[18][2]*t2*t19-P[18][3]*t2*t22+P[18][5]*t2*t27);
|
|
Kfusion[19][0] = t78*(P[19][0]*t2*t5-P[19][4]*t2*t7+P[19][1]*t2*t15+P[19][6]*t2*t10+P[19][2]*t2*t19-P[19][3]*t2*t22+P[19][5]*t2*t27);
|
|
Kfusion[20][0] = t78*(P[20][0]*t2*t5-P[20][4]*t2*t7+P[20][1]*t2*t15+P[20][6]*t2*t10+P[20][2]*t2*t19-P[20][3]*t2*t22+P[20][5]*t2*t27);
|
|
Kfusion[21][0] = t78*(P[21][0]*t2*t5-P[21][4]*t2*t7+P[21][1]*t2*t15+P[21][6]*t2*t10+P[21][2]*t2*t19-P[21][3]*t2*t22+P[21][5]*t2*t27);
|
|
Kfusion[22][0] = t78*(P[22][0]*t2*t5-P[22][4]*t2*t7+P[22][1]*t2*t15+P[22][6]*t2*t10+P[22][2]*t2*t19-P[22][3]*t2*t22+P[22][5]*t2*t27);
|
|
Kfusion[23][0] = t78*(P[23][0]*t2*t5-P[23][4]*t2*t7+P[23][1]*t2*t15+P[23][6]*t2*t10+P[23][2]*t2*t19-P[23][3]*t2*t22+P[23][5]*t2*t27);
|
|
|
|
// calculate Y axis observation Jacobian
|
|
float t2 = 1.0f / range;
|
|
H_LOS[1][0] = -t2*(q2*vd*-2.0f+q3*ve*2.0f+q0*vn*2.0f);
|
|
H_LOS[1][1] = -t2*(q3*vd*2.0f+q2*ve*2.0f+q1*vn*2.0f);
|
|
H_LOS[1][2] = t2*(q0*vd*2.0f-q1*ve*2.0f+q2*vn*2.0f);
|
|
H_LOS[1][3] = -t2*(q1*vd*2.0f+q0*ve*2.0f-q3*vn*2.0f);
|
|
H_LOS[1][4] = -t2*(q0*q0+q1*q1-q2*q2-q3*q3);
|
|
H_LOS[1][5] = -t2*(q0*q3*2.0f+q1*q2*2.0f);
|
|
H_LOS[1][6] = t2*(q0*q2*2.0f-q1*q3*2.0f);
|
|
|
|
// calculate intermediate variables for the Y axis observaton innovation variance and Kalman gains
|
|
float t3 = q3*ve*2.0f;
|
|
float t4 = q0*vn*2.0f;
|
|
float t11 = q2*vd*2.0f;
|
|
float t5 = t3+t4-t11;
|
|
float t6 = q0*q3*2.0f;
|
|
float t7 = q1*q2*2.0f;
|
|
float t8 = t6+t7;
|
|
float t9 = q0*q2*2.0f;
|
|
float t28 = q1*q3*2.0f;
|
|
float t10 = t9-t28;
|
|
float t12 = P[0][0]*t2*t5;
|
|
float t13 = q3*vd*2.0f;
|
|
float t14 = q2*ve*2.0f;
|
|
float t15 = q1*vn*2.0f;
|
|
float t16 = t13+t14+t15;
|
|
float t17 = q0*vd*2.0f;
|
|
float t18 = q2*vn*2.0f;
|
|
float t29 = q1*ve*2.0f;
|
|
float t19 = t17+t18-t29;
|
|
float t20 = q1*vd*2.0f;
|
|
float t21 = q0*ve*2.0f;
|
|
float t30 = q3*vn*2.0f;
|
|
float t22 = t20+t21-t30;
|
|
float t23 = q0*q0;
|
|
float t24 = q1*q1;
|
|
float t25 = q2*q2;
|
|
float t26 = q3*q3;
|
|
float t27 = t23+t24-t25-t26;
|
|
float t31 = P[1][1]*t2*t16;
|
|
float t32 = P[5][0]*t2*t8;
|
|
float t33 = P[1][0]*t2*t16;
|
|
float t34 = P[3][0]*t2*t22;
|
|
float t35 = P[4][0]*t2*t27;
|
|
float t80 = P[6][0]*t2*t10;
|
|
float t81 = P[2][0]*t2*t19;
|
|
float t36 = t12+t32+t33+t34+t35-t80-t81;
|
|
float t37 = t2*t5*t36;
|
|
float t38 = P[5][1]*t2*t8;
|
|
float t39 = P[0][1]*t2*t5;
|
|
float t40 = P[3][1]*t2*t22;
|
|
float t41 = P[4][1]*t2*t27;
|
|
float t82 = P[6][1]*t2*t10;
|
|
float t83 = P[2][1]*t2*t19;
|
|
float t42 = t31+t38+t39+t40+t41-t82-t83;
|
|
float t43 = t2*t16*t42;
|
|
float t44 = P[5][2]*t2*t8;
|
|
float t45 = P[0][2]*t2*t5;
|
|
float t46 = P[1][2]*t2*t16;
|
|
float t47 = P[3][2]*t2*t22;
|
|
float t48 = P[4][2]*t2*t27;
|
|
float t79 = P[2][2]*t2*t19;
|
|
float t84 = P[6][2]*t2*t10;
|
|
float t49 = t44+t45+t46+t47+t48-t79-t84;
|
|
float t50 = P[5][3]*t2*t8;
|
|
float t51 = P[0][3]*t2*t5;
|
|
float t52 = P[1][3]*t2*t16;
|
|
float t53 = P[3][3]*t2*t22;
|
|
float t54 = P[4][3]*t2*t27;
|
|
float t86 = P[6][3]*t2*t10;
|
|
float t87 = P[2][3]*t2*t19;
|
|
float t55 = t50+t51+t52+t53+t54-t86-t87;
|
|
float t56 = t2*t22*t55;
|
|
float t57 = P[5][4]*t2*t8;
|
|
float t58 = P[0][4]*t2*t5;
|
|
float t59 = P[1][4]*t2*t16;
|
|
float t60 = P[3][4]*t2*t22;
|
|
float t61 = P[4][4]*t2*t27;
|
|
float t88 = P[6][4]*t2*t10;
|
|
float t89 = P[2][4]*t2*t19;
|
|
float t62 = t57+t58+t59+t60+t61-t88-t89;
|
|
float t63 = t2*t27*t62;
|
|
float t64 = P[5][5]*t2*t8;
|
|
float t65 = P[0][5]*t2*t5;
|
|
float t66 = P[1][5]*t2*t16;
|
|
float t67 = P[3][5]*t2*t22;
|
|
float t68 = P[4][5]*t2*t27;
|
|
float t90 = P[6][5]*t2*t10;
|
|
float t91 = P[2][5]*t2*t19;
|
|
float t69 = t64+t65+t66+t67+t68-t90-t91;
|
|
float t70 = t2*t8*t69;
|
|
float t71 = P[5][6]*t2*t8;
|
|
float t72 = P[0][6]*t2*t5;
|
|
float t73 = P[1][6]*t2*t16;
|
|
float t74 = P[3][6]*t2*t22;
|
|
float t75 = P[4][6]*t2*t27;
|
|
float t92 = P[6][6]*t2*t10;
|
|
float t93 = P[2][6]*t2*t19;
|
|
float t76 = t71+t72+t73+t74+t75-t92-t93;
|
|
float t85 = t2*t19*t49;
|
|
float t94 = t2*t10*t76;
|
|
float t77 = R_LOS+t37+t43+t56+t63+t70-t85-t94;
|
|
float t78 = 1.0f / t77;
|
|
|
|
// calculate Kalman gains for Y-axis observation
|
|
Kfusion[0][1] = -t78*(t12+P[0][5]*t2*t8-P[0][6]*t2*t10+P[0][1]*t2*t16-P[0][2]*t2*t19+P[0][3]*t2*t22+P[0][4]*t2*t27);
|
|
Kfusion[1][1] = -t78*(t31+P[1][0]*t2*t5+P[1][5]*t2*t8-P[1][6]*t2*t10-P[1][2]*t2*t19+P[1][3]*t2*t22+P[1][4]*t2*t27);
|
|
Kfusion[2][1] = -t78*(-t79+P[2][0]*t2*t5+P[2][5]*t2*t8-P[2][6]*t2*t10+P[2][1]*t2*t16+P[2][3]*t2*t22+P[2][4]*t2*t27);
|
|
Kfusion[3][1] = -t78*(t53+P[3][0]*t2*t5+P[3][5]*t2*t8-P[3][6]*t2*t10+P[3][1]*t2*t16-P[3][2]*t2*t19+P[3][4]*t2*t27);
|
|
Kfusion[4][1] = -t78*(t61+P[4][0]*t2*t5+P[4][5]*t2*t8-P[4][6]*t2*t10+P[4][1]*t2*t16-P[4][2]*t2*t19+P[4][3]*t2*t22);
|
|
Kfusion[5][1] = -t78*(t64+P[5][0]*t2*t5-P[5][6]*t2*t10+P[5][1]*t2*t16-P[5][2]*t2*t19+P[5][3]*t2*t22+P[5][4]*t2*t27);
|
|
Kfusion[6][1] = -t78*(-t92+P[6][0]*t2*t5+P[6][5]*t2*t8+P[6][1]*t2*t16-P[6][2]*t2*t19+P[6][3]*t2*t22+P[6][4]*t2*t27);
|
|
Kfusion[7][1] = -t78*(P[7][0]*t2*t5+P[7][5]*t2*t8-P[7][6]*t2*t10+P[7][1]*t2*t16-P[7][2]*t2*t19+P[7][3]*t2*t22+P[7][4]*t2*t27);
|
|
Kfusion[8][1] = -t78*(P[8][0]*t2*t5+P[8][5]*t2*t8-P[8][6]*t2*t10+P[8][1]*t2*t16-P[8][2]*t2*t19+P[8][3]*t2*t22+P[8][4]*t2*t27);
|
|
Kfusion[9][1] = -t78*(P[9][0]*t2*t5+P[9][5]*t2*t8-P[9][6]*t2*t10+P[9][1]*t2*t16-P[9][2]*t2*t19+P[9][3]*t2*t22+P[9][4]*t2*t27);
|
|
Kfusion[10][1] = -t78*(P[10][0]*t2*t5+P[10][5]*t2*t8-P[10][6]*t2*t10+P[10][1]*t2*t16-P[10][2]*t2*t19+P[10][3]*t2*t22+P[10][4]*t2*t27);
|
|
Kfusion[11][1] = -t78*(P[11][0]*t2*t5+P[11][5]*t2*t8-P[11][6]*t2*t10+P[11][1]*t2*t16-P[11][2]*t2*t19+P[11][3]*t2*t22+P[11][4]*t2*t27);
|
|
Kfusion[12][1] = -t78*(P[12][0]*t2*t5+P[12][5]*t2*t8-P[12][6]*t2*t10+P[12][1]*t2*t16-P[12][2]*t2*t19+P[12][3]*t2*t22+P[12][4]*t2*t27);
|
|
Kfusion[13][1] = -t78*(P[13][0]*t2*t5+P[13][5]*t2*t8-P[13][6]*t2*t10+P[13][1]*t2*t16-P[13][2]*t2*t19+P[13][3]*t2*t22+P[13][4]*t2*t27);
|
|
Kfusion[14][1] = -t78*(P[14][0]*t2*t5+P[14][5]*t2*t8-P[14][6]*t2*t10+P[14][1]*t2*t16-P[14][2]*t2*t19+P[14][3]*t2*t22+P[14][4]*t2*t27);
|
|
Kfusion[15][1] = -t78*(P[15][0]*t2*t5+P[15][5]*t2*t8-P[15][6]*t2*t10+P[15][1]*t2*t16-P[15][2]*t2*t19+P[15][3]*t2*t22+P[15][4]*t2*t27);
|
|
Kfusion[16][1] = -t78*(P[16][0]*t2*t5+P[16][5]*t2*t8-P[16][6]*t2*t10+P[16][1]*t2*t16-P[16][2]*t2*t19+P[16][3]*t2*t22+P[16][4]*t2*t27);
|
|
Kfusion[17][1] = -t78*(P[17][0]*t2*t5+P[17][5]*t2*t8-P[17][6]*t2*t10+P[17][1]*t2*t16-P[17][2]*t2*t19+P[17][3]*t2*t22+P[17][4]*t2*t27);
|
|
Kfusion[18][1] = -t78*(P[18][0]*t2*t5+P[18][5]*t2*t8-P[18][6]*t2*t10+P[18][1]*t2*t16-P[18][2]*t2*t19+P[18][3]*t2*t22+P[18][4]*t2*t27);
|
|
Kfusion[19][1] = -t78*(P[19][0]*t2*t5+P[19][5]*t2*t8-P[19][6]*t2*t10+P[19][1]*t2*t16-P[19][2]*t2*t19+P[19][3]*t2*t22+P[19][4]*t2*t27);
|
|
Kfusion[20][1] = -t78*(P[20][0]*t2*t5+P[20][5]*t2*t8-P[20][6]*t2*t10+P[20][1]*t2*t16-P[20][2]*t2*t19+P[20][3]*t2*t22+P[20][4]*t2*t27);
|
|
Kfusion[21][1] = -t78*(P[21][0]*t2*t5+P[21][5]*t2*t8-P[21][6]*t2*t10+P[21][1]*t2*t16-P[21][2]*t2*t19+P[21][3]*t2*t22+P[21][4]*t2*t27);
|
|
Kfusion[22][1] = -t78*(P[22][0]*t2*t5+P[22][5]*t2*t8-P[22][6]*t2*t10+P[22][1]*t2*t16-P[22][2]*t2*t19+P[22][3]*t2*t22+P[22][4]*t2*t27);
|
|
Kfusion[23][1] = -t78*(P[23][0]*t2*t5+P[23][5]*t2*t8-P[23][6]*t2*t10+P[23][1]*t2*t16-P[23][2]*t2*t19+P[23][3]*t2*t22+P[23][4]*t2*t27);
|