C_code.txt 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347
  1. t2 = dax*(1.0/2.0);
  2. t3 = dax_b*(1.0/2.0);
  3. t4 = t2-t3;
  4. t5 = day*(1.0/2.0);
  5. t6 = day_b*(1.0/2.0);
  6. t7 = t5-t6;
  7. t8 = daz*(1.0/2.0);
  8. t9 = daz_b*(1.0/2.0);
  9. t10 = t8-t9;
  10. t11 = q2*t4*(1.0/2.0);
  11. t12 = q1*t7*(1.0/2.0);
  12. t13 = q0*t10*(1.0/2.0);
  13. t14 = q2*(1.0/2.0);
  14. t15 = q3*t4*(1.0/2.0);
  15. t16 = q1*t10*(1.0/2.0);
  16. t17 = q1*(1.0/2.0);
  17. t18 = q0*t4*(1.0/2.0);
  18. t19 = q3*t7*(1.0/2.0);
  19. t20 = q0*(1.0/2.0);
  20. t21 = q2*t7*(1.0/2.0);
  21. t22 = q3*t10*(1.0/2.0);
  22. t23 = q0*t7*(1.0/2.0);
  23. t24 = q3*(1.0/2.0);
  24. t25 = q1*t4*(1.0/2.0);
  25. t26 = q2*t10*(1.0/2.0);
  26. t27 = t11+t12+t13-t24;
  27. t28 = t14+t15+t16-t23;
  28. t29 = q2*t28*2.0;
  29. t30 = t17+t18+t19-t26;
  30. t31 = q1*t30*2.0;
  31. t32 = t20+t21+t22-t25;
  32. t33 = q0*t32*2.0;
  33. t40 = q3*t27*2.0;
  34. t34 = t29+t31+t33-t40;
  35. t35 = q0*q0;
  36. t36 = q1*q1;
  37. t37 = q2*q2;
  38. t38 = q3*q3;
  39. t39 = t35+t36+t37+t38;
  40. t41 = t11+t12-t13+t24;
  41. t42 = t14-t15+t16+t23;
  42. t43 = q1*t42*2.0;
  43. t44 = -t17+t18+t19+t26;
  44. t45 = q2*t44*2.0;
  45. t46 = t20-t21+t22+t25;
  46. t47 = q3*t46*2.0;
  47. t57 = q0*t41*2.0;
  48. t48 = t43+t45+t47-t57;
  49. t49 = -t14+t15+t16+t23;
  50. t50 = q0*t49*2.0;
  51. t51 = t11-t12+t13+t24;
  52. t52 = t20+t21-t22+t25;
  53. t53 = q2*t52*2.0;
  54. t54 = t17-t18+t19+t26;
  55. t55 = q3*t54*2.0;
  56. t58 = q1*t51*2.0;
  57. t56 = t50+t53+t55-t58;
  58. t59 = OP[0][0]*t34;
  59. t60 = OP[1][0]*t48;
  60. t66 = OP[6][0]*t39;
  61. t67 = OP[2][0]*t56;
  62. t61 = t59+t60-t66-t67;
  63. t62 = OP[0][1]*t34;
  64. t63 = OP[1][1]*t48;
  65. t64 = OP[0][2]*t34;
  66. t65 = OP[1][2]*t48;
  67. t71 = OP[6][1]*t39;
  68. t72 = OP[2][1]*t56;
  69. t68 = t62+t63-t71-t72;
  70. t79 = OP[6][2]*t39;
  71. t80 = OP[2][2]*t56;
  72. t69 = t64+t65-t79-t80;
  73. t70 = t35+t36-t37-t38;
  74. t73 = q0*q2*2.0;
  75. t74 = q1*q3*2.0;
  76. t75 = t73+t74;
  77. t76 = q0*q3*2.0;
  78. t78 = q1*q2*2.0;
  79. t77 = t76-t78;
  80. t81 = t35-t36+t37-t38;
  81. t82 = q0*q1*2.0;
  82. t86 = q2*q3*2.0;
  83. t83 = t82-t86;
  84. t84 = t76+t78;
  85. t85 = t35-t36-t37+t38;
  86. t87 = t82+t86;
  87. t88 = t73-t74;
  88. t89 = OP[0][6]*t34;
  89. t90 = OP[1][6]*t48;
  90. t265 = OP[6][6]*t39;
  91. t91 = t89+t90-t265-OP[2][6]*t56;
  92. t92 = OP[0][7]*t34;
  93. t93 = OP[1][7]*t48;
  94. t266 = OP[6][7]*t39;
  95. t94 = t92+t93-t266-OP[2][7]*t56;
  96. t95 = OP[0][8]*t34;
  97. t96 = OP[1][8]*t48;
  98. t267 = OP[6][8]*t39;
  99. t97 = t95+t96-t267-OP[2][8]*t56;
  100. t98 = q0*t27*2.0;
  101. t99 = q1*t28*2.0;
  102. t100 = q3*t32*2.0;
  103. t110 = q2*t30*2.0;
  104. t101 = t98+t99+t100-t110;
  105. t102 = q0*t46*2.0;
  106. t103 = q2*t42*2.0;
  107. t104 = q3*t41*2.0;
  108. t111 = q1*t44*2.0;
  109. t105 = t102+t103+t104-t111;
  110. t106 = q1*t52*2.0;
  111. t107 = q2*t51*2.0;
  112. t108 = q3*t49*2.0;
  113. t112 = q0*t54*2.0;
  114. t109 = t106+t107+t108-t112;
  115. t113 = OP[7][0]*t39;
  116. t114 = OP[0][0]*t101;
  117. t123 = OP[1][0]*t105;
  118. t124 = OP[2][0]*t109;
  119. t115 = t113+t114-t123-t124;
  120. t116 = OP[7][1]*t39;
  121. t117 = OP[0][1]*t101;
  122. t129 = OP[1][1]*t105;
  123. t130 = OP[2][1]*t109;
  124. t118 = t116+t117-t129-t130;
  125. t119 = OP[7][2]*t39;
  126. t120 = OP[0][2]*t101;
  127. t135 = OP[1][2]*t105;
  128. t136 = OP[2][2]*t109;
  129. t121 = t119+t120-t135-t136;
  130. t122 = t39*t39;
  131. t125 = q1*t27*2.0;
  132. t126 = q2*t32*2.0;
  133. t127 = q3*t30*2.0;
  134. t170 = q0*t28*2.0;
  135. t128 = t125+t126+t127-t170;
  136. t131 = q0*t44*2.0;
  137. t132 = q1*t46*2.0;
  138. t133 = q2*t41*2.0;
  139. t171 = q3*t42*2.0;
  140. t134 = t131+t132+t133-t171;
  141. t137 = q0*t52*2.0;
  142. t138 = q1*t54*2.0;
  143. t139 = q3*t51*2.0;
  144. t172 = q2*t49*2.0;
  145. t140 = t137+t138+t139-t172;
  146. t141 = dvy*t70;
  147. t142 = dvx*t77;
  148. t143 = t141+t142;
  149. t144 = dvx*t75;
  150. t145 = dvy*t75;
  151. t146 = dvz*t77;
  152. t147 = t145+t146;
  153. t148 = dvx*t81;
  154. t188 = dvy*t84;
  155. t149 = t148-t188;
  156. t150 = dvz*t81;
  157. t151 = dvy*t83;
  158. t152 = t150+t151;
  159. t153 = dvx*t83;
  160. t154 = dvz*t84;
  161. t155 = t153+t154;
  162. t156 = dvx*t85;
  163. t157 = dvz*t88;
  164. t158 = t156+t157;
  165. t159 = dvy*t85;
  166. t189 = dvz*t87;
  167. t160 = t159-t189;
  168. t161 = dvx*t87;
  169. t162 = dvy*t88;
  170. t163 = t161+t162;
  171. t164 = OP[7][6]*t39;
  172. t165 = OP[0][6]*t101;
  173. t166 = OP[7][7]*t39;
  174. t167 = OP[0][7]*t101;
  175. t168 = OP[7][8]*t39;
  176. t169 = OP[0][8]*t101;
  177. t173 = OP[8][0]*t39;
  178. t174 = OP[1][0]*t134;
  179. t182 = OP[0][0]*t128;
  180. t183 = OP[2][0]*t140;
  181. t175 = t173+t174-t182-t183;
  182. t176 = OP[8][1]*t39;
  183. t177 = OP[1][1]*t134;
  184. t184 = OP[0][1]*t128;
  185. t185 = OP[2][1]*t140;
  186. t178 = t176+t177-t184-t185;
  187. t179 = OP[8][2]*t39;
  188. t180 = OP[1][2]*t134;
  189. t186 = OP[0][2]*t128;
  190. t187 = OP[2][2]*t140;
  191. t181 = t179+t180-t186-t187;
  192. t190 = OP[8][6]*t39;
  193. t191 = OP[1][6]*t134;
  194. t192 = OP[8][7]*t39;
  195. t193 = OP[1][7]*t134;
  196. t194 = OP[8][8]*t39;
  197. t195 = OP[1][8]*t134;
  198. t197 = dvz*t70;
  199. t196 = t144-t197;
  200. t198 = OP[0][0]*t147;
  201. t204 = OP[2][0]*t143;
  202. t205 = OP[1][0]*t196;
  203. t199 = OP[3][0]+t198-t204-t205;
  204. t200 = OP[0][1]*t147;
  205. t206 = OP[2][1]*t143;
  206. t207 = OP[1][1]*t196;
  207. t201 = OP[3][1]+t200-t206-t207;
  208. t202 = OP[0][2]*t147;
  209. t208 = OP[2][2]*t143;
  210. t209 = OP[1][2]*t196;
  211. t203 = OP[3][2]+t202-t208-t209;
  212. t210 = -t144+t197;
  213. t211 = OP[1][0]*t210;
  214. t212 = OP[3][0]+t198-t204+t211;
  215. t213 = OP[1][1]*t210;
  216. t214 = OP[3][1]+t200-t206+t213;
  217. t215 = OP[1][2]*t210;
  218. t216 = OP[3][2]+t202-t208+t215;
  219. t217 = OP[0][6]*t147;
  220. t218 = OP[0][7]*t147;
  221. t219 = OP[0][8]*t147;
  222. t220 = OP[1][0]*t155;
  223. t221 = OP[2][0]*t149;
  224. t229 = OP[0][0]*t152;
  225. t222 = OP[4][0]+t220+t221-t229;
  226. t223 = OP[1][1]*t155;
  227. t224 = OP[2][1]*t149;
  228. t230 = OP[0][1]*t152;
  229. t225 = OP[4][1]+t223+t224-t230;
  230. t226 = OP[1][2]*t155;
  231. t227 = OP[2][2]*t149;
  232. t231 = OP[0][2]*t152;
  233. t228 = OP[4][2]+t226+t227-t231;
  234. t232 = dvxNoise*t70*t84;
  235. t233 = OP[1][6]*t155;
  236. t234 = OP[2][6]*t149;
  237. t235 = OP[4][6]+t233+t234-OP[0][6]*t152;
  238. t236 = OP[1][7]*t155;
  239. t237 = OP[2][7]*t149;
  240. t238 = OP[4][7]+t236+t237-OP[0][7]*t152;
  241. t239 = OP[1][8]*t155;
  242. t240 = OP[2][8]*t149;
  243. t241 = OP[4][8]+t239+t240-OP[0][8]*t152;
  244. t242 = OP[2][0]*t163;
  245. t243 = OP[0][0]*t160;
  246. t251 = OP[1][0]*t158;
  247. t244 = OP[5][0]+t242+t243-t251;
  248. t245 = OP[2][1]*t163;
  249. t246 = OP[0][1]*t160;
  250. t252 = OP[1][1]*t158;
  251. t247 = OP[5][1]+t245+t246-t252;
  252. t248 = OP[2][2]*t163;
  253. t249 = OP[0][2]*t160;
  254. t253 = OP[1][2]*t158;
  255. t250 = OP[5][2]+t248+t249-t253;
  256. t254 = dvzNoise*t75*t85;
  257. t255 = dvyNoise*t81*t87;
  258. t256 = OP[2][6]*t163;
  259. t257 = OP[0][6]*t160;
  260. t258 = OP[5][6]+t256+t257-OP[1][6]*t158;
  261. t259 = OP[2][7]*t163;
  262. t260 = OP[0][7]*t160;
  263. t261 = OP[5][7]+t259+t260-OP[1][7]*t158;
  264. t262 = OP[2][8]*t163;
  265. t263 = OP[0][8]*t160;
  266. t264 = OP[5][8]+t262+t263-OP[1][8]*t158;
  267. A0[0][0] = daxNoise*t122+t34*t61+t48*t68-t56*t69-t39*t91;
  268. A0[0][0] = -t39*t94-t61*t101+t68*t105+t69*t109;
  269. A0[0][1] = -t39*t97-t68*t134+t69*t140+t128*(t59+t60-t66-t67);
  270. A0[0][2] = OP[0][3]*t34+OP[1][3]*t48-OP[2][3]*t56-OP[6][3]*t39-t69*t143+t147*(t59+t60-t66-t67)-t196*(t62+t63-t71-t72);
  271. A0[0][3] = OP[0][4]*t34+OP[1][4]*t48-OP[2][4]*t56-OP[6][4]*t39-t61*t152+t69*t149+t155*(t62+t63-t71-t72);
  272. A0[0][4] = OP[0][5]*t34+OP[1][5]*t48-OP[2][5]*t56-OP[6][5]*t39+t61*t160-t68*t158+t163*(t64+t65-t79-t80);
  273. A0[0][5] = t91;
  274. A0[0][6] = t94;
  275. A0[0][7] = t97;
  276. A0[0][0] = -t34*t115-t48*t118+t56*t121+t39*(t164+t165-OP[1][6]*t105-OP[2][6]*t109);
  277. A0[0][0] = dayNoise*t122+t101*t115-t105*t118-t109*t121+t39*(t166+t167-OP[1][7]*t105-OP[2][7]*t109);
  278. A0[0][1] = -t115*t128+t118*t134-t121*t140+t39*(t168+t169-OP[1][8]*t105-OP[2][8]*t109);
  279. A0[0][2] = -OP[0][3]*t101-OP[7][3]*t39+OP[1][3]*t105+OP[2][3]*t109-t115*t147+t121*t143+t118*t196;
  280. A0[0][3] = -OP[0][4]*t101-OP[7][4]*t39+OP[1][4]*t105+OP[2][4]*t109+t115*t152-t121*t149-t118*t155;
  281. A0[0][4] = -OP[0][5]*t101-OP[7][5]*t39+OP[1][5]*t105+OP[2][5]*t109-t115*t160+t118*t158-t121*t163;
  282. A0[0][5] = -t164-t165+OP[1][6]*t105+OP[2][6]*t109;
  283. A0[0][6] = -t166-t167+OP[1][7]*t105+OP[2][7]*t109;
  284. A0[0][7] = -t168-t169+OP[1][8]*t105+OP[2][8]*t109;
  285. A0[1][0] = -t34*t175-t48*t178+t56*t181+t39*(t190+t191-OP[0][6]*t128-OP[2][6]*t140);
  286. A0[1][0] = t101*t175-t105*t178-t109*t181+t39*(t192+t193-OP[0][7]*t128-OP[2][7]*t140);
  287. A0[1][1] = dazNoise*t122-t128*t175+t134*t178-t140*t181+t39*(t194+t195-OP[0][8]*t128-OP[2][8]*t140);
  288. A0[1][2] = -OP[8][3]*t39+OP[0][3]*t128-OP[1][3]*t134+OP[2][3]*t140-t147*t175+t143*t181+t178*t196;
  289. A0[1][3] = -OP[8][4]*t39+OP[0][4]*t128-OP[1][4]*t134+OP[2][4]*t140+t152*t175-t149*t181-t155*t178;
  290. A0[1][4] = -OP[8][5]*t39+OP[0][5]*t128-OP[1][5]*t134+OP[2][5]*t140-t160*t175+t158*t178-t163*t181;
  291. A0[1][5] = -t190-t191+OP[0][6]*t128+OP[2][6]*t140;
  292. A0[1][6] = -t192-t193+OP[0][7]*t128+OP[2][7]*t140;
  293. A0[1][7] = -t194-t195+OP[0][8]*t128+OP[2][8]*t140;
  294. A0[2][0] = -t39*(OP[3][6]+t217-OP[2][6]*t143-OP[1][6]*t196)+t34*t199+t48*t201-t56*t203;
  295. A0[2][0] = -t39*(OP[3][7]+t218-OP[2][7]*t143-OP[1][7]*t196)-t101*t199+t105*t201+t109*t203;
  296. A0[2][1] = -t39*(OP[3][8]+t219-OP[2][8]*t143-OP[1][8]*t196)+t128*t199-t134*t201+t140*t203;
  297. A0[2][2] = OP[3][3]+OP[0][3]*t147-OP[2][3]*t143+OP[1][3]*t210-t143*t203+t147*t212+t210*t214+dvxNoise*(t70*t70)+dvyNoise*(t77*t77)+dvzNoise*(t75*t75);
  298. A0[2][3] = OP[3][4]+t232+OP[0][4]*t147-OP[2][4]*t143+OP[1][4]*t210-t152*t212+t149*t216+t155*t214-dvyNoise*t77*t81-dvzNoise*t75*t83;
  299. A0[2][4] = OP[3][5]+t254+OP[0][5]*t147-OP[2][5]*t143+OP[1][5]*t210-t158*t214+t160*t212+t163*t216-dvxNoise*t70*t88-dvyNoise*t77*t87;
  300. A0[2][5] = OP[3][6]+t217-OP[2][6]*t143+OP[1][6]*t210;
  301. A0[2][6] = OP[3][7]+t218-OP[2][7]*t143+OP[1][7]*t210;
  302. A0[2][7] = OP[3][8]+t219-OP[2][8]*t143+OP[1][8]*t210;
  303. A0[3][0] = t34*t222+t48*t225-t39*t235-t56*t228;
  304. A0[3][0] = -t39*t238-t101*t222+t105*t225+t109*t228;
  305. A0[3][1] = -t39*t241+t128*t222-t134*t225+t140*t228;
  306. A0[3][2] = OP[4][3]+t232-OP[0][3]*t152+OP[1][3]*t155+OP[2][3]*t149+t147*t222-t143*t228+t210*t225-dvyNoise*t77*t81-dvzNoise*t75*t83;
  307. A0[3][3] = OP[4][4]-OP[0][4]*t152+OP[1][4]*t155+OP[2][4]*t149-t152*t222+t149*t228+t155*t225+dvxNoise*(t84*t84)+dvyNoise*(t81*t81)+dvzNoise*(t83*t83);
  308. A0[3][4] = OP[4][5]+t255-OP[0][5]*t152+OP[1][5]*t155+OP[2][5]*t149+t160*t222-t158*t225+t163*t228-dvxNoise*t84*t88-dvzNoise*t83*t85;
  309. A0[3][5] = t235;
  310. A0[3][6] = t238;
  311. A0[3][7] = t241;
  312. A0[4][0] = t34*t244+t48*t247-t39*t258-t56*t250;
  313. A0[4][0] = -t39*t261-t101*t244+t105*t247+t109*t250;
  314. A0[4][1] = -t39*t264+t128*t244-t134*t247+t140*t250;
  315. A0[4][2] = OP[5][3]+t254+OP[0][3]*t160-OP[1][3]*t158+OP[2][3]*t163+t147*t244-t143*t250+t210*t247-dvxNoise*t70*t88-dvyNoise*t77*t87;
  316. A0[4][3] = OP[5][4]+t255+OP[0][4]*t160-OP[1][4]*t158+OP[2][4]*t163-t152*t244+t149*t250+t155*t247-dvxNoise*t84*t88-dvzNoise*t83*t85;
  317. A0[4][4] = OP[5][5]+OP[0][5]*t160-OP[1][5]*t158+OP[2][5]*t163+t160*t244-t158*t247+t163*t250+dvxNoise*(t88*t88)+dvyNoise*(t87*t87)+dvzNoise*(t85*t85);
  318. A0[4][5] = t258;
  319. A0[4][6] = t261;
  320. A0[4][7] = t264;
  321. A0[5][0] = -t265+OP[6][0]*t34+OP[6][1]*t48-OP[6][2]*t56;
  322. A0[5][0] = -t266-OP[6][0]*t101+OP[6][1]*t105+OP[6][2]*t109;
  323. A0[5][1] = -t267+OP[6][0]*t128-OP[6][1]*t134+OP[6][2]*t140;
  324. A0[5][2] = OP[6][3]-OP[6][2]*t143+OP[6][0]*t147+OP[6][1]*t210;
  325. A0[5][3] = OP[6][4]+OP[6][2]*t149-OP[6][0]*t152+OP[6][1]*t155;
  326. A0[5][4] = OP[6][5]-OP[6][1]*t158+OP[6][0]*t160+OP[6][2]*t163;
  327. A0[5][5] = OP[6][6];
  328. A0[5][6] = OP[6][7];
  329. A0[5][7] = OP[6][8];
  330. A0[6][0] = -t164+OP[7][0]*t34+OP[7][1]*t48-OP[7][2]*t56;
  331. A0[6][0] = -t166-OP[7][0]*t101+OP[7][1]*t105+OP[7][2]*t109;
  332. A0[6][1] = -t168+OP[7][0]*t128-OP[7][1]*t134+OP[7][2]*t140;
  333. A0[6][2] = OP[7][3]-OP[7][2]*t143+OP[7][0]*t147+OP[7][1]*t210;
  334. A0[6][3] = OP[7][4]+OP[7][2]*t149-OP[7][0]*t152+OP[7][1]*t155;
  335. A0[6][4] = OP[7][5]-OP[7][1]*t158+OP[7][0]*t160+OP[7][2]*t163;
  336. A0[6][5] = OP[7][6];
  337. A0[6][6] = OP[7][7];
  338. A0[6][7] = OP[7][8];
  339. A0[7][0] = -t190+OP[8][0]*t34+OP[8][1]*t48-OP[8][2]*t56;
  340. A0[7][0] = -t192-OP[8][0]*t101+OP[8][1]*t105+OP[8][2]*t109;
  341. A0[7][1] = -t194+OP[8][0]*t128-OP[8][1]*t134+OP[8][2]*t140;
  342. A0[7][2] = OP[8][3]-OP[8][2]*t143+OP[8][0]*t147+OP[8][1]*t210;
  343. A0[7][3] = OP[8][4]+OP[8][2]*t149-OP[8][0]*t152+OP[8][1]*t155;
  344. A0[7][4] = OP[8][5]-OP[8][1]*t158+OP[8][0]*t160+OP[8][2]*t163;
  345. A0[7][5] = OP[8][6];
  346. A0[7][6] = OP[8][7];
  347. A0[7][7] = OP[8][8];