From 16154423c86cd6676b7efe600da2dd6cfd6e3869 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Mon, 6 Nov 2017 17:42:23 +1100 Subject: [PATCH] matlab: update optical flow derivation Support use of sensors with arbitrary orientation in body frame --- .../GenerateNavFilterEquations.m | 74 ++++---- matlab/scripts/Inertial Nav EKF/LOSX.c | 160 +++++++++++++++++ matlab/scripts/Inertial Nav EKF/LOSY.c | 162 ++++++++++++++++++ 3 files changed, 357 insertions(+), 39 deletions(-) create mode 100644 matlab/scripts/Inertial Nav EKF/LOSX.c create mode 100644 matlab/scripts/Inertial Nav EKF/LOSY.c diff --git a/matlab/scripts/Inertial Nav EKF/GenerateNavFilterEquations.m b/matlab/scripts/Inertial Nav EKF/GenerateNavFilterEquations.m index f841cb2b28..13ab8267a0 100644 --- a/matlab/scripts/Inertial Nav EKF/GenerateNavFilterEquations.m +++ b/matlab/scripts/Inertial Nav EKF/GenerateNavFilterEquations.m @@ -228,25 +228,43 @@ reset(symengine); %% derive equations for sequential fusion of optical flow measurements load('StatePrediction.mat'); -% range is defined as distance from camera focal point to centre of sensor fov +% Range is defined as distance from camera focal point to object measured +% along sensor Z axis syms range real; -% calculate relative velocity in body frame -relVelBody = transpose(Tbn)*[vn;ve;vd]; +% Define rotation matrix from body to sensor frame +syms Tbs_a_x Tbs_a_y Tbs_a_z real; +syms Tbs_b_x Tbs_b_y Tbs_b_z real; +syms Tbs_c_x Tbs_c_y Tbs_c_z real; +Tbs = [ ... + Tbs_a_x Tbs_a_y Tbs_a_z ; ... + Tbs_b_x Tbs_b_y Tbs_b_z ; ... + Tbs_c_x Tbs_c_y Tbs_c_z ... + ]; -% divide by range to get predicted angular LOS rates relative to X and Y -% axes. Note these are body angular rate motion compensated optical flow rates -losRateX = +relVelBody(2)/range; -losRateY = -relVelBody(1)/range; +% Calculate earth relative velocity in a non-rotating sensor frame +relVelSensor = Tbs * transpose(Tbn) * [vn;ve;vd]; -save('temp1.mat','losRateX','losRateY'); +% Divide by range to get predicted angular LOS rates relative to X and Y +% axes. Note these are rates in a non-rotating sensor frame +losRateSensorX = +relVelSensor(2)/range; +losRateSensorY = -relVelSensor(1)/range; -% calculate the observation Jacobian for the X axis -H_LOSX = jacobian(losRateX,stateVector); % measurement Jacobian +save('temp1.mat','losRateSensorX','losRateSensorY'); + +clear all; +reset(symengine); +load('StatePrediction.mat'); +load('temp1.mat'); + +% calculate the observation Jacobian and Kalman gain for the X axis +H_LOSX = jacobian(losRateSensorX,stateVector); % measurement Jacobian H_LOSX = simplify(H_LOSX); -save('temp2.mat','H_LOSX'); -ccode(H_LOSX,'file','H_LOSX.c'); -fix_c_code('H_LOSX.c'); +K_LOSX = (P*transpose(H_LOSX))/(H_LOSX*P*transpose(H_LOSX) + R_LOS); % Kalman gain vector +K_LOSX = simplify(K_LOSX); +save('temp2.mat','H_LOSX','K_LOSX'); +ccode([H_LOSX;transpose(K_LOSX)],'file','LOSX.c'); +fix_c_code('LOSX.c'); clear all; reset(symengine); @@ -254,35 +272,13 @@ load('StatePrediction.mat'); load('temp1.mat'); % calculate the observation Jacobian for the Y axis -H_LOSY = jacobian(losRateY,stateVector); % measurement Jacobian +H_LOSY = jacobian(losRateSensorY,stateVector); % measurement Jacobian H_LOSY = simplify(H_LOSY); -save('temp3.mat','H_LOSY'); -ccode(H_LOSY,'file','H_LOSY.c'); -fix_c_code('H_LOSY.c'); - -clear all; -reset(symengine); -load('StatePrediction.mat'); -load('temp1.mat'); -load('temp2.mat'); - -% calculate Kalman gain vector for the X axis -K_LOSX = (P*transpose(H_LOSX))/(H_LOSX*P*transpose(H_LOSX) + R_LOS); % Kalman gain vector -K_LOSX = simplify(K_LOSX); -ccode(K_LOSX,'file','K_LOSX.c'); -fix_c_code('K_LOSX.c'); - -clear all; -reset(symengine); -load('StatePrediction.mat'); -load('temp1.mat'); -load('temp3.mat'); - -% calculate Kalman gain vector for the Y axis K_LOSY = (P*transpose(H_LOSY))/(H_LOSY*P*transpose(H_LOSY) + R_LOS); % Kalman gain vector K_LOSY = simplify(K_LOSY); -ccode(K_LOSY,'file','K_LOSY.c'); -fix_c_code('K_LOSY.c'); +save('temp3.mat','H_LOSY','K_LOSY'); +ccode([H_LOSY;transpose(K_LOSY)],'file','LOSY.c'); +fix_c_code('LOSY.c'); % reset workspace clear all; diff --git a/matlab/scripts/Inertial Nav EKF/LOSX.c b/matlab/scripts/Inertial Nav EKF/LOSX.c new file mode 100644 index 0000000000..ea7b36c36e --- /dev/null +++ b/matlab/scripts/Inertial Nav EKF/LOSX.c @@ -0,0 +1,160 @@ +float t2 = 1.0f/range; +float t3 = Tbs.b.y*q0*2.0f; +float t4 = Tbs.b.x*q3*2.0f; +float t18 = Tbs.b.z*q1*2.0f; +float t5 = t3+t4-t18; +float t6 = Tbs.b.y*q1*2.0f; +float t7 = Tbs.b.z*q0*2.0f; +float t16 = Tbs.b.x*q2*2.0f; +float t8 = t6+t7-t16; +float t9 = Tbs.b.x*q0*2.0f; +float t10 = Tbs.b.z*q2*2.0f; +float t17 = Tbs.b.y*q3*2.0f; +float t11 = t9+t10-t17; +float t12 = Tbs.b.x*q1*2.0f; +float t13 = Tbs.b.y*q2*2.0f; +float t14 = Tbs.b.z*q3*2.0f; +float t15 = t12+t13+t14; +float t19 = q0*q0; +float t20 = q1*q1; +float t21 = q2*q2; +float t22 = q3*q3; +float t23 = q0*q3*2.0f; +float t24 = q0*q2*2.0f; +float t25 = q1*q3*2.0f; +float t26 = q0*q1*2.0f; +float t27 = t19+t20-t21-t22; +float t28 = Tbs.b.x*t27; +float t29 = q1*q2*2.0f; +float t30 = t24+t25; +float t31 = Tbs.b.z*t30; +float t32 = t19-t20+t21-t22; +float t33 = Tbs.b.y*t32; +float t34 = t23+t29; +float t35 = Tbs.b.x*t34; +float t36 = q2*q3*2.0f; +float t37 = t19-t20-t21+t22; +float t38 = Tbs.b.z*t37; +float t39 = t24-t25; +float t40 = t26+t36; +float t41 = Tbs.b.y*t40; +float t60 = Tbs.b.x*t39; +float t42 = t38+t41-t60; +float t43 = t8*vd; +float t44 = t5*ve; +float t45 = t11*vn; +float t46 = t43+t44+t45; +float t47 = t5*vd; +float t48 = t15*vn; +float t62 = t8*ve; +float t49 = t47+t48-t62; +float t50 = t15*ve; +float t51 = t8*vn; +float t63 = t11*vd; +float t52 = t50+t51-t63; +float t53 = t15*vd; +float t54 = t11*ve; +float t64 = t5*vn; +float t55 = t53+t54-t64; +float t56 = t23-t29; +float t65 = Tbs.b.y*t56; +float t57 = t28+t31-t65; +float t58 = t26-t36; +float t66 = Tbs.b.z*t58; +float t59 = t33+t35-t66; +float t61 = P[0][0]*t2*t46; +float t67 = P[1][1]*t2*t49; +float t68 = P[4][0]*t2*t57; +float t69 = P[5][0]*t2*t59; +float t70 = P[6][0]*t2*t42; +float t71 = P[1][0]*t2*t49; +float t72 = P[2][0]*t2*t52; +float t73 = P[3][0]*t2*t55; +float t74 = t61+t68+t69+t70+t71+t72+t73; +float t75 = t2*t46*t74; +float t76 = P[4][1]*t2*t57; +float t77 = P[5][1]*t2*t59; +float t78 = P[6][1]*t2*t42; +float t79 = P[0][1]*t2*t46; +float t80 = P[2][1]*t2*t52; +float t81 = P[3][1]*t2*t55; +float t82 = t67+t76+t77+t78+t79+t80+t81; +float t83 = t2*t49*t82; +float t84 = P[4][2]*t2*t57; +float t85 = P[5][2]*t2*t59; +float t86 = P[6][2]*t2*t42; +float t87 = P[0][2]*t2*t46; +float t88 = P[1][2]*t2*t49; +float t89 = P[2][2]*t2*t52; +float t90 = P[3][2]*t2*t55; +float t91 = t84+t85+t86+t87+t88+t89+t90; +float t92 = t2*t52*t91; +float t93 = P[4][3]*t2*t57; +float t94 = P[5][3]*t2*t59; +float t95 = P[6][3]*t2*t42; +float t96 = P[0][3]*t2*t46; +float t97 = P[1][3]*t2*t49; +float t98 = P[2][3]*t2*t52; +float t99 = P[3][3]*t2*t55; +float t100 = t93+t94+t95+t96+t97+t98+t99; +float t101 = t2*t55*t100; +float t102 = P[4][4]*t2*t57; +float t103 = P[5][4]*t2*t59; +float t104 = P[6][4]*t2*t42; +float t105 = P[0][4]*t2*t46; +float t106 = P[1][4]*t2*t49; +float t107 = P[2][4]*t2*t52; +float t108 = P[3][4]*t2*t55; +float t109 = t102+t103+t104+t105+t106+t107+t108; +float t110 = t2*t57*t109; +float t111 = P[4][5]*t2*t57; +float t112 = P[5][5]*t2*t59; +float t113 = P[6][5]*t2*t42; +float t114 = P[0][5]*t2*t46; +float t115 = P[1][5]*t2*t49; +float t116 = P[2][5]*t2*t52; +float t117 = P[3][5]*t2*t55; +float t118 = t111+t112+t113+t114+t115+t116+t117; +float t119 = t2*t59*t118; +float t120 = P[4][6]*t2*t57; +float t121 = P[5][6]*t2*t59; +float t122 = P[6][6]*t2*t42; +float t123 = P[0][6]*t2*t46; +float t124 = P[1][6]*t2*t49; +float t125 = P[2][6]*t2*t52; +float t126 = P[3][6]*t2*t55; +float t127 = t120+t121+t122+t123+t124+t125+t126; +float t128 = t2*t42*t127; +float t129 = R_LOS+t75+t83+t92+t101+t110+t119+t128; +float t130 = 1.0f/t129; +H_LOS[0] = t2*t46; +H_LOS[1] = t2*t49; +H_LOS[2] = t2*t52; +H_LOS[3] = t2*t55; +H_LOS[4] = t2*(t28+t31-Tbs.b.y*(t23-q1*q2*2.0)); +H_LOS[5] = t2*(t33+t35-Tbs.b.z*(t26-q2*q3*2.0)); +H_LOS[6] = t2*t42; +Kfusion[0] = t130*(t61+P[0][6]*t2*t42+P[0][1]*t2*t49+P[0][2]*t2*t52+P[0][3]*t2*t55+P[0][4]*t2*t57+P[0][5]*t2*t59); +Kfusion[1] = t130*(t67+P[1][0]*t2*t46+P[1][6]*t2*t42+P[1][2]*t2*t52+P[1][3]*t2*t55+P[1][4]*t2*t57+P[1][5]*t2*t59); +Kfusion[2] = t130*(t89+P[2][0]*t2*t46+P[2][6]*t2*t42+P[2][1]*t2*t49+P[2][3]*t2*t55+P[2][4]*t2*t57+P[2][5]*t2*t59); +Kfusion[3] = t130*(t99+P[3][0]*t2*t46+P[3][6]*t2*t42+P[3][1]*t2*t49+P[3][2]*t2*t52+P[3][4]*t2*t57+P[3][5]*t2*t59); +Kfusion[4] = t130*(t102+P[4][0]*t2*t46+P[4][6]*t2*t42+P[4][1]*t2*t49+P[4][2]*t2*t52+P[4][3]*t2*t55+P[4][5]*t2*t59); +Kfusion[5] = t130*(t112+P[5][0]*t2*t46+P[5][6]*t2*t42+P[5][1]*t2*t49+P[5][2]*t2*t52+P[5][3]*t2*t55+P[5][4]*t2*t57); +Kfusion[6] = t130*(t122+P[6][0]*t2*t46+P[6][1]*t2*t49+P[6][2]*t2*t52+P[6][3]*t2*t55+P[6][4]*t2*t57+P[6][5]*t2*t59); +Kfusion[7] = t130*(P[7][0]*t2*t46+P[7][6]*t2*t42+P[7][1]*t2*t49+P[7][2]*t2*t52+P[7][3]*t2*t55+P[7][4]*t2*t57+P[7][5]*t2*t59); +Kfusion[8] = t130*(P[8][0]*t2*t46+P[8][6]*t2*t42+P[8][1]*t2*t49+P[8][2]*t2*t52+P[8][3]*t2*t55+P[8][4]*t2*t57+P[8][5]*t2*t59); +Kfusion[9] = t130*(P[9][0]*t2*t46+P[9][6]*t2*t42+P[9][1]*t2*t49+P[9][2]*t2*t52+P[9][3]*t2*t55+P[9][4]*t2*t57+P[9][5]*t2*t59); +Kfusion[10] = t130*(P[10][0]*t2*t46+P[10][6]*t2*t42+P[10][1]*t2*t49+P[10][2]*t2*t52+P[10][3]*t2*t55+P[10][4]*t2*t57+P[10][5]*t2*t59); +Kfusion[11] = t130*(P[11][0]*t2*t46+P[11][6]*t2*t42+P[11][1]*t2*t49+P[11][2]*t2*t52+P[11][3]*t2*t55+P[11][4]*t2*t57+P[11][5]*t2*t59); +Kfusion[12] = t130*(P[12][0]*t2*t46+P[12][6]*t2*t42+P[12][1]*t2*t49+P[12][2]*t2*t52+P[12][3]*t2*t55+P[12][4]*t2*t57+P[12][5]*t2*t59); +Kfusion[13] = t130*(P[13][0]*t2*t46+P[13][6]*t2*t42+P[13][1]*t2*t49+P[13][2]*t2*t52+P[13][3]*t2*t55+P[13][4]*t2*t57+P[13][5]*t2*t59); +Kfusion[14] = t130*(P[14][0]*t2*t46+P[14][6]*t2*t42+P[14][1]*t2*t49+P[14][2]*t2*t52+P[14][3]*t2*t55+P[14][4]*t2*t57+P[14][5]*t2*t59); +Kfusion[15] = t130*(P[15][0]*t2*t46+P[15][6]*t2*t42+P[15][1]*t2*t49+P[15][2]*t2*t52+P[15][3]*t2*t55+P[15][4]*t2*t57+P[15][5]*t2*t59); +Kfusion[16] = t130*(P[16][0]*t2*t46+P[16][6]*t2*t42+P[16][1]*t2*t49+P[16][2]*t2*t52+P[16][3]*t2*t55+P[16][4]*t2*t57+P[16][5]*t2*t59); +Kfusion[17] = t130*(P[17][0]*t2*t46+P[17][6]*t2*t42+P[17][1]*t2*t49+P[17][2]*t2*t52+P[17][3]*t2*t55+P[17][4]*t2*t57+P[17][5]*t2*t59); +Kfusion[18] = t130*(P[18][0]*t2*t46+P[18][6]*t2*t42+P[18][1]*t2*t49+P[18][2]*t2*t52+P[18][3]*t2*t55+P[18][4]*t2*t57+P[18][5]*t2*t59); +Kfusion[19] = t130*(P[19][0]*t2*t46+P[19][6]*t2*t42+P[19][1]*t2*t49+P[19][2]*t2*t52+P[19][3]*t2*t55+P[19][4]*t2*t57+P[19][5]*t2*t59); +Kfusion[20] = t130*(P[20][0]*t2*t46+P[20][6]*t2*t42+P[20][1]*t2*t49+P[20][2]*t2*t52+P[20][3]*t2*t55+P[20][4]*t2*t57+P[20][5]*t2*t59); +Kfusion[21] = t130*(P[21][0]*t2*t46+P[21][6]*t2*t42+P[21][1]*t2*t49+P[21][2]*t2*t52+P[21][3]*t2*t55+P[21][4]*t2*t57+P[21][5]*t2*t59); +Kfusion[22] = t130*(P[22][0]*t2*t46+P[22][6]*t2*t42+P[22][1]*t2*t49+P[22][2]*t2*t52+P[22][3]*t2*t55+P[22][4]*t2*t57+P[22][5]*t2*t59); +Kfusion[23] = t130*(P[23][0]*t2*t46+P[23][6]*t2*t42+P[23][1]*t2*t49+P[23][2]*t2*t52+P[23][3]*t2*t55+P[23][4]*t2*t57+P[23][5]*t2*t59); diff --git a/matlab/scripts/Inertial Nav EKF/LOSY.c b/matlab/scripts/Inertial Nav EKF/LOSY.c new file mode 100644 index 0000000000..260e50c048 --- /dev/null +++ b/matlab/scripts/Inertial Nav EKF/LOSY.c @@ -0,0 +1,162 @@ +float t2 = 1.0f/range; +float t3 = Tbs.a.y*q0*2.0f; +float t4 = Tbs.a.x*q3*2.0f; +float t18 = Tbs.a.z*q1*2.0f; +float t5 = t3+t4-t18; +float t6 = Tbs.a.y*q1*2.0f; +float t7 = Tbs.a.z*q0*2.0f; +float t16 = Tbs.a.x*q2*2.0f; +float t8 = t6+t7-t16; +float t9 = Tbs.a.x*q0*2.0f; +float t10 = Tbs.a.z*q2*2.0f; +float t17 = Tbs.a.y*q3*2.0f; +float t11 = t9+t10-t17; +float t12 = Tbs.a.x*q1*2.0f; +float t13 = Tbs.a.y*q2*2.0f; +float t14 = Tbs.a.z*q3*2.0f; +float t15 = t12+t13+t14; +float t19 = q0*q0; +float t20 = q1*q1; +float t21 = q2*q2; +float t22 = q3*q3; +float t23 = q0*q3*2.0f; +float t24 = q0*q2*2.0f; +float t25 = q1*q3*2.0f; +float t26 = q0*q1*2.0f; +float t27 = t19+t20-t21-t22; +float t28 = Tbs.a.x*t27; +float t29 = q1*q2*2.0f; +float t30 = t24+t25; +float t31 = Tbs.a.z*t30; +float t32 = t19-t20+t21-t22; +float t33 = Tbs.a.y*t32; +float t34 = t23+t29; +float t35 = Tbs.a.x*t34; +float t36 = q2*q3*2.0f; +float t37 = t19-t20-t21+t22; +float t38 = Tbs.a.z*t37; +float t39 = t24-t25; +float t40 = t26+t36; +float t41 = Tbs.a.y*t40; +float t60 = Tbs.a.x*t39; +float t42 = t38+t41-t60; +float t43 = t8*vd; +float t44 = t5*ve; +float t45 = t11*vn; +float t46 = t43+t44+t45; +float t47 = t5*vd; +float t48 = t15*vn; +float t62 = t8*ve; +float t49 = t47+t48-t62; +float t50 = t15*ve; +float t51 = t8*vn; +float t63 = t11*vd; +float t52 = t50+t51-t63; +float t53 = t15*vd; +float t54 = t11*ve; +float t64 = t5*vn; +float t55 = t53+t54-t64; +float t56 = t23-t29; +float t65 = Tbs.a.y*t56; +float t57 = t28+t31-t65; +float t58 = t26-t36; +float t66 = Tbs.a.z*t58; +float t59 = t33+t35-t66; +float t61 = P[0][0]*t2*t46; +float t67 = P[1][1]*t2*t49; +float t68 = P[4][0]*t2*t57; +float t69 = P[5][0]*t2*t59; +float t70 = P[6][0]*t2*t42; +float t71 = P[1][0]*t2*t49; +float t72 = P[2][0]*t2*t52; +float t73 = P[3][0]*t2*t55; +float t74 = t61+t68+t69+t70+t71+t72+t73; +float t75 = t2*t46*t74; +float t76 = P[4][1]*t2*t57; +float t77 = P[5][1]*t2*t59; +float t78 = P[6][1]*t2*t42; +float t79 = P[0][1]*t2*t46; +float t80 = P[2][1]*t2*t52; +float t81 = P[3][1]*t2*t55; +float t82 = t67+t76+t77+t78+t79+t80+t81; +float t83 = t2*t49*t82; +float t84 = P[4][2]*t2*t57; +float t85 = P[5][2]*t2*t59; +float t86 = P[6][2]*t2*t42; +float t87 = P[0][2]*t2*t46; +float t88 = P[1][2]*t2*t49; +float t89 = P[2][2]*t2*t52; +float t90 = P[3][2]*t2*t55; +float t91 = t84+t85+t86+t87+t88+t89+t90; +float t92 = t2*t52*t91; +float t93 = P[4][3]*t2*t57; +float t94 = P[5][3]*t2*t59; +float t95 = P[6][3]*t2*t42; +float t96 = P[0][3]*t2*t46; +float t97 = P[1][3]*t2*t49; +float t98 = P[2][3]*t2*t52; +float t99 = P[3][3]*t2*t55; +float t100 = t93+t94+t95+t96+t97+t98+t99; +float t101 = t2*t55*t100; +float t102 = P[4][4]*t2*t57; +float t103 = P[5][4]*t2*t59; +float t104 = P[6][4]*t2*t42; +float t105 = P[0][4]*t2*t46; +float t106 = P[1][4]*t2*t49; +float t107 = P[2][4]*t2*t52; +float t108 = P[3][4]*t2*t55; +float t109 = t102+t103+t104+t105+t106+t107+t108; +float t110 = t2*t57*t109; +float t111 = P[4][5]*t2*t57; +float t112 = P[5][5]*t2*t59; +float t113 = P[6][5]*t2*t42; +float t114 = P[0][5]*t2*t46; +float t115 = P[1][5]*t2*t49; +float t116 = P[2][5]*t2*t52; +float t117 = P[3][5]*t2*t55; +float t118 = t111+t112+t113+t114+t115+t116+t117; +float t119 = t2*t59*t118; +float t120 = P[4][6]*t2*t57; +float t121 = P[5][6]*t2*t59; +float t122 = P[6][6]*t2*t42; +float t123 = P[0][6]*t2*t46; +float t124 = P[1][6]*t2*t49; +float t125 = P[2][6]*t2*t52; +float t126 = P[3][6]*t2*t55; +float t127 = t120+t121+t122+t123+t124+t125+t126; +float t128 = t2*t42*t127; +float t129 = R_LOS+t75+t83+t92+t101+t110+t119+t128; +float t130 = 1.0f/t129; + +H_LOS[0] = -t2*t46; +H_LOS[1] = -t2*t49; +H_LOS[2] = -t2*t52; +H_LOS[3] = -t2*t55; +H_LOS[4] = -t2*(t28+t31-Tbs.a.y*(t23-q1*q2*2.0f)); +H_LOS[5] = -t2*(t33+t35-Tbs.a.z*(t26-q2*q3*2.0f)); +H_LOS[6] = -t2*t42; + +Kfusion[0] = -t130*(t61+P[0][6]*t2*t42+P[0][1]*t2*t49+P[0][2]*t2*t52+P[0][3]*t2*t55+P[0][4]*t2*t57+P[0][5]*t2*t59); +Kfusion[1] = -t130*(t67+P[1][0]*t2*t46+P[1][6]*t2*t42+P[1][2]*t2*t52+P[1][3]*t2*t55+P[1][4]*t2*t57+P[1][5]*t2*t59); +Kfusion[2] = -t130*(t89+P[2][0]*t2*t46+P[2][6]*t2*t42+P[2][1]*t2*t49+P[2][3]*t2*t55+P[2][4]*t2*t57+P[2][5]*t2*t59); +Kfusion[3] = -t130*(t99+P[3][0]*t2*t46+P[3][6]*t2*t42+P[3][1]*t2*t49+P[3][2]*t2*t52+P[3][4]*t2*t57+P[3][5]*t2*t59); +Kfusion[4] = -t130*(t102+P[4][0]*t2*t46+P[4][6]*t2*t42+P[4][1]*t2*t49+P[4][2]*t2*t52+P[4][3]*t2*t55+P[4][5]*t2*t59); +Kfusion[5] = -t130*(t112+P[5][0]*t2*t46+P[5][6]*t2*t42+P[5][1]*t2*t49+P[5][2]*t2*t52+P[5][3]*t2*t55+P[5][4]*t2*t57); +Kfusion[6] = -t130*(t122+P[6][0]*t2*t46+P[6][1]*t2*t49+P[6][2]*t2*t52+P[6][3]*t2*t55+P[6][4]*t2*t57+P[6][5]*t2*t59); +Kfusion[7] = -t130*(P[7][0]*t2*t46+P[7][6]*t2*t42+P[7][1]*t2*t49+P[7][2]*t2*t52+P[7][3]*t2*t55+P[7][4]*t2*t57+P[7][5]*t2*t59); +Kfusion[8] = -t130*(P[8][0]*t2*t46+P[8][6]*t2*t42+P[8][1]*t2*t49+P[8][2]*t2*t52+P[8][3]*t2*t55+P[8][4]*t2*t57+P[8][5]*t2*t59); +Kfusion[9] = -t130*(P[9][0]*t2*t46+P[9][6]*t2*t42+P[9][1]*t2*t49+P[9][2]*t2*t52+P[9][3]*t2*t55+P[9][4]*t2*t57+P[9][5]*t2*t59); +Kfusion[10] = -t130*(P[10][0]*t2*t46+P[10][6]*t2*t42+P[10][1]*t2*t49+P[10][2]*t2*t52+P[10][3]*t2*t55+P[10][4]*t2*t57+P[10][5]*t2*t59); +Kfusion[11] = -t130*(P[11][0]*t2*t46+P[11][6]*t2*t42+P[11][1]*t2*t49+P[11][2]*t2*t52+P[11][3]*t2*t55+P[11][4]*t2*t57+P[11][5]*t2*t59); +Kfusion[12] = -t130*(P[12][0]*t2*t46+P[12][6]*t2*t42+P[12][1]*t2*t49+P[12][2]*t2*t52+P[12][3]*t2*t55+P[12][4]*t2*t57+P[12][5]*t2*t59); +Kfusion[13] = -t130*(P[13][0]*t2*t46+P[13][6]*t2*t42+P[13][1]*t2*t49+P[13][2]*t2*t52+P[13][3]*t2*t55+P[13][4]*t2*t57+P[13][5]*t2*t59); +Kfusion[14] = -t130*(P[14][0]*t2*t46+P[14][6]*t2*t42+P[14][1]*t2*t49+P[14][2]*t2*t52+P[14][3]*t2*t55+P[14][4]*t2*t57+P[14][5]*t2*t59); +Kfusion[15] = -t130*(P[15][0]*t2*t46+P[15][6]*t2*t42+P[15][1]*t2*t49+P[15][2]*t2*t52+P[15][3]*t2*t55+P[15][4]*t2*t57+P[15][5]*t2*t59); +Kfusion[16] = -t130*(P[16][0]*t2*t46+P[16][6]*t2*t42+P[16][1]*t2*t49+P[16][2]*t2*t52+P[16][3]*t2*t55+P[16][4]*t2*t57+P[16][5]*t2*t59); +Kfusion[17] = -t130*(P[17][0]*t2*t46+P[17][6]*t2*t42+P[17][1]*t2*t49+P[17][2]*t2*t52+P[17][3]*t2*t55+P[17][4]*t2*t57+P[17][5]*t2*t59); +Kfusion[18] = -t130*(P[18][0]*t2*t46+P[18][6]*t2*t42+P[18][1]*t2*t49+P[18][2]*t2*t52+P[18][3]*t2*t55+P[18][4]*t2*t57+P[18][5]*t2*t59); +Kfusion[19] = -t130*(P[19][0]*t2*t46+P[19][6]*t2*t42+P[19][1]*t2*t49+P[19][2]*t2*t52+P[19][3]*t2*t55+P[19][4]*t2*t57+P[19][5]*t2*t59); +Kfusion[20] = -t130*(P[20][0]*t2*t46+P[20][6]*t2*t42+P[20][1]*t2*t49+P[20][2]*t2*t52+P[20][3]*t2*t55+P[20][4]*t2*t57+P[20][5]*t2*t59); +Kfusion[21] = -t130*(P[21][0]*t2*t46+P[21][6]*t2*t42+P[21][1]*t2*t49+P[21][2]*t2*t52+P[21][3]*t2*t55+P[21][4]*t2*t57+P[21][5]*t2*t59); +Kfusion[22] = -t130*(P[22][0]*t2*t46+P[22][6]*t2*t42+P[22][1]*t2*t49+P[22][2]*t2*t52+P[22][3]*t2*t55+P[22][4]*t2*t57+P[22][5]*t2*t59); +Kfusion[23] = -t130*(P[23][0]*t2*t46+P[23][6]*t2*t42+P[23][1]*t2*t49+P[23][2]*t2*t52+P[23][3]*t2*t55+P[23][4]*t2*t57+P[23][5]*t2*t59);