Browse Source
Work around limitation in Symbolic toolbox environment space by incrementally saving and clearing workspace Remove vehicle vertical position from optical flow prediction equations (use range measurement instead) and regenerate auto-code Remove legacy optical flow auto-code conversion method as it is not required now a work around for symbolic toolbox limitations has been developed Fix out of date syntaxmaster
7 changed files with 488 additions and 489 deletions
@ -1,281 +0,0 @@
@@ -1,281 +0,0 @@
|
||||
// Auto code for fusion of line of sight rate massurements from a optical flow camera aligned with the Z body axis |
||||
// Generated using MAtlab in-built symbolic toolbox to c-code function |
||||
// 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) |
||||
|
||||
// intermediate variable from algebraic optimisation |
||||
float SH_LOS[14]; |
||||
SH_LOS[0] = sq(q0) - sq(q1) - sq(q2) + sq(q3); |
||||
SH_LOS[1] = vn*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) - vd*(2*q0*q2 - 2*q1*q3) + ve*(2*q0*q3 + 2*q1*q2); |
||||
SH_LOS[2] = ve*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + vd*(2*q0*q1 + 2*q2*q3) - vn*(2*q0*q3 - 2*q1*q2); |
||||
SH_LOS[3] = 1/(pd - ptd); |
||||
SH_LOS[4] = vd*SH_LOS[0] - ve*(2*q0*q1 - 2*q2*q3) + vn*(2*q0*q2 + 2*q1*q3); |
||||
SH_LOS[5] = 2.0f*q0*q2 - 2.0f*q1*q3; |
||||
SH_LOS[6] = 2.0f*q0*q1 + 2.0f*q2*q3; |
||||
SH_LOS[7] = q0*q0; |
||||
SH_LOS[8] = q1*q1; |
||||
SH_LOS[9] = q2*q2; |
||||
SH_LOS[10] = q3*q3; |
||||
SH_LOS[11] = q0*q3*2.0f; |
||||
SH_LOS[12] = pd-ptd; |
||||
SH_LOS[13] = 1.0f/(SH_LOS[12]*SH_LOS[12]); |
||||
|
||||
// Calculate the observation jacobians for the LOS rate about the X body axis |
||||
float H_LOS[24]; |
||||
H_LOS[0] = SH_LOS[3]*SH_LOS[2]*SH_LOS[6]-SH_LOS[3]*SH_LOS[0]*SH_LOS[4]; |
||||
H_LOS[1] = SH_LOS[3]*SH_LOS[2]*SH_LOS[5]; |
||||
H_LOS[2] = SH_LOS[3]*SH_LOS[0]*SH_LOS[1]; |
||||
H_LOS[3] = SH_LOS[3]*SH_LOS[0]*(SH_LOS[11]-q1*q2*2.0f); |
||||
H_LOS[4] = -SH_LOS[3]*SH_LOS[0]*(SH_LOS[7]-SH_LOS[8]+SH_LOS[9]-SH_LOS[10]); |
||||
H_LOS[5] = -SH_LOS[3]*SH_LOS[0]*SH_LOS[6]; |
||||
H_LOS[8] = SH_LOS[2]*SH_LOS[0]*SH_LOS[13]; |
||||
|
||||
// Calculate the observation jacobians for the LOS rate about the Y body axis |
||||
float H_LOS[24]; |
||||
H_LOS[0] = -SH_LOS[3]*SH_LOS[6]*SH_LOS[1]; |
||||
H_LOS[1] = -SH_LOS[3]*SH_LOS[0]*SH_LOS[4]-SH_LOS[3]*SH_LOS[1]*SH_LOS[5]; |
||||
H_LOS[2] = SH_LOS[3]*SH_LOS[2]*SH_LOS[0]; |
||||
H_LOS[3] = SH_LOS[3]*SH_LOS[0]*(SH_LOS[7]+SH_LOS[8]-SH_LOS[9]-SH_LOS[10]); |
||||
H_LOS[4] = SH_LOS[3]*SH_LOS[0]*(SH_LOS[11]+q1*q2*2.0f); |
||||
H_LOS[5] = -SH_LOS[3]*SH_LOS[0]*SH_LOS[5]; |
||||
H_LOS[8] = -SH_LOS[0]*SH_LOS[1]*SH_LOS[13]; |
||||
|
||||
// Intermediate variables used to calculate the Kalman gain matrices for the LOS rate about the X body axis |
||||
float t2 = SH_LOS[3]; |
||||
float t3 = SH_LOS[0]; |
||||
float t4 = SH_LOS[2]; |
||||
float t5 = SH_LOS[6]; |
||||
float t100 = t2 * t3 * t5; |
||||
float t6 = SH_LOS[4]; |
||||
float t7 = t2*t3*t6; |
||||
float t9 = t2*t4*t5; |
||||
float t8 = t7-t9; |
||||
float t10 = q0*q3*2.0f; |
||||
float t21 = q1*q2*2.0f; |
||||
float t11 = t10-t21; |
||||
float t101 = t2 * t3 * t11; |
||||
float t12 = pd-ptd; |
||||
float t13 = 1.0f/(t12*t12); |
||||
float t104 = t3 * t4 * t13; |
||||
float t14 = SH_LOS[5]; |
||||
float t102 = t2 * t4 * t14; |
||||
float t15 = SH_LOS[1]; |
||||
float t103 = t2 * t3 * t15; |
||||
float t16 = q0*q0; |
||||
float t17 = q1*q1; |
||||
float t18 = q2*q2; |
||||
float t19 = q3*q3; |
||||
float t20 = t16-t17+t18-t19; |
||||
float t105 = t2 * t3 * t20; |
||||
float t22 = P[1][1]*t102; |
||||
float t23 = P[3][0]*t101; |
||||
float t24 = P[8][0]*t104; |
||||
float t25 = P[1][0]*t102; |
||||
float t26 = P[2][0]*t103; |
||||
float t63 = P[0][0]*t8; |
||||
float t64 = P[5][0]*t100; |
||||
float t65 = P[4][0]*t105; |
||||
float t27 = t23+t24+t25+t26-t63-t64-t65; |
||||
float t28 = P[3][3]*t101; |
||||
float t29 = P[8][3]*t104; |
||||
float t30 = P[1][3]*t102; |
||||
float t31 = P[2][3]*t103; |
||||
float t67 = P[0][3]*t8; |
||||
float t68 = P[5][3]*t100; |
||||
float t69 = P[4][3]*t105; |
||||
float t32 = t28+t29+t30+t31-t67-t68-t69; |
||||
float t33 = t101*t32; |
||||
float t34 = P[3][8]*t101; |
||||
float t35 = P[8][8]*t104; |
||||
float t36 = P[1][8]*t102; |
||||
float t37 = P[2][8]*t103; |
||||
float t70 = P[0][8]*t8; |
||||
float t71 = P[5][8]*t100; |
||||
float t72 = P[4][8]*t105; |
||||
float t38 = t34+t35+t36+t37-t70-t71-t72; |
||||
float t39 = t104*t38; |
||||
float t40 = P[3][1]*t101; |
||||
float t41 = P[8][1]*t104; |
||||
float t42 = P[2][1]*t103; |
||||
float t73 = P[0][1]*t8; |
||||
float t74 = P[5][1]*t100; |
||||
float t75 = P[4][1]*t105; |
||||
float t43 = t22+t40+t41+t42-t73-t74-t75; |
||||
float t44 = t102*t43; |
||||
float t45 = P[3][2]*t101; |
||||
float t46 = P[8][2]*t104; |
||||
float t47 = P[1][2]*t102; |
||||
float t48 = P[2][2]*t103; |
||||
float t76 = P[0][2]*t8; |
||||
float t77 = P[5][2]*t100; |
||||
float t78 = P[4][2]*t105; |
||||
float t49 = t45+t46+t47+t48-t76-t77-t78; |
||||
float t50 = t103*t49; |
||||
float t51 = P[3][5]*t101; |
||||
float t52 = P[8][5]*t104; |
||||
float t53 = P[1][5]*t102; |
||||
float t54 = P[2][5]*t103; |
||||
float t79 = P[0][5]*t8; |
||||
float t80 = P[5][5]*t100; |
||||
float t81 = P[4][5]*t105; |
||||
float t55 = t51+t52+t53+t54-t79-t80-t81; |
||||
float t56 = P[3][4]*t101; |
||||
float t57 = P[8][4]*t104; |
||||
float t58 = P[1][4]*t102; |
||||
float t59 = P[2][4]*t103; |
||||
float t83 = P[0][4]*t8; |
||||
float t84 = P[5][4]*t100; |
||||
float t85 = P[4][4]*t105; |
||||
float t60 = t56+t57+t58+t59-t83-t84-t85; |
||||
float t66 = t8*t27; |
||||
float t82 = t100*t55; |
||||
float t86 = t105*t60; |
||||
float t61 = R_LOS+t33+t39+t44+t50-t66-t82-t86; // innovation variance - should always be >= R_LOS |
||||
float t62 = 1.0f/t61; |
||||
|
||||
// Calculate the Kalman gain matrix for the LOS rate about the X body axis |
||||
float Kfusion[24]; |
||||
Kfusion[0] = t62*(-P[0][0]*t8-P[0][5]*t100+P[0][3]*t101+P[0][1]*t102+P[0][2]*t103+P[0][8]*t104-P[0][4]*t105); |
||||
Kfusion[1] = t62*(t22-P[1][0]*t8-P[1][5]*t100+P[1][3]*t101+P[1][2]*t103+P[1][8]*t104-P[1][4]*t105); |
||||
Kfusion[2] = t62*(t48-P[2][0]*t8-P[2][5]*t100+P[2][3]*t101+P[2][1]*t102+P[2][8]*t104-P[2][4]*t105); |
||||
Kfusion[3] = t62*(t28-P[3][0]*t8-P[3][5]*t100+P[3][1]*t102+P[3][2]*t103+P[3][8]*t104-P[3][4]*t105); |
||||
Kfusion[4] = t62*(-t85-P[4][0]*t8-P[4][5]*t100+P[4][3]*t101+P[4][1]*t102+P[4][2]*t103+P[4][8]*t104); |
||||
Kfusion[5] = t62*(-t80-P[5][0]*t8+P[5][3]*t101+P[5][1]*t102+P[5][2]*t103+P[5][8]*t104-P[5][4]*t105); |
||||
Kfusion[6] = t62*(-P[6][0]*t8-P[6][5]*t100+P[6][3]*t101+P[6][1]*t102+P[6][2]*t103+P[6][8]*t104-P[6][4]*t105); |
||||
Kfusion[7] = t62*(-P[7][0]*t8-P[7][5]*t100+P[7][3]*t101+P[7][1]*t102+P[7][2]*t103+P[7][8]*t104-P[7][4]*t105); |
||||
Kfusion[8] = t62*(t35-P[8][0]*t8-P[8][5]*t100+P[8][3]*t101+P[8][1]*t102+P[8][2]*t103-P[8][4]*t105); |
||||
Kfusion[9] = t62*(-P[9][0]*t8-P[9][5]*t100+P[9][3]*t101+P[9][1]*t102+P[9][2]*t103+P[9][8]*t104-P[9][4]*t105); |
||||
Kfusion[10] = t62*(-P[10][0]*t8-P[10][5]*t100+P[10][3]*t101+P[10][1]*t102+P[10][2]*t103+P[10][8]*t104-P[10][4]*t105); |
||||
Kfusion[11] = t62*(-P[11][0]*t8-P[11][5]*t100+P[11][3]*t101+P[11][1]*t102+P[11][2]*t103+P[11][8]*t104-P[11][4]*t105); |
||||
Kfusion[12] = t62*(-P[12][0]*t8-P[12][5]*t100+P[12][3]*t101+P[12][1]*t102+P[12][2]*t103+P[12][8]*t104-P[12][4]*t105); |
||||
Kfusion[13] = t62*(-P[13][0]*t8-P[13][5]*t100+P[13][3]*t101+P[13][1]*t102+P[13][2]*t103+P[13][8]*t104-P[13][4]*t105); |
||||
Kfusion[14] = t62*(-P[14][0]*t8-P[14][5]*t100+P[14][3]*t101+P[14][1]*t102+P[14][2]*t103+P[14][8]*t104-P[14][4]*t105); |
||||
Kfusion[15] = t62*(-P[15][0]*t8-P[15][5]*t100+P[15][3]*t101+P[15][1]*t102+P[15][2]*t103+P[15][8]*t104-P[15][4]*t105); |
||||
Kfusion[16] = t62*(-P[16][0]*t8-P[16][5]*t100+P[16][3]*t101+P[16][1]*t102+P[16][2]*t103+P[16][8]*t104-P[16][4]*t105); |
||||
Kfusion[17] = t62*(-P[17][0]*t8-P[17][5]*t100+P[17][3]*t101+P[17][1]*t102+P[17][2]*t103+P[17][8]*t104-P[17][4]*t105); |
||||
Kfusion[18] = t62*(-P[18][0]*t8-P[18][5]*t100+P[18][3]*t101+P[18][1]*t102+P[18][2]*t103+P[18][8]*t104-P[18][4]*t105); |
||||
Kfusion[19] = t62*(-P[19][0]*t8-P[19][5]*t100+P[19][3]*t101+P[19][1]*t102+P[19][2]*t103+P[19][8]*t104-P[19][4]*t105); |
||||
Kfusion[20] = t62*(-P[20][0]*t8-P[20][5]*t100+P[20][3]*t101+P[20][1]*t102+P[20][2]*t103+P[20][8]*t104-P[20][4]*t105); |
||||
Kfusion[21] = t62*(-P[21][0]*t8-P[21][5]*t100+P[21][3]*t101+P[21][1]*t102+P[21][2]*t103+P[21][8]*t104-P[21][4]*t105); |
||||
Kfusion[22] = t62*(-P[22][0]*t8-P[22][5]*t100+P[22][3]*t101+P[22][1]*t102+P[22][2]*t103+P[22][8]*t104-P[22][4]*t105); |
||||
Kfusion[23] = t62*(-P[23][0]*t8-P[23][5]*t100+P[23][3]*t101+P[23][1]*t102+P[23][2]*t103+P[23][8]*t104-P[23][4]*t105); |
||||
|
||||
// Intermediate variables used to calculate the Kalman gain matrices for the LOS rate about the Y body axis |
||||
float t2 = SH_LOS[3]; |
||||
float t3 = SH_LOS[0]; |
||||
float t4 = SH_LOS[1]; |
||||
float t5 = SH_LOS[5]; |
||||
float t100 = t2 * t3 * t5; |
||||
float t6 = SH_LOS[4]; |
||||
float t7 = t2*t3*t6; |
||||
float t8 = t2*t4*t5; |
||||
float t9 = t7+t8; |
||||
float t10 = q0*q3*2.0f; |
||||
float t11 = q1*q2*2.0f; |
||||
float t12 = t10+t11; |
||||
float t101 = t2 * t3 * t12; |
||||
float t13 = pd-ptd; |
||||
float t14 = 1.0f/(t13*t13); |
||||
float t104 = t3 * t4 * t14; |
||||
float t15 = SH_LOS[6]; |
||||
float t105 = t2 * t4 * t15; |
||||
float t16 = SH_LOS[2]; |
||||
float t102 = t2 * t3 * t16; |
||||
float t17 = q0*q0; |
||||
float t18 = q1*q1; |
||||
float t19 = q2*q2; |
||||
float t20 = q3*q3; |
||||
float t21 = t17+t18-t19-t20; |
||||
float t103 = t2 * t3 * t21; |
||||
float t22 = P[0][0]*t105; |
||||
float t23 = P[1][1]*t9; |
||||
float t24 = P[8][1]*t104; |
||||
float t25 = P[0][1]*t105; |
||||
float t26 = P[5][1]*t100; |
||||
float t64 = P[4][1]*t101; |
||||
float t65 = P[2][1]*t102; |
||||
float t66 = P[3][1]*t103; |
||||
float t27 = t23+t24+t25+t26-t64-t65-t66; |
||||
float t28 = t9*t27; |
||||
float t29 = P[1][4]*t9; |
||||
float t30 = P[8][4]*t104; |
||||
float t31 = P[0][4]*t105; |
||||
float t32 = P[5][4]*t100; |
||||
float t67 = P[4][4]*t101; |
||||
float t68 = P[2][4]*t102; |
||||
float t69 = P[3][4]*t103; |
||||
float t33 = t29+t30+t31+t32-t67-t68-t69; |
||||
float t34 = P[1][8]*t9; |
||||
float t35 = P[8][8]*t104; |
||||
float t36 = P[0][8]*t105; |
||||
float t37 = P[5][8]*t100; |
||||
float t71 = P[4][8]*t101; |
||||
float t72 = P[2][8]*t102; |
||||
float t73 = P[3][8]*t103; |
||||
float t38 = t34+t35+t36+t37-t71-t72-t73; |
||||
float t39 = t104*t38; |
||||
float t40 = P[1][0]*t9; |
||||
float t41 = P[8][0]*t104; |
||||
float t42 = P[5][0]*t100; |
||||
float t74 = P[4][0]*t101; |
||||
float t75 = P[2][0]*t102; |
||||
float t76 = P[3][0]*t103; |
||||
float t43 = t22+t40+t41+t42-t74-t75-t76; |
||||
float t44 = t105*t43; |
||||
float t45 = P[1][2]*t9; |
||||
float t46 = P[8][2]*t104; |
||||
float t47 = P[0][2]*t105; |
||||
float t48 = P[5][2]*t100; |
||||
float t63 = P[2][2]*t102; |
||||
float t77 = P[4][2]*t101; |
||||
float t78 = P[3][2]*t103; |
||||
float t49 = t45+t46+t47+t48-t63-t77-t78; |
||||
float t50 = P[1][5]*t9; |
||||
float t51 = P[8][5]*t104; |
||||
float t52 = P[0][5]*t105; |
||||
float t53 = P[5][5]*t100; |
||||
float t80 = P[4][5]*t101; |
||||
float t81 = P[2][5]*t102; |
||||
float t82 = P[3][5]*t103; |
||||
float t54 = t50+t51+t52+t53-t80-t81-t82; |
||||
float t55 = t100*t54; |
||||
float t56 = P[1][3]*t9; |
||||
float t57 = P[8][3]*t104; |
||||
float t58 = P[0][3]*t105; |
||||
float t59 = P[5][3]*t100; |
||||
float t83 = P[4][3]*t101; |
||||
float t84 = P[2][3]*t102; |
||||
float t85 = P[3][3]*t103; |
||||
float t60 = t56+t57+t58+t59-t83-t84-t85; |
||||
float t70 = t101*t33; |
||||
float t79 = t102*t49; |
||||
float t86 = t103*t60; |
||||
float t61 = R_LOS+t28+t39+t44+t55-t70-t79-t86; // innovation variance - should always be >= R_LOS |
||||
float t62 = 1.0f/t61; |
||||
|
||||
// Calculate the Kalman gain matrix for the LOS rate about the Y body axis |
||||
float Kfusion[24]; |
||||
Kfusion[0] = -t62*(t22+P[0][1]*t9+P[0][5]*t100-P[0][4]*t101-P[0][2]*t102-P[0][3]*t103+P[0][8]*t104); |
||||
Kfusion[1] = -t62*(t23+P[1][5]*t100+P[1][0]*t105-P[1][4]*t101-P[1][2]*t102-P[1][3]*t103+P[1][8]*t104); |
||||
Kfusion[2] = -t62*(-t63+P[2][1]*t9+P[2][5]*t100+P[2][0]*t105-P[2][4]*t101-P[2][3]*t103+P[2][8]*t104); |
||||
Kfusion[3] = -t62*(-t85+P[3][1]*t9+P[3][5]*t100+P[3][0]*t105-P[3][4]*t101-P[3][2]*t102+P[3][8]*t104); |
||||
Kfusion[4] = -t62*(-t67+P[4][1]*t9+P[4][5]*t100+P[4][0]*t105-P[4][2]*t102-P[4][3]*t103+P[4][8]*t104); |
||||
Kfusion[5] = -t62*(t53+P[5][1]*t9+P[5][0]*t105-P[5][4]*t101-P[5][2]*t102-P[5][3]*t103+P[5][8]*t104); |
||||
Kfusion[6] = -t62*(P[6][1]*t9+P[6][5]*t100+P[6][0]*t105-P[6][4]*t101-P[6][2]*t102-P[6][3]*t103+P[6][8]*t104); |
||||
Kfusion[7] = -t62*(P[7][1]*t9+P[7][5]*t100+P[7][0]*t105-P[7][4]*t101-P[7][2]*t102-P[7][3]*t103+P[7][8]*t104); |
||||
Kfusion[8] = -t62*(t35+P[8][1]*t9+P[8][5]*t100+P[8][0]*t105-P[8][4]*t101-P[8][2]*t102-P[8][3]*t103); |
||||
Kfusion[9] = -t62*(P[9][1]*t9+P[9][5]*t100+P[9][0]*t105-P[9][4]*t101-P[9][2]*t102-P[9][3]*t103+P[9][8]*t104); |
||||
Kfusion[10] = -t62*(P[10][1]*t9+P[10][5]*t100+P[10][0]*t105-P[10][4]*t101-P[10][2]*t102-P[10][3]*t103+P[10][8]*t104); |
||||
Kfusion[11] = -t62*(P[11][1]*t9+P[11][5]*t100+P[11][0]*t105-P[11][4]*t101-P[11][2]*t102-P[11][3]*t103+P[11][8]*t104); |
||||
Kfusion[12] = -t62*(P[12][1]*t9+P[12][5]*t100+P[12][0]*t105-P[12][4]*t101-P[12][2]*t102-P[12][3]*t103+P[12][8]*t104); |
||||
Kfusion[13] = -t62*(P[13][1]*t9+P[13][5]*t100+P[13][0]*t105-P[13][4]*t101-P[13][2]*t102-P[13][3]*t103+P[13][8]*t104); |
||||
Kfusion[14] = -t62*(P[14][1]*t9+P[14][5]*t100+P[14][0]*t105-P[14][4]*t101-P[14][2]*t102-P[14][3]*t103+P[14][8]*t104); |
||||
Kfusion[15] = -t62*(P[15][1]*t9+P[15][5]*t100+P[15][0]*t105-P[15][4]*t101-P[15][2]*t102-P[15][3]*t103+P[15][8]*t104); |
||||
Kfusion[16] = -t62*(P[16][1]*t9+P[16][5]*t100+P[16][0]*t105-P[16][4]*t101-P[16][2]*t102-P[16][3]*t103+P[16][8]*t104); |
||||
Kfusion[17] = -t62*(P[17][1]*t9+P[17][5]*t100+P[17][0]*t105-P[17][4]*t101-P[17][2]*t102-P[17][3]*t103+P[17][8]*t104); |
||||
Kfusion[18] = -t62*(P[18][1]*t9+P[18][5]*t100+P[18][0]*t105-P[18][4]*t101-P[18][2]*t102-P[18][3]*t103+P[18][8]*t104); |
||||
Kfusion[19] = -t62*(P[19][1]*t9+P[19][5]*t100+P[19][0]*t105-P[19][4]*t101-P[19][2]*t102-P[19][3]*t103+P[19][8]*t104); |
||||
Kfusion[20] = -t62*(P[20][1]*t9+P[20][5]*t100+P[20][0]*t105-P[20][4]*t101-P[20][2]*t102-P[20][3]*t103+P[20][8]*t104); |
||||
Kfusion[21] = -t62*(P[21][1]*t9+P[21][5]*t100+P[21][0]*t105-P[21][4]*t101-P[21][2]*t102-P[21][3]*t103+P[21][8]*t104); |
||||
Kfusion[22] = -t62*(P[22][1]*t9+P[22][5]*t100+P[22][0]*t105-P[22][4]*t101-P[22][2]*t102-P[22][3]*t103+P[22][8]*t104); |
||||
Kfusion[23] = -t62*(P[23][1]*t9+P[23][5]*t100+P[23][0]*t105-P[23][4]*t101-P[23][2]*t102-P[23][3]*t103+P[23][8]*t104); |
@ -0,0 +1,92 @@
@@ -0,0 +1,92 @@
|
||||
function fix_c_code(fileName) |
||||
%% Initialize variables |
||||
delimiter = ''; |
||||
|
||||
%% Format string for each line of text: |
||||
% column1: text (%s) |
||||
% For more information, see the TEXTSCAN documentation. |
||||
formatSpec = '%s%[^\n\r]'; |
||||
|
||||
%% Open the text file. |
||||
fileID = fopen(fileName,'r'); |
||||
|
||||
%% Read columns of data according to format string. |
||||
% This call is based on the structure of the file used to generate this |
||||
% code. If an error occurs for a different file, try regenerating the code |
||||
% from the Import Tool. |
||||
dataArray = textscan(fileID, formatSpec, 'Delimiter', delimiter, 'ReturnOnError', false); |
||||
|
||||
%% Close the text file. |
||||
fclose(fileID); |
||||
|
||||
%% Create output variable |
||||
SymbolicOutput = [dataArray{1:end-1}]; |
||||
|
||||
%% Clear temporary variables |
||||
clearvars filename delimiter formatSpec fileID dataArray ans; |
||||
|
||||
%% replace brackets and commas |
||||
for lineIndex = 1:length(SymbolicOutput) |
||||
SymbolicOutput(lineIndex) = regexprep(SymbolicOutput(lineIndex), '_l_', '('); |
||||
SymbolicOutput(lineIndex) = regexprep(SymbolicOutput(lineIndex), '_c_', ','); |
||||
SymbolicOutput(lineIndex) = regexprep(SymbolicOutput(lineIndex), '_r_', ')'); |
||||
end |
||||
|
||||
%% Convert indexing and replace brackets |
||||
|
||||
% replace 1-D indexes |
||||
for arrayIndex = 1:99 |
||||
strIndex = int2str(arrayIndex); |
||||
strRep = sprintf('[%d]',(arrayIndex-1)); |
||||
strPat = strcat('\(',strIndex,'\)'); |
||||
for lineIndex = 1:length(SymbolicOutput) |
||||
str = char(SymbolicOutput(lineIndex)); |
||||
SymbolicOutput(lineIndex) = {regexprep(str, strPat, strRep)}; |
||||
end |
||||
end |
||||
|
||||
% replace 2-D left indexes |
||||
for arrayIndex = 1:99 |
||||
strIndex = int2str(arrayIndex); |
||||
strRep = sprintf('[%d,',(arrayIndex-1)); |
||||
strPat = strcat('\(',strIndex,'\,'); |
||||
for lineIndex = 1:length(SymbolicOutput) |
||||
str = char(SymbolicOutput(lineIndex)); |
||||
SymbolicOutput(lineIndex) = {regexprep(str, strPat, strRep)}; |
||||
end |
||||
end |
||||
|
||||
% replace 2-D right indexes |
||||
for arrayIndex = 1:99 |
||||
strIndex = int2str(arrayIndex); |
||||
strRep = sprintf(',%d]',(arrayIndex-1)); |
||||
strPat = strcat('\,',strIndex,'\)'); |
||||
for lineIndex = 1:length(SymbolicOutput) |
||||
str = char(SymbolicOutput(lineIndex)); |
||||
SymbolicOutput(lineIndex) = {regexprep(str, strPat, strRep)}; |
||||
end |
||||
end |
||||
|
||||
% replace commas |
||||
for lineIndex = 1:length(SymbolicOutput) |
||||
str = char(SymbolicOutput(lineIndex)); |
||||
SymbolicOutput(lineIndex) = {regexprep(str, '\,', '][')}; |
||||
end |
||||
|
||||
%% Change covariance matrix variable name to P |
||||
for lineIndex = 1:length(SymbolicOutput) |
||||
strIn = char(SymbolicOutput(lineIndex)); |
||||
strIn = regexprep(strIn,'OP\[','P['); |
||||
SymbolicOutput(lineIndex) = cellstr(strIn); |
||||
end |
||||
|
||||
%% Write to file |
||||
fid = fopen(fileName,'wt'); |
||||
for lineIndex = 1:length(SymbolicOutput) |
||||
fprintf(fid,char(SymbolicOutput(lineIndex))); |
||||
fprintf(fid,'\n'); |
||||
end |
||||
fclose(fid); |
||||
clear all; |
||||
|
||||
end |
Loading…
Reference in new issue