From 569921243a7210200da05a00fff90c79bf7427f3 Mon Sep 17 00:00:00 2001 From: Chi Chow Date: Sat, 6 Mar 2021 12:28:58 -0800 Subject: [PATCH 1/7] Reads arguments to choose whether to use real/fake sensors; Removed most getInstance() methods to group initialization in FlightComputer.java --- build.xml | 1 + lib/commons-cli-1.4.jar | Bin 0 -> 53820 bytes .../flightcomputer/FlightComputer.java | 161 ++++++++-- .../flightcomputer/Main.java | 45 +-- .../flightcomputer/SensorProvider.java | 35 +++ .../flightcomputer/comm/PacketRouter.java | 8 - .../flightcomputer/looper/Looper.java | 9 - .../subsystems/PTSubsystem.java | 13 - .../subsystems/ParachuteSubsystem.java | 274 +++++++++--------- .../subsystems/SCMCommandSubsystem.java | 8 - .../flightcomputer/subsystems/Telemetry.java | 9 - .../subsystems/ValveStateSubsystem.java | 7 - .../flightcomputer/FlightComputerTest.java | 32 +- .../flightcomputer/looper/TestLooper.java | 15 - .../subsystems/TestPTSubsystem.java | 2 +- .../subsystems/TestSCMCommandSubsystem.java | 1 + 16 files changed, 333 insertions(+), 287 deletions(-) create mode 100644 lib/commons-cli-1.4.jar create mode 100644 src/org/rocketproplab/marginalstability/flightcomputer/SensorProvider.java diff --git a/build.xml b/build.xml index 1af994b..9fcb2b3 100644 --- a/build.xml +++ b/build.xml @@ -11,6 +11,7 @@ + diff --git a/lib/commons-cli-1.4.jar b/lib/commons-cli-1.4.jar new file mode 100644 index 0000000000000000000000000000000000000000..22deb3089e2f79a983406bd13a75a3e6238afdcf GIT binary patch literal 53820 zcmagF1C%A(vNl?_ZQHhO+qUg4+qP>}RhRARvTfT&cc}}n_dWMNcklPVb6<{?W8@ku z=E|87-wb>+Qb`sR3WiG~jy!JGQP$dJoZNE3J|1&7F)gGOTTNYh)IwEqA>PQbkmt&n?CFmH!n@QM zNT}Gj9BE_E>2ou-e8$mc^w6Mh59Yzgk0(2YtGSL$u;F+mVe59W9zjxSJsiyk!quPNzn6L|&Ll`Al0BDX)^_Pxs&Z#{jsee4^hQP%>W zwoFyzYRekjNUDS`TFhZU4#oGIRRn}f2e+goz-3sn6(-Va<6e3*F;a<0MqqRmaTdnkPoxYawhCPYXz@>WHD2_PWFeL}K>{4pzMi z;%8YTfoJx!oao2nDP>#=45e3;pE9Z7#jMG!r@_G->Ex)RW+wTm)2T^l!Myr9*ld5C zVvNQ0Te!3})~yR$m``X}zgYp&n5D%U%N$F_1`5#|9o8&~ZQEvc*MA`nR(WKPe^H7r zsD`DZw=sM9_|k0j9(Os%xj}%iju%@gio>so0$%I=Surx4Tm^1I$yBKdeRcK^%$YPF|YW5KYl~| z?XtIQUa|TKq$CRo^><(@{TF0`pn(1hvVTze?*sbJ)xRP8KVqzZko|9&KNnzsPDd9@ z#{Vn<``;4APR6EI=KqTz>OTcd9qsKM9bEsH0hs^a15E9#|2F8arT9ng-v{EKtA9V2 zy|IV6!~Y_T`+p1n_q6E$_q$O3?*squKl#gRu>6@SQ>pKr-Jdxc(EY!>hMcshxPq!U zgPWJzwvMjr<_LPgY~7j*K-C%okf*!Jr5H<2X@@UEI^oWm#YYze-oYLy?g6ZPRd?HQ z1y4rawb*9EQX_3Lo6nzd>vu{Q`ZBazoN=rW<=Ls0r)tRecqEwWzTtLI^;#wJF7Hv& z40*p?rMb)3VZ{meahbvR{QE<1fy33bjS+WeqURk1bH{M^qZ=b;InB$psZ(c%(NV+p z{^>-a+t3j6;O6b==H%i7_r0^Qyf*#vch@oE?L98a-LaltrH-c$(DBwgY~A!!ffdD; z0!N%x+SL#cC4Q=XUZOs^%%Xa?%+g5oe5HuivaV_zd4Rr`@{3*Bw$U$(q1!OG;sJVf zat_D_4RY95lp|eM2hRguW1E-4eQwqGnu~DLo>+e6YPOI5i)#lYi(P73A#$yXh>*m? zdRC3EoTo>ZnHnq)7o__06&bBH`*UK)2sz-Ew77PPc}kgBe1gPgO_6jmaw}kqK+7I1 zP(&~A7ME^zEVp_9b!ane)(e_VFjU>#)3vR}3$^yXzZ3@et3oD09;QRRiQF%Z4x>PVyL z(aDfAowrVl_=#716!LblH`(koecd*eBGIKt7}X_V^PGTuxf8$TX*R- zTxJA3Ay`}pZr{Zjs8fnMgA`a2?s5>a418^_)a*|=hOgmRR%c+_dqWS8EMNRj(Hy=r z8!>H-qx*gE3duPQUNx|v4lS-|cW9QmU`OdGO1gs%Q41H6BcBuLMYKQaK-aABisE6GfRU6gOl^&d#Nzhgf0nS-pubp$PYhO zHs=>^_tGWI@0^=nF+&F`FB*C8Jon-oiry<~toKJM!vXHSNzk;`*6yIiyf{zSkHU=8R1rwRsu_)07nM}{SbCQ6uUsx3 zRrwIO)D;(gAdQ|pt_)f|^^)HA+Gs7y;6JMVT2Lu1)IYEuS zZ7|J}L^#=abB^ZagZemzjv7MDA5@nUxOKZ7`08#C*$Yw}(^}!;Rjn`%YE;om{Ej89 z%d$#bK@BO*+Bfz&4#afDD7t)n@>JcIImR;ETU+mzlx~n@SqMZ2)JU%olcTYSYeQFW z75Np5*U>*nI}ul(T(l?;A|pBM>NeU^R(Yt_5AlWZ94xW|S8ofb49r@4JX&oGf2&X@ zLzHW2OW7Ejx>Dkea_vLwHM2&nHVwCD%*YG{Jga5iq0f18UOBBCUw1%OkyH@rplqR( zAOsm;34aeI>D4)4i>&z z1x$xJfLK^p`GnIUVcCg!|E{zcnz*|Q^=LOf{y&UwysdY+&mS&jbZ)^<_*e*(IT}WGVo_$l9-0#WISdlsB^?+ z6@A4lndA4|U6X`bs1^r?boMvFClQ217*ie|^Eq7&VF&V0IigeC=NPqmlD5{74oov9 zJ_&1yBgJ=YK1OlUXNM(Ff)-_61`wl$Lcaqr$%+@eK4p2M;XKEdlw20>Q>1wG_jwdm zaAvt-KoS;}s+EL4AXI|%IFr#kNZr}J4^8|wOe={2sTHOdt{<}ocA;Le8Vja3D~2~s zG5n<2ofZ*#Jzg2gNeR+{wZFtti=YF{n$(U1WK0>4xFqO{vw=i$(}H1Nkw`m9hnPhQ zrbdJM$;BS$EULX1^2!JQ;wr5BC?y`rT6YO^`7i)<>-&Brln(c=xNYLkJUlfOf36#{ z-f|Y4r!6zzhdl~q>#LIbZ>L4^!$`qT!k$=^Tl}4NzM<_{3sk7O&-B=$4Y}tt=B-WY zpk!LeUal(xs-8eN_=F6bTn?Ea#eHzH%MEw)`b2aZFy5+3NzgF!#AP{xxCulvXRdIS zFBzG*C6faSGJKLiU7Iex3^Yw8Z8^g7HC6o)_lQmXK%*`-;Lv|5Ly`-=eNqjci2 zH$T1*v_55Se{zRB`kh*D!*FGq`JT^u>f|$oWwjciISew?8PK{m(VPb3U1G#p4#KJH z9204S5=!>mZ+uVVNW*fAnRof4Al-AWqYwfT_PQ}8z{SfJ$queL zkyE8$%RONNl&CPRy`Yjumc;=uqqyp2oi=u$_IYA*Ko~b)!Mq8~ad3FySVrMZ<6?_6 zXIYt$Yxi8AYfOsUy1DGi7c`Nr3-$TXee-*?uHZ2Dr(^0PNx2d$JjNZCSbjLyc^xb! z%7bO&@6zb;)wq`9Vr9(n6sB2gm3ZzT zs1bg$)A2u`_YBw@gg7y8c`J(Ja{&a#B`T)BWl@@7leu=e@S4W#GSlK3^6~V^0SUYW zh%T8I_7CTe-xjmIv&C&JfCou3J2m#7l2+@c0%H!Y;g>Vw_5pB<9BuV6aY_ie z-_Z=gjB(5u?s1vB_JFCim|Mkk&(5jt5CudlNL3TQPZ8w@a^ehquW9zHbKCNL=?WAC zMS}o2K*C@p(8m^;38MD&APo(F#h1)d9%g3~OrxZ>)NO1BT8kWGUxEY1KI>9D)Iy;EJ+vGHJU9Ks1(_zf|~rqjJJ2m1!5d>HE14@^1L{m0eK9txx@rGo)&wy`Z^VTjQiHE%vhJhqtlf8fPOJx z%eS~4q$1MeR<4A|XAI*>;9VgnH{JjNK`egCW6%hee)Bj$+=p189<6Ri-prk|yB9f8 z58j?nnCIpCH7gk!l5Vez5Xc~_es|)d2&l;66#UN-=ayq$*Xn}?jl-II=Mvc!JkpWa z_qdyGR#v@fN(ju^ohZnfyS2Fez-=7WYxk5{1VIsH4u3{xnaErtv0>ZFoOu`aWO;s% zs4XRAzDEkE9T20tlc&A7w2;1jF0tSMzQ{+G115b9#B2s>+pjkWvp`M}ua5qhQ@9rg z1`P5Qux1e0yW<@0&GKb7R+?VmOota!XL=jyiByS~R>P??B`xQzQ;PAxDMhrS7HJU` z!{=LGu6Jgn_-BC_QXFw+0R`fw61XJ{czvr?wAEFo1|cQ8m~Cx$V-E#&^I>fCKw|ta ztC$a(&v%?E=7hJ&d$*sgm}sBu(dTT$b2gybrbY0C18OBwd44tOs@%ZfAjx^c-$L3_ zVMtt`E*+bo{MfSYmT!=Pqm-6C{k19iF)=j(zg7JVi6-ZX-Vrl`JKb$m@#kP8!3tlL z5qI&;%z3+VhV`5w`yNNVkY(igX@R(aVR0ic)!v&6QXtUEEx8?tCK4N5HpSVR5Qn++ zY8=#j%)=a{LMRY0XN0(M^hhCQ>ow#Y1wJMjD=5J7k&#z}5>{x2FoB3)v6qD6Dg;x)=se{7{oYJ=@9yct z09Ez%UxdluYw~~b9Dh~oe=#9KlRdzHQ6S2YKtL3KO8&o?kpJd6{ttce7f&GR;I3rs z;%e@~U}|UV>Kdlb?}RIk_Nl>hPIhbpjh%%Tb@$U|(#UH*PMp(GWZYE;Gm&h+nCdxx%t7^Hb%rz$A#9YQYfJ~D+O4Ta333lHURQJ?3 z-tZ-II`}bOeq=o9F-`rTtvceySN_@!ws^x<$J1>E)jM9uxJ+lP@$&sVJC(#%yOk+h z&Fz}opOd0w-<+)Caa*M^-t=nB2g^@X6vu+O+{8c>!F7q7duPBM-5cJ~RCu^J9Jjr8 zAD_-zYb2VDlfBv`E|YsLA>6Y;q3wYLn%RvI#QGZYbvs)b(26q7?@y1>>aA?1;>M5v zyCV%{oh+QBmI-gaHmlf;sCB$OmOnu1A;%3z`52`!`*eh2|J3t4xgxm#^^8q9Amyu0 z3dL;PNmoQw-Ztf1vsXmEAxj2{b;Pz#|F8IBT=^3hdsVXJ>yK#LfT^BUM#8B2o*WA) z3dffH`Z&aLH`MIY-2 zQ7%`P)0>bf^5hF1gz+VHBjn+cxaOkyFNYzX#KE5mO}879wpHS97*LkvXDNkGm;*y= zr4Vp*kNjV*6s-$Bg@MIHAqNp71tg{-3howG#cFp+zX&?V4ajU5kzY;4+{38~#0VKk z!)Sl5I;CB)^&Dtd8xyph>pK!73g5o6`V1MGfD112exhH#;N!l;AbmUZe-8o44{BnP zsRrG=!kVbg7zv1NfNj6jfAUTJ#UW4*qd*dh8hTlj6-~t(r&?NE*nI;)JGz3Kk@23Z z#ypkcb6JU4tw>?Y5lX&LFKl4`nZg(t1jxnl4QW0dO{DC6EERk0m_yrTy8FX7LPGuB zbNth%Y-8l)m;do4=YP&WB;bGYDN^QkP7;nT_Qq~*<}PH+|MDzxvBEF|Oi1EiRxK?s z7>au$dN@814QC>HUcp!q8_5*pl>{?kkatQZLutI0nP1pm-KUqIK#8V!r18uorINnx z(J?Zt#;xYt7%S|JmuodP-YKEyBUJYO<`ev$n7;8zDCsL{BCRU=T2z~CD_%uzl-;A#=###3@eJMrWXAt)!wA|7f=x(7H8ewa4qGqWuDXDI|ykT~it1%BGsYtdWMs> zPdE(vF-TT)@b_SxK{G0lh%R~L(D+;aUf+nIZBwkxyB?+kgQX(}O|#wJ&->-K&k>8U z*SyF;xJP)wdikCGm0l+LAKL(sMHhTmN{DLYpMXQ|d7i=Md9N8mr^VxZ`x}X%!*$y< z3Q>zeN9gdV@WZHU2VX_7gqM8TER(@DDO5^xG|F+g=G#!XU&{W3T*gvUZ6IBn7zWL+ z3n)L*sO*u$x8k!RQkm$mMyE)IG3=19$(l0aCK?v2x&k=shtf$~G9;pOlU&$x2hawu z3KkqZ@!QBjUVY9JMNgrlKBo|W_Md7kv(uT12UYIFT;SBoxT1(dJPNK3*K-vg5F?5> zgJp0W8Mt&WA{)dQzd9OvQ>9Ib!P0!VhKR|*{$Mm*A z9rVJJpA+RJ5|roOU|zS5UZE~1X4S0u)xR^khTUkBt1pu7!7aNp1r)Z(1v<2YH-i#! z#FOE~Pwo)4P*srRvmn`-c}}c*Nh~ReC`0&ab4>~pp+8ay(ypM#$&|26n)fqA!KYf+ zgJ$1vVLaB9NcSUfpbNB9FLx`}x*3?LsOTG;#QBf^itvAj+&{r6*+}z)>dy`y!yitb z_CJGB@xP!)CgN^wXZC->e4e_j>!JqQrx|zpbtD;>lqf-*v^SSbKSH7qG<3q9713~6 z5%5Ae-7Z&gqZwIF(PC|vqo@9yeb-s>6w(4U>$O~$5rFjr__}l3lSiMG|5=BNBt7a( zO9o)3L~T!I)i+}ixa>zJUWGq!7U7-*#v)1mhwTRPoG=w+3zeagnR24Ld& zbeI^44Su)F)L#QTx~AWFAJMf~rQ7#tc%FaFOn)ibG&PfXOSWB1nW~fIq$F}#Z&=uC z4Ak0Hy)}?OaGa(_*7)`}ucH?oXB#wQC9E*J*-CrL3p`OCwy39=(O6yr)J+)93)<{Y zV7_7l@U)z^TomdqMrbCn70M3Q3}))5^n}5BR!5U&e!g}=pr(N3AfRGq(afk42~W;Q zj#{lBpT#T!H1AR^M;MHtAsYCH3hNQ-`8n{EAYMgK<-oB5o-D3f4r>4e`Odgy+`Z<#j;SeAp zC0~SMuB-zIh1wTWNd zfRTGmmXSHmS9U>k89fAF+r4uQ`O9DhFzAS5n9@8Q21YA)7n@))R$=V}2)oqH>LrJX zZsDC+hvYHhL-VJRsVly>PmhN)SDN5Zs!y4y44jQjcu$&`JEO1CPSvvCl68*H;i3-faN~G(;U4&QqV})kY0NHU= zdh+!A)t=%X2?7%wzdThFk`*;dk`(M?XKgN(TGnuqb#7bPhem%$W^nXE9QOt$q~HsI zBw8Y6Ad--u&ePADMEJpcJXm+jeEr4|euJStwN(+xmHPAjPHK8Dwc5_g2TfKJht%m!8Gow$>;9mP-M zQ|_)J4qX6IGD7CuD(Qh+`n5PN)!1-?D*m^)7km4mvoHnZ*bVZ!ru`TW`=^d7ZNd6# z^&9F^j)Mf>zGSr(KP%#V6ZerL2r=z+;<*ScthNL6tEI}TEN&XB+k@9w(|*?v|EAPk z5zlX}9ltUCskb-wGL#MsNeN)9YIhstKS_xyyQnL3#&EQ`mQ&e|Wo2ym6$jQn#Y8@7 ziRjkRJa8=i;%yH~K}$A3sS+AevX@N%5Q;lFJ-jOokL8ky4mJxs9`^N~%8kTdaSX47 zowA?sURd^CXVM3BCw_?BML24%h;tp@yKkU-2)U2_r=tDmR(r5TdunWV;@t!w3IVv# ze1sR;Q75k`3=x5-^L&hSNmyz3u z;+8nH*^(r}72BUtx}_rV-~_c;I~aJfWUwY%l8+HqAL5p%$o~HvuAQ#4KV&l>@joNehbP!Uy}H2|U=fLZhgMQB&7;o;a0&l1{;|8hh0m$1)prD`KQMof`E`ohtifotEAf!QYTtvmLIi zzsJJGvI%c?d{1Vc^F}>qr;aMW41Cb~Xu45`d~%oWc8K`6w4>a;2ocNKwy?#*OgmyC zo+0Oh5JT^T{UR+15%x*jc|#KpO!@ru1}TFp`YA)2f2s2Qc7rPDw`AWM{P7IY0QG#| z0^RE&h*)sA|Hvn`1nKnxf@pZ;ZwPZR`2y4BL^#`vGqif=9{vV_Snln`6zX^Y-1|nK zzg@GxDJ*uE7=CN@;((OLh28i3@(c&*%@G*keJ=%c`tn>I{)j`tu7^}Ho{c>zb;Zo8 zO`EpWbBFP@Y=`&QwoFji?4b+;Kw!ZMW-gznV#EusEnss5@ z&3z6>7RQ6Z6vmFBx3gcHBKAnjZEi+uyy0d?&4SLRG;Y2f8(%&y0oB}%%~%{d&+mLk zDlkZlhWn)c9Q*MpH;vhJrV#+tyE?Ja+)*~9CdJLp_f!H93~0bu;&2WKiTW9@R<`}!St~cK^(d}Stem34lGEnNtV%x zD;?@B!kq>B+>eZ%-$M=0JE!ZvJj2oL3XBs*=(8*#Tg&K{VugO*zsI?0iaI}Y<>%iJ zY1({)$s^ShL|oB!s3GH5I5k%0#!9wEzdo1$!v<_euY_D=?PEpj2KBA1Qq`Rkpw_F# z6N12&+Zy^Q^pJLlg2b^h*w1K3Wo8xO_xGzYu-Z5@aTRrbSEIaLZ2-cWQ%u~lsf>wr-)d%K=Gjy1|%!sF1dfzRK4P6A-lTX4qSU3G>M#R(`pRDM?) zH022hrN$Q=IRuf{jMW)cybFyt9&&p}qhx!R8=bu;%iH7Q{mo&8@~nzw@>Ov1!IErv z<`o_l5QWN zeRTKE(+4f%M0Hd!5!EWc%We@mPa96=u(zH@NYl$utJgEs{T=md!5LCPsb&CjY$i`O z`-^@Lnh;6L=h#5)sP<7q$R~+{79Bs;QFH}=CJIJp{oH_v@Ph32;vhuC!X}fvT)4;f z?kVgT2TyvraXQwxoN6Mxn4?8>y~BK}S)~N9xa3GcYGA1HiAJl>tom*0WE1P!etVLU z4BhR)!v(jN#^h! zt?J~@TLUhrY_%nwPI|WxD9eP>T0Q{bX z5tPttk7-2D?MIrP(&cZqjPLZ*G*Ix+iFT(rl90@V@Z(960y$U6eUlrEL>0=LNesgu zMjgceTD1ZrQwUcc1Bx#^`xD`o%x05^LYY&nO>Lnx-$D0mc)XRXE_!qZnJPa z(UU}G%QmV9HU#aHVWUaX2a7_m_~_Bz?72~JLNot*z~TIh01lbPce`dm-4{D1JnI__ zJP2kzm!cjqXLk?LyAJrd+Fp$r?ubEJxPT17V)zEhz@|WyZ8(g{-Zvzmwh|QVRn3hH zAFKg^s|++^yuvI=5kj>&QLt;(xmEYnFahy7Pnk0gOIz);Hf1(~j3HWSIB^r@;EwlS zWO3R1QogDsw;(v??lR*yMPggD<10LE?Pk9iwD~2>@c2x1>T;QD5^57Vn?04YY0ug! z6I&*C&z>82a6ZTpmd4KrB-jc1MREsGax>!X+=TQbv;X}`C0!u*AvcP(wegfVN{jdKwc=aw?~ElmPQo+j2jsInf$ zhH924@k3tCp!t0aVh$Od$}d6MGdRshgYKv1cTvHX0n*EIsmv|cN(x3LgI98;Hw0hC z^+kP{DFkwO@kw@l66_(tus{jxD`u@f!(O2tgHGVUY-u*XrQQ$;RwnPIO!*EK6KH1V zq_q9hg9aJeM6S}TTk1#kYe=##`;q`f_P`}rWK9}A^xScprQRdj2G|>~8ftfuD0{zD zM%}!micLY_&d!;uo6FmB#>Tp)qXB^l@#}_ATr=|I5K41o*%`9&7ELxYold=BwNpX> zqBtkXu)IKL5}sO;n)0sPqUf+_&)9gq>3HIBrCPcjhYQUjq#7V2!|W|!sbXuQ*|vA_ z&YO_N0o4SZy9YqjFsbjE-WA1vp<=J8#=fWq(}VVlLS$PlQ0K6CrM==d6MtEgAg!|v zD--k=Ry^%e4NTgx#<;$Sb#;l@xQQdMSq-dqRea4}9TK>=jBssNtU|I{GpEY)n{+i! zbp33K7X7KaEkJ$=b9Lbj-i1Gk^CT)mg)o8%8OfBakt-bvcKU#cA)Ub*~v55D@c!PP>%;i+*zWSNZ#o>Nia@ z&QVnz?Q6T{T6Z#p9|nA*e+?_7_BWMbv7PBcTF`LgerFsrlHcXd2IRJ_wIMRn52WEb zF;rk9>v7t#|F>9Yow2Brq?3~UZ$g)^}#6rAh&8cJm3S{tnA^HLEY^)+q8 zxPLQsp;_)Xg0DoDUs;q6D{_AFwj7s`Qv9w{S`uS7)O!QU{~1)g={@}>p-5xQ@3_M2 zRo_+qP1&O7JW83|I&=N$4Zg$n={pD%fbomH8Ky_2e!nt{Ch-ZyZk17;! zW}w3QlRob|;6fiR?FK*$ks>G{Fg4ipwb+X^( z$YGeEqDD*(-y7SD`S(Up(HQ#f>kgd=Feu_Var=>D2|Q_fqc~|sZXjb zV22mS>jx%h_x#Xy?D@ozdGAXj<*kq!f>=2%>2tlgY!B^VEjPI~gCN2;UQyBRNoJzC zA|6Tn&M@v#7@)kghiJX@`^1qQ_mU%tEPK3EhjiQN4(z*0O*pCUFSKjMiKa(fMl^b< zE$oherx>qK6ARJaL99i6j30Mh$#v^FEkNaOf3y65~1?o`^2()|HgugStg|!GeK>b zOmpO%K)2)D)peEA=w;gE?CG<#1-o`9sYHNFYjWbsSlGKqDoi-*^QHx=@wTw=Gtih+ z8r_P_TQ#aX%gi%sORTY6%z>h#Ow572qekp0xw}kkN9Lgw#hZ7WSLTS)2(ZhxK2%VQ z&sYIt7*;PTtf}9maCkCR7o|HDmF$@4Wu1kD711kAB zMCC<@><5Le=>((695jnG>Yh8IDYXx=&>q%AZnZVCI6`0Zj!!FuOQw zGi%f(Yco~2OwMjuzfR6>rgWRk!&>1it&h#6mrNOAlW{cNcaeNiC(0y0pyq9>fzOa8 zc9S1}HM%2$-&m?I?yFr{+vLJ|`2j5(zZJ6P@O{hLBa@$-?gQlesPT;PxH*U3+ZYVR#z&Cl2FXgA3eI>)rWB{~Y`~~M z^M9k|lk@x7RZs_~DuZk97T;=u=1HTKAx0PtxQ2n8%<7z1M;D`)J8e8RT5Be^gAU^6*`ND4|2Fsc;plALE|8sRS0HVBO^Hq)&CQsT zX1Fhp4bRQwLlB%T&IQg2woBIl=DljTT#5HU;SD5%rPdWp!4Et{Up~H8UjpJXhrP9( zD14aLf?yjyBxKPR+))2Xg7uj|T?HmQhyXM0{Cb1YflXtr=mVwL&Ml9y-EW`9Y%>%c$Y+qqx*z;vU+^Wm#GrqmPcpC#H56fJU+}1~YH_wN_pqET& z@xjh#cc8>Ir)6!ecGi7;AR!Aj)>c?n18h#HxDXukB*l2_p!U$ZYbF)%mQ8TOf((eh zMqzfIlfNi$@uJ@}u{B4Dj z#VaG&2k|jR(U4Y{@G3R!RP5vGSMV!VbQlck6BH-#VKe7OpjD;fYE$S{)rZLJ@s8G4 zd~FZo^i*h;Q!S>Z6R-;~?O+$`QiYNLF``~>ByGOB)qp8ON#YV$?0RuDI$WB%WAaWWgCY#z`T!1V|V*vunEa8!1zk|Z<5{w z2o8zn84RBkTbjJY7){8z>vf^q9$^1UNdAtc|3TSbjqw3v!Z-eZ&{h5C{Oe7DfA{b! zD60KwjsL4J-hZke280+1Xs*kUd6cL0#vs@s1_^9?gAgfC!*~@LKjpKRs?+0JH?=M% z5}ZA58O(_fa`;2j5IIw<4q}8dqGaZ-#oGezcE@J06Cl0&SV}sQdkCf@(J`KwqKzW~ z{UX7~Z%+oBUkl@laSi;$Pv!eF!*zr-P0WVuJ;-0P|N9*OXZC+J3ZUcihuQ%H0hRt) zCshA=jffb#TATi(RX}-M22>cWI%9dr>Yz6yI)dsT(N)YzSSdJK2EoT>l%sXZEh0aD zw~Vqsgm6zX%FzNOnrtniO|9qqj=+x{K_IqzH3^JIaXPdHDXJ@)nk@oi-Ca9WmxvPs zl<)Lq$J&hDDNj0E;IVS8v5dj3^)xrXjb`}2N7m1?v>ry)-Vv6a<}k7GJiH5eLz1X` zhSeuE%ZuC-Bh5(5b5$a$=6dEGbb4?4pv(@yhTeE-&d_XI@7N&#tuL3N3|xEzgeKSL z8Bnzx-d6^BERSW~^zyRus3V_+EA_JQUrw5$?{+?2>hLyzKT0;*mNDjbQ_|@@HLDic zRY~2mUfbH|o)tJht>z16TYz&PL0^9TAT>50Q<^Y^$Nt>)G8bx~9|iFwusq1!^#Sdn za7!{J2F_p}Xh=pV3}rdRlRzcID4@`&UJrOJu_K$PNxh~$w1GQ>E)Yg%k9TGdk`~ax zP?hG4%QEw5y=8~=1O3Z_f49>=Etu_6ygT&Aa^-)l$nc*nDEjBE6=Mf8Ico>=zuPfS zQ5FGM7|H*b6Ap!zGqHZYA-}9XJ9G%9YK5o79ALQ+&Xp4e%9VOX(Jv7xL-WhO?n1w| zoHYQGJ`b#d3scm>`=`p#cn`>A; zI|q)lB-Rg?a}&RPFo>5u@;+U-J3R-H=T4OG)!0Fxc;DTt2h?$IMv}c7+0kWh8lf9p z*ioLWxDwz+mKP5|_PZv{(qfrU#UqF+CCM^_>2K=pD0AMvsFmNYne5UaLE^h(BS$@# zBTLdIj7pFIe_cIp=InBEca>cQ#E%^F#d9A{=J4h;9)b`j;@@6bU)prLsE%%&q_5B- zzgI<&Y?8R&OPLhbvZh3nL!{3cc{uw@X0$xW$(s0XMoY7@mQT5Hc(T>nU)dPufL1tP zN6XvCX|ko@ycK^W&3gfOS2D20=F%l4Rpxi3C^jOH^mwz!hQdoOP0!cTy_%Vmq%26P z$rm)W5muu3LsxBC^zg4|-NfD~Akrlldt3^a@Xoff#>70_N{c@l@KGl>iZ?Y!QItV! z5fY6XZ7s~aDN#YW2iI%jDuY_bm>lI5m;q6qY^X7-^0BA}nwEA%$m6j9tKDI6OnUu1 zIrt@U36h?W`OclAJ0|MFT26v0Ry~VxmV<*B+(e#|bg|zHS|sV(;Y8nUS4b=5#|2Q7 z2O?~7@pn+<-NmIU?S7d#lJyECM?3H0sj-GIFFbe;i`B)BNa`e4?n_ai9;CEAlT!;Kl?@ z7^twvc3Da~0g0EkLz^y;k|dq{4Ak~SmRjZP+_i;>au;te)hT(yoJ{5wZYJvSA2N_I zaV!**vrD0VOhmTTOG1gK0hZ>9T+6_im|5BJn`r=8Xjl!*^kI!TA4>gb>Do3|vdaMY zFz#Felo+SD#1EFMBB&S`u0dZ`X<35&oqYk0`h7|>|3itzvqVJU9h?qjXarl2h#+GVOI)PSe+EQnsU{jq z94=gtlUABJrqZ+tjI-wz>>l1*)kVdVj$UYGo4vWD-$BVU&;Xh8ID1+PTbHj}Qw6p$ zPKmPMCs`)i6i4;qX+UKt#9;xV0U@E&)u%4vS`V5mY+LhL(GK`=W$kWoiksMFP2wt` z_|lEV4EUY=xR)7dhb|kiq=yndvgxLt(X;EL?&@xk9RuAYu`zqJ(sK+7lBoo|tkMhJ zl;S!u0J_r4Xc`9|qZr;!(&QT27m)=f^JkDM(|dsqy|@G?CY9euqHwMkOR=4k?VwVi zMbtZ*V%=`MhlK!;uF@x+Xu{S+keC96*!uZNKx8{z{#6fz@v9+yxv~%YDhtaVS+$V} z1gDnR@0E#n+B6DUY0YnRX){>rWnF^lXQo06w6k=Hnd3HUvZjn5+3oK$Vk+1jYl}J2 z3ss5gM3CQM*D_`a5>V*ONv~VWtei5xe~6^H7WGKEG|wDaedpXjNx4Nz*?~NH#K6A^ z`AtowcnU5Op=(r*(B|9(>yf+}=b~U;v9#~e9`rq6W$xXr6~<$)h9>~-gU2t}vOyz) zH&e+bYGXQ;sBL*)fdW$=vXA>!oUUjz;nE3nOa2{tq{k@)0kIz#-yqo0>5-i#09MZ! z-*HgC`_%)V;P|+J{iz#pNVyk)e;Wu2N1OTzgbPj~+`qx%+o!RmgSSpVjot;^YfLDk@?75*Pi&b(ogb}dsz z+~a}YZEu?=0Oi*B<@v%1EuQ;M0RMIr60coywC9ByQlR3n+_@nB_dRiF^m8m74?$l9 z{!3(h!hxmRJ01I-e8vgYLr*Q{Xw zbV|1+p4YI-+q~{|mUuA|;THzI48OvFs@8*zO$_!Qn{G@_p*1T$;GYfRH&{lT5+#Jr`l0 zOU{bNy9T8TUh_uTS)%YQS^g`RR3xxl_KD zJg8-pw}9u7cr_QY?1`(?S682IvjCLw`KeTtEFnqKL0Jj|Nb6#MHddDGyd*>Dx5JWi z;Ryz`IEbTFP*Sw@xK1MyRRz}Kf{&f?886LNo>#|VZgbro-fH&2LeMaa$h>R?fD|J8 zvNyDY^!=*w?NJ)qxTyuU6axpezCzkX0gnu^D^s#V%DJ-Is@HosDHDb%z5JViDTqm5Fbl>yWx9c_y7P?OLOmmX0*Z;7 zr0u zx+FB&qv{L5^LJ6G?NmAbagFzBT69*`5L*6Da{G(2>Q1GPkpc?}hdgcTOmdgf*$QU6 zWeIrWTm0Bk9M*7?oW=%Y683u2=g|Xa9qpcmO6eUPk{4|r;Ff3Tm4yRKl}#NWn|@515-vH4RmJ|qj-jtZQ?Koq5|eJgqb7s!NY z?{{HvtUE$~3Wm%Gq?BqVzSFEBvfp7X^{duH#S4@2LHb%pIP3)}_J=(96;Q-Nte6jJ z@1urWAWuO{XXEh$b8t~}r(##hA;?{4f;=qzg2#wg(Q8A|}|MFO9`SiHsN!C}WTd z;zBFvz%F&rM_Iu_Ag@9k=wL3TOh|?TiCDncG$3YEU@Qhmk&J{=okU1JLB;B?IkJzO zhMGoA$dd(S4Tos-@D%tR<uJz$JEr&mCb zcR!+fisrCV!<-4CnYmaEJrM&TpQWtRMr>rWF%6PBO)q5c%yp)>6f?Itkv!c|o})pw z5K*2-$(|D%-uT;D-BAq4(dbTT0l83l^Ad`lRD5+D6${8S6PPRzIOJ>?E=dhbCf z?fbW83+BokK_^hJB<1DyfPCh=bc>37N}@jKgRP6tE-1C@ z+0Ysxas?|atgn0XsM_smUZMOyguP>w9D+H_afT#KNyWk!_zMjO3EX4q=;8P~`jdf3R zNtR*HnK;@j@%uabH7?5b1})D|CYEIp$*_o|n}^d*!D?k= zHLLR-0hQJ_U=L(%LwLwaO}7@CfT$N@9u-sRpy1d z1V0zL!)}iZO|^q}YX)5_&Y~|47wr*l`4a1OnT&DL{^slmVTY>z*sX#nqZ{5uHaNnh zRpF5FhNaJgJj__g`%wlqo~oW%S4;f+XLw91yYe6GQ^k&5>N1?-ad1rK`f$5(^EUmn z5It#Ne8rXlfHXFLMeG2|xcqCAa~*IK`iXi-tT=@M?!z#l`5LDho2F4M(BP9XI&!!mNFZaxnO(3>$y#~>C2z9EL ze(ocn)ly!_KjZwE>iA90!@?bmwG!?pp=BeXiwM%uPj#~~iW!RuiSK)lwwJys?$|C4 zbGZWrqEnbp6z5DUdT1!rMJTKVp;$(}Io_K|6d^1F{s~O8#`W5b5cCxz<0-p)5PHvi z4V;ra`emL%W{X0MdCZp%Y%TNJaRd-S3?oOrY3g^u(PPvTamWP_YF@#_Lq^d_3LPK9!f%m++6 zt>yY4-*LEPm$J7?C%g=7_0(*MXe4bu{Q2>YTKZM zOZyXYp6!yDZWY>Eh|n`Euu##czTs$*R1H0n8b&k?tQh($kCLcrXN-0~ERdI{;0fV2 z9!R#d@}^|=eoHY>v5sV+L1~$dQ?#2U2V1u^AAwGgX+2+uXA|46TVGPTem z?h5Mso_z|=dv*5Vb88VXhUTnag>HCB*H(T(Hi3(Tfer=dxo@&?L?Xl9yD9Yq^9Z@H%*4^H?~Rhq zG+Glh_h~w$!nSxjZz&XiQBH1iI<*Q4VW+c@X18Z7Zsc@e!4NLX8<(AFn`sr-ksmgw zkOS3m+@9d9;M&|{c0$Zh$DfzP=M1K4Q*oV&pDMF@gcopI0}gNQX$G&-h50UjHcTu9QdlCxXMD`raRJ{9Q6% z=Rs_!_gvR!ZAkTLsSvIG8^24};r1RmrL0G6wixS*ALE zQEiFdlM^v5e-CMYqlclUee0N)KdO-?nXDHnD$-Rnb^P2$Z%|r)3=_d6FJ^wgJ&xav zS#y9jyV6ne|6zOHq!`xKVeWfkvuNI>0yp}e2Jj8ZrVvD62{5MzD7}^J!mUy-_C)mQ z>pRep-|ki^=`~7>-d*pvx@15`-Z>H)R%&;XVk1iWXgMb92M|{D8Cy4E1;Cl4}{`l%w$~-m}#q zVw5*qA@#>tt@RtpE^Oub@d$ulBPlETe#*!h#F-+@N?*z8hxI@%TJj}x&-fq46#R96 z%Cd-v&qKmCdu4^BaLcO_Lxjq;yvZ}7YGf|SW8ZGOAQnlZ9gvJyeyU3dMwL&<>cNB} z`Oi?)XBACyfA|{=2LSaQ&M9hdn9!Y%b8hRH({|X^e!?MVK={QV6%B;@fL3LZ&N4+O z-OyEfwUCqJL0h%q@!i;8m$($m)P>@__2Kh#mEmN{s6QQB zcw2-yOu=0MKWtOL!huV=W=}{LC>!vazk&YcBmdJa{!bq{4c`oMf zGrhgvK!z~?VJ;qwOeJvJ^JSkQ7; zvm6Nv^;MUZSppn9WF!di)E{;B8%!;W#ZgpKlr8}x#AauB4t!>3;230-VKEYY$4S}T zV0>$dN!MjZ=oZvfy_&11bS#pb_yo?DEV&m_S{^(OXK`oU;gsb=Qn}$2EEfM&wz&m~ zK0$qR)A=N-AW6O-Pc2=FjCN%h6`-Hp=F6_{px7Hc;$Xgi)TOBfrfPAiW#gqjDw)!g zpeLl6EklZ2^ibb(omdze?)vSoe$@rzR3}M$AqVkY!GzA=IcECTK(^Tf@q*{4PbV@_ zo!v%1$5U5-)WsT4ZY*&nSjU@Ewupc}(IUE!bXj1?>u@sUB{?6n(@G+^psl-5QOUFb z&dwiXWbzk}^|7$%D|S}=$HSN&(6DL(#gH6nZ(up%(5CZHG_@dFI}Od1=gF&QTubG0 z)EW_#jXBfjTb9tLRqIuGw_Gj*Fw2EW)cfVfyUT&C>Zl{8pcO_?R*4(Bf~S=E8B{*v zJ~@4)C3v`9bq52(Gu(6sQsXB)#YSpQm*%4A;WS*k!dJldAKIE|Ok_yd)QCHCLCxN( zkG$Vs79XrHECz_#k zz#hqCk@SF58oxDsCsqGGJBl@n-3^1(9TA@5G3N=Um29ev*vxO3E*>rEo_}s!xJH^76QJ04>>v z4{nXZ>be=mS8Y@vaYdn1Vk>(_&%Pn@WybD=`7;CEYE$IIE7Y(sIf0dpOR_+fjaxy2 zqK4|0L3K{A+??Y=&};Pd&ZIag)P-rBa&O}9icwu`Lrvj`@SGk~)X#RDP~Q`Byhg@2 z#F9~?d!M0q-&s}$djt65!nOLcN+(%4aW!o~4U2ScO=!Y-nH>n$O^uWlHFx!hI5lMdGl)?BBogk&(y9Sqoa)yQ%@JISq$A-dP#dtO7?VP zGp9t?I>`ULsnIm8>omi@K+TG?hlN-*>63umHJRq`m-Zc(|BUr}=6W(<3vqHmdJ|zEk4g10Vl9i2w75rn}7kCG~eMu1yIKJ+`^{TQ;{C z{ltWsR8h&1U(ogZ82@~cFSn!0MgGOr-sEJ{2W6h!3aj9cQ^3m$=grE^Xa465NW>4> z3U7w=19OD*JsxQLyM6V`dt!ptvFR&){OiQ-eBjIBJg`^#>*PIquousweSNMEeV}VV z9`v)PQtS=PxIWm6kCJuLRs|td&W9Q2t{4M8qA>)_Z6Tr$qDSXlB8C~~;jmG^w<>xO;fU}Bl8~3Y=$|N9 zfwVmfX#eZshk+w74t>`H4B)q9M^CMAJ>qQ|X#X=Y5`Qw}ul1OnUA6u{b-^oLnGq{! zU3+3I_U;EB_ut*H3Q&VN!uxbt-E;tg&{ZDdnGNW#%3VFM0OCUk?hPmu3<+brCv8<2 z+t~|{r0Ho%PJIGMu#1yBU6@t|`0%GSP%>n;U|&(nnXrb%V8h+wOn)b0%!Q4N^2BHi zhedXqCnyrkY6IL@9N5Eb6j+Ej@$`}=YqowShWUDy>RTHr*ZKvMnr1hmZ7MBXD9fTH zZCXkjp9LdZNai)Cc2lkLp?&YzcF%*3q;zB9BgLi|((QQI)adc*q9;0|ShPQC^hT3F z(li$$*+!>E0|P{6?X$uNR(tX9Y2vh)*O^=DX=W*8_C2hHI-1biB%CG1{6$Zyo`;LA z4uYP|ni9n-2spLYR_ay66$5+#(+T6GN_>`J?@v>+d+`Oz(5A~$NV^L2w-l5jN_){_ zIdK_MTO<-i9HRGcmZ34|2splSEF^LKB?db5b&6j@7JkltGOTGgC?9*1Sd@Y!2P?;f zc_6-=BQk;sBN=9)alOnEkj`d~_RGRh>BDG^ei!i7Mez4#I~S3Pp*50Ot|~R z&+Frc5}GW?OzM?Ks9EN}TOpYzm#NZl-O@sa{|Jh;oi{|{G_!`4r&J`WP#X}h*JHi^ zKv0D(>+#a7jU_b(^7B{RZ|>{xEQcoH=hjFVehf4RkKAE@J2&JVW!gf8mw=rzS4}5c zgUVf_)}AZh2WHHfN8x50GG0ellI{PXUN3^#EKsZM*G9uJs(giU1q)ES)B2R_-%g*DKHz=Z?1}&-P6au@`$DyVh#ZcLXZ3hjfQk58uO090i zc_B;os#vCsU6hCN~qh;V9g^r-WG`{il zRIA9dkuP4&8vRKfhb~?*cSaqDbZlakD}8i$^f;5}iMycl*d~3TWoK_=tZZP}A&q9d z>~JTDatlNu4L_Cvdf?PzAW$S$8AUBO5CJWxZWSG=N@aQuL9t-EbCwl4I}}#e+j~qN zT;yJb-XpuPhHg!%Q59XSR&8`~P}3$}rrju!muXSW$*h5@y|zHXpI*N)ik7a(tX=uP?90(&4Ps(PwwW>_tZD7G3M=s}BM=}>sda2iU3-8^bZgwc-iuQFl> zY%*{T92<*9ONNtWiV6{y+B7aXV=!G5yLMWWlitLh19(L2%QNi?sGKvpnElewUTD~4 z=gWrZy2;h_ITcH3Ii&5xf})8hGlmDWQJK_N2=-Wma+#mNZ0A3 zoput5!MbA;G7*68XXd#C5++mXvjXKXd=7OIZIq zV^a_lNha}YTHZq~zu5uaxf8Iz5GZ_Vh^K^ zusPv!WqLa7CBW61PI1t4155+!ZIB}Aq_tG*-;#r5<4^`@qNEu!l@WYnQfYM_x|+RrhMP2 z7&h_B|8Q$Xp(VjIEpDTfcC`L$6b>W_5B^NX(;`GF67kT1gq_O~gzFonq@89~b!gT+03j;|j3y-Hd#`-hXAp1qrAlGeKdMMfz$ zj`%cBJu+ftjD0c6q5CxV$R*IWD2;YuN1c}ZTMeX)g%QL{Tfs(#9QiFU&KHp7#uG;Y z$X=Sk_Lb!65|MZTJtwc5=N+Wv%)L@g4E7ToTP-Lmo?Z9{P9)?m3|e7$oCF+BWUFIn zyXf$fdbvuiF0Q}4+fqsn>~-UP?#wRx-Bu?Qr7nkow!IQZL_8yhJW&(&v~U42p3n|^ zR$U<$w?O$M5c;J?o>4g08lw>!R;>CZQJx{?dvex&8>|R7v%Xz2Fn9RBcm1^c9Z;bv z>T+!kxbBfxCym_s12T4%+c1Bk>bx!jlrN8GH=tWXWvMSc%_Hz;E*lQA&~}(pex!E! zAr$Oor9629Wi$@cFJEifi|4>U%Y z*xe_u>&qf3;O$D0H4gn&u?Jn#QtpFbaLK#0#>0M|3a&ZW0-}e?h3hUE|Br zW>HQ2>R{?PEP1YNGfn4ndBQa?35O%$Q2l5}ow?@P?ut;`47X{>t0_lgz1WLbT@vzg zOhzdyHH7ujlwz=!8q!jYZU1c3mMha#Fgq<(l5FT~ozv6>IHX;v#$UV!@W~C+X9xSd z?loq7e3LF6Fm^sUaf2w#!Y;hgtXAb+rZP17WWn%worpXyDyTHcxC3ACss}%y_X>U=WbFmYfn| z>zH*DSP)!$$S9Ghazm6@+7H9+wXRiYvfhu};Du*cj-B+TC;Vl(-6-s2R36m zhqD%K0Qg<2O|`IP{2sm}wZUuX9W}Y;E??5s{8X1m^RD@QQ7-iJ08L<>4rR|wKPqZD znoqMTdYEYolLE^HaY`3(l0hrE&&$ur5EaH|4y_gV$zyO08G$zL9_{I+mNQuFT6iOc z0T@ee8w3lZ2QYTvs=1PF7~xEp*E9syi^J%}ur>45b#87@@vS%`ZCURerRU?*4#6Gc zaljm0YVsBR9jx!z86^-nyMo;84`{SNsrl6g10cKg>?p;c+e}*XmgftGsyahfx3j{4 z25VRju0Hy+M?w61pf;JOa8~Yiu8y)|LvxOYG0xqDeQU_cRiOi`YCw|Z_uuWf`D*qx zdOjj=ev0tfogjxCM2lhim?S*~6d}~`odtKD4pL5ooWYRy;3M~Q5au8{9y$8F=ymCj)IK`h9+~lPWWcJC|sUiRvdmXG%5#&h(mF) zMt9MnH>mb87om?SMinvuB(b(Owuoo(jjR_=DbcyFV+<+t1PtnTauODa52wr~g$Hb3 zgnbe137c>5M~deCBWi9^)$hQKdb~O}&rzInj%AUn^~#RE9380vC{Ea;pccF>M60kn z3#Rn^8c2I?E1^9!^kE+KdNZ)#ms3x`N6)U5d%?rhe|*8g1XVX?hbG*xJL9nf8N`LJYexZTv-SR?bNmm`;3{dWIf@s;4Vo} zPwo>LmT;9PnN3yHk}R9P(NfgP`uu@t;^?!|@dos@!ro|}o=ftFr>j^ZlbN&NuG~=$ zbv|?TSp`TuUts=qMD1X3*?6cDZ&$0)zy8Zm{O2$KpPG1G;=TXWaK`)T3k(?03ypt(vXri2< z?70&d$}CEzDkM{0pUIhTaUtFrIx>s$40y}fY|Hg( z{)}BfhK?Fi9)G-F-o@p%MI^djg|-pq7?-`$37UOss6FQq^PU@k`N;#V0J%H45-dCu zg%=C_=djFau~p6&vxoxqOH#mo$Iw-A&rxT&p04B#v*>bOu;J-wR*R<&-AP#I)C0O# zhjY9TDkoBr2LS6%rhJ6aO>0YS0DMpyuOs1a*g&zh!=JPB5KJq&SI(~+v4h;61bGf0L~L87VJrkH@pj@Q18+5$DC zhCkm(p?yZE`c7TCDpNujC%PJK&~t0nBEO5m1N8voi>%V@y_&(nGnDU)+jzEaJbG@j zIx+1}kJ6*C2DYDbD_!ZaCSpS_S*c2CYP2<{LO-MVH;rb$U4FqP&_{XB=qcp(hp9O8 zG3i%9cJ?v)&k3=&V}lf1A?UWlOUrKfkicVhs7zT=`oF&87+RK*QlMfX_oyI@ApYs# zIh`Sj^>^JzKaD&?8?bwyy#&q~mf#lNnX8xDE?HrI6Dc*xx&^ZEQ-mM^=^`e#TBIqqfY;*Ib$u52!?iyN%UDHmbGI(gg(gf z7-G?(Ld-bGg+;P*87MB)l@YU>uzo>_^)Be=St}Q~m!L7sKM)$J>9;O7_2) zEyn-;to+A7`+wq%(o%L578FrOdMhr}*{cbGqlom@a++V=f@9L-@GL~Vwcp?37?gz zGH;Qi=6c5%vhN4RoVY%26>h+%ycFX#S`=Y@5L-uyTJv~hpA}uA)aC`n1~U?^I;26T zh?BnmNd%dxI4w%YaA7b*0`=)u9gc3eh^@ghw_W-5g8j)vtR>Qn30DhxVuH`uU|pC zCBLI16>1f<>*{`5*0G5}mad{VwxHFhUDPbU)GP<|?F_nHPfpvjciJb6jd8yLgBoGF{-<`$~ekH~~JTibT0znA7W$c;U`gwa$1N-sY z+ZQk8^EEu!;l5g8b+)zbiBh0vss{gH#N(BzY}d)ZKphcbuagrXX@Mpifj9(}&oxr_ z@H=yF8s(`ikjj5H+yuI(Vpj@Gfyz@`u${_+6s3c#5I(cqekfU+y~YA8yQ#y>atvu} z9NWs}q>miPsYXzQ*3R5+s#&7hR32gA4Fwoz3j4?|1md?-9fJkVSdS2i%}lJ3rubJBz3Kh!D)eQNp z?=9na&K^_X0M^Sm;IG?iBx7_Lic!~tLZfp)`=bBWdeN1_yySx+w>-Y}A;r^He;}W^ zX_h4z50kZxd2s(~D-+#?Cb}imjGOsV-e7R9k%N(d6hstko6#Fos*Q(rZ zYN_Y-8OM*;#y(PlYtNITQoJ3JrGZ+$B0K{l#L`5mNcb1KPom=9LqA zO>+!1vNCO5phOm67*O1HdulE)bK_hgXyXcT>5_=5VI*>7LqG3q@#rQ-T)f((Z#{MD zj4sm6E9l})nKFPpa%~L^+>QCo7!JdTCVVB!tj|;>sz=Ou(KLn}Fuz+b-zPTT@rKp9f_G|O zK}0^00*Je1@|5o^KE?VC)IQ_dF9Ahb`xw&|(Y*%*)L&5=Z(q&M9nk@M$-yg>2sH*J zzi3Yw1V-YMt~clfL}E+ivEo!CboPdf`!50VCkequHsLNClifD2)ar+MjZb~HT;xqH z`NbwbbwD?mGf!ILRGXw|^kl}Wlg3WT@yhbO^c3mkUUuQPd96{r)PN;E^E9Ck!#DYW{2xsG;Q-DuUD3|>GJS~mGQQ;{To9B>yB zwr_FbO%SqcRZh~FY>%DJ+RPW0ESc;QN0uONxjbu86}1avq<%x86B-OyN+g|JX^mB` zU`@kHdfK>!Mm$&Q&5oWPSQ_K8b7%F1oAOOEL1W2`Swea;iM%@G%qH9x*#(j=J#eXN zBL!n?WcM8|52-5(*puApU@uN+e`wp_RTK9{lxs)8t#>2~F8FOlSukYJcSt{&&K;=F z9fpZP+cxJ%(Xrd(5J9^)NKOceF?Kr-a6c`O3e6L<*({29={ewMe`U1<$AZtw^aiM> zoZ&dq#8twBZifqfP4zvkge4$#C2Yqfu_zL6ohb5za1-D^5!xIsXNFq2rFSrHu1DLk z&IGo$2Xf5+U2np$5=fY3J(np8k10Iot>g~w&=XdwBa?@9L+JkVcpc}eAd-j89S4Rn zD=E*x)@zSF#k#uLm54uQMO(bWs$D)uU0#|-sAZE`HqK*d%7AM5_+i_7I4gAu{bzk6 z3Tdo-#bn`vyG7=C``Woz#9Cqnz0TY};%sUZZ_?o|QPrXCM2m9n1QAtbF8^=qEun=< zAyEBxrlk{dvN&-S^~?!7C()D`K2@R!P^K8dep#NL;7&V;?+i%rnD-4l#xB+Mp`q+; zHe6Nu0#Qq?@R6nm&F{Ye3->W^kljUHRzCQPnwe{)pWQ;w6hC3D z?;wb4>dsxSn8iGL#<6G^h|o*X$WNHwwcZ|&ZxyX-Ro<0yog%y>$yJkGVK}2F8|Wjc zEED;KoG=GeKzv?tCYgH&+=)zMddfLSHItQEqe#c~t3Wysq2yZ2P25v3*m zp8K74JrLs-{hfFm!h@^*{E$HDHuvv|}uRW;RCS?#w<>Io5oz+uyI zdI&?J_^=RK++g^_!7G?36_?LAsYSK7^ER=Ii(UgAXp0V9s${Odv!F{`~vzeMf71S9i%B5Jooi)NhMC6?==DmNWJ?LHBdp|#4q562!of{a_M0&NFD326}o5P}m zENCaS9cd@EGA$@Wi4!+BkcBAIzH7fCgX&lgZN?GUUY^ijI*4@wKAtuZE;?ssTWS5O zG%)AO?$Jfc%k?3{UEt1QDz=_mAlctqBt{KI+DRv*a`RCbOFT>^nK-z!gO^l00U-5i zeTFN32B2&S5k-W<#v)*J5gu)wB)A&CH&Wvcyyv}WyQZ_D*L7`>WFOB}v1mEGiw$ea z4n&Px&!K)!xJhfev9eixf?CUV0T|V+FYhxp@7i{p*;_oqYHA{qoVS3JXhz6A8^+(N z&s@)!Z~;|(nBdt>M=o1zb)NpZ>Uwm1Cl24~3Y9KoPATJ7;wB_JnIUDC?d9j-^_nSj zYXqa_%WbQayIpaeZ5BrT!+x~Pv42=H<0deF-v%1(^_m9_*S1=Q@0C=4!M&&sF?w~F zFG$QGzejn>376gXsB^dx{!xDtBxf3COr1O{uWt24i^N8t+Lt_Q=*$8{Etm!q`)&V` zH2T5C7`qQ^+vN35R_ch3rG177iA6d{G%;#kAwc-VUkp39ZqYZ18*b$=0vfxEtYtn; z;-pXEzRpPPBRMnM9WmL79~Y4%&U8$MZSDc4L86Ca(kz3fF7={a+$m`bm{HK+C*cu! z!GHG-d!fik2!lDMCMT9LRgp5gJRPSW3>DBabHd{|^~2^M`2w{Ub4SJ)gP)%su)7~O z+MI>?^KZ28KUMsn`sNpQDJuG_>&3q>vj1M+|5o(>N7(lJKZI?z-)NU$q8RmXd?A!= ziS)ceu|;xHDf6lbCj%g!luTtl7MTLRp5FmIKRE(%sX$CL5tD0tT$S^hl|q{>eXcHh z&=rI<@#Aak3(k`JcdhyoKL!pMV!o?hs%=aWRA>sgJK}A5L`vm`r>3=@ie?GGq1`asEUrvYG z-xe{~N?{Du09cuLlOdrLT$JFRfMI*Myou$24`TS<**6N5A8)(*Ys225gk-9#X*MFLn>mk~B=dPe_?0wG!WLKUK{zqP**>{LIM|wj;qIo@C~0O`GPwyiU;4c4 zF+3Ia1?@$GR^Pp>19RqRGLTl)+uQHD@FJgtxBGVzqql%I?5SCo#xRxpiGG){1tqmS z81Q_Bg(l)IZ8Z5LqelmutrKhb2z4$&n2!;+Ne>Uq$I@pIsJXpPYk*7sNC7qX8HDJ` zEIwl^3;sBvjm+T;hLziW5$ZPH^&6)Ifh5ABLWw{((ClBbYO;ALAnPw=*0gz#a!hjf zQiMUO1gKC&;0zO-QIZnvGcP$zs&~>i?3rFgBBv!PCQA{oXzc4{R^RB9WWa_1Nozx# z6~CsWyBD5sTSy#ln4Md|!6<7V9#x!QF032^V%yN&^maZoeRjL#0!=&s;ijB&pk)Lh zS<;d&DnDX%d4|CUPnU4Ju!XH@08@mbejakTDn=@KA+uPcJs7NZ4?I8V4{%ta4hqo# znG@_t)eTy-dOG&HOb3t9yD6inxR%?~87o9qNr$z3w;#|$eb05)isj8k{+6ifMlibf z2J`09PWVR5f+}dLqbJASwK=6x7hC3cW0p80$ue}>JJ`Ph@1NoIpMkeCi5{yC`QwKI z;{WKFC_1=UdH!>7Do*{v1JwfSyL)XdZ_3=+%AQk_P*9npQp=uQpTsxN%-yNdOydsU2twTq z3rpu3Db6jR=cDW9WAf&WZzT&spyv%J@Z+` z^7#OYUq;Oc)=FO%D~l0cR1uB_HirRk+tiC|bfO4y*eR1Co^ifalbiZL6O=mtaH>^n zj}ymJdN>L)ow$F(gP1ewrpYzhNdDoTwI<&v^XBdzmSM*t*22uz_|LD}CtQY^2~LUw z2wmh#kgC^=;`7-lzg>e`xK=K@{iJ0QT(2EzN%-a$ zWD-POr`EWt9aiil1TT>)<<0426nJ!4;*H9|(&4g~B`ebBl1scT=5cXY7ThhE&0M{q zL5XteMN_qJYHd=SExVK0bM=D+n@uDI&p9HZY_AHFmRn6nkUM^>$dsOz`p?Q*R}oDy zd)^R8PgffKvVqB5GhZKmWuIzti;oj<%#w)$)HBk z8}BETCx`>}E7P_zW7Gt*fAMaGr%pc)EK8^!w0}4aa30K}$ByOz=2*6tKkQ8` zh$ii5NOrM_+2Rq9bw)LpL3h@PMh~p%Q(U#)3QaZkdBFSYvY#mn_pH!D&HOaEZSQ4v z2?z+@(eT_nPlDXNv#1CA%p~_sLmh6!n^G#A&w=JJmu#x-LFDzYsiApGD!<;nV{evp z()TC$z7i54@a2=>8l?KXol#;v-Nd>5ODolI*1u&$M|3 z%WKx-d8_E>45FZ;$ESIz9RuWZFH~VexGU<0bbnSfy{zMy4+WN_FSGd~FX;>K^(SIM zWJQde;K(iEp=&D8dXbJ}{<|M_pIi`4Bt>z}Ktl^78MlQs3mSvxC3rha!;nOnJ{a?? z!oVzwY^JcH6q2FVk<+lcbqExDM2{)#{c66VozjB3WY*5K{&;&c+k!`|#DfOPP@U3* z6!A@^klAiaTmA3YY?%^Qpw$-_x>OO~$3@^3P6}Y|a?x)NGiR&_{EtbR%k93FX%f*!kitSi)|ya4oV%bEL5RAE-yCa*Nx+9Xe@C zx2Whl@k2|FhS&x5hRj~H?eXaB{xC9Bl@qJBG*>$Jn)1r{G`#Yre~`2J(&dP(9PnxU zn%X2yZFHL|R&!c*$ta!D*JE6-^9F%lD#yyWg08mfc}m00Q(&u!$gwm;%5Xc6G=m7V ztj#L?-0?k0a>fo=QX*f!MpUh!=f)BeSj-s4OppCk6-q*sOf;wxfH-z68k3hnkC>#g zHY3C_AF1+%Vaboaez23o=y8U2KZ@lKA>jg)a)(nmBMu(x`GY1n#eTL|++pPQ@7%$D zi9~)6JqQ;&+?(fO)U^?+AAmK+pBEx9L{E8Y@rG**B6$xH0C4tM>0^F*>g0~_>=W0w zJ*5kwt#wAitwthh@dZWPL9z`oHGP{|7cv&vIhG+B(G_jbcf>{g!6fV^Tq!ZAp>>jh z(s+kvcPdF_m9)bUEb)x`+z{?@AX`%BzN4+B)7F%E=Bu+SeNt6gOpRpNgTR}l~4DsA4757VMa@=_8UIS3yQbb`vXB4eO z*wN<KaMv89I;yX}sFV0lr?%gVO7b zF3-Cmr+5 zHrk?8$Zkw6Ey~U(i^a$R6iQyqgyaHPIZj;}y5W(tylR#3HnY^{vozQJ(|- ziwYy#A{zqDHm%Cr!i=_|h&5Ts#+|y-B&5TxzktsacVgK>CLfC37PL zP_$XZ%8bNlQl-YDWT^v`{L`>~#v@6yRmQYN1C|AeNG9ojhK{CgUsGj0CnX1eZ-7?J zv}X~KupDGhmUWPz7>bod9?Y?l>;52g3Z`T)gMJEfSqR%-$Rcv47d*mJ@H2G@$&Tem zZ?YU&$%pp#Pt&Rw7dzNQ>^$_a;C9}W26Ibx`3wPSLQWx-Ur^A z>Yrb%8br91dSpLBl!Uw`NSJY-M*n^}j?FQ$J+Kb`-JiZ9J-B)X1bUmW3KEC+*|-M! zxv&o585j-klJWFC$vfc~6rG_#jk~zdiPVcf1`jPI(Y1b}3#mp15(V4jH6GhV@}a0< z=<4M|IDGO=GReGM3q2%bZ?Of~oxwjpKZkth7Q`8v2=mc5_wNSkW%n+idyy-ibM`>_(F?1rfzcBw5khdw`%MgVq`lFqy{+`KL?E@eQh<_xWA7KBNg12Dbjy5zz8PIytCdy z4kXNshHyVSYNrAR&k3GPRH;dK3eh%1Rp&N5T@`pKl|EODvEE?nIDz)}Hn{;KYKyhH z-zACsm^54~v<<_*M+ztFOc1L9!8DsB!1M5Iz`Hzt4BJN$eFaM>s4`{nmHDXespmo3 z;%58ssWpx+mn7~p#-u#g{1O5Wh4ejiENqxNF6_MsD^7HA=2yQ|(hNAzoG*xb1o{QC zV`GCCDk+V5Dt6~~)iWsZ(;z8@dG+_V8N#k0;58J1BcZ=C>NG->#`m84!i_Ru#ZF&B zu-BomSxNQC-XOThPxdmfG!W12`bV5MiI@d2d zntlh#z&mHH+koCP2Y*P6g&smopq>|RDLTSXU$!iNr{qH22Hw3Fs(?N>*Z`GIuS`di-t@_zMHRvk@t`E; zPfMhno#r3HRP=gN4J0dU!|MuNuFyPUK~F*0&4lk>TkY48<{50M@-8i;&|`nuNv+~w z$r41>WyGJ_y|m83(%4`L;PDMhuP?6?u(5j1Er77w$VN0L^ zCyUJ8eMDkw_E8VV?H_{IyFU|w#Q5Y?`JM%><^!_X?6+%UkIpB2f^cQx$|D|`Vy0kq zrhDq?MR*W~Rc2uhF#@tVoPcyqjzT1T2c=rBwaOztqy3F1fH^Ffdy2sV8?r7qO}eQz z>&QVmc9X<8Qa@H9pJhQSKX)+zmpVPS`h#4yJJ&`}Fdv{u3+ODT%S)w7{!BU~y|FkO zrrFbAPsn20Mhh>B&Q}Jz$oHnAOE7-^5mmzM43CmDnvc)IKn^9@e{2dmB{_+{F^VKp z;uKkM3vt@pFcZ<`P381ex0>2k{c)Mi9=unumGmv_8j(A^aheKcA8EAC%Y@>At*F=B zpr}JkE@A?eN|LtWAi*KHyF0<%-QC^Y-GjTky9Rfc zAi>==I0ScxpX}`Ho6JsTzrRmzE}TO@U0q$RxB97D?@FDs1tZOnB|xI<_(!*xaKn)v z$lgY6;-^%%V=Tu=7LSMQ7A%gmE|@9Au1ClpbPYsUp&1G%X zi~1aS%!T8+0lX!Y?aS*F=`*SltNyCG)9Z7uK0fg~DNj%+Z{@{1m;Nv8DJcjQIvv0- zKrDf-$=Wx9MhK1>#^=}^10%hUuFb9f%LA4DtbqM!QIPKW6WX@2$YCCuC0Ggm4wZ5W z=85530ed2?a&w9m;8{kcPS4wlU)r7GSG7TnvK3JgLEr0BKLrtLam7=9-U!U7QfaJ( zs05!565x!}dw{FC!9?%uMm((~wkffkD4|yA&>Ph&Fi*7Zn5om8+CZGTe*z6^B)6Cj zh@1hMsy|WR<2jPW{=yQb(&H`e?+DoMn4SDNp6$#yFz}88L{maa(HPyqR#SJe&@xMh zNIAwH!@4dB(p5x=X0)GnzSf!+BRo~En!?QJK`4`ljIqqHn@CdBPW+Ut&gWs4BDrU2 zKM;u-v!OxG%z5ST#N^{zY5dcAINGLX-YCA&;j!vl zWZIV(>GDL2@^-AkJ0ZHems8qg(#`L1=Jm6jDi9lH&idjB7zlSnM{IsCj`2j`0g!fl z`p{NKT?)*b**@BZXUmg`UtDH6rD~+8(==3#hJsVv$|<@dSnSW7>K)Iz<$ArM{m>b6 z{CEM%GL!(m?+Ide#EzI0J`1c3LE|xR;G-MMA2%;7lYi5CbY}_XB-$K-(qM>_DWE>< zp>MJTFX@{y@GWH5MM&+liQ7Fy4{6QG2KaPMZssX#X$~vlo5}#8gmXY%HH0&zu)OIVQ6E$hFMGWlNh#2vuvF5n!k4^ z7=YhEkrooVN1c5mEnY29)cqK>1L%0!O)3;f=jD&VXh;`8k$q8M$(7~IV+oo&d}=M; zk#K%btHQaeB)b9sy^f|`4JDLXMs97uNZC zd}l}o0M+1Ho$Mxzv@*al>PF%6Yuml7{8m{NA)eG)a$1RJ*MXjD^Bh#+Z@Tyn<0|e6 zg&Aqb2y9aH9~>U?%|g(6Kft?Fi>$OrGAB%g)orjEy?gL=J*&K#)9G7tycCquEw*wh zWqb~y2W$`y;w-jqw^BRIFL`eNqFeb9EdIlQ5b5|@8OuFF3FAJ& zyFY7&o5&lp_r0ny!m!yU?n?J`7CnSQuHB}|0X2<(0m2Gd$8yG~_ObON1)sZNp61R% z%ng!29<$Z83a@=KbZL~yteQ6US@kIO*{!i(#vga*e_o#d-@^R|%W%||sBGxl>3;cJ zIO2bDb+yzpHFmUiwEtV*=YoHSEwnmXh|J@FHFfbvGZ=HzgF6^!}hShK3#1ee5h?iC0<%# zR!^K>Ik~IL8UCo*+|#)s^i91%*2z*md8%sUV~sf@)(L2)4ry-!JKkdA9a8zO?E#a`0AD^TGrLcmZlco!^>ngE8c@uHMK#9zhyUvugYWy=_ z-*qa;sZA{r)U;(|32{#y)s|VS6(bPyzED8LDx+YLvdR!N(Loap=VBE9WXEw^xXX^? z=Mc-VG8sz<@59*_obesdj89x$4B4mpg(OWh4FZkBY4J7(*ULEb!2+C3qc*wY4pdb~ zfoH+A2KP|%pc+) zpQWEvar~LKIHg6%zs)yoLI2~+o(erB%tG~^%NK{V$m#phn`y!e~=eYvrM>3^5@ZFXnEz=`txpSQ2`z zUO|8{Vd1A87EiiDH1_E^L8=AwZeS#~i1OJm{!0uw48-|aP}gXLB3uEgvFpV7f^NQZ zgM6~D&}Db;_}@P(6M7L-`b=M8eK-cGX$l5^z%a=-ox~1xLk25wwuyWa6BWYv(n?72 zI3SUn6z-i_#k%b_2|Yz<+;j#Bf6M0!l>*T{tXn)VXhWm0O(;D$LAB3%pA;)PrS^(7 zSUIx+Dq?vM@F?P)^BJuf5l7EIhwT+sHSn~$_;X%P!n=SC>2Sdn*rS-t*YeL>aCeS>LvsDdbuf=Xk5dF$$G!!l>faZCA) z%=~eS)4b)OSZC+0=iVrx#HVB9*W^9Vigiz}%kM$s?O-|`E9hNXZLnR~ZN)t$9xz3Y zcl20VQyb%w9u%LFXi<5vwI(wl2=nEc684(X$g9#P=d)8{FC-r57k-*{^G$A`j!I~El=wl9>weQn80koFhV?by~d&1D9voiz%gwcgY(urL4a74 zHPreJO2s`Yn#c#wwuOkGRWLN$gDzf%zSLg%&SFzwMrjhOln zj_Ws0Y|Mr88yMGSk)nvq)!FmvDOf*zT}sWZ9+2}vJCzc2B}`^Q?_%2np^1_#++4jb zNpu-mL>PeanO%w#5zs3cJ#UAzLSjA!KZTrk3e-QYPm>EVDa(k~Utu?GD%m3z3ijPz zGr4`R!50P2hg)37GL;lua*@&s!$jvSF)_B3XGqz6UNM|hVW{`rR32L;KPwM!6db4y zU7VV(r-)s^T$@Fcz1b|^7%SfpP?$d{q?v^yT3XDrbu=_^ZYrWLI1+#-+&!I3(Q)6o zk8ilNupDXsIJ_N%aLlPWgNBBY^&UE-QPg19FeX$e7G+33 zdl?8W-bk2e;XLT9ehW}_|K%0oflu^d8R0zh#NI!d-?e^i^SZ4L@1PN@cM454E2q9@ zNS2a^*VKW733oU~gJzb=o|X?m6vjPKf@->Ep9t%ok4ep%yx`pM2(jR# zfp~t#(UJX@l8tS@q_MRk$0U-J>q(_pB=K~!p#(#72|?zWourg=dYM>W+>zQBO@&WL zl1zR2$6DwF{C$y>>U!?_=NS4GA{E_qr-@N3Eo`aZgKzWEt@gp4;px%LkAs(jM6Y8u zQp^??jr}`zPU^cx(rM@-AQY_ka!~X z1opg^rP$AgX++C|OxXRp@=hu>^6#4i@i%PSiDr=_i`P0Udh%LcgV);TVh^|TEV#zv zq$sb*Mv@eT=f#u3Osh4g%tX@!92P7^Td|!)W@0&O=3}J}YR(uU=`fh?=B`klo0r03Ch$QKo6uh)Z7ZXOR&388>(x&vr?-*pK`8h%*TwRltCUr;CWwIpgvw=3d=i#Ke1&2aS)thV?>dU2H2yo|<(hFHO9 z4&*Dj(;k+n3(>VrJt=j5Ak4EV8I{V5uFo zbTU3xNu!x@@(h!i)m$U5XjA!UN6(57VtGvdWi)xHiF}NOMU?D0MbASp8Rp4=Ly}2N z&S!Pe$V$wEozf6re*_p9=H~ou3CtM+HTL=PnPb2WC1`fgquj|-Oi@}QA~F$Y1bwAL zzA{UDe9Yr*2YzXe0zJ^!5*z%48ER7%vu3(Aedeb3H$YVFLrdmbqLJ(b)lPj~RTDQK z(apn-v>V+K->nTu-yDgxP^-! zm60-_Fn+jBlA=y!b(>~B^1(bgiR|6iokf`;Y%w%1>A^C*B~on!&XENoR$m&%>oG1F z8fMs{FK^rBaTXTXLF4B%WNIe1Wf_O|HaF%#o-DFeSAU3)3UzQQ3~y^;%B_wKcIdkm zw4uGxp#jeLxG^0G^)2Z*@7WO4)O%59LHj1==2pl#>lwc@4s84-Zi`A|_JZQ+!4D`p zFCDchLBFD%6$xj{gcaq?cBQ|v%J3Q3n(T}me{_SH2DLQS3spMmleSThwEaob8Jm1y zU#2H~Bf_RUle;gw#gTK%0&{d>)VhaW<=BDnn8=kR(?hoXAb-|r&bagB;Su$UBvT;5 z!xp7~K0ag)^eZTznSYG`i7l8Y*6oF>o%crvs1BWwQ`GBBd#Gk!RuFm@c-LkA=K&m^ zZ>SI~wNg6a*<;$f+&+A|jhv#!`tOTm6_V5w#WSJ~*)Kr=!Wuv5Jkd%NqYD@&0Jb%e zG8@OJ>LqS-g-+3Vhq#JrYE@BMzawf)n{wWjOl@UQ;rtYmE&;(62F_1c`GqC2wItpN zF&juQIM+XtISyu?CuLslJF-}FhLsbQrUeexA#!9E?iJR|C}+B7;Dby?c}^aaOjuTb zmd(o7^>+Uuc`O&Vw)N?)=S=KVXXrxu*wT&ORr$D+mwalA4;`QiSBP z7Pc>gg1%nyjWS%?j@;zmJq$aPWnAFp8&ISR&ZeafL{lnpP(F`=&^C;$M;-Wm^z=O2 zp&U}|gSF|$(@>6e2V3UX7%8Ji(o>=-+;_ggrF?wc#G8q~9~$u*Ip`VL6w4Up^dIcw zbyiZqv@>q@G_C+oya$mn#OOGc2outZEPuu#-EpDWd7z{^a}EE>tMH9?q#H%1uV`M6 z3!$P**P<`UB=4(9TqWH^r%*eGR4|F_1ER7pix-0M{giHA*q$wB(E{;jK_)qEO_iYW zNf=^UoPN*r9oSc1xn?GnWjU68; zbD=#6TYMT49cIQ1XUx07&!{}X^rdr+S}Q(^lvbjsyIIC?+N)G_3%17C9AaTG=}zfpZ*k>^PlZntbHXJACB`?PXGIQZ zXoYAUnyaC937=Esc1{T@2$ODGXs>(EX2^{|0_39jO2oS-k}AS((JN+@0LVXkrJaTt zZNg(ji6%MPAe)CKo}Uc^C(DI$q--Z-bF8rrWXp;HM9FpKU70w6E483^+A)9|r3?Gg zxVvN#ps4XVGh)}GM)Vo@G9#dD(^ z_xyR_MGd$B&9Mf1*nl9_5OQv?0g9H%MbF}_SLG-a&cNw0m7;%s8gB$@zcykn89A>X zd5d<0xbcNQxzur!aIU(pf@WAra*mT-zb23&_3JCD=qLg6XNi3 zGO4q{MB4UbT71A7Gl!e-N`qCsS_B`Hxn%iVsv7F{9AIGvmxAr7S;J(M?ue+xGIl9? z*Nwc}(dQvnA1sit9;rl)xu%?@U6!5afh0eJQ(grTn%x2ZWSXFAv5xpjs)`#G&EuNX zafKUT43(bGOk-nl1f`?$TA>}`?)gEjSoKsN5*{mzb?RBDRrkc_UyO>n(aF9UtvV25 zeul4Uc(g=A8p$HdYtXZjq8Xme9W#(H&e}qBMj!5D%?D$r7>3&|&a>Fd%*lw*ZVFv@jBCLVHU5|ueG_%Tv7mT=92>1n4;Sl@C z@u^n}4Ps{0;WlLYKIhV7AWOp?i+9%e^y8@3A*Lve^Q#SgNoi3WN&l->AW8=Q!m7Rw8AqL1N550XtvuzLxKV-BCAzD!w921TVSZXfT? zE`U!rfe7|HqRoEXu136w?UqPu>%LtPY~Za!$KE>Z5`Dn250i-KfI@rUDn+o8KQ{k8 zv85sUd7o?|aNcQTBVyOVGYHM{46Ric4GY!yh&N^O?W1zIm_+uHh+%v#dQ>NRTGB>= zN!QkQyvBpiBFo%<_uYHx{2!roHR%m;4D z)&&h^NKvhV2)fg9Cws-Wpy|Lmx}`CG|G2wo4OpbHIPR;;TQp8eUZjsg%61dPMN+@L zZgs}{`Yrksqep#@3p~IUSU-j^ZJ!GW?-ptRd!*17aB4UT9IaH2pR-=Sc;2?Ie3~ zq+YJ~R%(kX(Wa0N9;e7g6@i9s!Es+dac??NMH{lyJnQ)9=qs?%q3SPWm4gnikS#*` z2;T~UB%pwQ%)m*1sg2(2Mwgd<<)GG*$m=q1|*!(2-yc8 zCemw>Jzq*zj$&7bTM2smgsDUiv+i(q%!suhEOAV)IP32&bH%SfXIp#A$op@>irNs zi?8+MP(>Xv+~b_u4BG|Hw;@i`Nzx@qlSf?)$DEZ)0ku*)%g4{o#F_CM7A9S-O69s2 zMxT?IJp3MOH*K@g%HXktG1?dV&FsxT2*_FvMw@#0uIld%II$GP zQqu6LN-98w9#4tQxSihsax(oIxwH*S9tyZC_$dQ z-Wt~Z`h5jIdl5sptTdReoY^p$xaNz1pyJ{zH|*=|(E=a7^-e=f{$Lx=)R9L>Q_7OS ze5fJ%_iPnreq9?3)4)9ztC)r$T?BV!zV$tCO8YD^&-;68bA&=Y#MyAEytr+S*-r7Y zlSv?CT7M#qeu#cs9Oo*rIqOv0!ZC78u~4fWok@zo;sd{#D=<^`V_8+EjOzu~i;Q{A zCZ2ng`kU#0IamGMOMmUZPq#DMNFUz4!y^1g^2|Rv?jN`2GgKfw)Ms5^vnW(!cPKhz zS#04+#K5{^FxhEhzxgA6h3O8l2x5sMHbt%|FjvPF7g7cU%p<~57jJb6uQ$(t9@<|j zqbLB^NrS~bSSrBKG@UQUFduHPI?gsOlHZvxC8l+ZW3+PsdCG zb1(qAGx{8e3-;dQgFd=Hx_`KGB65p5`3?u$&M==bjQ*ZVoh9EewB?lQ0il?CA#4Bm zkhALZUT;oCZ?~o&$1CwDh8tJ8AHfVNc|?nH8vVk`gQfXQM^ zWH%pI2G*jGoPph941gAl*?o+cr36Z`=z$Pj7B&qmt&faWXM6J4AsN0~JhHu=*095l zut<@Gt%b<=2dL>_hYJ*`NCY1cP?8cF+EQ$ZD1&-FTIs{f)x%|db`$Y$Fmnk5Giir? zd~DM(A{g)0)OS*sxYW^z;pjy7w+JnmWmhuC3L)8n^~ysuyz==m=HL9}h3S}?gwC7@ z=?@|SO2){CQJ3d1@u^zu$zp4$W5&Ke%XI=R$p{$(+l%_D5>%O5NIpR3nZ~-_FVpK3 z2Z@1n8byAY7@J#k8_U$q>1jO?`+m^`hiL1g6cs1j9t9%A$gfswFSSB0Q-VGT*}hHK zF~_*w34ne)D;-;|KJRjmRhecboB=dtZghf)+M+03v*RaZ+T%O7csSBLd8pDPj5B^H zTHY18+}4>)mH+jM-;_X7=y1r${=K9g(Zn{3CRc65PRdUINV#btLbO350cCo9)~ec4 zpo2vGCZz=n2qXvW9zuPfe-Wn1%UqsarUavY=0ssO)O4L>ZDP|k3qf+oXfjw)#Iuvk z{Dhfn@04Q#JixFfcCwZpjPGvO$5H+F-sUu6`+4y^WSI>n!I z2%q8)AtP8n+(_n~B(7Q-Ce@NEE4>9iIOT#tYP(th6xp8|}D8&iMI}rOm54ld-(ZRxg z4HIKc1w@(c@i0ItYjNSeau&YZ&lmtmjd%nfD~}vB@7tVWIi&?*wn|kfmK66zN^||( zdsfuHwjKQQk^wRE%Ci-2@={##p#gnguEuDhkjM@pP-$} zYj1yU3YF)85pdmP=~JznUdg~M3YogFAL)oHI6wg+r>?fq#vipo`w;!2hm#;_A0i5o zU174bv!9U)M-{$n?<{6&ZB+5NIA1}Az@5w}wg=LG-PWd#bp;73bZtV`o2T!l%a9aW z7(vRPF^23gG+DB5LybeEJX;%JGC8rF=hv5$uSzK#F{wctw`mHWFJan`q!U-rqB<{k z?7#PQ@$B~7;TsbKnHgGLH`<2oZjYQnye)(E)4d&2#vy9_wey3Oz1uyKo~n*viiS0D zUev&F8;ejWJ5TFSbqGzhkDjiMi*ZG=BwC~<9Tj?ispH|?;5O4&y7^&E@%%aZk|`ZO z`>GgF`^p0MVG?H6L5;_-7*;i|=0#B>$Pa9<+~i5vL_}ih-n2f&BC5{~>VxdlWVLoB z?L9|_K#ARegR)fXiXRV&yz&gLjzo0h%`jCJwB4v~LR-aPlY*Cp+_yRO>Y zqRnQCav{H(6j;5Ta$)6raeRwCqJ*fbQT)&e7hNS&?yy-vDU8pkmUTLX_M8d;&JBMz zE)1@(Q5%9Vu1!4l0z~BGoo3{@EoDE=hCgS=`v?!(A+I4b$In;|YAu9@X>b1*8;YaQ zPol*=Q$9~yT0~hFdACU3Ct-b;h2x=cp4g`#{LE)b#{^AODDefyyew4!*9oATU>Zy^ zmkrq)WJ7eu=Cc(37t3S9?@i@7dxiQPGamnMyzM>4atgttRlJd-=G|Q;i7q zSDb*{R(y;%xiHVbJ+ftlE_%S@Aif20I*X!RM|dJP{CTr@;3Jw2HG_y~B({xDtN5ZR zk4d6v-Ge)E+>lj)2I`8r--lOgIpwAC`gnYBzLK~MrOvDz-EcFriT^z z5kCp;D$8emkGN)lmrxIZ)exb%J2ZwEf72V4ocY?COU-9V478p&ZRyknootgX*5q<# z&$&GU(H5vR;M1xaz=H0u$Om`8D*pw z7{%-YburHGAyyF>s|cB5&zTV-NscafI33|2R)w&h`Mw3yFm{lZc2TSYWK67`uW`zD zm_2bTB(T}SiSH(ZJw*pFJ#WF^A71{QODb=RUJ%-EyA(=b_%u-2&t?gh(Gq)zV z4Io^MyMdV46J_JvKuvr-79Sz=S@*mv3j*%ivp97xQgoo&>>0`n*60c)h@dF4o$XWc zK>s}SjlpgeH&alABS`2R5IHmqCK`FM4rK%UAPM3%T-Vk$bIfjbQuy|07Gb~8==%D+ zK)%UHIP3!4f^c_sZ&Iuh?IvL+4=laAMrCE5E`V`5xKI75Q35aXqjb9KArUgwE;&K( zJS^h+C-M%_&31`RPYm;33KN9&KBIHaBiKs4#ydFpO~+O!xoSx@1-zY#KGh2ZYP1In z#kYTBi=~*2@67SAmZa2O$`f2-;Lk5jlx-FwmZU}Nm?wDl63M^#sD+J|_URGb?V*J! zHX`wkDi}LTz=qHl8xwb2suX>LFV%pnD2CBzUe3HA%&a-t;2J(%1x`}HU)YSUUrel5 ztBs{8a99P*B@1Gm$#DxdR z=3~mCA9LEsqpCQk3x256I&oRd76n~4Ce+B50pp>xc$faQ7MW{Iq|^!LkK?nyk)YADQh(YuWeS{E0za?#CJ@U>fu=fYtb#24#+04xtWKx|7kYsnT z^-T@Yp7haP0C|P)(2>2vKQK1h3ZbzsHjmp+WS$v>jzmNw;LTp)&vc>j9dZXtmsiPOk$%_yVL1V` zivJ!rk^%=`2HU}<)X2RwkUMtP8q!VVskOk^YjAAXbQo?fl}=dV!~O&ZtgQT0 z@BxtBL*lXc(3e>{`W^k`B9HVk#*M08HStfbS4t21hjy(N-0!(0Xvx-j5OG_o&s=B3IfvuFO%yg@IxNW6}e2tS{_Q!EE0Tc@kj_OR-$%w8&W*F*P2(d@X11uCzi5?&apuEn8v5+ZlKXe|S-_3=Bc3-3OZitCl%&&n1Lp)MBQ zwy*Ti<=pkOrC7JyukKFVBubm64V#9jI3}UoOCXZV#}xD!jR#LFyyJ2`{0uzvVWRjc zx*~oaD_lt>ywvtXhY_t=3`KlHFFh&?#U!QpJwo&Kp%dn#dQ5V1|7ZorKIB+c zDroHkm5_5(wdiO) zJ_zw1w30YE3A3sKE{eWKx%~X(spz>9dbZN&1na$g8;0#%8^_+5dAL4TGHMZ9*-&vg z58OUOvI-Gf#h#!kM~xmv0ICF05_(l-+%@kx4r{0U5r-Q61;--?yDXkj{{(Rsr@4B1 zQ}i?`yRP&a;M_<@YHRj6|4%GrI{BCKTZ!~8g~Ot|E;AIcwls#O3o^b-8FconzWss6 z21^c?Fy7j7FYd;V0E20=@kXJa4A`v;FOlZbAwSeH@3 zH-I-Xn{lwXKgJST5lu5yWDWO8C~ekhje9Oz&MsSCn+pgq|I9$iX{ouNb;xs_pCW(X z(4Yi0G3QpJr;g-2uK`J5THwIW%&I^wyGOD=xlF`uSsVu>U!aB774D#c70BPBRF2$h= z_;kV`70ytRruz_jy*-n00Y%1GQ=z{;ha}OOAP)YKsiqADIZVYM_uIY^V`}Vu_650O zxH?IgbJJDBd<|5G-*!_6@jm~AYlxZ$S9{4utk+kz!NZJmJ&k*f zX%iA|$W|VlvF!|h$6h7ob>*0HIxs&-_f{W96-%9R#Lrb~*&Q5QK;1b?Sc#vLanaj=W??ji(Li~GqyZk1r=V)1 zK`8s72p=DG(*s7>@x6sKWdLzZdUVn6a;+*DdyCEEZhj}L!2ox{r#5pj(MZpLjmRY6 z4{1_oBh&Ov9MB3M8r?*u1B5_gaO>8Ilw#>i=PnOa3np~Oft^ac)}g6Xz?4PX6ebc_ z-6f~L zt^+F*c9-ZiWR=heZZF9Q34CQLucHfynh6N4S%!3k01AXB&@^BqoM-SWBNT!sFf>b~ zP`DoJUd?-J+CEyf<9_TY<02H3x{SN&k0(iesko_%@aBl_iYa;vK~f*|Gf>PKzEp8Q z$@<3N^|S6&uV1o!tDa-_hNQCl5F;~L8~;qMTA5HakD%YK#|@jz%kpjuX7Tiaj%DBQ z%uEMFjR!;Ry88x|a4;14_gM|}^LmC!` z|LDRC34WE6r37#O_>}z|EEpxD-dmEmm%FO`DGxOpTfwLEU=i~YHfX<*pUQW0U&%ct zAj}Y{6?HL_ZieZ*?)o6{_b*Q9cn{}YVQ^{-47SPp!XEp1Yke%;f^ZjmD^FmKQ8L<@ zm%-!S5)pTzTyUAaNK?z$az$nzt1QrCii*Ac1HT4G^`UV0#*%#Dr@o?>vJRduMkaoI z`vCccyoX~)*Xt{Nh?~L{w~#}bCwfkh$*yBy~hLFPr zDywhVO#%FyOm4-Gy;zE=#E#sNH4LATv~bqCTMbBw5&I7A%RA*&Yk}=>xP*om_}f^3 z{Cqgil7hTx@F`8H8byJes(Zrjq{D-jcB*+?VCOvIzncY8b}uLMXEjnwOr|Q!h&jWVz0mDK_M6&oan)e(~3mp$cpJnM)y#w3ou1U z0O%P*CQmvHp59ydB1Va`PJl;NhF}aY(xs6 zAq^!H2OU;QsKr^t^H)UaOFR^GU7*{%XhWZ8}!h5a{in`8Y`E9*Fh zH>(*?^e}0s&*DCX0neX53nEX4)c8Yl)8>#A;wOvHh-@Y=x8usKHGh0_wta7xdU5Fn zOp-Vk`f>bmTG}Q^)CkZu-)LiW{p2{M!}slQ_S*Z}wpaQqa~LDy9VEaP@=(%q>Py8> zJ;6rz94N^L^vd5f*H+vBId@Ybq?wJ`kB)MOil0lq;G6M8epeZ)MQ<*;{}&1P&zk765@;E#YXJx0Xz6E31-z_M zjxn=TqsqWT^r^3&pKijmM?!*FQ}cVr>7&|hJMtrs`!?qFB52fC?k?sm&zruj+cY#j zupEZH?X}aj$7iqG##Q&d##gTgv@YcIsf8m&U6UsCEnUKx*#7tp|7=m-M_^Uo8%Q=> zQYsU%XsUr2VuBt}V8i!23<_O}G0L_weR$BHtC{_Krf_0*ivx)<5vKgevEjwB6T1oU zFz3%mv8T^iGAGUmGv&_f0-@hXK5OwfigXDgOI)=06&_IdTx9#i(V2$#4UsBIix-U+ z6I(TT4aE9{ z66h1&rc~$CGwv)jtI%2Y1x6W+Xa;78r7gm|uOBQkZQ3o48I!;1PrUQm%7zoixG|vI zFrsp=$ulvs@#su(U{^zto}5WfLkdG4v>!xU@3bkwEx5*%N=2K`wS}-^xjoS|B}k&^ zbakY&#N;gf_C?U)y(FZcz^NZkIXRJam=y_kdKIx{AeDffpkfzmSB792J2vTs9l zEki?!gwrE>Q<>QS%JC;m-U(-9T{j+ zj~r{{1J&E4WrQ;$Aebog+^CtU_IfU-bMG-6F2^^u)TmF@4w9=l_Bc~wa##qO>w+y? zXzfU0Q?mA%rx32DBy0;7Cc7fF#Krb8#i&S#)9)t+f^$@rrM6Gx(5N=HYX^0bT5<_m zRfE|oy6f9u#Q+Poh>v8>OC#qeO12zLt@^03tijNGt+1>i(7THx8-bzma<(jaoj0to zPQl!iQ{8PUBX5CMLpa&ignheJD-cs|iB8g2g_w+y&y|t_v+1o1U{4d~N7Y(+E0T{LTfy{7vXacTM-$AmnWHh{Aw+ z>4t)QEZ43@p!4;cw80hGpR6h4un|_d+WI2?gr}hBYMtl6XS&$zF*Z;#ONfz| z)D4-j*X$F2@5Vdx-g zh=qV*8w`F_VMw&Jsaz>_a&<_SljrdOqR$|}p;VTIMIW!UU~Vc%&oyNP69jBO6k zG;YL~p{TQ{i8UDg>gj`{W!KxHzo#fiz+!1igQ`~(gY}~a0fpXQOXU!#eh$){x zTWrTMCglkk5sXoa38ng3AYt@0vXIKg*>}*6_;)_So1Voh+HUoC1tV!ebZ(7^X2!?| zjGCi1vk>fAbIH^+Ys2&~_-28053Y(yewj0>wk_+}fl~7(WA*Gr#?q#;A*Ec0x97)2 zzyBW$9X58>HimW%riS+NPSj$Ol%kTdBBcs8lp+#iB8q2{l;WfEALr=jYPaQJ21(yT zAd;b~kfWxmprNXzBvY`o29lzpp{Cj=6d)rR@9r(4e^0R~K-oz`b}3vS-rL*V-9tJg z-ZQWxLQXI!BqC1A1_yfgqbffOEF%s8hzNxE4h#(J-H*zY`t~l`zVVE*zJK=)@vSm{ zrhK0tKmDg_lDtx)LW1%N)RIDfAV9o(_eQAp1L4mcKi+Sw^#4w2w z*Cqe_!yoUrAPE0XKe8>oW&7b+^G`Y62vUB^@$~N;|8~Xsr;G@H=6m;}D55uCp1<+o z`6mFBUjUT;9^i))(9a-$)zg~`!oSlGDZ<`B{-dWqXkPv)^IPE0pE5W7cjljYVg3n- zEisKf&Lrx44qz%$$q@WTvb-!9J*|3|EM@A7@N-&*W%n&^jyg{>TazFGHI%vI#H%%V4}gSY1g z-R7Su--iYDx0t^Y>eBw<1M*koE=e6u@;95qd6W3Z2=Hgh_hCi*E%Lve!g%eB9W4#5 z9R9M|_-hfuHRPS7Z+(*bO|3unEq|tbpZ>S@|BXWaI8pmGQpjI{B_zJm620})t+(hA zgny#Gz4Lv9@%{&}{oiXND6t4<c#E9!8+b(rQ;YwW_J^%{4e*|LzJZjzJ^wct{HVY5n@8V& zY*k8H;munA&Qy^wIQ=c&c9Z#UGX2=i{F(B7pc#HE51+2Rss2A1YpPxDdhZ)l(Hk=L zpOA0we4p_*3;Rti`QON(-Zo4UrdEdkg#B~8_qP`LPs;Z>W%@1lFCF2(Rr#aS{v4$E zS4}WW{ucL-7XK-B{9oJq=Kx~_|B>~FCYI!Wi~3L1|2aCy$||1;(LbldzE^%vXw4XgQImGd+0GSQ!PNbYCs zAASAjtMI>?w|)3;CFcD{u8aRF;wQK3Uxz83=-(FcH#hA6iu8>0xPQ0N`m^QoeKg*t%KuE&|J$DbZ`&m!{{HPC^2fwY P`tJ2@y+YFW { - try { - this.telemetry.reportError(Errors.TOP_LEVEL_EXCEPTION); - } catch (Exception e) { - System.err.println("Unable to log errors!"); - e.printStackTrace(); - } - }); - } + private static FlightComputer instance; + + public static FlightComputer create(String[] args) { + if (instance != null) { + throw new RuntimeException("FlightComputer has already been created."); + } + instance = new FlightComputer(args); + return instance; + } + + public static FlightComputer create() { + return create(new String[0]); + } + + private final Time time; + private final Looper looper; + + private PacketRouter packetRouter = new PacketRouter(); + private Telemetry telemetry = new Telemetry(Logger.getLogger("Telemetry"), packetRouter); + private SensorProvider sensorProvider; + + // TODO: all the arguments + private FlightComputer(String[] args) { + this.time = new Time(); + this.looper = new Looper(this.time); + initWithArgs(args); + } + + private void initWithArgs(String[] args) { + // TODO: initialize all input/output devices based on arguments + CommandLine cmd = parseArgs(args); + + // use real/fake sensors + boolean useRealSensors = cmd.hasOption("real-sensors"); + sensorProvider = SensorProvider.create(useRealSensors); + } + + private CommandLine parseArgs(String[] args) { + Options options = new Options(); + + Option sensorType = new Option(null, "real-sensors", false, "use real sensors"); + options.addOption(sensorType); + + CommandLineParser parser = new DefaultParser(); + HelpFormatter formatter = new HelpFormatter(); + try { + return parser.parse(options, args); + } catch (ParseException e) { + System.out.println(e.getMessage()); + formatter.printHelp("Base11-FC", options); + System.exit(1); + } + return null; + } + + public void registerSubsystem(Subsystem subsystem) { + subsystem.prepare(this.looper); + } + + public void initHighLevelObjects() { + // TODO: after all input/output devices are initialized, create higher level objects using these basic devices + // TODO: use local variables; simply inject all the objects needed to create any higher level object + + // PacketRouter + PacketRouter packetRouter = new PacketRouter(); + + // Telemetry + Telemetry telemetry = new Telemetry(Logger.getLogger("Telemetry"), packetRouter); + + telemetry.logInfo(Info.INIT_SUBSYSTEMS_START); + + // ParachuteSubsystem + registerSubsystem(new ParachuteSubsystem(null, null, null, null)); + + // SensorSubsystem + SensorSubsystem sensorSubsystem = new SensorSubsystem(this.time); + // add sensors + telemetry.logInfo(Info.DONE_CREATING_SENSORS); + registerSubsystem(sensorSubsystem); + + // SCMCommandSubsystem + registerSubsystem(new SCMCommandSubsystem()); // TODO: should listen to PacketRouter + + // ValveStateSubsystem + packetRouter.addListener(new ValveStateSubsystem(packetRouter), SCMPacket.class, + PacketSources.EngineControllerUnit); + + telemetry.logInfo(Info.FINISH_SUBSYSTEM_START); + } + + public void tick() { + this.looper.tick((tag, from, exception) -> { + try { + this.telemetry.reportError(Errors.TOP_LEVEL_EXCEPTION); + } catch (Exception e) { + System.err.println("Unable to log errors!"); + e.printStackTrace(); + } + }); + } + + public static class Builder { + private Telemetry telemetry; + private final FlightComputer fc; + + public Builder(String[] args) { + fc = FlightComputer.create(args); + } + + public Builder() { + this(new String[0]); + } + + public Builder withTelemetry(Telemetry telemetry) { + this.telemetry = telemetry; + return this; + } + + public FlightComputer build() { + if (telemetry != null) fc.telemetry = this.telemetry; + return fc; + } + } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/Main.java b/src/org/rocketproplab/marginalstability/flightcomputer/Main.java index ef8dbb8..112d246 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/Main.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/Main.java @@ -14,7 +14,7 @@ * Subsystems}, and registering subsystems with the * {@link org.rocketproplab.marginalstability.flightcomputer.comm.PacketRouter * Packet Router}. - * + *

* The application is split up into three main sections. *

    *
  • Subsystems are classes which hold state for a particular part of @@ -44,47 +44,12 @@ *
*/ public class Main { - - public static void main(String[] args) { - Time time = new Time(); - FlightComputer flightComputer = new FlightComputer(Telemetry.getInstance(), time); - Main.registerSubsystems(flightComputer); - Main.registerPacketListeners(); + public static void main(String[] args) { + FlightComputer flightComputer = FlightComputer.create(args); + flightComputer.initHighLevelObjects(); // while(true) { // flightComputer.tick(); // } - } - - private static void registerSubsystems(FlightComputer flightComputer) { - Telemetry telemetry = Telemetry.getInstance(); - - telemetry.logInfo(Info.INIT_SUBSYSTEMS_START); - - flightComputer.registerSubsystem(ParachuteSubsystem.getInstance()); - ValveStateSubsystem.getInstance(); - - SensorSubsystem sensorSubsystem = new SensorSubsystem(flightComputer.getTime()); - Main.addSensors(sensorSubsystem); - flightComputer.registerSubsystem(sensorSubsystem); - - SCMCommandSubsystem scmCommandSubsystem = SCMCommandSubsystem.getInstance(); - flightComputer.registerSubsystem(scmCommandSubsystem); // TODO: should listen to PacketRouter - - telemetry.logInfo(Info.FINISH_SUBSYSTEM_START); - } - - private static void addSensors(SensorSubsystem sensorSubsystem) { - Telemetry telemetry = Telemetry.getInstance(); - - telemetry.logInfo(Info.DONE_CREATING_SENSORS); - } - - private static void registerPacketListeners() { - PacketRouter packetRouter = PacketRouter.getInstance(); - - packetRouter.addListener(ValveStateSubsystem.getInstance(), SCMPacket.class, - PacketSources.EngineControllerUnit); - } - + } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/SensorProvider.java b/src/org/rocketproplab/marginalstability/flightcomputer/SensorProvider.java new file mode 100644 index 0000000..4bdc218 --- /dev/null +++ b/src/org/rocketproplab/marginalstability/flightcomputer/SensorProvider.java @@ -0,0 +1,35 @@ +package org.rocketproplab.marginalstability.flightcomputer; + +public abstract class SensorProvider { + + abstract void getSensor(); + + private static SensorProvider instance; + + public static SensorProvider create(boolean useRealSensors) { + if (instance != null) { + throw new RuntimeException("SensorProvider has already been created."); + } + if (useRealSensors) { + instance = new RealSensorProvider(); + } else { + instance = new SimulatorProvider(); + } + return instance; + } + + // TODO: add all necessary sensors + private static class SimulatorProvider extends SensorProvider { + @Override + public void getSensor() { + // TODO: implement methods to get different simulators + } + } + + private static class RealSensorProvider extends SensorProvider { + @Override + public void getSensor() { + // TODO: implement methods to get different real sensors + } + } +} diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRouter.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRouter.java index 4830ac9..953d680 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRouter.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRouter.java @@ -22,14 +22,6 @@ * */ public class PacketRouter implements PacketRelay { - private static PacketRouter instance; - - public static PacketRouter getInstance() { - if (instance == null) { - instance = new PacketRouter(); - } - return instance; - } private HashMap>> listenerMap; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java b/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java index 3fa2f49..b082365 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java @@ -21,15 +21,6 @@ * @author Chi Chow, Enlil Odisho */ public class Looper { - private static Looper mainLooper; - - public static Looper getInstance() { - if (mainLooper == null) { - mainLooper = new Looper(new Time()); - } - return mainLooper; - } - private final Time time; private final HashMap callbackMap; /** diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/PTSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/PTSubsystem.java index da89f76..b1f67ab 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/PTSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/PTSubsystem.java @@ -9,19 +9,6 @@ * @author Clara Chun, Chi Chow */ public class PTSubsystem { - private static PTSubsystem instance; - - /** - * Singleton instance of PTSubsystem - * - * @return a PTSubsystem instance - */ - public static PTSubsystem getInstance() { - if (instance == null) { - instance = new PTSubsystem(null); - } - return instance; - } private AnalogDigitalConverter adc; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java index 7d88688..5d70977 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java @@ -23,159 +23,151 @@ public class ParachuteSubsystem implements FlightStateListener, PositionListener, Subsystem { - private static final String MAIN_CHUTE_TAG = "MainChute"; - private static ParachuteSubsystem instance; + private static final String MAIN_CHUTE_TAG = "MainChute"; + + private Solenoid mainChute; + private Solenoid drogueChute; + private InterpolatingVector3 position; + private Time time; + private Barometer barometer; + private Looper looper; + + private List parachuteListeners; + + /** + * Create a new parachute subsystem + * + * @param mainChute the solenoid to deploy the main chute + * @param drogueChute the solenoid to deploy the drogue chute + * @param time the rocket time + */ + public ParachuteSubsystem(Solenoid mainChute, Solenoid drogueChute, + Time time, Barometer barometer) { + this.mainChute = mainChute; + this.drogueChute = drogueChute; + this.time = time; + this.barometer = barometer; + this.parachuteListeners = new ArrayList<>(); + } + + /** + * Register drogue chute and main chute open conditions as + * events in the provided Looper. + * + * @param looper to register events to + */ + @Override + public void prepare(Looper looper) { + this.looper = looper; + } - public static ParachuteSubsystem getInstance() { - if (instance == null) { - instance = new ParachuteSubsystem(null, null, null, null); + /** + * Determine whether the flight mode should trigger the drogue chute to open. + * + * @param flightMode FlightMode to test + * @return whether the drogue chute should open + */ + private boolean shouldDrogueChuteOpenByFlightMode(FlightMode flightMode) { + return flightMode.ordinal() >= FlightMode.Apogee.ordinal(); } - return instance; - } - - private Solenoid mainChute; - private Solenoid drogueChute; - private InterpolatingVector3 position; - private Time time; - private Barometer barometer; - private Looper looper; - - private List parachuteListeners; - - /** - * Create a new parachute subsystem - * - * @param mainChute the solenoid to deploy the main chute - * @param drogueChute the solenoid to deploy the drogue chute - * @param time the rocket time - */ - public ParachuteSubsystem(Solenoid mainChute, Solenoid drogueChute, - Time time, Barometer barometer) { - this.mainChute = mainChute; - this.drogueChute = drogueChute; - this.time = time; - this.barometer = barometer; - this.parachuteListeners = new ArrayList<>(); - } - - /** - * Register drogue chute and main chute open conditions as - * events in the provided Looper. - * - * @param looper to register events to - */ - @Override - public void prepare(Looper looper) { - this.looper = looper; - } - - /** - * Determine whether the flight mode should trigger the drogue chute to open. - * - * @param flightMode FlightMode to test - * @return whether the drogue chute should open - */ - private boolean shouldDrogueChuteOpenByFlightMode(FlightMode flightMode) { - return flightMode.ordinal() >= FlightMode.Apogee.ordinal(); - } - - private boolean shouldMainChuteOpenByPressure() { - Vector3 currentPos = this.position.getAt(time.getSystemTime()); - boolean b1 = currentPos.getZ() < Settings.MAIN_CHUTE_HEIGHT; - boolean b2 = barometer.getPressure() < Settings.MAIN_CHUTE_PRESSURE; - return b1 && b2; + + private boolean shouldMainChuteOpenByPressure() { + Vector3 currentPos = this.position.getAt(time.getSystemTime()); + boolean b1 = currentPos.getZ() < Settings.MAIN_CHUTE_HEIGHT; + boolean b2 = barometer.getPressure() < Settings.MAIN_CHUTE_PRESSURE; + return b1 && b2; // return currentPos.getZ() < Settings.MAIN_CHUTE_HEIGHT && // barometer.getPressure() >= Settings.MAIN_CHUTE_PRESSURE; - } - - private boolean shouldMainChuteCheckPressure(FlightMode flightMode) { - return this.position != null && flightMode == FlightMode.Falling; - } - - /** - * Set drogueChute to active and - * emit drogue chute open event to all listeners. - */ - private void drogueChuteOpen() { - boolean wasActive = drogueChute.isActive(); - drogueChute.set(true); - if (!wasActive) { - for (ParachuteListener listener : parachuteListeners) { - listener.onDrogueOpen(); - } } - } - - /** - * Set mainChute to active and - * emit main chute open event to all listeners. - */ - private void mainChuteOpen() { - // remove main chute open event from Looper - if (this.looper.removeEvent(MAIN_CHUTE_TAG) == null) { - // TODO: Log that main chute was deployed because of pressure + + private boolean shouldMainChuteCheckPressure(FlightMode flightMode) { + return this.position != null && flightMode == FlightMode.Falling; + } + + /** + * Set drogueChute to active and + * emit drogue chute open event to all listeners. + */ + private void drogueChuteOpen() { + boolean wasActive = drogueChute.isActive(); + drogueChute.set(true); + if (!wasActive) { + for (ParachuteListener listener : parachuteListeners) { + listener.onDrogueOpen(); + } + } } - boolean wasActive = mainChute.isActive(); - mainChute.set(true); - if (!wasActive) { - for (ParachuteListener listener : parachuteListeners) { - listener.onMainChuteOpen(); - } + /** + * Set mainChute to active and + * emit main chute open event to all listeners. + */ + private void mainChuteOpen() { + // remove main chute open event from Looper + if (this.looper.removeEvent(MAIN_CHUTE_TAG) == null) { + // TODO: Log that main chute was deployed because of pressure + } + + boolean wasActive = mainChute.isActive(); + mainChute.set(true); + if (!wasActive) { + for (ParachuteListener listener : parachuteListeners) { + listener.onMainChuteOpen(); + } + } } - } - - /** - * Attempt to open the main chute - * - * @return if the deployment was successful - */ - public boolean attemptMainChuteOpen() { + + /** + * Attempt to open the main chute + * + * @return if the deployment was successful + */ + public boolean attemptMainChuteOpen() { /* TODO: Find a better way to check if the drogue chute is currently open, and if the main chute deployed successfully */ - if(drogueChute.isActive()) - mainChuteOpen(); - else { - return false; + if (drogueChute.isActive()) + mainChuteOpen(); + else { + return false; + } + + return mainChute.isActive(); + } + + /** + * Attempt to open the drogue chute + * + * @return if the deployment was successful + */ + public boolean attemptDrogueChuteOpen() { + drogueChuteOpen(); + + // TODO: Find a better way to check if the drogue chute deployed successfully + return drogueChute.isActive(); } - return mainChute.isActive(); - } - - /** - * Attempt to open the drogue chute - * - * @return if the deployment was successful - */ - public boolean attemptDrogueChuteOpen() { - drogueChuteOpen(); - - // TODO: Find a better way to check if the drogue chute deployed successfully - return drogueChute.isActive(); - } - - @Override - public void onFlightModeChange(FlightMode newMode) { - if (shouldDrogueChuteOpenByFlightMode(newMode)) { - drogueChuteOpen(); + @Override + public void onFlightModeChange(FlightMode newMode) { + if (shouldDrogueChuteOpenByFlightMode(newMode)) { + drogueChuteOpen(); + } + if (shouldMainChuteCheckPressure(newMode)) { + looper.emitOnceIf(MAIN_CHUTE_TAG, Settings.MAIN_CHUTE_PRESSURE_TIME_THRESHOLD, + this::shouldMainChuteOpenByPressure, (tag, from) -> mainChuteOpen()); + } } - if (shouldMainChuteCheckPressure(newMode)) { - looper.emitOnceIf(MAIN_CHUTE_TAG, Settings.MAIN_CHUTE_PRESSURE_TIME_THRESHOLD, - this::shouldMainChuteOpenByPressure, (tag, from) -> mainChuteOpen()); + + @Override + public void onPositionEstimate(InterpolatingVector3 positionEstimate) { + this.position = positionEstimate; + } + + /** + * Add a ParachuteListener to emit parachute changes + * + * @param parachuteListener ParachuteListener to emit callbacks to + */ + public void addParachuteListener(ParachuteListener parachuteListener) { + parachuteListeners.add(parachuteListener); } - } - - @Override - public void onPositionEstimate(InterpolatingVector3 positionEstimate) { - this.position = positionEstimate; - } - - /** - * Add a ParachuteListener to emit parachute changes - * - * @param parachuteListener ParachuteListener to emit callbacks to - */ - public void addParachuteListener(ParachuteListener parachuteListener) { - parachuteListeners.add(parachuteListener); - } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SCMCommandSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SCMCommandSubsystem.java index 846d9b8..61ec12b 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SCMCommandSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SCMCommandSubsystem.java @@ -19,14 +19,6 @@ */ public class SCMCommandSubsystem implements Subsystem, PacketListener, FramedPacketProcessor { - private static SCMCommandSubsystem instance; - - public static SCMCommandSubsystem getInstance() { - if (instance == null) { - instance = new SCMCommandSubsystem(); - } - return instance; - } private Looper looper; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java index 2e56304..a66df7d 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java @@ -19,15 +19,6 @@ * */ public class Telemetry { - private static Telemetry instance; - - public static Telemetry getInstance() { - if (instance == null) { - instance = new Telemetry(Logger.getLogger("Telemetry"), PacketRouter.getInstance()); - } - return instance; - } - public static final int BASE_10 = 10; public static final int BASE_16 = 16; public static final int MAX_PACKET_BASE_10 = (int) Math.round(Math.pow(BASE_10, SCMPacket.DATA_LENGTH)) - 1; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java index b258780..bcec3d7 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java @@ -18,13 +18,6 @@ * */ public class ValveStateSubsystem implements PacketListener { - private static ValveStateSubsystem instance; - public static ValveStateSubsystem getInstance() { - if(instance == null) { - instance = new ValveStateSubsystem(PacketRouter.getInstance()); - } - return instance; - } private SCMPacket packet; private int[] valveStates = {-1, -1, -1, -1, -1, -1, -1, -1}; diff --git a/test/org/rocketproplab/marginalstability/flightcomputer/FlightComputerTest.java b/test/org/rocketproplab/marginalstability/flightcomputer/FlightComputerTest.java index 3978fdb..f877781 100644 --- a/test/org/rocketproplab/marginalstability/flightcomputer/FlightComputerTest.java +++ b/test/org/rocketproplab/marginalstability/flightcomputer/FlightComputerTest.java @@ -3,9 +3,11 @@ import static org.junit.Assert.assertEquals; import static org.junit.Assert.assertTrue; +import java.lang.reflect.Field; import java.util.ArrayList; import java.util.logging.Logger; +import org.junit.After; import org.junit.Before; import org.junit.Test; import org.rocketproplab.marginalstability.flightcomputer.looper.Looper; @@ -48,9 +50,21 @@ public void reportError(Errors error) { }; } + @After + public void afterEach() throws Exception { + Field fcInstance = FlightComputer.class.getDeclaredField("instance"); + fcInstance.setAccessible(true); + fcInstance.set(null, null); + Field sensorInstance = SensorProvider.class.getDeclaredField("instance"); + sensorInstance.setAccessible(true); + sensorInstance.set(null, null); + } + @Test public void flightComputerCallsSubsystemUpdateOnTick() { - FlightComputer flightComputer = new FlightComputer(this.telemetry, null); + FlightComputer flightComputer = new FlightComputer.Builder() + .withTelemetry(telemetry) + .build(); MockSubsystem mockSubsystem = new MockSubsystem(); flightComputer.registerSubsystem(mockSubsystem); flightComputer.tick(); @@ -59,7 +73,9 @@ public void flightComputerCallsSubsystemUpdateOnTick() { @Test public void flightComputerRecoversFromException() { - FlightComputer flightComputer = new FlightComputer(this.telemetry, null); + FlightComputer flightComputer = new FlightComputer.Builder() + .withTelemetry(telemetry) + .build(); MockSubsystem mockSubsystem = new MockSubsystem(); mockSubsystem.throwError = true; flightComputer.registerSubsystem(mockSubsystem); @@ -72,7 +88,9 @@ public void flightComputerRecoversFromException() { @Test public void flightComputerReportsErrorToTelemetry() { - FlightComputer flightComputer = new FlightComputer(this.telemetry, null); + FlightComputer flightComputer = new FlightComputer.Builder() + .withTelemetry(telemetry) + .build(); MockSubsystem mockSubsystem = new MockSubsystem(); mockSubsystem.throwError = true; flightComputer.registerSubsystem(mockSubsystem); @@ -83,7 +101,9 @@ public void flightComputerReportsErrorToTelemetry() { @Test public void errorInReportErrorAllowContinuedExecution() { - FlightComputer flightComputer = new FlightComputer(this.telemetry, null); + FlightComputer flightComputer = new FlightComputer.Builder() + .withTelemetry(telemetry) + .build(); MockSubsystem mockSubsystem = new MockSubsystem(); mockSubsystem.throwError = true; this.throwErrorOnError = true; @@ -97,7 +117,9 @@ public void errorInReportErrorAllowContinuedExecution() { @Test public void errorAllowContinuedExecutionInSameTick() { - FlightComputer flightComputer = new FlightComputer(this.telemetry, null); + FlightComputer flightComputer = new FlightComputer.Builder() + .withTelemetry(telemetry) + .build(); MockSubsystem mockSubsystem1 = new MockSubsystem(); mockSubsystem1.throwError = true; flightComputer.registerSubsystem(mockSubsystem1); diff --git a/test/org/rocketproplab/marginalstability/flightcomputer/looper/TestLooper.java b/test/org/rocketproplab/marginalstability/flightcomputer/looper/TestLooper.java index 966ee79..a716ee3 100644 --- a/test/org/rocketproplab/marginalstability/flightcomputer/looper/TestLooper.java +++ b/test/org/rocketproplab/marginalstability/flightcomputer/looper/TestLooper.java @@ -46,21 +46,6 @@ public double getSystemTime() { } - @Test - public void checkSingletonInstance() { - // get an instance of command scheduler - Looper singletonInstance = Looper.getInstance(); - - // instance should never be null - assertNotNull(singletonInstance); - - // create a new command scheduler - Looper differentScheduler = new Looper(new Time()); - - // new command scheduler must be different than singleton instance - assertNotEquals(differentScheduler, singletonInstance); - } - @Test public void testScheduleSameCommandMultipleTimes() { Looper looper = new Looper(new Time()); diff --git a/test/org/rocketproplab/marginalstability/flightcomputer/subsystems/TestPTSubsystem.java b/test/org/rocketproplab/marginalstability/flightcomputer/subsystems/TestPTSubsystem.java index 1efc57f..97f8949 100644 --- a/test/org/rocketproplab/marginalstability/flightcomputer/subsystems/TestPTSubsystem.java +++ b/test/org/rocketproplab/marginalstability/flightcomputer/subsystems/TestPTSubsystem.java @@ -30,7 +30,7 @@ public class TestPTSubsystem { @Test(expected = NullPointerException.class) public void nullADCInDefaultInstance() { - PTSubsystem ptSubsystem = PTSubsystem.getInstance(); + PTSubsystem ptSubsystem = new PTSubsystem(null); ptSubsystem.getPTValue(PTSubsystem.ChannelIndex.CH0); } diff --git a/test/org/rocketproplab/marginalstability/flightcomputer/subsystems/TestSCMCommandSubsystem.java b/test/org/rocketproplab/marginalstability/flightcomputer/subsystems/TestSCMCommandSubsystem.java index 4bbe9f5..3ed4f2a 100644 --- a/test/org/rocketproplab/marginalstability/flightcomputer/subsystems/TestSCMCommandSubsystem.java +++ b/test/org/rocketproplab/marginalstability/flightcomputer/subsystems/TestSCMCommandSubsystem.java @@ -109,5 +109,6 @@ public void scheduleCommandWithFramedSCM() { looper.tick(); assertTrue(factory.getCommandByFramedSCM(framedSCMData).isDone()); +// fail(); } } \ No newline at end of file From e4c74d104a0492380be13a76aab56d8cb40da2ca Mon Sep 17 00:00:00 2001 From: Chi Chow Date: Sat, 6 Mar 2021 13:27:35 -0800 Subject: [PATCH 2/7] FlightComputer and sensors documentation --- .../flightcomputer/FlightComputer.java | 83 +++++++++++++++++-- .../flightcomputer/SensorProvider.java | 28 ++++++- 2 files changed, 101 insertions(+), 10 deletions(-) diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java b/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java index 9bfd0aa..b4fe3e5 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java @@ -10,8 +10,20 @@ import java.util.logging.Logger; public class FlightComputer { + /** + * CLI argument names and descriptions + */ + private static final String REAL_SENSORS = "real-sensors", + REAL_SENSORS_DESC = "use real sensors"; + private static FlightComputer instance; + /** + * Creates a FlightComputer instance, which can only be created once. + * + * @param args arguments to configure FightComputer settings + * @return new FlightComputer instance + */ public static FlightComputer create(String[] args) { if (instance != null) { throw new RuntimeException("FlightComputer has already been created."); @@ -20,37 +32,68 @@ public static FlightComputer create(String[] args) { return instance; } + /** + * Convenient method to create a FlightComputer instance without any arguments. + * + * @return new FlightComputer instance + */ public static FlightComputer create() { return create(new String[0]); } + /** + * Time used by all objects created in the FC. + */ private final Time time; + + /** + * Looper used by objects created in the FC, e.g. subsystems. + */ private final Looper looper; private PacketRouter packetRouter = new PacketRouter(); private Telemetry telemetry = new Telemetry(Logger.getLogger("Telemetry"), packetRouter); + + /** + * Providers to provide singleton objects to higher level management objects. + */ private SensorProvider sensorProvider; - // TODO: all the arguments + /** + * Private FlightComputer constructor to avoid multiple initializations. + * + * @param args arguments to configure FlightComputer settings + */ private FlightComputer(String[] args) { this.time = new Time(); this.looper = new Looper(this.time); initWithArgs(args); } + /** + * Initialize input/output devices and other settings based on arguments. + * + * @param args arguments for configuration + */ private void initWithArgs(String[] args) { - // TODO: initialize all input/output devices based on arguments CommandLine cmd = parseArgs(args); // use real/fake sensors - boolean useRealSensors = cmd.hasOption("real-sensors"); + boolean useRealSensors = cmd.hasOption(REAL_SENSORS); sensorProvider = SensorProvider.create(useRealSensors); } + /** + * Defines command line options and possible arguments. + * Also prints help and exits if invalid arguments are detected. + * + * @param args arguments to parse + * @return command line options for configuration + */ private CommandLine parseArgs(String[] args) { Options options = new Options(); - Option sensorType = new Option(null, "real-sensors", false, "use real sensors"); + Option sensorType = new Option(null, REAL_SENSORS, false, REAL_SENSORS_DESC); options.addOption(sensorType); CommandLineParser parser = new DefaultParser(); @@ -65,13 +108,20 @@ private CommandLine parseArgs(String[] args) { return null; } + /** + * Allows subsystems to register events and callbacks with the looper. + * + * @param subsystem subsystem to register + */ public void registerSubsystem(Subsystem subsystem) { subsystem.prepare(this.looper); } + /** + * After all input/output devices and settings are initialized, higher level objects can be created. + * Use objects provided by the providers, and simply inject all objects needed to create any higher level object. + */ public void initHighLevelObjects() { - // TODO: after all input/output devices are initialized, create higher level objects using these basic devices - // TODO: use local variables; simply inject all the objects needed to create any higher level object // PacketRouter PacketRouter packetRouter = new PacketRouter(); @@ -111,23 +161,44 @@ public void tick() { }); } + /** + * Builder class to create FlightComputer objects with more customization. + */ public static class Builder { private Telemetry telemetry; private final FlightComputer fc; + /** + * Creates a new Builder instance, which can be used to customize the FC. + * + * @param args arguments to configure FlightComputer settings. + */ public Builder(String[] args) { fc = FlightComputer.create(args); } + /** + * Convenient method to create a Builder instance without any arguments. + */ public Builder() { this(new String[0]); } + /** + * Set custom telemetry. + * + * @param telemetry customized telemetry + * @return this Builder + */ public Builder withTelemetry(Telemetry telemetry) { this.telemetry = telemetry; return this; } + /** + * Customizations set programmatically in the Builder will override defaults and arguments. + * @return customized FlightComputer + */ public FlightComputer build() { if (telemetry != null) fc.telemetry = this.telemetry; return fc; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/SensorProvider.java b/src/org/rocketproplab/marginalstability/flightcomputer/SensorProvider.java index 4bdc218..0fdc65f 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/SensorProvider.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/SensorProvider.java @@ -1,11 +1,24 @@ package org.rocketproplab.marginalstability.flightcomputer; +import org.rocketproplab.marginalstability.flightcomputer.hal.LPS22HD; + +/** + * A provider to provide singleton sensor instances. + * + * @author Chi Chow + */ public abstract class SensorProvider { - abstract void getSensor(); + abstract LPS22HD getPressureSensor(); private static SensorProvider instance; + /** + * Create singleton SensorProvider. + * + * @param useRealSensors whether to use real sensors or simulators + * @return new SensorProvider instance + */ public static SensorProvider create(boolean useRealSensors) { if (instance != null) { throw new RuntimeException("SensorProvider has already been created."); @@ -18,18 +31,25 @@ public static SensorProvider create(boolean useRealSensors) { return instance; } - // TODO: add all necessary sensors + /** + * SensorProvider that returns simulators + */ private static class SimulatorProvider extends SensorProvider { @Override - public void getSensor() { + public LPS22HD getPressureSensor() { // TODO: implement methods to get different simulators + throw new RuntimeException("Not implemented!"); } } + /** + * SensorProvider that returns real sensors + */ private static class RealSensorProvider extends SensorProvider { @Override - public void getSensor() { + public LPS22HD getPressureSensor() { // TODO: implement methods to get different real sensors + throw new RuntimeException("Not implemented!"); } } } From 38031166d4a91982247185623f72523daac4f251 Mon Sep 17 00:00:00 2001 From: Chi Chow Date: Sat, 6 Mar 2021 13:52:01 -0800 Subject: [PATCH 3/7] FlightComputer and SensorProvider tests --- .../flightcomputer/FlightComputer.java | 2 +- .../flightcomputer/FlightComputerTest.java | 13 ++++++-- .../flightcomputer/SensorProviderTest.java | 30 +++++++++++++++++++ 3 files changed, 41 insertions(+), 4 deletions(-) create mode 100644 test/org/rocketproplab/marginalstability/flightcomputer/SensorProviderTest.java diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java b/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java index b4fe3e5..2b0b502 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java @@ -90,7 +90,7 @@ private void initWithArgs(String[] args) { * @param args arguments to parse * @return command line options for configuration */ - private CommandLine parseArgs(String[] args) { + public CommandLine parseArgs(String[] args) { Options options = new Options(); Option sensorType = new Option(null, REAL_SENSORS, false, REAL_SENSORS_DESC); diff --git a/test/org/rocketproplab/marginalstability/flightcomputer/FlightComputerTest.java b/test/org/rocketproplab/marginalstability/flightcomputer/FlightComputerTest.java index f877781..cb25514 100644 --- a/test/org/rocketproplab/marginalstability/flightcomputer/FlightComputerTest.java +++ b/test/org/rocketproplab/marginalstability/flightcomputer/FlightComputerTest.java @@ -1,8 +1,5 @@ package org.rocketproplab.marginalstability.flightcomputer; -import static org.junit.Assert.assertEquals; -import static org.junit.Assert.assertTrue; - import java.lang.reflect.Field; import java.util.ArrayList; import java.util.logging.Logger; @@ -14,6 +11,8 @@ import org.rocketproplab.marginalstability.flightcomputer.subsystems.Subsystem; import org.rocketproplab.marginalstability.flightcomputer.subsystems.Telemetry; +import static org.junit.Assert.*; + public class FlightComputerTest { private Telemetry telemetry; private ArrayList errorList; @@ -52,6 +51,7 @@ public void reportError(Errors error) { @After public void afterEach() throws Exception { + // use reflection to reset singleton fields Field fcInstance = FlightComputer.class.getDeclaredField("instance"); fcInstance.setAccessible(true); fcInstance.set(null, null); @@ -129,4 +129,11 @@ public void errorAllowContinuedExecutionInSameTick() { flightComputer.tick(); assertTrue(mockSubsystem2.hasUpdateCalled); } + + @Test(expected = Test.None.class) + public void runOnGoodArguments() { + FlightComputer flightComputer = new FlightComputer.Builder(new String[]{"--real-sensors"}) + .withTelemetry(telemetry) + .build(); + } } diff --git a/test/org/rocketproplab/marginalstability/flightcomputer/SensorProviderTest.java b/test/org/rocketproplab/marginalstability/flightcomputer/SensorProviderTest.java new file mode 100644 index 0000000..8e9499d --- /dev/null +++ b/test/org/rocketproplab/marginalstability/flightcomputer/SensorProviderTest.java @@ -0,0 +1,30 @@ +package org.rocketproplab.marginalstability.flightcomputer; + +import org.junit.After; +import org.junit.Test; + +import java.lang.reflect.Field; + + +public class SensorProviderTest { + @After + public void afterEach() throws Exception { + Field sensorInstance = SensorProvider.class.getDeclaredField("instance"); + sensorInstance.setAccessible(true); + sensorInstance.set(null, null); + } + + @Test(expected = RuntimeException.class) + public void switchToRealSensors() { + // TODO: replace with real sensor checks when RealSensorProvider is implemented + SensorProvider sensorProvider = SensorProvider.create(true); + sensorProvider.getPressureSensor(); + } + + @Test(expected = RuntimeException.class) + public void switchToSimulators() { + // TODO: replace with simulator checks when SimulatorProvider is implemented + SensorProvider sensorProvider = SensorProvider.create(true); + sensorProvider.getPressureSensor(); + } +} From 39308401f371e8158c6bf27e0c809ffc68de458b Mon Sep 17 00:00:00 2001 From: Chi Chow Date: Sat, 6 Mar 2021 19:03:42 -0800 Subject: [PATCH 4/7] Remove commons-cli library for parsing command line args --- build.xml | 1 - lib/commons-cli-1.4.jar | Bin 53820 -> 0 bytes .../flightcomputer/FlightComputer.java | 101 ++++--- .../flightcomputer/FlightComputerTest.java | 272 ++++++++++-------- 4 files changed, 218 insertions(+), 156 deletions(-) delete mode 100644 lib/commons-cli-1.4.jar diff --git a/build.xml b/build.xml index 9fcb2b3..1af994b 100644 --- a/build.xml +++ b/build.xml @@ -11,7 +11,6 @@ - diff --git a/lib/commons-cli-1.4.jar b/lib/commons-cli-1.4.jar deleted file mode 100644 index 22deb3089e2f79a983406bd13a75a3e6238afdcf..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 53820 zcmagF1C%A(vNl?_ZQHhO+qUg4+qP>}RhRARvTfT&cc}}n_dWMNcklPVb6<{?W8@ku z=E|87-wb>+Qb`sR3WiG~jy!JGQP$dJoZNE3J|1&7F)gGOTTNYh)IwEqA>PQbkmt&n?CFmH!n@QM zNT}Gj9BE_E>2ou-e8$mc^w6Mh59Yzgk0(2YtGSL$u;F+mVe59W9zjxSJsiyk!quPNzn6L|&Ll`Al0BDX)^_Pxs&Z#{jsee4^hQP%>W zwoFyzYRekjNUDS`TFhZU4#oGIRRn}f2e+goz-3sn6(-Va<6e3*F;a<0MqqRmaTdnkPoxYawhCPYXz@>WHD2_PWFeL}K>{4pzMi z;%8YTfoJx!oao2nDP>#=45e3;pE9Z7#jMG!r@_G->Ex)RW+wTm)2T^l!Myr9*ld5C zVvNQ0Te!3})~yR$m``X}zgYp&n5D%U%N$F_1`5#|9o8&~ZQEvc*MA`nR(WKPe^H7r zsD`DZw=sM9_|k0j9(Os%xj}%iju%@gio>so0$%I=Surx4Tm^1I$yBKdeRcK^%$YPF|YW5KYl~| z?XtIQUa|TKq$CRo^><(@{TF0`pn(1hvVTze?*sbJ)xRP8KVqzZko|9&KNnzsPDd9@ z#{Vn<``;4APR6EI=KqTz>OTcd9qsKM9bEsH0hs^a15E9#|2F8arT9ng-v{EKtA9V2 zy|IV6!~Y_T`+p1n_q6E$_q$O3?*squKl#gRu>6@SQ>pKr-Jdxc(EY!>hMcshxPq!U zgPWJzwvMjr<_LPgY~7j*K-C%okf*!Jr5H<2X@@UEI^oWm#YYze-oYLy?g6ZPRd?HQ z1y4rawb*9EQX_3Lo6nzd>vu{Q`ZBazoN=rW<=Ls0r)tRecqEwWzTtLI^;#wJF7Hv& z40*p?rMb)3VZ{meahbvR{QE<1fy33bjS+WeqURk1bH{M^qZ=b;InB$psZ(c%(NV+p z{^>-a+t3j6;O6b==H%i7_r0^Qyf*#vch@oE?L98a-LaltrH-c$(DBwgY~A!!ffdD; z0!N%x+SL#cC4Q=XUZOs^%%Xa?%+g5oe5HuivaV_zd4Rr`@{3*Bw$U$(q1!OG;sJVf zat_D_4RY95lp|eM2hRguW1E-4eQwqGnu~DLo>+e6YPOI5i)#lYi(P73A#$yXh>*m? zdRC3EoTo>ZnHnq)7o__06&bBH`*UK)2sz-Ew77PPc}kgBe1gPgO_6jmaw}kqK+7I1 zP(&~A7ME^zEVp_9b!ane)(e_VFjU>#)3vR}3$^yXzZ3@et3oD09;QRRiQF%Z4x>PVyL z(aDfAowrVl_=#716!LblH`(koecd*eBGIKt7}X_V^PGTuxf8$TX*R- zTxJA3Ay`}pZr{Zjs8fnMgA`a2?s5>a418^_)a*|=hOgmRR%c+_dqWS8EMNRj(Hy=r z8!>H-qx*gE3duPQUNx|v4lS-|cW9QmU`OdGO1gs%Q41H6BcBuLMYKQaK-aABisE6GfRU6gOl^&d#Nzhgf0nS-pubp$PYhO zHs=>^_tGWI@0^=nF+&F`FB*C8Jon-oiry<~toKJM!vXHSNzk;`*6yIiyf{zSkHU=8R1rwRsu_)07nM}{SbCQ6uUsx3 zRrwIO)D;(gAdQ|pt_)f|^^)HA+Gs7y;6JMVT2Lu1)IYEuS zZ7|J}L^#=abB^ZagZemzjv7MDA5@nUxOKZ7`08#C*$Yw}(^}!;Rjn`%YE;om{Ej89 z%d$#bK@BO*+Bfz&4#afDD7t)n@>JcIImR;ETU+mzlx~n@SqMZ2)JU%olcTYSYeQFW z75Np5*U>*nI}ul(T(l?;A|pBM>NeU^R(Yt_5AlWZ94xW|S8ofb49r@4JX&oGf2&X@ zLzHW2OW7Ejx>Dkea_vLwHM2&nHVwCD%*YG{Jga5iq0f18UOBBCUw1%OkyH@rplqR( zAOsm;34aeI>D4)4i>&z z1x$xJfLK^p`GnIUVcCg!|E{zcnz*|Q^=LOf{y&UwysdY+&mS&jbZ)^<_*e*(IT}WGVo_$l9-0#WISdlsB^?+ z6@A4lndA4|U6X`bs1^r?boMvFClQ217*ie|^Eq7&VF&V0IigeC=NPqmlD5{74oov9 zJ_&1yBgJ=YK1OlUXNM(Ff)-_61`wl$Lcaqr$%+@eK4p2M;XKEdlw20>Q>1wG_jwdm zaAvt-KoS;}s+EL4AXI|%IFr#kNZr}J4^8|wOe={2sTHOdt{<}ocA;Le8Vja3D~2~s zG5n<2ofZ*#Jzg2gNeR+{wZFtti=YF{n$(U1WK0>4xFqO{vw=i$(}H1Nkw`m9hnPhQ zrbdJM$;BS$EULX1^2!JQ;wr5BC?y`rT6YO^`7i)<>-&Brln(c=xNYLkJUlfOf36#{ z-f|Y4r!6zzhdl~q>#LIbZ>L4^!$`qT!k$=^Tl}4NzM<_{3sk7O&-B=$4Y}tt=B-WY zpk!LeUal(xs-8eN_=F6bTn?Ea#eHzH%MEw)`b2aZFy5+3NzgF!#AP{xxCulvXRdIS zFBzG*C6faSGJKLiU7Iex3^Yw8Z8^g7HC6o)_lQmXK%*`-;Lv|5Ly`-=eNqjci2 zH$T1*v_55Se{zRB`kh*D!*FGq`JT^u>f|$oWwjciISew?8PK{m(VPb3U1G#p4#KJH z9204S5=!>mZ+uVVNW*fAnRof4Al-AWqYwfT_PQ}8z{SfJ$queL zkyE8$%RONNl&CPRy`Yjumc;=uqqyp2oi=u$_IYA*Ko~b)!Mq8~ad3FySVrMZ<6?_6 zXIYt$Yxi8AYfOsUy1DGi7c`Nr3-$TXee-*?uHZ2Dr(^0PNx2d$JjNZCSbjLyc^xb! z%7bO&@6zb;)wq`9Vr9(n6sB2gm3ZzT zs1bg$)A2u`_YBw@gg7y8c`J(Ja{&a#B`T)BWl@@7leu=e@S4W#GSlK3^6~V^0SUYW zh%T8I_7CTe-xjmIv&C&JfCou3J2m#7l2+@c0%H!Y;g>Vw_5pB<9BuV6aY_ie z-_Z=gjB(5u?s1vB_JFCim|Mkk&(5jt5CudlNL3TQPZ8w@a^ehquW9zHbKCNL=?WAC zMS}o2K*C@p(8m^;38MD&APo(F#h1)d9%g3~OrxZ>)NO1BT8kWGUxEY1KI>9D)Iy;EJ+vGHJU9Ks1(_zf|~rqjJJ2m1!5d>HE14@^1L{m0eK9txx@rGo)&wy`Z^VTjQiHE%vhJhqtlf8fPOJx z%eS~4q$1MeR<4A|XAI*>;9VgnH{JjNK`egCW6%hee)Bj$+=p189<6Ri-prk|yB9f8 z58j?nnCIpCH7gk!l5Vez5Xc~_es|)d2&l;66#UN-=ayq$*Xn}?jl-II=Mvc!JkpWa z_qdyGR#v@fN(ju^ohZnfyS2Fez-=7WYxk5{1VIsH4u3{xnaErtv0>ZFoOu`aWO;s% zs4XRAzDEkE9T20tlc&A7w2;1jF0tSMzQ{+G115b9#B2s>+pjkWvp`M}ua5qhQ@9rg z1`P5Qux1e0yW<@0&GKb7R+?VmOota!XL=jyiByS~R>P??B`xQzQ;PAxDMhrS7HJU` z!{=LGu6Jgn_-BC_QXFw+0R`fw61XJ{czvr?wAEFo1|cQ8m~Cx$V-E#&^I>fCKw|ta ztC$a(&v%?E=7hJ&d$*sgm}sBu(dTT$b2gybrbY0C18OBwd44tOs@%ZfAjx^c-$L3_ zVMtt`E*+bo{MfSYmT!=Pqm-6C{k19iF)=j(zg7JVi6-ZX-Vrl`JKb$m@#kP8!3tlL z5qI&;%z3+VhV`5w`yNNVkY(igX@R(aVR0ic)!v&6QXtUEEx8?tCK4N5HpSVR5Qn++ zY8=#j%)=a{LMRY0XN0(M^hhCQ>ow#Y1wJMjD=5J7k&#z}5>{x2FoB3)v6qD6Dg;x)=se{7{oYJ=@9yct z09Ez%UxdluYw~~b9Dh~oe=#9KlRdzHQ6S2YKtL3KO8&o?kpJd6{ttce7f&GR;I3rs z;%e@~U}|UV>Kdlb?}RIk_Nl>hPIhbpjh%%Tb@$U|(#UH*PMp(GWZYE;Gm&h+nCdxx%t7^Hb%rz$A#9YQYfJ~D+O4Ta333lHURQJ?3 z-tZ-II`}bOeq=o9F-`rTtvceySN_@!ws^x<$J1>E)jM9uxJ+lP@$&sVJC(#%yOk+h z&Fz}opOd0w-<+)Caa*M^-t=nB2g^@X6vu+O+{8c>!F7q7duPBM-5cJ~RCu^J9Jjr8 zAD_-zYb2VDlfBv`E|YsLA>6Y;q3wYLn%RvI#QGZYbvs)b(26q7?@y1>>aA?1;>M5v zyCV%{oh+QBmI-gaHmlf;sCB$OmOnu1A;%3z`52`!`*eh2|J3t4xgxm#^^8q9Amyu0 z3dL;PNmoQw-Ztf1vsXmEAxj2{b;Pz#|F8IBT=^3hdsVXJ>yK#LfT^BUM#8B2o*WA) z3dffH`Z&aLH`MIY-2 zQ7%`P)0>bf^5hF1gz+VHBjn+cxaOkyFNYzX#KE5mO}879wpHS97*LkvXDNkGm;*y= zr4Vp*kNjV*6s-$Bg@MIHAqNp71tg{-3howG#cFp+zX&?V4ajU5kzY;4+{38~#0VKk z!)Sl5I;CB)^&Dtd8xyph>pK!73g5o6`V1MGfD112exhH#;N!l;AbmUZe-8o44{BnP zsRrG=!kVbg7zv1NfNj6jfAUTJ#UW4*qd*dh8hTlj6-~t(r&?NE*nI;)JGz3Kk@23Z z#ypkcb6JU4tw>?Y5lX&LFKl4`nZg(t1jxnl4QW0dO{DC6EERk0m_yrTy8FX7LPGuB zbNth%Y-8l)m;do4=YP&WB;bGYDN^QkP7;nT_Qq~*<}PH+|MDzxvBEF|Oi1EiRxK?s z7>au$dN@814QC>HUcp!q8_5*pl>{?kkatQZLutI0nP1pm-KUqIK#8V!r18uorINnx z(J?Zt#;xYt7%S|JmuodP-YKEyBUJYO<`ev$n7;8zDCsL{BCRU=T2z~CD_%uzl-;A#=###3@eJMrWXAt)!wA|7f=x(7H8ewa4qGqWuDXDI|ykT~it1%BGsYtdWMs> zPdE(vF-TT)@b_SxK{G0lh%R~L(D+;aUf+nIZBwkxyB?+kgQX(}O|#wJ&->-K&k>8U z*SyF;xJP)wdikCGm0l+LAKL(sMHhTmN{DLYpMXQ|d7i=Md9N8mr^VxZ`x}X%!*$y< z3Q>zeN9gdV@WZHU2VX_7gqM8TER(@DDO5^xG|F+g=G#!XU&{W3T*gvUZ6IBn7zWL+ z3n)L*sO*u$x8k!RQkm$mMyE)IG3=19$(l0aCK?v2x&k=shtf$~G9;pOlU&$x2hawu z3KkqZ@!QBjUVY9JMNgrlKBo|W_Md7kv(uT12UYIFT;SBoxT1(dJPNK3*K-vg5F?5> zgJp0W8Mt&WA{)dQzd9OvQ>9Ib!P0!VhKR|*{$Mm*A z9rVJJpA+RJ5|roOU|zS5UZE~1X4S0u)xR^khTUkBt1pu7!7aNp1r)Z(1v<2YH-i#! z#FOE~Pwo)4P*srRvmn`-c}}c*Nh~ReC`0&ab4>~pp+8ay(ypM#$&|26n)fqA!KYf+ zgJ$1vVLaB9NcSUfpbNB9FLx`}x*3?LsOTG;#QBf^itvAj+&{r6*+}z)>dy`y!yitb z_CJGB@xP!)CgN^wXZC->e4e_j>!JqQrx|zpbtD;>lqf-*v^SSbKSH7qG<3q9713~6 z5%5Ae-7Z&gqZwIF(PC|vqo@9yeb-s>6w(4U>$O~$5rFjr__}l3lSiMG|5=BNBt7a( zO9o)3L~T!I)i+}ixa>zJUWGq!7U7-*#v)1mhwTRPoG=w+3zeagnR24Ld& zbeI^44Su)F)L#QTx~AWFAJMf~rQ7#tc%FaFOn)ibG&PfXOSWB1nW~fIq$F}#Z&=uC z4Ak0Hy)}?OaGa(_*7)`}ucH?oXB#wQC9E*J*-CrL3p`OCwy39=(O6yr)J+)93)<{Y zV7_7l@U)z^TomdqMrbCn70M3Q3}))5^n}5BR!5U&e!g}=pr(N3AfRGq(afk42~W;Q zj#{lBpT#T!H1AR^M;MHtAsYCH3hNQ-`8n{EAYMgK<-oB5o-D3f4r>4e`Odgy+`Z<#j;SeAp zC0~SMuB-zIh1wTWNd zfRTGmmXSHmS9U>k89fAF+r4uQ`O9DhFzAS5n9@8Q21YA)7n@))R$=V}2)oqH>LrJX zZsDC+hvYHhL-VJRsVly>PmhN)SDN5Zs!y4y44jQjcu$&`JEO1CPSvvCl68*H;i3-faN~G(;U4&QqV})kY0NHU= zdh+!A)t=%X2?7%wzdThFk`*;dk`(M?XKgN(TGnuqb#7bPhem%$W^nXE9QOt$q~HsI zBw8Y6Ad--u&ePADMEJpcJXm+jeEr4|euJStwN(+xmHPAjPHK8Dwc5_g2TfKJht%m!8Gow$>;9mP-M zQ|_)J4qX6IGD7CuD(Qh+`n5PN)!1-?D*m^)7km4mvoHnZ*bVZ!ru`TW`=^d7ZNd6# z^&9F^j)Mf>zGSr(KP%#V6ZerL2r=z+;<*ScthNL6tEI}TEN&XB+k@9w(|*?v|EAPk z5zlX}9ltUCskb-wGL#MsNeN)9YIhstKS_xyyQnL3#&EQ`mQ&e|Wo2ym6$jQn#Y8@7 ziRjkRJa8=i;%yH~K}$A3sS+AevX@N%5Q;lFJ-jOokL8ky4mJxs9`^N~%8kTdaSX47 zowA?sURd^CXVM3BCw_?BML24%h;tp@yKkU-2)U2_r=tDmR(r5TdunWV;@t!w3IVv# ze1sR;Q75k`3=x5-^L&hSNmyz3u z;+8nH*^(r}72BUtx}_rV-~_c;I~aJfWUwY%l8+HqAL5p%$o~HvuAQ#4KV&l>@joNehbP!Uy}H2|U=fLZhgMQB&7;o;a0&l1{;|8hh0m$1)prD`KQMof`E`ohtifotEAf!QYTtvmLIi zzsJJGvI%c?d{1Vc^F}>qr;aMW41Cb~Xu45`d~%oWc8K`6w4>a;2ocNKwy?#*OgmyC zo+0Oh5JT^T{UR+15%x*jc|#KpO!@ru1}TFp`YA)2f2s2Qc7rPDw`AWM{P7IY0QG#| z0^RE&h*)sA|Hvn`1nKnxf@pZ;ZwPZR`2y4BL^#`vGqif=9{vV_Snln`6zX^Y-1|nK zzg@GxDJ*uE7=CN@;((OLh28i3@(c&*%@G*keJ=%c`tn>I{)j`tu7^}Ho{c>zb;Zo8 zO`EpWbBFP@Y=`&QwoFji?4b+;Kw!ZMW-gznV#EusEnss5@ z&3z6>7RQ6Z6vmFBx3gcHBKAnjZEi+uyy0d?&4SLRG;Y2f8(%&y0oB}%%~%{d&+mLk zDlkZlhWn)c9Q*MpH;vhJrV#+tyE?Ja+)*~9CdJLp_f!H93~0bu;&2WKiTW9@R<`}!St~cK^(d}Stem34lGEnNtV%x zD;?@B!kq>B+>eZ%-$M=0JE!ZvJj2oL3XBs*=(8*#Tg&K{VugO*zsI?0iaI}Y<>%iJ zY1({)$s^ShL|oB!s3GH5I5k%0#!9wEzdo1$!v<_euY_D=?PEpj2KBA1Qq`Rkpw_F# z6N12&+Zy^Q^pJLlg2b^h*w1K3Wo8xO_xGzYu-Z5@aTRrbSEIaLZ2-cWQ%u~lsf>wr-)d%K=Gjy1|%!sF1dfzRK4P6A-lTX4qSU3G>M#R(`pRDM?) zH022hrN$Q=IRuf{jMW)cybFyt9&&p}qhx!R8=bu;%iH7Q{mo&8@~nzw@>Ov1!IErv z<`o_l5QWN zeRTKE(+4f%M0Hd!5!EWc%We@mPa96=u(zH@NYl$utJgEs{T=md!5LCPsb&CjY$i`O z`-^@Lnh;6L=h#5)sP<7q$R~+{79Bs;QFH}=CJIJp{oH_v@Ph32;vhuC!X}fvT)4;f z?kVgT2TyvraXQwxoN6Mxn4?8>y~BK}S)~N9xa3GcYGA1HiAJl>tom*0WE1P!etVLU z4BhR)!v(jN#^h! zt?J~@TLUhrY_%nwPI|WxD9eP>T0Q{bX z5tPttk7-2D?MIrP(&cZqjPLZ*G*Ix+iFT(rl90@V@Z(960y$U6eUlrEL>0=LNesgu zMjgceTD1ZrQwUcc1Bx#^`xD`o%x05^LYY&nO>Lnx-$D0mc)XRXE_!qZnJPa z(UU}G%QmV9HU#aHVWUaX2a7_m_~_Bz?72~JLNot*z~TIh01lbPce`dm-4{D1JnI__ zJP2kzm!cjqXLk?LyAJrd+Fp$r?ubEJxPT17V)zEhz@|WyZ8(g{-Zvzmwh|QVRn3hH zAFKg^s|++^yuvI=5kj>&QLt;(xmEYnFahy7Pnk0gOIz);Hf1(~j3HWSIB^r@;EwlS zWO3R1QogDsw;(v??lR*yMPggD<10LE?Pk9iwD~2>@c2x1>T;QD5^57Vn?04YY0ug! z6I&*C&z>82a6ZTpmd4KrB-jc1MREsGax>!X+=TQbv;X}`C0!u*AvcP(wegfVN{jdKwc=aw?~ElmPQo+j2jsInf$ zhH924@k3tCp!t0aVh$Od$}d6MGdRshgYKv1cTvHX0n*EIsmv|cN(x3LgI98;Hw0hC z^+kP{DFkwO@kw@l66_(tus{jxD`u@f!(O2tgHGVUY-u*XrQQ$;RwnPIO!*EK6KH1V zq_q9hg9aJeM6S}TTk1#kYe=##`;q`f_P`}rWK9}A^xScprQRdj2G|>~8ftfuD0{zD zM%}!micLY_&d!;uo6FmB#>Tp)qXB^l@#}_ATr=|I5K41o*%`9&7ELxYold=BwNpX> zqBtkXu)IKL5}sO;n)0sPqUf+_&)9gq>3HIBrCPcjhYQUjq#7V2!|W|!sbXuQ*|vA_ z&YO_N0o4SZy9YqjFsbjE-WA1vp<=J8#=fWq(}VVlLS$PlQ0K6CrM==d6MtEgAg!|v zD--k=Ry^%e4NTgx#<;$Sb#;l@xQQdMSq-dqRea4}9TK>=jBssNtU|I{GpEY)n{+i! zbp33K7X7KaEkJ$=b9Lbj-i1Gk^CT)mg)o8%8OfBakt-bvcKU#cA)Ub*~v55D@c!PP>%;i+*zWSNZ#o>Nia@ z&QVnz?Q6T{T6Z#p9|nA*e+?_7_BWMbv7PBcTF`LgerFsrlHcXd2IRJ_wIMRn52WEb zF;rk9>v7t#|F>9Yow2Brq?3~UZ$g)^}#6rAh&8cJm3S{tnA^HLEY^)+q8 zxPLQsp;_)Xg0DoDUs;q6D{_AFwj7s`Qv9w{S`uS7)O!QU{~1)g={@}>p-5xQ@3_M2 zRo_+qP1&O7JW83|I&=N$4Zg$n={pD%fbomH8Ky_2e!nt{Ch-ZyZk17;! zW}w3QlRob|;6fiR?FK*$ks>G{Fg4ipwb+X^( z$YGeEqDD*(-y7SD`S(Up(HQ#f>kgd=Feu_Var=>D2|Q_fqc~|sZXjb zV22mS>jx%h_x#Xy?D@ozdGAXj<*kq!f>=2%>2tlgY!B^VEjPI~gCN2;UQyBRNoJzC zA|6Tn&M@v#7@)kghiJX@`^1qQ_mU%tEPK3EhjiQN4(z*0O*pCUFSKjMiKa(fMl^b< zE$oherx>qK6ARJaL99i6j30Mh$#v^FEkNaOf3y65~1?o`^2()|HgugStg|!GeK>b zOmpO%K)2)D)peEA=w;gE?CG<#1-o`9sYHNFYjWbsSlGKqDoi-*^QHx=@wTw=Gtih+ z8r_P_TQ#aX%gi%sORTY6%z>h#Ow572qekp0xw}kkN9Lgw#hZ7WSLTS)2(ZhxK2%VQ z&sYIt7*;PTtf}9maCkCR7o|HDmF$@4Wu1kD711kAB zMCC<@><5Le=>((695jnG>Yh8IDYXx=&>q%AZnZVCI6`0Zj!!FuOQw zGi%f(Yco~2OwMjuzfR6>rgWRk!&>1it&h#6mrNOAlW{cNcaeNiC(0y0pyq9>fzOa8 zc9S1}HM%2$-&m?I?yFr{+vLJ|`2j5(zZJ6P@O{hLBa@$-?gQlesPT;PxH*U3+ZYVR#z&Cl2FXgA3eI>)rWB{~Y`~~M z^M9k|lk@x7RZs_~DuZk97T;=u=1HTKAx0PtxQ2n8%<7z1M;D`)J8e8RT5Be^gAU^6*`ND4|2Fsc;plALE|8sRS0HVBO^Hq)&CQsT zX1Fhp4bRQwLlB%T&IQg2woBIl=DljTT#5HU;SD5%rPdWp!4Et{Up~H8UjpJXhrP9( zD14aLf?yjyBxKPR+))2Xg7uj|T?HmQhyXM0{Cb1YflXtr=mVwL&Ml9y-EW`9Y%>%c$Y+qqx*z;vU+^Wm#GrqmPcpC#H56fJU+}1~YH_wN_pqET& z@xjh#cc8>Ir)6!ecGi7;AR!Aj)>c?n18h#HxDXukB*l2_p!U$ZYbF)%mQ8TOf((eh zMqzfIlfNi$@uJ@}u{B4Dj z#VaG&2k|jR(U4Y{@G3R!RP5vGSMV!VbQlck6BH-#VKe7OpjD;fYE$S{)rZLJ@s8G4 zd~FZo^i*h;Q!S>Z6R-;~?O+$`QiYNLF``~>ByGOB)qp8ON#YV$?0RuDI$WB%WAaWWgCY#z`T!1V|V*vunEa8!1zk|Z<5{w z2o8zn84RBkTbjJY7){8z>vf^q9$^1UNdAtc|3TSbjqw3v!Z-eZ&{h5C{Oe7DfA{b! zD60KwjsL4J-hZke280+1Xs*kUd6cL0#vs@s1_^9?gAgfC!*~@LKjpKRs?+0JH?=M% z5}ZA58O(_fa`;2j5IIw<4q}8dqGaZ-#oGezcE@J06Cl0&SV}sQdkCf@(J`KwqKzW~ z{UX7~Z%+oBUkl@laSi;$Pv!eF!*zr-P0WVuJ;-0P|N9*OXZC+J3ZUcihuQ%H0hRt) zCshA=jffb#TATi(RX}-M22>cWI%9dr>Yz6yI)dsT(N)YzSSdJK2EoT>l%sXZEh0aD zw~Vqsgm6zX%FzNOnrtniO|9qqj=+x{K_IqzH3^JIaXPdHDXJ@)nk@oi-Ca9WmxvPs zl<)Lq$J&hDDNj0E;IVS8v5dj3^)xrXjb`}2N7m1?v>ry)-Vv6a<}k7GJiH5eLz1X` zhSeuE%ZuC-Bh5(5b5$a$=6dEGbb4?4pv(@yhTeE-&d_XI@7N&#tuL3N3|xEzgeKSL z8Bnzx-d6^BERSW~^zyRus3V_+EA_JQUrw5$?{+?2>hLyzKT0;*mNDjbQ_|@@HLDic zRY~2mUfbH|o)tJht>z16TYz&PL0^9TAT>50Q<^Y^$Nt>)G8bx~9|iFwusq1!^#Sdn za7!{J2F_p}Xh=pV3}rdRlRzcID4@`&UJrOJu_K$PNxh~$w1GQ>E)Yg%k9TGdk`~ax zP?hG4%QEw5y=8~=1O3Z_f49>=Etu_6ygT&Aa^-)l$nc*nDEjBE6=Mf8Ico>=zuPfS zQ5FGM7|H*b6Ap!zGqHZYA-}9XJ9G%9YK5o79ALQ+&Xp4e%9VOX(Jv7xL-WhO?n1w| zoHYQGJ`b#d3scm>`=`p#cn`>A; zI|q)lB-Rg?a}&RPFo>5u@;+U-J3R-H=T4OG)!0Fxc;DTt2h?$IMv}c7+0kWh8lf9p z*ioLWxDwz+mKP5|_PZv{(qfrU#UqF+CCM^_>2K=pD0AMvsFmNYne5UaLE^h(BS$@# zBTLdIj7pFIe_cIp=InBEca>cQ#E%^F#d9A{=J4h;9)b`j;@@6bU)prLsE%%&q_5B- zzgI<&Y?8R&OPLhbvZh3nL!{3cc{uw@X0$xW$(s0XMoY7@mQT5Hc(T>nU)dPufL1tP zN6XvCX|ko@ycK^W&3gfOS2D20=F%l4Rpxi3C^jOH^mwz!hQdoOP0!cTy_%Vmq%26P z$rm)W5muu3LsxBC^zg4|-NfD~Akrlldt3^a@Xoff#>70_N{c@l@KGl>iZ?Y!QItV! z5fY6XZ7s~aDN#YW2iI%jDuY_bm>lI5m;q6qY^X7-^0BA}nwEA%$m6j9tKDI6OnUu1 zIrt@U36h?W`OclAJ0|MFT26v0Ry~VxmV<*B+(e#|bg|zHS|sV(;Y8nUS4b=5#|2Q7 z2O?~7@pn+<-NmIU?S7d#lJyECM?3H0sj-GIFFbe;i`B)BNa`e4?n_ai9;CEAlT!;Kl?@ z7^twvc3Da~0g0EkLz^y;k|dq{4Ak~SmRjZP+_i;>au;te)hT(yoJ{5wZYJvSA2N_I zaV!**vrD0VOhmTTOG1gK0hZ>9T+6_im|5BJn`r=8Xjl!*^kI!TA4>gb>Do3|vdaMY zFz#Felo+SD#1EFMBB&S`u0dZ`X<35&oqYk0`h7|>|3itzvqVJU9h?qjXarl2h#+GVOI)PSe+EQnsU{jq z94=gtlUABJrqZ+tjI-wz>>l1*)kVdVj$UYGo4vWD-$BVU&;Xh8ID1+PTbHj}Qw6p$ zPKmPMCs`)i6i4;qX+UKt#9;xV0U@E&)u%4vS`V5mY+LhL(GK`=W$kWoiksMFP2wt` z_|lEV4EUY=xR)7dhb|kiq=yndvgxLt(X;EL?&@xk9RuAYu`zqJ(sK+7lBoo|tkMhJ zl;S!u0J_r4Xc`9|qZr;!(&QT27m)=f^JkDM(|dsqy|@G?CY9euqHwMkOR=4k?VwVi zMbtZ*V%=`MhlK!;uF@x+Xu{S+keC96*!uZNKx8{z{#6fz@v9+yxv~%YDhtaVS+$V} z1gDnR@0E#n+B6DUY0YnRX){>rWnF^lXQo06w6k=Hnd3HUvZjn5+3oK$Vk+1jYl}J2 z3ss5gM3CQM*D_`a5>V*ONv~VWtei5xe~6^H7WGKEG|wDaedpXjNx4Nz*?~NH#K6A^ z`AtowcnU5Op=(r*(B|9(>yf+}=b~U;v9#~e9`rq6W$xXr6~<$)h9>~-gU2t}vOyz) zH&e+bYGXQ;sBL*)fdW$=vXA>!oUUjz;nE3nOa2{tq{k@)0kIz#-yqo0>5-i#09MZ! z-*HgC`_%)V;P|+J{iz#pNVyk)e;Wu2N1OTzgbPj~+`qx%+o!RmgSSpVjot;^YfLDk@?75*Pi&b(ogb}dsz z+~a}YZEu?=0Oi*B<@v%1EuQ;M0RMIr60coywC9ByQlR3n+_@nB_dRiF^m8m74?$l9 z{!3(h!hxmRJ01I-e8vgYLr*Q{Xw zbV|1+p4YI-+q~{|mUuA|;THzI48OvFs@8*zO$_!Qn{G@_p*1T$;GYfRH&{lT5+#Jr`l0 zOU{bNy9T8TUh_uTS)%YQS^g`RR3xxl_KD zJg8-pw}9u7cr_QY?1`(?S682IvjCLw`KeTtEFnqKL0Jj|Nb6#MHddDGyd*>Dx5JWi z;Ryz`IEbTFP*Sw@xK1MyRRz}Kf{&f?886LNo>#|VZgbro-fH&2LeMaa$h>R?fD|J8 zvNyDY^!=*w?NJ)qxTyuU6axpezCzkX0gnu^D^s#V%DJ-Is@HosDHDb%z5JViDTqm5Fbl>yWx9c_y7P?OLOmmX0*Z;7 zr0u zx+FB&qv{L5^LJ6G?NmAbagFzBT69*`5L*6Da{G(2>Q1GPkpc?}hdgcTOmdgf*$QU6 zWeIrWTm0Bk9M*7?oW=%Y683u2=g|Xa9qpcmO6eUPk{4|r;Ff3Tm4yRKl}#NWn|@515-vH4RmJ|qj-jtZQ?Koq5|eJgqb7s!NY z?{{HvtUE$~3Wm%Gq?BqVzSFEBvfp7X^{duH#S4@2LHb%pIP3)}_J=(96;Q-Nte6jJ z@1urWAWuO{XXEh$b8t~}r(##hA;?{4f;=qzg2#wg(Q8A|}|MFO9`SiHsN!C}WTd z;zBFvz%F&rM_Iu_Ag@9k=wL3TOh|?TiCDncG$3YEU@Qhmk&J{=okU1JLB;B?IkJzO zhMGoA$dd(S4Tos-@D%tR<uJz$JEr&mCb zcR!+fisrCV!<-4CnYmaEJrM&TpQWtRMr>rWF%6PBO)q5c%yp)>6f?Itkv!c|o})pw z5K*2-$(|D%-uT;D-BAq4(dbTT0l83l^Ad`lRD5+D6${8S6PPRzIOJ>?E=dhbCf z?fbW83+BokK_^hJB<1DyfPCh=bc>37N}@jKgRP6tE-1C@ z+0Ysxas?|atgn0XsM_smUZMOyguP>w9D+H_afT#KNyWk!_zMjO3EX4q=;8P~`jdf3R zNtR*HnK;@j@%uabH7?5b1})D|CYEIp$*_o|n}^d*!D?k= zHLLR-0hQJ_U=L(%LwLwaO}7@CfT$N@9u-sRpy1d z1V0zL!)}iZO|^q}YX)5_&Y~|47wr*l`4a1OnT&DL{^slmVTY>z*sX#nqZ{5uHaNnh zRpF5FhNaJgJj__g`%wlqo~oW%S4;f+XLw91yYe6GQ^k&5>N1?-ad1rK`f$5(^EUmn z5It#Ne8rXlfHXFLMeG2|xcqCAa~*IK`iXi-tT=@M?!z#l`5LDho2F4M(BP9XI&!!mNFZaxnO(3>$y#~>C2z9EL ze(ocn)ly!_KjZwE>iA90!@?bmwG!?pp=BeXiwM%uPj#~~iW!RuiSK)lwwJys?$|C4 zbGZWrqEnbp6z5DUdT1!rMJTKVp;$(}Io_K|6d^1F{s~O8#`W5b5cCxz<0-p)5PHvi z4V;ra`emL%W{X0MdCZp%Y%TNJaRd-S3?oOrY3g^u(PPvTamWP_YF@#_Lq^d_3LPK9!f%m++6 zt>yY4-*LEPm$J7?C%g=7_0(*MXe4bu{Q2>YTKZM zOZyXYp6!yDZWY>Eh|n`Euu##czTs$*R1H0n8b&k?tQh($kCLcrXN-0~ERdI{;0fV2 z9!R#d@}^|=eoHY>v5sV+L1~$dQ?#2U2V1u^AAwGgX+2+uXA|46TVGPTem z?h5Mso_z|=dv*5Vb88VXhUTnag>HCB*H(T(Hi3(Tfer=dxo@&?L?Xl9yD9Yq^9Z@H%*4^H?~Rhq zG+Glh_h~w$!nSxjZz&XiQBH1iI<*Q4VW+c@X18Z7Zsc@e!4NLX8<(AFn`sr-ksmgw zkOS3m+@9d9;M&|{c0$Zh$DfzP=M1K4Q*oV&pDMF@gcopI0}gNQX$G&-h50UjHcTu9QdlCxXMD`raRJ{9Q6% z=Rs_!_gvR!ZAkTLsSvIG8^24};r1RmrL0G6wixS*ALE zQEiFdlM^v5e-CMYqlclUee0N)KdO-?nXDHnD$-Rnb^P2$Z%|r)3=_d6FJ^wgJ&xav zS#y9jyV6ne|6zOHq!`xKVeWfkvuNI>0yp}e2Jj8ZrVvD62{5MzD7}^J!mUy-_C)mQ z>pRep-|ki^=`~7>-d*pvx@15`-Z>H)R%&;XVk1iWXgMb92M|{D8Cy4E1;Cl4}{`l%w$~-m}#q zVw5*qA@#>tt@RtpE^Oub@d$ulBPlETe#*!h#F-+@N?*z8hxI@%TJj}x&-fq46#R96 z%Cd-v&qKmCdu4^BaLcO_Lxjq;yvZ}7YGf|SW8ZGOAQnlZ9gvJyeyU3dMwL&<>cNB} z`Oi?)XBACyfA|{=2LSaQ&M9hdn9!Y%b8hRH({|X^e!?MVK={QV6%B;@fL3LZ&N4+O z-OyEfwUCqJL0h%q@!i;8m$($m)P>@__2Kh#mEmN{s6QQB zcw2-yOu=0MKWtOL!huV=W=}{LC>!vazk&YcBmdJa{!bq{4c`oMf zGrhgvK!z~?VJ;qwOeJvJ^JSkQ7; zvm6Nv^;MUZSppn9WF!di)E{;B8%!;W#ZgpKlr8}x#AauB4t!>3;230-VKEYY$4S}T zV0>$dN!MjZ=oZvfy_&11bS#pb_yo?DEV&m_S{^(OXK`oU;gsb=Qn}$2EEfM&wz&m~ zK0$qR)A=N-AW6O-Pc2=FjCN%h6`-Hp=F6_{px7Hc;$Xgi)TOBfrfPAiW#gqjDw)!g zpeLl6EklZ2^ibb(omdze?)vSoe$@rzR3}M$AqVkY!GzA=IcECTK(^Tf@q*{4PbV@_ zo!v%1$5U5-)WsT4ZY*&nSjU@Ewupc}(IUE!bXj1?>u@sUB{?6n(@G+^psl-5QOUFb z&dwiXWbzk}^|7$%D|S}=$HSN&(6DL(#gH6nZ(up%(5CZHG_@dFI}Od1=gF&QTubG0 z)EW_#jXBfjTb9tLRqIuGw_Gj*Fw2EW)cfVfyUT&C>Zl{8pcO_?R*4(Bf~S=E8B{*v zJ~@4)C3v`9bq52(Gu(6sQsXB)#YSpQm*%4A;WS*k!dJldAKIE|Ok_yd)QCHCLCxN( zkG$Vs79XrHECz_#k zz#hqCk@SF58oxDsCsqGGJBl@n-3^1(9TA@5G3N=Um29ev*vxO3E*>rEo_}s!xJH^76QJ04>>v z4{nXZ>be=mS8Y@vaYdn1Vk>(_&%Pn@WybD=`7;CEYE$IIE7Y(sIf0dpOR_+fjaxy2 zqK4|0L3K{A+??Y=&};Pd&ZIag)P-rBa&O}9icwu`Lrvj`@SGk~)X#RDP~Q`Byhg@2 z#F9~?d!M0q-&s}$djt65!nOLcN+(%4aW!o~4U2ScO=!Y-nH>n$O^uWlHFx!hI5lMdGl)?BBogk&(y9Sqoa)yQ%@JISq$A-dP#dtO7?VP zGp9t?I>`ULsnIm8>omi@K+TG?hlN-*>63umHJRq`m-Zc(|BUr}=6W(<3vqHmdJ|zEk4g10Vl9i2w75rn}7kCG~eMu1yIKJ+`^{TQ;{C z{ltWsR8h&1U(ogZ82@~cFSn!0MgGOr-sEJ{2W6h!3aj9cQ^3m$=grE^Xa465NW>4> z3U7w=19OD*JsxQLyM6V`dt!ptvFR&){OiQ-eBjIBJg`^#>*PIquousweSNMEeV}VV z9`v)PQtS=PxIWm6kCJuLRs|td&W9Q2t{4M8qA>)_Z6Tr$qDSXlB8C~~;jmG^w<>xO;fU}Bl8~3Y=$|N9 zfwVmfX#eZshk+w74t>`H4B)q9M^CMAJ>qQ|X#X=Y5`Qw}ul1OnUA6u{b-^oLnGq{! zU3+3I_U;EB_ut*H3Q&VN!uxbt-E;tg&{ZDdnGNW#%3VFM0OCUk?hPmu3<+brCv8<2 z+t~|{r0Ho%PJIGMu#1yBU6@t|`0%GSP%>n;U|&(nnXrb%V8h+wOn)b0%!Q4N^2BHi zhedXqCnyrkY6IL@9N5Eb6j+Ej@$`}=YqowShWUDy>RTHr*ZKvMnr1hmZ7MBXD9fTH zZCXkjp9LdZNai)Cc2lkLp?&YzcF%*3q;zB9BgLi|((QQI)adc*q9;0|ShPQC^hT3F z(li$$*+!>E0|P{6?X$uNR(tX9Y2vh)*O^=DX=W*8_C2hHI-1biB%CG1{6$Zyo`;LA z4uYP|ni9n-2spLYR_ay66$5+#(+T6GN_>`J?@v>+d+`Oz(5A~$NV^L2w-l5jN_){_ zIdK_MTO<-i9HRGcmZ34|2splSEF^LKB?db5b&6j@7JkltGOTGgC?9*1Sd@Y!2P?;f zc_6-=BQk;sBN=9)alOnEkj`d~_RGRh>BDG^ei!i7Mez4#I~S3Pp*50Ot|~R z&+Frc5}GW?OzM?Ks9EN}TOpYzm#NZl-O@sa{|Jh;oi{|{G_!`4r&J`WP#X}h*JHi^ zKv0D(>+#a7jU_b(^7B{RZ|>{xEQcoH=hjFVehf4RkKAE@J2&JVW!gf8mw=rzS4}5c zgUVf_)}AZh2WHHfN8x50GG0ellI{PXUN3^#EKsZM*G9uJs(giU1q)ES)B2R_-%g*DKHz=Z?1}&-P6au@`$DyVh#ZcLXZ3hjfQk58uO090i zc_B;os#vCsU6hCN~qh;V9g^r-WG`{il zRIA9dkuP4&8vRKfhb~?*cSaqDbZlakD}8i$^f;5}iMycl*d~3TWoK_=tZZP}A&q9d z>~JTDatlNu4L_Cvdf?PzAW$S$8AUBO5CJWxZWSG=N@aQuL9t-EbCwl4I}}#e+j~qN zT;yJb-XpuPhHg!%Q59XSR&8`~P}3$}rrju!muXSW$*h5@y|zHXpI*N)ik7a(tX=uP?90(&4Ps(PwwW>_tZD7G3M=s}BM=}>sda2iU3-8^bZgwc-iuQFl> zY%*{T92<*9ONNtWiV6{y+B7aXV=!G5yLMWWlitLh19(L2%QNi?sGKvpnElewUTD~4 z=gWrZy2;h_ITcH3Ii&5xf})8hGlmDWQJK_N2=-Wma+#mNZ0A3 zoput5!MbA;G7*68XXd#C5++mXvjXKXd=7OIZIq zV^a_lNha}YTHZq~zu5uaxf8Iz5GZ_Vh^K^ zusPv!WqLa7CBW61PI1t4155+!ZIB}Aq_tG*-;#r5<4^`@qNEu!l@WYnQfYM_x|+RrhMP2 z7&h_B|8Q$Xp(VjIEpDTfcC`L$6b>W_5B^NX(;`GF67kT1gq_O~gzFonq@89~b!gT+03j;|j3y-Hd#`-hXAp1qrAlGeKdMMfz$ zj`%cBJu+ftjD0c6q5CxV$R*IWD2;YuN1c}ZTMeX)g%QL{Tfs(#9QiFU&KHp7#uG;Y z$X=Sk_Lb!65|MZTJtwc5=N+Wv%)L@g4E7ToTP-Lmo?Z9{P9)?m3|e7$oCF+BWUFIn zyXf$fdbvuiF0Q}4+fqsn>~-UP?#wRx-Bu?Qr7nkow!IQZL_8yhJW&(&v~U42p3n|^ zR$U<$w?O$M5c;J?o>4g08lw>!R;>CZQJx{?dvex&8>|R7v%Xz2Fn9RBcm1^c9Z;bv z>T+!kxbBfxCym_s12T4%+c1Bk>bx!jlrN8GH=tWXWvMSc%_Hz;E*lQA&~}(pex!E! zAr$Oor9629Wi$@cFJEifi|4>U%Y z*xe_u>&qf3;O$D0H4gn&u?Jn#QtpFbaLK#0#>0M|3a&ZW0-}e?h3hUE|Br zW>HQ2>R{?PEP1YNGfn4ndBQa?35O%$Q2l5}ow?@P?ut;`47X{>t0_lgz1WLbT@vzg zOhzdyHH7ujlwz=!8q!jYZU1c3mMha#Fgq<(l5FT~ozv6>IHX;v#$UV!@W~C+X9xSd z?loq7e3LF6Fm^sUaf2w#!Y;hgtXAb+rZP17WWn%worpXyDyTHcxC3ACss}%y_X>U=WbFmYfn| z>zH*DSP)!$$S9Ghazm6@+7H9+wXRiYvfhu};Du*cj-B+TC;Vl(-6-s2R36m zhqD%K0Qg<2O|`IP{2sm}wZUuX9W}Y;E??5s{8X1m^RD@QQ7-iJ08L<>4rR|wKPqZD znoqMTdYEYolLE^HaY`3(l0hrE&&$ur5EaH|4y_gV$zyO08G$zL9_{I+mNQuFT6iOc z0T@ee8w3lZ2QYTvs=1PF7~xEp*E9syi^J%}ur>45b#87@@vS%`ZCURerRU?*4#6Gc zaljm0YVsBR9jx!z86^-nyMo;84`{SNsrl6g10cKg>?p;c+e}*XmgftGsyahfx3j{4 z25VRju0Hy+M?w61pf;JOa8~Yiu8y)|LvxOYG0xqDeQU_cRiOi`YCw|Z_uuWf`D*qx zdOjj=ev0tfogjxCM2lhim?S*~6d}~`odtKD4pL5ooWYRy;3M~Q5au8{9y$8F=ymCj)IK`h9+~lPWWcJC|sUiRvdmXG%5#&h(mF) zMt9MnH>mb87om?SMinvuB(b(Owuoo(jjR_=DbcyFV+<+t1PtnTauODa52wr~g$Hb3 zgnbe137c>5M~deCBWi9^)$hQKdb~O}&rzInj%AUn^~#RE9380vC{Ea;pccF>M60kn z3#Rn^8c2I?E1^9!^kE+KdNZ)#ms3x`N6)U5d%?rhe|*8g1XVX?hbG*xJL9nf8N`LJYexZTv-SR?bNmm`;3{dWIf@s;4Vo} zPwo>LmT;9PnN3yHk}R9P(NfgP`uu@t;^?!|@dos@!ro|}o=ftFr>j^ZlbN&NuG~=$ zbv|?TSp`TuUts=qMD1X3*?6cDZ&$0)zy8Zm{O2$KpPG1G;=TXWaK`)T3k(?03ypt(vXri2< z?70&d$}CEzDkM{0pUIhTaUtFrIx>s$40y}fY|Hg( z{)}BfhK?Fi9)G-F-o@p%MI^djg|-pq7?-`$37UOss6FQq^PU@k`N;#V0J%H45-dCu zg%=C_=djFau~p6&vxoxqOH#mo$Iw-A&rxT&p04B#v*>bOu;J-wR*R<&-AP#I)C0O# zhjY9TDkoBr2LS6%rhJ6aO>0YS0DMpyuOs1a*g&zh!=JPB5KJq&SI(~+v4h;61bGf0L~L87VJrkH@pj@Q18+5$DC zhCkm(p?yZE`c7TCDpNujC%PJK&~t0nBEO5m1N8voi>%V@y_&(nGnDU)+jzEaJbG@j zIx+1}kJ6*C2DYDbD_!ZaCSpS_S*c2CYP2<{LO-MVH;rb$U4FqP&_{XB=qcp(hp9O8 zG3i%9cJ?v)&k3=&V}lf1A?UWlOUrKfkicVhs7zT=`oF&87+RK*QlMfX_oyI@ApYs# zIh`Sj^>^JzKaD&?8?bwyy#&q~mf#lNnX8xDE?HrI6Dc*xx&^ZEQ-mM^=^`e#TBIqqfY;*Ib$u52!?iyN%UDHmbGI(gg(gf z7-G?(Ld-bGg+;P*87MB)l@YU>uzo>_^)Be=St}Q~m!L7sKM)$J>9;O7_2) zEyn-;to+A7`+wq%(o%L578FrOdMhr}*{cbGqlom@a++V=f@9L-@GL~Vwcp?37?gz zGH;Qi=6c5%vhN4RoVY%26>h+%ycFX#S`=Y@5L-uyTJv~hpA}uA)aC`n1~U?^I;26T zh?BnmNd%dxI4w%YaA7b*0`=)u9gc3eh^@ghw_W-5g8j)vtR>Qn30DhxVuH`uU|pC zCBLI16>1f<>*{`5*0G5}mad{VwxHFhUDPbU)GP<|?F_nHPfpvjciJb6jd8yLgBoGF{-<`$~ekH~~JTibT0znA7W$c;U`gwa$1N-sY z+ZQk8^EEu!;l5g8b+)zbiBh0vss{gH#N(BzY}d)ZKphcbuagrXX@Mpifj9(}&oxr_ z@H=yF8s(`ikjj5H+yuI(Vpj@Gfyz@`u${_+6s3c#5I(cqekfU+y~YA8yQ#y>atvu} z9NWs}q>miPsYXzQ*3R5+s#&7hR32gA4Fwoz3j4?|1md?-9fJkVSdS2i%}lJ3rubJBz3Kh!D)eQNp z?=9na&K^_X0M^Sm;IG?iBx7_Lic!~tLZfp)`=bBWdeN1_yySx+w>-Y}A;r^He;}W^ zX_h4z50kZxd2s(~D-+#?Cb}imjGOsV-e7R9k%N(d6hstko6#Fos*Q(rZ zYN_Y-8OM*;#y(PlYtNITQoJ3JrGZ+$B0K{l#L`5mNcb1KPom=9LqA zO>+!1vNCO5phOm67*O1HdulE)bK_hgXyXcT>5_=5VI*>7LqG3q@#rQ-T)f((Z#{MD zj4sm6E9l})nKFPpa%~L^+>QCo7!JdTCVVB!tj|;>sz=Ou(KLn}Fuz+b-zPTT@rKp9f_G|O zK}0^00*Je1@|5o^KE?VC)IQ_dF9Ahb`xw&|(Y*%*)L&5=Z(q&M9nk@M$-yg>2sH*J zzi3Yw1V-YMt~clfL}E+ivEo!CboPdf`!50VCkequHsLNClifD2)ar+MjZb~HT;xqH z`NbwbbwD?mGf!ILRGXw|^kl}Wlg3WT@yhbO^c3mkUUuQPd96{r)PN;E^E9Ck!#DYW{2xsG;Q-DuUD3|>GJS~mGQQ;{To9B>yB zwr_FbO%SqcRZh~FY>%DJ+RPW0ESc;QN0uONxjbu86}1avq<%x86B-OyN+g|JX^mB` zU`@kHdfK>!Mm$&Q&5oWPSQ_K8b7%F1oAOOEL1W2`Swea;iM%@G%qH9x*#(j=J#eXN zBL!n?WcM8|52-5(*puApU@uN+e`wp_RTK9{lxs)8t#>2~F8FOlSukYJcSt{&&K;=F z9fpZP+cxJ%(Xrd(5J9^)NKOceF?Kr-a6c`O3e6L<*({29={ewMe`U1<$AZtw^aiM> zoZ&dq#8twBZifqfP4zvkge4$#C2Yqfu_zL6ohb5za1-D^5!xIsXNFq2rFSrHu1DLk z&IGo$2Xf5+U2np$5=fY3J(np8k10Iot>g~w&=XdwBa?@9L+JkVcpc}eAd-j89S4Rn zD=E*x)@zSF#k#uLm54uQMO(bWs$D)uU0#|-sAZE`HqK*d%7AM5_+i_7I4gAu{bzk6 z3Tdo-#bn`vyG7=C``Woz#9Cqnz0TY};%sUZZ_?o|QPrXCM2m9n1QAtbF8^=qEun=< zAyEBxrlk{dvN&-S^~?!7C()D`K2@R!P^K8dep#NL;7&V;?+i%rnD-4l#xB+Mp`q+; zHe6Nu0#Qq?@R6nm&F{Ye3->W^kljUHRzCQPnwe{)pWQ;w6hC3D z?;wb4>dsxSn8iGL#<6G^h|o*X$WNHwwcZ|&ZxyX-Ro<0yog%y>$yJkGVK}2F8|Wjc zEED;KoG=GeKzv?tCYgH&+=)zMddfLSHItQEqe#c~t3Wysq2yZ2P25v3*m zp8K74JrLs-{hfFm!h@^*{E$HDHuvv|}uRW;RCS?#w<>Io5oz+uyI zdI&?J_^=RK++g^_!7G?36_?LAsYSK7^ER=Ii(UgAXp0V9s${Odv!F{`~vzeMf71S9i%B5Jooi)NhMC6?==DmNWJ?LHBdp|#4q562!of{a_M0&NFD326}o5P}m zENCaS9cd@EGA$@Wi4!+BkcBAIzH7fCgX&lgZN?GUUY^ijI*4@wKAtuZE;?ssTWS5O zG%)AO?$Jfc%k?3{UEt1QDz=_mAlctqBt{KI+DRv*a`RCbOFT>^nK-z!gO^l00U-5i zeTFN32B2&S5k-W<#v)*J5gu)wB)A&CH&Wvcyyv}WyQZ_D*L7`>WFOB}v1mEGiw$ea z4n&Px&!K)!xJhfev9eixf?CUV0T|V+FYhxp@7i{p*;_oqYHA{qoVS3JXhz6A8^+(N z&s@)!Z~;|(nBdt>M=o1zb)NpZ>Uwm1Cl24~3Y9KoPATJ7;wB_JnIUDC?d9j-^_nSj zYXqa_%WbQayIpaeZ5BrT!+x~Pv42=H<0deF-v%1(^_m9_*S1=Q@0C=4!M&&sF?w~F zFG$QGzejn>376gXsB^dx{!xDtBxf3COr1O{uWt24i^N8t+Lt_Q=*$8{Etm!q`)&V` zH2T5C7`qQ^+vN35R_ch3rG177iA6d{G%;#kAwc-VUkp39ZqYZ18*b$=0vfxEtYtn; z;-pXEzRpPPBRMnM9WmL79~Y4%&U8$MZSDc4L86Ca(kz3fF7={a+$m`bm{HK+C*cu! z!GHG-d!fik2!lDMCMT9LRgp5gJRPSW3>DBabHd{|^~2^M`2w{Ub4SJ)gP)%su)7~O z+MI>?^KZ28KUMsn`sNpQDJuG_>&3q>vj1M+|5o(>N7(lJKZI?z-)NU$q8RmXd?A!= ziS)ceu|;xHDf6lbCj%g!luTtl7MTLRp5FmIKRE(%sX$CL5tD0tT$S^hl|q{>eXcHh z&=rI<@#Aak3(k`JcdhyoKL!pMV!o?hs%=aWRA>sgJK}A5L`vm`r>3=@ie?GGq1`asEUrvYG z-xe{~N?{Du09cuLlOdrLT$JFRfMI*Myou$24`TS<**6N5A8)(*Ys225gk-9#X*MFLn>mk~B=dPe_?0wG!WLKUK{zqP**>{LIM|wj;qIo@C~0O`GPwyiU;4c4 zF+3Ia1?@$GR^Pp>19RqRGLTl)+uQHD@FJgtxBGVzqql%I?5SCo#xRxpiGG){1tqmS z81Q_Bg(l)IZ8Z5LqelmutrKhb2z4$&n2!;+Ne>Uq$I@pIsJXpPYk*7sNC7qX8HDJ` zEIwl^3;sBvjm+T;hLziW5$ZPH^&6)Ifh5ABLWw{((ClBbYO;ALAnPw=*0gz#a!hjf zQiMUO1gKC&;0zO-QIZnvGcP$zs&~>i?3rFgBBv!PCQA{oXzc4{R^RB9WWa_1Nozx# z6~CsWyBD5sTSy#ln4Md|!6<7V9#x!QF032^V%yN&^maZoeRjL#0!=&s;ijB&pk)Lh zS<;d&DnDX%d4|CUPnU4Ju!XH@08@mbejakTDn=@KA+uPcJs7NZ4?I8V4{%ta4hqo# znG@_t)eTy-dOG&HOb3t9yD6inxR%?~87o9qNr$z3w;#|$eb05)isj8k{+6ifMlibf z2J`09PWVR5f+}dLqbJASwK=6x7hC3cW0p80$ue}>JJ`Ph@1NoIpMkeCi5{yC`QwKI z;{WKFC_1=UdH!>7Do*{v1JwfSyL)XdZ_3=+%AQk_P*9npQp=uQpTsxN%-yNdOydsU2twTq z3rpu3Db6jR=cDW9WAf&WZzT&spyv%J@Z+` z^7#OYUq;Oc)=FO%D~l0cR1uB_HirRk+tiC|bfO4y*eR1Co^ifalbiZL6O=mtaH>^n zj}ymJdN>L)ow$F(gP1ewrpYzhNdDoTwI<&v^XBdzmSM*t*22uz_|LD}CtQY^2~LUw z2wmh#kgC^=;`7-lzg>e`xK=K@{iJ0QT(2EzN%-a$ zWD-POr`EWt9aiil1TT>)<<0426nJ!4;*H9|(&4g~B`ebBl1scT=5cXY7ThhE&0M{q zL5XteMN_qJYHd=SExVK0bM=D+n@uDI&p9HZY_AHFmRn6nkUM^>$dsOz`p?Q*R}oDy zd)^R8PgffKvVqB5GhZKmWuIzti;oj<%#w)$)HBk z8}BETCx`>}E7P_zW7Gt*fAMaGr%pc)EK8^!w0}4aa30K}$ByOz=2*6tKkQ8` zh$ii5NOrM_+2Rq9bw)LpL3h@PMh~p%Q(U#)3QaZkdBFSYvY#mn_pH!D&HOaEZSQ4v z2?z+@(eT_nPlDXNv#1CA%p~_sLmh6!n^G#A&w=JJmu#x-LFDzYsiApGD!<;nV{evp z()TC$z7i54@a2=>8l?KXol#;v-Nd>5ODolI*1u&$M|3 z%WKx-d8_E>45FZ;$ESIz9RuWZFH~VexGU<0bbnSfy{zMy4+WN_FSGd~FX;>K^(SIM zWJQde;K(iEp=&D8dXbJ}{<|M_pIi`4Bt>z}Ktl^78MlQs3mSvxC3rha!;nOnJ{a?? z!oVzwY^JcH6q2FVk<+lcbqExDM2{)#{c66VozjB3WY*5K{&;&c+k!`|#DfOPP@U3* z6!A@^klAiaTmA3YY?%^Qpw$-_x>OO~$3@^3P6}Y|a?x)NGiR&_{EtbR%k93FX%f*!kitSi)|ya4oV%bEL5RAE-yCa*Nx+9Xe@C zx2Whl@k2|FhS&x5hRj~H?eXaB{xC9Bl@qJBG*>$Jn)1r{G`#Yre~`2J(&dP(9PnxU zn%X2yZFHL|R&!c*$ta!D*JE6-^9F%lD#yyWg08mfc}m00Q(&u!$gwm;%5Xc6G=m7V ztj#L?-0?k0a>fo=QX*f!MpUh!=f)BeSj-s4OppCk6-q*sOf;wxfH-z68k3hnkC>#g zHY3C_AF1+%Vaboaez23o=y8U2KZ@lKA>jg)a)(nmBMu(x`GY1n#eTL|++pPQ@7%$D zi9~)6JqQ;&+?(fO)U^?+AAmK+pBEx9L{E8Y@rG**B6$xH0C4tM>0^F*>g0~_>=W0w zJ*5kwt#wAitwthh@dZWPL9z`oHGP{|7cv&vIhG+B(G_jbcf>{g!6fV^Tq!ZAp>>jh z(s+kvcPdF_m9)bUEb)x`+z{?@AX`%BzN4+B)7F%E=Bu+SeNt6gOpRpNgTR}l~4DsA4757VMa@=_8UIS3yQbb`vXB4eO z*wN<KaMv89I;yX}sFV0lr?%gVO7b zF3-Cmr+5 zHrk?8$Zkw6Ey~U(i^a$R6iQyqgyaHPIZj;}y5W(tylR#3HnY^{vozQJ(|- ziwYy#A{zqDHm%Cr!i=_|h&5Ts#+|y-B&5TxzktsacVgK>CLfC37PL zP_$XZ%8bNlQl-YDWT^v`{L`>~#v@6yRmQYN1C|AeNG9ojhK{CgUsGj0CnX1eZ-7?J zv}X~KupDGhmUWPz7>bod9?Y?l>;52g3Z`T)gMJEfSqR%-$Rcv47d*mJ@H2G@$&Tem zZ?YU&$%pp#Pt&Rw7dzNQ>^$_a;C9}W26Ibx`3wPSLQWx-Ur^A z>Yrb%8br91dSpLBl!Uw`NSJY-M*n^}j?FQ$J+Kb`-JiZ9J-B)X1bUmW3KEC+*|-M! zxv&o585j-klJWFC$vfc~6rG_#jk~zdiPVcf1`jPI(Y1b}3#mp15(V4jH6GhV@}a0< z=<4M|IDGO=GReGM3q2%bZ?Of~oxwjpKZkth7Q`8v2=mc5_wNSkW%n+idyy-ibM`>_(F?1rfzcBw5khdw`%MgVq`lFqy{+`KL?E@eQh<_xWA7KBNg12Dbjy5zz8PIytCdy z4kXNshHyVSYNrAR&k3GPRH;dK3eh%1Rp&N5T@`pKl|EODvEE?nIDz)}Hn{;KYKyhH z-zACsm^54~v<<_*M+ztFOc1L9!8DsB!1M5Iz`Hzt4BJN$eFaM>s4`{nmHDXespmo3 z;%58ssWpx+mn7~p#-u#g{1O5Wh4ejiENqxNF6_MsD^7HA=2yQ|(hNAzoG*xb1o{QC zV`GCCDk+V5Dt6~~)iWsZ(;z8@dG+_V8N#k0;58J1BcZ=C>NG->#`m84!i_Ru#ZF&B zu-BomSxNQC-XOThPxdmfG!W12`bV5MiI@d2d zntlh#z&mHH+koCP2Y*P6g&smopq>|RDLTSXU$!iNr{qH22Hw3Fs(?N>*Z`GIuS`di-t@_zMHRvk@t`E; zPfMhno#r3HRP=gN4J0dU!|MuNuFyPUK~F*0&4lk>TkY48<{50M@-8i;&|`nuNv+~w z$r41>WyGJ_y|m83(%4`L;PDMhuP?6?u(5j1Er77w$VN0L^ zCyUJ8eMDkw_E8VV?H_{IyFU|w#Q5Y?`JM%><^!_X?6+%UkIpB2f^cQx$|D|`Vy0kq zrhDq?MR*W~Rc2uhF#@tVoPcyqjzT1T2c=rBwaOztqy3F1fH^Ffdy2sV8?r7qO}eQz z>&QVmc9X<8Qa@H9pJhQSKX)+zmpVPS`h#4yJJ&`}Fdv{u3+ODT%S)w7{!BU~y|FkO zrrFbAPsn20Mhh>B&Q}Jz$oHnAOE7-^5mmzM43CmDnvc)IKn^9@e{2dmB{_+{F^VKp z;uKkM3vt@pFcZ<`P381ex0>2k{c)Mi9=unumGmv_8j(A^aheKcA8EAC%Y@>At*F=B zpr}JkE@A?eN|LtWAi*KHyF0<%-QC^Y-GjTky9Rfc zAi>==I0ScxpX}`Ho6JsTzrRmzE}TO@U0q$RxB97D?@FDs1tZOnB|xI<_(!*xaKn)v z$lgY6;-^%%V=Tu=7LSMQ7A%gmE|@9Au1ClpbPYsUp&1G%X zi~1aS%!T8+0lX!Y?aS*F=`*SltNyCG)9Z7uK0fg~DNj%+Z{@{1m;Nv8DJcjQIvv0- zKrDf-$=Wx9MhK1>#^=}^10%hUuFb9f%LA4DtbqM!QIPKW6WX@2$YCCuC0Ggm4wZ5W z=85530ed2?a&w9m;8{kcPS4wlU)r7GSG7TnvK3JgLEr0BKLrtLam7=9-U!U7QfaJ( zs05!565x!}dw{FC!9?%uMm((~wkffkD4|yA&>Ph&Fi*7Zn5om8+CZGTe*z6^B)6Cj zh@1hMsy|WR<2jPW{=yQb(&H`e?+DoMn4SDNp6$#yFz}88L{maa(HPyqR#SJe&@xMh zNIAwH!@4dB(p5x=X0)GnzSf!+BRo~En!?QJK`4`ljIqqHn@CdBPW+Ut&gWs4BDrU2 zKM;u-v!OxG%z5ST#N^{zY5dcAINGLX-YCA&;j!vl zWZIV(>GDL2@^-AkJ0ZHems8qg(#`L1=Jm6jDi9lH&idjB7zlSnM{IsCj`2j`0g!fl z`p{NKT?)*b**@BZXUmg`UtDH6rD~+8(==3#hJsVv$|<@dSnSW7>K)Iz<$ArM{m>b6 z{CEM%GL!(m?+Ide#EzI0J`1c3LE|xR;G-MMA2%;7lYi5CbY}_XB-$K-(qM>_DWE>< zp>MJTFX@{y@GWH5MM&+liQ7Fy4{6QG2KaPMZssX#X$~vlo5}#8gmXY%HH0&zu)OIVQ6E$hFMGWlNh#2vuvF5n!k4^ z7=YhEkrooVN1c5mEnY29)cqK>1L%0!O)3;f=jD&VXh;`8k$q8M$(7~IV+oo&d}=M; zk#K%btHQaeB)b9sy^f|`4JDLXMs97uNZC zd}l}o0M+1Ho$Mxzv@*al>PF%6Yuml7{8m{NA)eG)a$1RJ*MXjD^Bh#+Z@Tyn<0|e6 zg&Aqb2y9aH9~>U?%|g(6Kft?Fi>$OrGAB%g)orjEy?gL=J*&K#)9G7tycCquEw*wh zWqb~y2W$`y;w-jqw^BRIFL`eNqFeb9EdIlQ5b5|@8OuFF3FAJ& zyFY7&o5&lp_r0ny!m!yU?n?J`7CnSQuHB}|0X2<(0m2Gd$8yG~_ObON1)sZNp61R% z%ng!29<$Z83a@=KbZL~yteQ6US@kIO*{!i(#vga*e_o#d-@^R|%W%||sBGxl>3;cJ zIO2bDb+yzpHFmUiwEtV*=YoHSEwnmXh|J@FHFfbvGZ=HzgF6^!}hShK3#1ee5h?iC0<%# zR!^K>Ik~IL8UCo*+|#)s^i91%*2z*md8%sUV~sf@)(L2)4ry-!JKkdA9a8zO?E#a`0AD^TGrLcmZlco!^>ngE8c@uHMK#9zhyUvugYWy=_ z-*qa;sZA{r)U;(|32{#y)s|VS6(bPyzED8LDx+YLvdR!N(Loap=VBE9WXEw^xXX^? z=Mc-VG8sz<@59*_obesdj89x$4B4mpg(OWh4FZkBY4J7(*ULEb!2+C3qc*wY4pdb~ zfoH+A2KP|%pc+) zpQWEvar~LKIHg6%zs)yoLI2~+o(erB%tG~^%NK{V$m#phn`y!e~=eYvrM>3^5@ZFXnEz=`txpSQ2`z zUO|8{Vd1A87EiiDH1_E^L8=AwZeS#~i1OJm{!0uw48-|aP}gXLB3uEgvFpV7f^NQZ zgM6~D&}Db;_}@P(6M7L-`b=M8eK-cGX$l5^z%a=-ox~1xLk25wwuyWa6BWYv(n?72 zI3SUn6z-i_#k%b_2|Yz<+;j#Bf6M0!l>*T{tXn)VXhWm0O(;D$LAB3%pA;)PrS^(7 zSUIx+Dq?vM@F?P)^BJuf5l7EIhwT+sHSn~$_;X%P!n=SC>2Sdn*rS-t*YeL>aCeS>LvsDdbuf=Xk5dF$$G!!l>faZCA) z%=~eS)4b)OSZC+0=iVrx#HVB9*W^9Vigiz}%kM$s?O-|`E9hNXZLnR~ZN)t$9xz3Y zcl20VQyb%w9u%LFXi<5vwI(wl2=nEc684(X$g9#P=d)8{FC-r57k-*{^G$A`j!I~El=wl9>weQn80koFhV?by~d&1D9voiz%gwcgY(urL4a74 zHPreJO2s`Yn#c#wwuOkGRWLN$gDzf%zSLg%&SFzwMrjhOln zj_Ws0Y|Mr88yMGSk)nvq)!FmvDOf*zT}sWZ9+2}vJCzc2B}`^Q?_%2np^1_#++4jb zNpu-mL>PeanO%w#5zs3cJ#UAzLSjA!KZTrk3e-QYPm>EVDa(k~Utu?GD%m3z3ijPz zGr4`R!50P2hg)37GL;lua*@&s!$jvSF)_B3XGqz6UNM|hVW{`rR32L;KPwM!6db4y zU7VV(r-)s^T$@Fcz1b|^7%SfpP?$d{q?v^yT3XDrbu=_^ZYrWLI1+#-+&!I3(Q)6o zk8ilNupDXsIJ_N%aLlPWgNBBY^&UE-QPg19FeX$e7G+33 zdl?8W-bk2e;XLT9ehW}_|K%0oflu^d8R0zh#NI!d-?e^i^SZ4L@1PN@cM454E2q9@ zNS2a^*VKW733oU~gJzb=o|X?m6vjPKf@->Ep9t%ok4ep%yx`pM2(jR# zfp~t#(UJX@l8tS@q_MRk$0U-J>q(_pB=K~!p#(#72|?zWourg=dYM>W+>zQBO@&WL zl1zR2$6DwF{C$y>>U!?_=NS4GA{E_qr-@N3Eo`aZgKzWEt@gp4;px%LkAs(jM6Y8u zQp^??jr}`zPU^cx(rM@-AQY_ka!~X z1opg^rP$AgX++C|OxXRp@=hu>^6#4i@i%PSiDr=_i`P0Udh%LcgV);TVh^|TEV#zv zq$sb*Mv@eT=f#u3Osh4g%tX@!92P7^Td|!)W@0&O=3}J}YR(uU=`fh?=B`klo0r03Ch$QKo6uh)Z7ZXOR&388>(x&vr?-*pK`8h%*TwRltCUr;CWwIpgvw=3d=i#Ke1&2aS)thV?>dU2H2yo|<(hFHO9 z4&*Dj(;k+n3(>VrJt=j5Ak4EV8I{V5uFo zbTU3xNu!x@@(h!i)m$U5XjA!UN6(57VtGvdWi)xHiF}NOMU?D0MbASp8Rp4=Ly}2N z&S!Pe$V$wEozf6re*_p9=H~ou3CtM+HTL=PnPb2WC1`fgquj|-Oi@}QA~F$Y1bwAL zzA{UDe9Yr*2YzXe0zJ^!5*z%48ER7%vu3(Aedeb3H$YVFLrdmbqLJ(b)lPj~RTDQK z(apn-v>V+K->nTu-yDgxP^-! zm60-_Fn+jBlA=y!b(>~B^1(bgiR|6iokf`;Y%w%1>A^C*B~on!&XENoR$m&%>oG1F z8fMs{FK^rBaTXTXLF4B%WNIe1Wf_O|HaF%#o-DFeSAU3)3UzQQ3~y^;%B_wKcIdkm zw4uGxp#jeLxG^0G^)2Z*@7WO4)O%59LHj1==2pl#>lwc@4s84-Zi`A|_JZQ+!4D`p zFCDchLBFD%6$xj{gcaq?cBQ|v%J3Q3n(T}me{_SH2DLQS3spMmleSThwEaob8Jm1y zU#2H~Bf_RUle;gw#gTK%0&{d>)VhaW<=BDnn8=kR(?hoXAb-|r&bagB;Su$UBvT;5 z!xp7~K0ag)^eZTznSYG`i7l8Y*6oF>o%crvs1BWwQ`GBBd#Gk!RuFm@c-LkA=K&m^ zZ>SI~wNg6a*<;$f+&+A|jhv#!`tOTm6_V5w#WSJ~*)Kr=!Wuv5Jkd%NqYD@&0Jb%e zG8@OJ>LqS-g-+3Vhq#JrYE@BMzawf)n{wWjOl@UQ;rtYmE&;(62F_1c`GqC2wItpN zF&juQIM+XtISyu?CuLslJF-}FhLsbQrUeexA#!9E?iJR|C}+B7;Dby?c}^aaOjuTb zmd(o7^>+Uuc`O&Vw)N?)=S=KVXXrxu*wT&ORr$D+mwalA4;`QiSBP z7Pc>gg1%nyjWS%?j@;zmJq$aPWnAFp8&ISR&ZeafL{lnpP(F`=&^C;$M;-Wm^z=O2 zp&U}|gSF|$(@>6e2V3UX7%8Ji(o>=-+;_ggrF?wc#G8q~9~$u*Ip`VL6w4Up^dIcw zbyiZqv@>q@G_C+oya$mn#OOGc2outZEPuu#-EpDWd7z{^a}EE>tMH9?q#H%1uV`M6 z3!$P**P<`UB=4(9TqWH^r%*eGR4|F_1ER7pix-0M{giHA*q$wB(E{;jK_)qEO_iYW zNf=^UoPN*r9oSc1xn?GnWjU68; zbD=#6TYMT49cIQ1XUx07&!{}X^rdr+S}Q(^lvbjsyIIC?+N)G_3%17C9AaTG=}zfpZ*k>^PlZntbHXJACB`?PXGIQZ zXoYAUnyaC937=Esc1{T@2$ODGXs>(EX2^{|0_39jO2oS-k}AS((JN+@0LVXkrJaTt zZNg(ji6%MPAe)CKo}Uc^C(DI$q--Z-bF8rrWXp;HM9FpKU70w6E483^+A)9|r3?Gg zxVvN#ps4XVGh)}GM)Vo@G9#dD(^ z_xyR_MGd$B&9Mf1*nl9_5OQv?0g9H%MbF}_SLG-a&cNw0m7;%s8gB$@zcykn89A>X zd5d<0xbcNQxzur!aIU(pf@WAra*mT-zb23&_3JCD=qLg6XNi3 zGO4q{MB4UbT71A7Gl!e-N`qCsS_B`Hxn%iVsv7F{9AIGvmxAr7S;J(M?ue+xGIl9? z*Nwc}(dQvnA1sit9;rl)xu%?@U6!5afh0eJQ(grTn%x2ZWSXFAv5xpjs)`#G&EuNX zafKUT43(bGOk-nl1f`?$TA>}`?)gEjSoKsN5*{mzb?RBDRrkc_UyO>n(aF9UtvV25 zeul4Uc(g=A8p$HdYtXZjq8Xme9W#(H&e}qBMj!5D%?D$r7>3&|&a>Fd%*lw*ZVFv@jBCLVHU5|ueG_%Tv7mT=92>1n4;Sl@C z@u^n}4Ps{0;WlLYKIhV7AWOp?i+9%e^y8@3A*Lve^Q#SgNoi3WN&l->AW8=Q!m7Rw8AqL1N550XtvuzLxKV-BCAzD!w921TVSZXfT? zE`U!rfe7|HqRoEXu136w?UqPu>%LtPY~Za!$KE>Z5`Dn250i-KfI@rUDn+o8KQ{k8 zv85sUd7o?|aNcQTBVyOVGYHM{46Ric4GY!yh&N^O?W1zIm_+uHh+%v#dQ>NRTGB>= zN!QkQyvBpiBFo%<_uYHx{2!roHR%m;4D z)&&h^NKvhV2)fg9Cws-Wpy|Lmx}`CG|G2wo4OpbHIPR;;TQp8eUZjsg%61dPMN+@L zZgs}{`Yrksqep#@3p~IUSU-j^ZJ!GW?-ptRd!*17aB4UT9IaH2pR-=Sc;2?Ie3~ zq+YJ~R%(kX(Wa0N9;e7g6@i9s!Es+dac??NMH{lyJnQ)9=qs?%q3SPWm4gnikS#*` z2;T~UB%pwQ%)m*1sg2(2Mwgd<<)GG*$m=q1|*!(2-yc8 zCemw>Jzq*zj$&7bTM2smgsDUiv+i(q%!suhEOAV)IP32&bH%SfXIp#A$op@>irNs zi?8+MP(>Xv+~b_u4BG|Hw;@i`Nzx@qlSf?)$DEZ)0ku*)%g4{o#F_CM7A9S-O69s2 zMxT?IJp3MOH*K@g%HXktG1?dV&FsxT2*_FvMw@#0uIld%II$GP zQqu6LN-98w9#4tQxSihsax(oIxwH*S9tyZC_$dQ z-Wt~Z`h5jIdl5sptTdReoY^p$xaNz1pyJ{zH|*=|(E=a7^-e=f{$Lx=)R9L>Q_7OS ze5fJ%_iPnreq9?3)4)9ztC)r$T?BV!zV$tCO8YD^&-;68bA&=Y#MyAEytr+S*-r7Y zlSv?CT7M#qeu#cs9Oo*rIqOv0!ZC78u~4fWok@zo;sd{#D=<^`V_8+EjOzu~i;Q{A zCZ2ng`kU#0IamGMOMmUZPq#DMNFUz4!y^1g^2|Rv?jN`2GgKfw)Ms5^vnW(!cPKhz zS#04+#K5{^FxhEhzxgA6h3O8l2x5sMHbt%|FjvPF7g7cU%p<~57jJb6uQ$(t9@<|j zqbLB^NrS~bSSrBKG@UQUFduHPI?gsOlHZvxC8l+ZW3+PsdCG zb1(qAGx{8e3-;dQgFd=Hx_`KGB65p5`3?u$&M==bjQ*ZVoh9EewB?lQ0il?CA#4Bm zkhALZUT;oCZ?~o&$1CwDh8tJ8AHfVNc|?nH8vVk`gQfXQM^ zWH%pI2G*jGoPph941gAl*?o+cr36Z`=z$Pj7B&qmt&faWXM6J4AsN0~JhHu=*095l zut<@Gt%b<=2dL>_hYJ*`NCY1cP?8cF+EQ$ZD1&-FTIs{f)x%|db`$Y$Fmnk5Giir? zd~DM(A{g)0)OS*sxYW^z;pjy7w+JnmWmhuC3L)8n^~ysuyz==m=HL9}h3S}?gwC7@ z=?@|SO2){CQJ3d1@u^zu$zp4$W5&Ke%XI=R$p{$(+l%_D5>%O5NIpR3nZ~-_FVpK3 z2Z@1n8byAY7@J#k8_U$q>1jO?`+m^`hiL1g6cs1j9t9%A$gfswFSSB0Q-VGT*}hHK zF~_*w34ne)D;-;|KJRjmRhecboB=dtZghf)+M+03v*RaZ+T%O7csSBLd8pDPj5B^H zTHY18+}4>)mH+jM-;_X7=y1r${=K9g(Zn{3CRc65PRdUINV#btLbO350cCo9)~ec4 zpo2vGCZz=n2qXvW9zuPfe-Wn1%UqsarUavY=0ssO)O4L>ZDP|k3qf+oXfjw)#Iuvk z{Dhfn@04Q#JixFfcCwZpjPGvO$5H+F-sUu6`+4y^WSI>n!I z2%q8)AtP8n+(_n~B(7Q-Ce@NEE4>9iIOT#tYP(th6xp8|}D8&iMI}rOm54ld-(ZRxg z4HIKc1w@(c@i0ItYjNSeau&YZ&lmtmjd%nfD~}vB@7tVWIi&?*wn|kfmK66zN^||( zdsfuHwjKQQk^wRE%Ci-2@={##p#gnguEuDhkjM@pP-$} zYj1yU3YF)85pdmP=~JznUdg~M3YogFAL)oHI6wg+r>?fq#vipo`w;!2hm#;_A0i5o zU174bv!9U)M-{$n?<{6&ZB+5NIA1}Az@5w}wg=LG-PWd#bp;73bZtV`o2T!l%a9aW z7(vRPF^23gG+DB5LybeEJX;%JGC8rF=hv5$uSzK#F{wctw`mHWFJan`q!U-rqB<{k z?7#PQ@$B~7;TsbKnHgGLH`<2oZjYQnye)(E)4d&2#vy9_wey3Oz1uyKo~n*viiS0D zUev&F8;ejWJ5TFSbqGzhkDjiMi*ZG=BwC~<9Tj?ispH|?;5O4&y7^&E@%%aZk|`ZO z`>GgF`^p0MVG?H6L5;_-7*;i|=0#B>$Pa9<+~i5vL_}ih-n2f&BC5{~>VxdlWVLoB z?L9|_K#ARegR)fXiXRV&yz&gLjzo0h%`jCJwB4v~LR-aPlY*Cp+_yRO>Y zqRnQCav{H(6j;5Ta$)6raeRwCqJ*fbQT)&e7hNS&?yy-vDU8pkmUTLX_M8d;&JBMz zE)1@(Q5%9Vu1!4l0z~BGoo3{@EoDE=hCgS=`v?!(A+I4b$In;|YAu9@X>b1*8;YaQ zPol*=Q$9~yT0~hFdACU3Ct-b;h2x=cp4g`#{LE)b#{^AODDefyyew4!*9oATU>Zy^ zmkrq)WJ7eu=Cc(37t3S9?@i@7dxiQPGamnMyzM>4atgttRlJd-=G|Q;i7q zSDb*{R(y;%xiHVbJ+ftlE_%S@Aif20I*X!RM|dJP{CTr@;3Jw2HG_y~B({xDtN5ZR zk4d6v-Ge)E+>lj)2I`8r--lOgIpwAC`gnYBzLK~MrOvDz-EcFriT^z z5kCp;D$8emkGN)lmrxIZ)exb%J2ZwEf72V4ocY?COU-9V478p&ZRyknootgX*5q<# z&$&GU(H5vR;M1xaz=H0u$Om`8D*pw z7{%-YburHGAyyF>s|cB5&zTV-NscafI33|2R)w&h`Mw3yFm{lZc2TSYWK67`uW`zD zm_2bTB(T}SiSH(ZJw*pFJ#WF^A71{QODb=RUJ%-EyA(=b_%u-2&t?gh(Gq)zV z4Io^MyMdV46J_JvKuvr-79Sz=S@*mv3j*%ivp97xQgoo&>>0`n*60c)h@dF4o$XWc zK>s}SjlpgeH&alABS`2R5IHmqCK`FM4rK%UAPM3%T-Vk$bIfjbQuy|07Gb~8==%D+ zK)%UHIP3!4f^c_sZ&Iuh?IvL+4=laAMrCE5E`V`5xKI75Q35aXqjb9KArUgwE;&K( zJS^h+C-M%_&31`RPYm;33KN9&KBIHaBiKs4#ydFpO~+O!xoSx@1-zY#KGh2ZYP1In z#kYTBi=~*2@67SAmZa2O$`f2-;Lk5jlx-FwmZU}Nm?wDl63M^#sD+J|_URGb?V*J! zHX`wkDi}LTz=qHl8xwb2suX>LFV%pnD2CBzUe3HA%&a-t;2J(%1x`}HU)YSUUrel5 ztBs{8a99P*B@1Gm$#DxdR z=3~mCA9LEsqpCQk3x256I&oRd76n~4Ce+B50pp>xc$faQ7MW{Iq|^!LkK?nyk)YADQh(YuWeS{E0za?#CJ@U>fu=fYtb#24#+04xtWKx|7kYsnT z^-T@Yp7haP0C|P)(2>2vKQK1h3ZbzsHjmp+WS$v>jzmNw;LTp)&vc>j9dZXtmsiPOk$%_yVL1V` zivJ!rk^%=`2HU}<)X2RwkUMtP8q!VVskOk^YjAAXbQo?fl}=dV!~O&ZtgQT0 z@BxtBL*lXc(3e>{`W^k`B9HVk#*M08HStfbS4t21hjy(N-0!(0Xvx-j5OG_o&s=B3IfvuFO%yg@IxNW6}e2tS{_Q!EE0Tc@kj_OR-$%w8&W*F*P2(d@X11uCzi5?&apuEn8v5+ZlKXe|S-_3=Bc3-3OZitCl%&&n1Lp)MBQ zwy*Ti<=pkOrC7JyukKFVBubm64V#9jI3}UoOCXZV#}xD!jR#LFyyJ2`{0uzvVWRjc zx*~oaD_lt>ywvtXhY_t=3`KlHFFh&?#U!QpJwo&Kp%dn#dQ5V1|7ZorKIB+c zDroHkm5_5(wdiO) zJ_zw1w30YE3A3sKE{eWKx%~X(spz>9dbZN&1na$g8;0#%8^_+5dAL4TGHMZ9*-&vg z58OUOvI-Gf#h#!kM~xmv0ICF05_(l-+%@kx4r{0U5r-Q61;--?yDXkj{{(Rsr@4B1 zQ}i?`yRP&a;M_<@YHRj6|4%GrI{BCKTZ!~8g~Ot|E;AIcwls#O3o^b-8FconzWss6 z21^c?Fy7j7FYd;V0E20=@kXJa4A`v;FOlZbAwSeH@3 zH-I-Xn{lwXKgJST5lu5yWDWO8C~ekhje9Oz&MsSCn+pgq|I9$iX{ouNb;xs_pCW(X z(4Yi0G3QpJr;g-2uK`J5THwIW%&I^wyGOD=xlF`uSsVu>U!aB774D#c70BPBRF2$h= z_;kV`70ytRruz_jy*-n00Y%1GQ=z{;ha}OOAP)YKsiqADIZVYM_uIY^V`}Vu_650O zxH?IgbJJDBd<|5G-*!_6@jm~AYlxZ$S9{4utk+kz!NZJmJ&k*f zX%iA|$W|VlvF!|h$6h7ob>*0HIxs&-_f{W96-%9R#Lrb~*&Q5QK;1b?Sc#vLanaj=W??ji(Li~GqyZk1r=V)1 zK`8s72p=DG(*s7>@x6sKWdLzZdUVn6a;+*DdyCEEZhj}L!2ox{r#5pj(MZpLjmRY6 z4{1_oBh&Ov9MB3M8r?*u1B5_gaO>8Ilw#>i=PnOa3np~Oft^ac)}g6Xz?4PX6ebc_ z-6f~L zt^+F*c9-ZiWR=heZZF9Q34CQLucHfynh6N4S%!3k01AXB&@^BqoM-SWBNT!sFf>b~ zP`DoJUd?-J+CEyf<9_TY<02H3x{SN&k0(iesko_%@aBl_iYa;vK~f*|Gf>PKzEp8Q z$@<3N^|S6&uV1o!tDa-_hNQCl5F;~L8~;qMTA5HakD%YK#|@jz%kpjuX7Tiaj%DBQ z%uEMFjR!;Ry88x|a4;14_gM|}^LmC!` z|LDRC34WE6r37#O_>}z|EEpxD-dmEmm%FO`DGxOpTfwLEU=i~YHfX<*pUQW0U&%ct zAj}Y{6?HL_ZieZ*?)o6{_b*Q9cn{}YVQ^{-47SPp!XEp1Yke%;f^ZjmD^FmKQ8L<@ zm%-!S5)pTzTyUAaNK?z$az$nzt1QrCii*Ac1HT4G^`UV0#*%#Dr@o?>vJRduMkaoI z`vCccyoX~)*Xt{Nh?~L{w~#}bCwfkh$*yBy~hLFPr zDywhVO#%FyOm4-Gy;zE=#E#sNH4LATv~bqCTMbBw5&I7A%RA*&Yk}=>xP*om_}f^3 z{Cqgil7hTx@F`8H8byJes(Zrjq{D-jcB*+?VCOvIzncY8b}uLMXEjnwOr|Q!h&jWVz0mDK_M6&oan)e(~3mp$cpJnM)y#w3ou1U z0O%P*CQmvHp59ydB1Va`PJl;NhF}aY(xs6 zAq^!H2OU;QsKr^t^H)UaOFR^GU7*{%XhWZ8}!h5a{in`8Y`E9*Fh zH>(*?^e}0s&*DCX0neX53nEX4)c8Yl)8>#A;wOvHh-@Y=x8usKHGh0_wta7xdU5Fn zOp-Vk`f>bmTG}Q^)CkZu-)LiW{p2{M!}slQ_S*Z}wpaQqa~LDy9VEaP@=(%q>Py8> zJ;6rz94N^L^vd5f*H+vBId@Ybq?wJ`kB)MOil0lq;G6M8epeZ)MQ<*;{}&1P&zk765@;E#YXJx0Xz6E31-z_M zjxn=TqsqWT^r^3&pKijmM?!*FQ}cVr>7&|hJMtrs`!?qFB52fC?k?sm&zruj+cY#j zupEZH?X}aj$7iqG##Q&d##gTgv@YcIsf8m&U6UsCEnUKx*#7tp|7=m-M_^Uo8%Q=> zQYsU%XsUr2VuBt}V8i!23<_O}G0L_weR$BHtC{_Krf_0*ivx)<5vKgevEjwB6T1oU zFz3%mv8T^iGAGUmGv&_f0-@hXK5OwfigXDgOI)=06&_IdTx9#i(V2$#4UsBIix-U+ z6I(TT4aE9{ z66h1&rc~$CGwv)jtI%2Y1x6W+Xa;78r7gm|uOBQkZQ3o48I!;1PrUQm%7zoixG|vI zFrsp=$ulvs@#su(U{^zto}5WfLkdG4v>!xU@3bkwEx5*%N=2K`wS}-^xjoS|B}k&^ zbakY&#N;gf_C?U)y(FZcz^NZkIXRJam=y_kdKIx{AeDffpkfzmSB792J2vTs9l zEki?!gwrE>Q<>QS%JC;m-U(-9T{j+ zj~r{{1J&E4WrQ;$Aebog+^CtU_IfU-bMG-6F2^^u)TmF@4w9=l_Bc~wa##qO>w+y? zXzfU0Q?mA%rx32DBy0;7Cc7fF#Krb8#i&S#)9)t+f^$@rrM6Gx(5N=HYX^0bT5<_m zRfE|oy6f9u#Q+Poh>v8>OC#qeO12zLt@^03tijNGt+1>i(7THx8-bzma<(jaoj0to zPQl!iQ{8PUBX5CMLpa&ignheJD-cs|iB8g2g_w+y&y|t_v+1o1U{4d~N7Y(+E0T{LTfy{7vXacTM-$AmnWHh{Aw+ z>4t)QEZ43@p!4;cw80hGpR6h4un|_d+WI2?gr}hBYMtl6XS&$zF*Z;#ONfz| z)D4-j*X$F2@5Vdx-g zh=qV*8w`F_VMw&Jsaz>_a&<_SljrdOqR$|}p;VTIMIW!UU~Vc%&oyNP69jBO6k zG;YL~p{TQ{i8UDg>gj`{W!KxHzo#fiz+!1igQ`~(gY}~a0fpXQOXU!#eh$){x zTWrTMCglkk5sXoa38ng3AYt@0vXIKg*>}*6_;)_So1Voh+HUoC1tV!ebZ(7^X2!?| zjGCi1vk>fAbIH^+Ys2&~_-28053Y(yewj0>wk_+}fl~7(WA*Gr#?q#;A*Ec0x97)2 zzyBW$9X58>HimW%riS+NPSj$Ol%kTdBBcs8lp+#iB8q2{l;WfEALr=jYPaQJ21(yT zAd;b~kfWxmprNXzBvY`o29lzpp{Cj=6d)rR@9r(4e^0R~K-oz`b}3vS-rL*V-9tJg z-ZQWxLQXI!BqC1A1_yfgqbffOEF%s8hzNxE4h#(J-H*zY`t~l`zVVE*zJK=)@vSm{ zrhK0tKmDg_lDtx)LW1%N)RIDfAV9o(_eQAp1L4mcKi+Sw^#4w2w z*Cqe_!yoUrAPE0XKe8>oW&7b+^G`Y62vUB^@$~N;|8~Xsr;G@H=6m;}D55uCp1<+o z`6mFBUjUT;9^i))(9a-$)zg~`!oSlGDZ<`B{-dWqXkPv)^IPE0pE5W7cjljYVg3n- zEisKf&Lrx44qz%$$q@WTvb-!9J*|3|EM@A7@N-&*W%n&^jyg{>TazFGHI%vI#H%%V4}gSY1g z-R7Su--iYDx0t^Y>eBw<1M*koE=e6u@;95qd6W3Z2=Hgh_hCi*E%Lve!g%eB9W4#5 z9R9M|_-hfuHRPS7Z+(*bO|3unEq|tbpZ>S@|BXWaI8pmGQpjI{B_zJm620})t+(hA zgny#Gz4Lv9@%{&}{oiXND6t4<c#E9!8+b(rQ;YwW_J^%{4e*|LzJZjzJ^wct{HVY5n@8V& zY*k8H;munA&Qy^wIQ=c&c9Z#UGX2=i{F(B7pc#HE51+2Rss2A1YpPxDdhZ)l(Hk=L zpOA0we4p_*3;Rti`QON(-Zo4UrdEdkg#B~8_qP`LPs;Z>W%@1lFCF2(Rr#aS{v4$E zS4}WW{ucL-7XK-B{9oJq=Kx~_|B>~FCYI!Wi~3L1|2aCy$||1;(LbldzE^%vXw4XgQImGd+0GSQ!PNbYCs zAASAjtMI>?w|)3;CFcD{u8aRF;wQK3Uxz83=-(FcH#hA6iu8>0xPQ0N`m^QoeKg*t%KuE&|J$DbZ`&m!{{HPC^2fwY P`tJ2@y+YFW errorList; - private boolean throwErrorOnError; - - private class MockSubsystem implements Subsystem { - public boolean hasUpdateCalled = false; - public boolean throwError = false; - - @Override - public void prepare(Looper looper) { - looper.emitAlways(this, (tag, from) -> { - this.hasUpdateCalled = true; - if (this.throwError) { - throw new RuntimeException(); + private Telemetry telemetry; + private ArrayList errorList; + private boolean throwErrorOnError; + private SecurityManager securityManager; // to test if System exits + + private class MockSubsystem implements Subsystem { + public boolean hasUpdateCalled = false; + public boolean throwError = false; + + @Override + public void prepare(Looper looper) { + looper.emitAlways(this, (tag, from) -> { + this.hasUpdateCalled = true; + if (this.throwError) { + throw new RuntimeException(); + } + }); } - }); } - } - - - @Before - public void beforeEach() { - this.throwErrorOnError = false; - errorList = new ArrayList<>(); - this.telemetry = new Telemetry(Logger.getLogger("Dummy"), null) { - @Override - public void reportError(Errors error) { - errorList.add(error); - if (throwErrorOnError) { - throw new RuntimeException(); - } - } - }; - } - - @After - public void afterEach() throws Exception { - // use reflection to reset singleton fields - Field fcInstance = FlightComputer.class.getDeclaredField("instance"); - fcInstance.setAccessible(true); - fcInstance.set(null, null); - Field sensorInstance = SensorProvider.class.getDeclaredField("instance"); - sensorInstance.setAccessible(true); - sensorInstance.set(null, null); - } - - @Test - public void flightComputerCallsSubsystemUpdateOnTick() { - FlightComputer flightComputer = new FlightComputer.Builder() - .withTelemetry(telemetry) - .build(); - MockSubsystem mockSubsystem = new MockSubsystem(); - flightComputer.registerSubsystem(mockSubsystem); - flightComputer.tick(); - assertTrue(mockSubsystem.hasUpdateCalled); - } - - @Test - public void flightComputerRecoversFromException() { - FlightComputer flightComputer = new FlightComputer.Builder() - .withTelemetry(telemetry) - .build(); - MockSubsystem mockSubsystem = new MockSubsystem(); - mockSubsystem.throwError = true; - flightComputer.registerSubsystem(mockSubsystem); - flightComputer.tick(); - mockSubsystem.hasUpdateCalled = false; - mockSubsystem.throwError = false; - flightComputer.tick(); - assertTrue(mockSubsystem.hasUpdateCalled); - } - - @Test - public void flightComputerReportsErrorToTelemetry() { - FlightComputer flightComputer = new FlightComputer.Builder() - .withTelemetry(telemetry) - .build(); - MockSubsystem mockSubsystem = new MockSubsystem(); - mockSubsystem.throwError = true; - flightComputer.registerSubsystem(mockSubsystem); - flightComputer.tick(); - assertEquals(1, this.errorList.size()); - assertEquals(Errors.TOP_LEVEL_EXCEPTION, this.errorList.get(0)); - } - - @Test - public void errorInReportErrorAllowContinuedExecution() { - FlightComputer flightComputer = new FlightComputer.Builder() - .withTelemetry(telemetry) - .build(); - MockSubsystem mockSubsystem = new MockSubsystem(); - mockSubsystem.throwError = true; - this.throwErrorOnError = true; - flightComputer.registerSubsystem(mockSubsystem); - flightComputer.tick(); - mockSubsystem.hasUpdateCalled = false; - mockSubsystem.throwError = false; - flightComputer.tick(); - assertTrue(mockSubsystem.hasUpdateCalled); - } - - @Test - public void errorAllowContinuedExecutionInSameTick() { - FlightComputer flightComputer = new FlightComputer.Builder() - .withTelemetry(telemetry) - .build(); - MockSubsystem mockSubsystem1 = new MockSubsystem(); - mockSubsystem1.throwError = true; - flightComputer.registerSubsystem(mockSubsystem1); - MockSubsystem mockSubsystem2 = new MockSubsystem(); - mockSubsystem2.throwError = false; - flightComputer.registerSubsystem(mockSubsystem2); - flightComputer.tick(); - assertTrue(mockSubsystem2.hasUpdateCalled); - } - - @Test(expected = Test.None.class) - public void runOnGoodArguments() { - FlightComputer flightComputer = new FlightComputer.Builder(new String[]{"--real-sensors"}) - .withTelemetry(telemetry) - .build(); - } + + + @Before + public void beforeEach() { + this.throwErrorOnError = false; + errorList = new ArrayList<>(); + this.telemetry = new Telemetry(Logger.getLogger("Dummy"), null) { + @Override + public void reportError(Errors error) { + errorList.add(error); + if (throwErrorOnError) { + throw new RuntimeException(); + } + } + }; + } + + @After + public void resetSingletonFields() throws Exception { + // use reflection to reset singleton fields + Field fcInstance = FlightComputer.class.getDeclaredField("instance"); + fcInstance.setAccessible(true); + fcInstance.set(null, null); + Field sensorInstance = SensorProvider.class.getDeclaredField("instance"); + sensorInstance.setAccessible(true); + sensorInstance.set(null, null); + } + + @Before + public void customSecurityManager() { + securityManager = System.getSecurityManager(); + System.setSecurityManager(new SecurityManager() { + @Override + public void checkExit(int status) { + super.checkExit(status); + throw new SecurityException("Overriding shutdown..."); + } + + @Override + public void checkPermission(Permission perm) { + // do nothing + } + }); + } + + @After + public void resetSecurityManager() { + System.setSecurityManager(securityManager); + } + + @Test + public void flightComputerCallsSubsystemUpdateOnTick() { + FlightComputer flightComputer = new FlightComputer.Builder() + .withTelemetry(telemetry) + .build(); + MockSubsystem mockSubsystem = new MockSubsystem(); + flightComputer.registerSubsystem(mockSubsystem); + flightComputer.tick(); + assertTrue(mockSubsystem.hasUpdateCalled); + } + + @Test + public void flightComputerRecoversFromException() { + FlightComputer flightComputer = new FlightComputer.Builder() + .withTelemetry(telemetry) + .build(); + MockSubsystem mockSubsystem = new MockSubsystem(); + mockSubsystem.throwError = true; + flightComputer.registerSubsystem(mockSubsystem); + flightComputer.tick(); + mockSubsystem.hasUpdateCalled = false; + mockSubsystem.throwError = false; + flightComputer.tick(); + assertTrue(mockSubsystem.hasUpdateCalled); + } + + @Test + public void flightComputerReportsErrorToTelemetry() { + FlightComputer flightComputer = new FlightComputer.Builder() + .withTelemetry(telemetry) + .build(); + MockSubsystem mockSubsystem = new MockSubsystem(); + mockSubsystem.throwError = true; + flightComputer.registerSubsystem(mockSubsystem); + flightComputer.tick(); + assertEquals(1, this.errorList.size()); + assertEquals(Errors.TOP_LEVEL_EXCEPTION, this.errorList.get(0)); + } + + @Test + public void errorInReportErrorAllowContinuedExecution() { + FlightComputer flightComputer = new FlightComputer.Builder() + .withTelemetry(telemetry) + .build(); + MockSubsystem mockSubsystem = new MockSubsystem(); + mockSubsystem.throwError = true; + this.throwErrorOnError = true; + flightComputer.registerSubsystem(mockSubsystem); + flightComputer.tick(); + mockSubsystem.hasUpdateCalled = false; + mockSubsystem.throwError = false; + flightComputer.tick(); + assertTrue(mockSubsystem.hasUpdateCalled); + } + + @Test + public void errorAllowContinuedExecutionInSameTick() { + FlightComputer flightComputer = new FlightComputer.Builder() + .withTelemetry(telemetry) + .build(); + MockSubsystem mockSubsystem1 = new MockSubsystem(); + mockSubsystem1.throwError = true; + flightComputer.registerSubsystem(mockSubsystem1); + MockSubsystem mockSubsystem2 = new MockSubsystem(); + mockSubsystem2.throwError = false; + flightComputer.registerSubsystem(mockSubsystem2); + flightComputer.tick(); + assertTrue(mockSubsystem2.hasUpdateCalled); + } + + @Test(expected = Test.None.class) + public void runOnGoodArguments() { + FlightComputer flightComputer = FlightComputer.create(new String[]{"--real-sensors"}); + } + + @Test(expected = SecurityException.class) + public void exitOnBadArguments() { + FlightComputer flightComputer = FlightComputer.create(new String[]{"--fake-arguments"}); + } + + @Test(expected = SecurityException.class) + public void exitOnHelp() { + FlightComputer flightComputer = FlightComputer.create(new String[]{"--help"}); + } } From 6e76c94dffdb81f90889fb02eda323799aeceda7 Mon Sep 17 00:00:00 2001 From: Chi Chow Date: Sat, 17 Apr 2021 13:09:09 -0700 Subject: [PATCH 5/7] I just clicked "Reformat Code" button... --- .../flightcomputer/ErrorReporter.java | 23 +- .../flightcomputer/Errors.java | 11 +- .../flightcomputer/FlightComputer.java | 383 ++++++++--------- .../flightcomputer/Info.java | 8 +- .../flightcomputer/Main.java | 13 +- .../flightcomputer/SensorProvider.java | 72 ++-- .../flightcomputer/SettingSectionHeader.java | 6 +- .../flightcomputer/Settings.java | 64 +-- .../flightcomputer/Time.java | 5 +- .../flightcomputer/UserSetting.java | 13 +- .../flightcomputer/comm/FramedSCM.java | 34 +- .../flightcomputer/comm/GPSPacket.java | 50 +-- .../flightcomputer/comm/GPSTransceiver.java | 6 +- .../flightcomputer/comm/PacketDirection.java | 20 +- .../flightcomputer/comm/PacketRelay.java | 6 +- .../flightcomputer/comm/PacketRouter.java | 23 +- .../flightcomputer/comm/PacketSources.java | 37 +- .../flightcomputer/comm/SCMPacket.java | 40 +- .../flightcomputer/comm/SCMPacketType.java | 55 +-- .../flightcomputer/comm/SCMTransceiver.java | 14 +- .../flightcomputer/commands/AbortCommand.java | 62 +-- .../flightcomputer/commands/Command.java | 7 +- .../commands/HeartbeatCommand.java | 19 +- .../commands/LaunchCommand.java | 62 +-- .../commands/OpenDrogueChuteCommand.java | 90 ++-- .../commands/OpenMainChuteCommand.java | 90 ++-- .../commands/SetValveCommand.java | 6 +- .../commands/UpdateSettingCommand.java | 58 +-- .../events/EngineEventListener.java | 9 +- .../events/FlightStateListener.java | 3 +- .../flightcomputer/events/PacketListener.java | 5 +- .../events/ParachuteListener.java | 8 +- .../events/PositionListener.java | 5 +- .../flightcomputer/events/SerialListener.java | 7 +- .../events/VelocityListener.java | 7 +- .../flightcomputer/hal/AccelGyroReading.java | 13 +- .../hal/AccelerometerGyroscope.java | 7 +- .../flightcomputer/hal/Barometer.java | 8 +- .../hal/DummyPiCommandsImu.java | 24 +- .../flightcomputer/hal/LPS22HD.java | 50 ++- .../flightcomputer/hal/LSM9DS1AccelGyro.java | 218 +++++----- .../flightcomputer/hal/LSM9DS1Mag.java | 208 +++++----- .../flightcomputer/hal/MAX14830.java | 112 +++-- .../flightcomputer/hal/MAX31856.java | 100 +++-- .../flightcomputer/hal/MagReading.java | 11 +- .../flightcomputer/hal/Magnetometer.java | 7 +- .../flightcomputer/hal/PollingGroup.java | 5 +- .../flightcomputer/hal/PollingSensor.java | 3 +- .../flightcomputer/hal/RegisterValue.java | 13 +- .../flightcomputer/hal/SamplableSensor.java | 9 +- .../flightcomputer/hal/SaraSMSSender.java | 106 +++-- .../flightcomputer/hal/SensorPoller.java | 23 +- .../flightcomputer/hal/SerialPort.java | 24 +- .../flightcomputer/hal/SerialPortAdapter.java | 11 +- .../flightcomputer/hal/Solenoid.java | 7 +- .../flightcomputer/hal/Thermocouple.java | 8 +- .../hal/TimeBasedSensorSampler.java | 31 +- .../flightcomputer/hal/Valves.java | 2 +- .../looper/DurationRequiredEvent.java | 4 +- .../flightcomputer/looper/GenericEvent.java | 4 +- .../flightcomputer/looper/Looper.java | 4 +- .../looper/ScheduledConditionEvent.java | 2 +- .../math/InterpolatingVector3.java | 1 + .../flightcomputer/math/Quaternion.java | 33 +- .../flightcomputer/math/StatisticArray.java | 49 ++- .../math/StatisticReporter.java | 41 +- .../flightcomputer/math/TimedRingBuffer.java | 58 ++- .../flightcomputer/math/Vector3.java | 7 +- .../mockPi4J/DummyGpioPinImpl.java | 388 +++++++++--------- .../subsystems/EngineSubsystem.java | 85 ++-- .../subsystems/GPSMessageSubsystem.java | 79 ++-- .../subsystems/LandedSMSSubsystem.java | 10 +- .../subsystems/ParachuteSubsystem.java | 270 ++++++------ .../subsystems/SensorSubsystem.java | 15 +- .../subsystems/StatsSubsystem.java | 15 +- .../flightcomputer/subsystems/Subsystem.java | 3 +- .../flightcomputer/subsystems/Telemetry.java | 46 +-- .../subsystems/ValveStateSubsystem.java | 176 ++++---- .../flightcomputer/tracking/FlightMode.java | 3 +- .../flightcomputer/tracking/FlightState.java | 23 +- .../tracking/VelocityCalculator.java | 4 +- 81 files changed, 1799 insertions(+), 1842 deletions(-) diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/ErrorReporter.java b/src/org/rocketproplab/marginalstability/flightcomputer/ErrorReporter.java index 74be501..aee71b7 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/ErrorReporter.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/ErrorReporter.java @@ -1,9 +1,9 @@ package org.rocketproplab.marginalstability.flightcomputer; -import java.io.PrintStream; - import org.rocketproplab.marginalstability.flightcomputer.subsystems.Telemetry; +import java.io.PrintStream; + /** * A class to report errors which are encountered during the operation of the * flight computer. Errors get logged to a printstream and to the Telemetry @@ -13,9 +13,8 @@ * along with a copy of that print stream writing to stderr. That was * interactive applications can report errors instantly while all errors will be * recorded. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class ErrorReporter { @@ -23,7 +22,7 @@ public class ErrorReporter { /** * Instantiate the singleton if not already and return it. - * + * * @return A singleton of type ErrorReporter */ public static ErrorReporter getInstance() { @@ -36,7 +35,7 @@ public static ErrorReporter getInstance() { /** * Sets the singleton in case you want to output to a particular stream. This * should be called before any calls to {@link #getInstance()}. - * + * * @param reporter the new singleton */ public static void setInstance(ErrorReporter reporter) { @@ -44,7 +43,7 @@ public static void setInstance(ErrorReporter reporter) { } private PrintStream stream; - private Telemetry telemetry; + private Telemetry telemetry; /** * No arg constructor that should print to stderr and not send telemetry. @@ -57,12 +56,12 @@ public ErrorReporter() { /** * Error reporter that should print to the given print stream and send telemetry * to the given telemetry. - * + * * @param stream the stream to print to * @param telemetry the telemetry object to use to send telemetry. */ public ErrorReporter(PrintStream stream, Telemetry telemetry) { - this.stream = stream; + this.stream = stream; this.telemetry = telemetry; } @@ -112,7 +111,7 @@ public void reportError(Exception exception, String extraInfo) { * Reports a given error, exception and extra info. The String gets sent to the * printstream along with the exception if present. The Errors enum gets * reported to telemetry. All parameters may be null. - * + * * @param error What error should be reported to the telemetry, may be null. * @param exception What exception caused the error, may be null. * @param extraInfo Additional useful text related to the error, may be null. @@ -122,7 +121,7 @@ public void reportError(Errors error, Exception exception, String extraInfo) { stream.print(extraInfo); stream.print("\n"); } - + if (error != null) { stream.print(error); stream.print("\n"); @@ -130,7 +129,7 @@ public void reportError(Errors error, Exception exception, String extraInfo) { telemetry.reportError(error); } } - + if (exception != null) { exception.printStackTrace(stream); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/Errors.java b/src/org/rocketproplab/marginalstability/flightcomputer/Errors.java index 9bc822b..0484a50 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/Errors.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/Errors.java @@ -3,25 +3,26 @@ public enum Errors { UNKNOWN_ERROR("Unexpected error occured!"), - TOP_LEVEL_EXCEPTION("Exception in main loop occured"), + TOP_LEVEL_EXCEPTION("Exception in main loop occured"), IMU_IO_ERROR("Unable to read IMU over SPI"), MAX14830_IO_ERROR("Unable to access /dev/spix.x via Pi4J"), LPS22HD_INITIALIZATION_ERROR("Unable to write from i2cDevice IO Exception"), LPS22HD_PRESSURE_IO_ERROR("Unable to read Pressure from i2cDevice IO Exception"); - + private String errorMessage; - + /** * Sets the error message in the error + * * @param errorMessage */ Errors(String errorMessage) { this.errorMessage = errorMessage; } - + @Override public String toString() { return this.errorMessage; } - + } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java b/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java index 71c1213..d9bec09 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java @@ -9,230 +9,231 @@ import java.util.logging.Logger; public class FlightComputer { - private static FlightComputer instance; - - /** - * Creates a FlightComputer instance, which can only be created once. - * - * @param args arguments to configure FightComputer settings - * @return new FlightComputer instance - */ - public static FlightComputer create(String[] args) { - if (instance != null) { - throw new RuntimeException("FlightComputer has already been created."); - } - instance = new FlightComputer(args); - return instance; + private static FlightComputer instance; + + /** + * Creates a FlightComputer instance, which can only be created once. + * + * @param args arguments to configure FightComputer settings + * @return new FlightComputer instance + */ + public static FlightComputer create(String[] args) { + if (instance != null) { + throw new RuntimeException("FlightComputer has already been created."); } + instance = new FlightComputer(args); + return instance; + } + + /** + * Convenient method to create a FlightComputer instance without any arguments. + * + * @return new FlightComputer instance + */ + public static FlightComputer create() { + return create(new String[0]); + } + + /** + * Time used by all objects created in the FC. + */ + private final Time time; + + /** + * Looper used by objects created in the FC, e.g. subsystems. + */ + private final Looper looper; + + private PacketRouter packetRouter = new PacketRouter(); + private Telemetry telemetry = new Telemetry(Logger.getLogger("Telemetry"), packetRouter); + + /** + * Providers to provide singleton objects to higher level management objects. + */ + private SensorProvider sensorProvider; + + /** + * Private FlightComputer constructor to avoid multiple initializations. + * + * @param args arguments to configure FlightComputer settings + */ + private FlightComputer(String[] args) { + this.time = new Time(); + this.looper = new Looper(this.time); + initWithArgs(args); + } + + /** + * Initialize input/output devices and other settings based on arguments. + * + * @param args arguments for configuration + */ + private void initWithArgs(String[] args) { + ParseCmdLine cmd = new ParseCmdLine(args); + + // use real/fake sensors + sensorProvider = SensorProvider.create(cmd.useRealSensors); + } + + /** + * Allows subsystems to register events and callbacks with the looper. + * + * @param subsystem subsystem to register + */ + public void registerSubsystem(Subsystem subsystem) { + subsystem.prepare(this.looper); + } + + /** + * After all input/output devices and settings are initialized, higher level objects can be created. + * Use objects provided by the providers, and simply inject all objects needed to create any higher level object. + */ + public void initHighLevelObjects() { + + // PacketRouter + PacketRouter packetRouter = new PacketRouter(); + + // Telemetry + Telemetry telemetry = new Telemetry(Logger.getLogger("Telemetry"), packetRouter); + + telemetry.logInfo(Info.INIT_SUBSYSTEMS_START); + + // ParachuteSubsystem + registerSubsystem(new ParachuteSubsystem(null, null, null, null)); + + // SensorSubsystem + SensorSubsystem sensorSubsystem = new SensorSubsystem(this.time); + // add sensors + telemetry.logInfo(Info.DONE_CREATING_SENSORS); + registerSubsystem(sensorSubsystem); + + // SCMCommandSubsystem + registerSubsystem(new SCMCommandSubsystem()); // TODO: should listen to PacketRouter + + // ValveStateSubsystem + packetRouter.addListener(new ValveStateSubsystem(packetRouter), SCMPacket.class, + PacketSources.EngineControllerUnit); + + telemetry.logInfo(Info.FINISH_SUBSYSTEM_START); + } + + public void tick() { + this.looper.tick((tag, from, exception) -> { + try { + this.telemetry.reportError(Errors.TOP_LEVEL_EXCEPTION); + } catch (Exception e) { + System.err.println("Unable to log errors!"); + e.printStackTrace(); + } + }); + } + + /** + * Builder class to create FlightComputer objects with more customization. + */ + public static class Builder { + private Telemetry telemetry; + private final FlightComputer fc; /** - * Convenient method to create a FlightComputer instance without any arguments. + * Creates a new Builder instance, which can be used to customize the FC. * - * @return new FlightComputer instance + * @param args arguments to configure FlightComputer settings. */ - public static FlightComputer create() { - return create(new String[0]); + public Builder(String[] args) { + fc = FlightComputer.create(args); } /** - * Time used by all objects created in the FC. - */ - private final Time time; - - /** - * Looper used by objects created in the FC, e.g. subsystems. - */ - private final Looper looper; - - private PacketRouter packetRouter = new PacketRouter(); - private Telemetry telemetry = new Telemetry(Logger.getLogger("Telemetry"), packetRouter); - - /** - * Providers to provide singleton objects to higher level management objects. + * Convenient method to create a Builder instance without any arguments. */ - private SensorProvider sensorProvider; + public Builder() { + this(new String[0]); + } /** - * Private FlightComputer constructor to avoid multiple initializations. + * Set custom telemetry. * - * @param args arguments to configure FlightComputer settings + * @param telemetry customized telemetry + * @return this Builder */ - private FlightComputer(String[] args) { - this.time = new Time(); - this.looper = new Looper(this.time); - initWithArgs(args); + public Builder withTelemetry(Telemetry telemetry) { + this.telemetry = telemetry; + return this; } /** - * Initialize input/output devices and other settings based on arguments. + * Customizations set programmatically in the Builder will override defaults and arguments. * - * @param args arguments for configuration + * @return customized FlightComputer */ - private void initWithArgs(String[] args) { - ParseCmdLine cmd = new ParseCmdLine(args); - - // use real/fake sensors - sensorProvider = SensorProvider.create(cmd.useRealSensors); + public FlightComputer build() { + if (telemetry != null) fc.telemetry = this.telemetry; + return fc; } + } + /** + * Defines command line options and possible arguments. + * Also prints help and exits if invalid arguments are detected. + */ + private static class ParseCmdLine { /** - * Allows subsystems to register events and callbacks with the looper. - * - * @param subsystem subsystem to register + * CLI argument names and descriptions */ - public void registerSubsystem(Subsystem subsystem) { - subsystem.prepare(this.looper); - } + private static final String + HELP = "--help", + HELP_DESC = "print help menu", + REAL_SENSORS = "--real-sensors", + REAL_SENSORS_DESC = "use real sensors"; /** - * After all input/output devices and settings are initialized, higher level objects can be created. - * Use objects provided by the providers, and simply inject all objects needed to create any higher level object. + * Real sensor flag */ - public void initHighLevelObjects() { - - // PacketRouter - PacketRouter packetRouter = new PacketRouter(); - - // Telemetry - Telemetry telemetry = new Telemetry(Logger.getLogger("Telemetry"), packetRouter); - - telemetry.logInfo(Info.INIT_SUBSYSTEMS_START); - - // ParachuteSubsystem - registerSubsystem(new ParachuteSubsystem(null, null, null, null)); - - // SensorSubsystem - SensorSubsystem sensorSubsystem = new SensorSubsystem(this.time); - // add sensors - telemetry.logInfo(Info.DONE_CREATING_SENSORS); - registerSubsystem(sensorSubsystem); - - // SCMCommandSubsystem - registerSubsystem(new SCMCommandSubsystem()); // TODO: should listen to PacketRouter - - // ValveStateSubsystem - packetRouter.addListener(new ValveStateSubsystem(packetRouter), SCMPacket.class, - PacketSources.EngineControllerUnit); - - telemetry.logInfo(Info.FINISH_SUBSYSTEM_START); - } - - public void tick() { - this.looper.tick((tag, from, exception) -> { - try { - this.telemetry.reportError(Errors.TOP_LEVEL_EXCEPTION); - } catch (Exception e) { - System.err.println("Unable to log errors!"); - e.printStackTrace(); - } - }); - } + private boolean useRealSensors = false; /** - * Builder class to create FlightComputer objects with more customization. + * Constructs a new object to parse CLI arguments + * + * @param args arguments to parse */ - public static class Builder { - private Telemetry telemetry; - private final FlightComputer fc; - - /** - * Creates a new Builder instance, which can be used to customize the FC. - * - * @param args arguments to configure FlightComputer settings. - */ - public Builder(String[] args) { - fc = FlightComputer.create(args); - } - - /** - * Convenient method to create a Builder instance without any arguments. - */ - public Builder() { - this(new String[0]); - } - - /** - * Set custom telemetry. - * - * @param telemetry customized telemetry - * @return this Builder - */ - public Builder withTelemetry(Telemetry telemetry) { - this.telemetry = telemetry; - return this; - } - - /** - * Customizations set programmatically in the Builder will override defaults and arguments. - * - * @return customized FlightComputer - */ - public FlightComputer build() { - if (telemetry != null) fc.telemetry = this.telemetry; - return fc; - } + private ParseCmdLine(String[] args) { + parse(args); } /** - * Defines command line options and possible arguments. - * Also prints help and exits if invalid arguments are detected. + * Checks arguments against each setting + * + * @param args */ - private static class ParseCmdLine { - /** - * CLI argument names and descriptions - */ - private static final String - HELP = "--help", - HELP_DESC = "print help menu", - REAL_SENSORS = "--real-sensors", - REAL_SENSORS_DESC = "use real sensors"; - - /** - * Real sensor flag - */ - private boolean useRealSensors = false; - - /** - * Constructs a new object to parse CLI arguments - * - * @param args arguments to parse - */ - private ParseCmdLine(String[] args) { - parse(args); - } - - /** - * Checks arguments against each setting - * @param args - */ - private void parse(String[] args) { - // help - if (args.length == 1 && args[0].equals("--help")) { - printHelp(); - System.exit(0); - } - - // settings - int i = 0; - while (i < args.length) { - String arg = args[i]; - if (arg.equals(REAL_SENSORS)) { - useRealSensors = true; - System.out.println(REAL_SENSORS_DESC); - } else { - System.out.println("Invalid argument: " + arg); - printHelp(); - System.exit(1); - } - i++; - } + private void parse(String[] args) { + // help + if (args.length == 1 && args[0].equals("--help")) { + printHelp(); + System.exit(0); + } + + // settings + int i = 0; + while (i < args.length) { + String arg = args[i]; + if (arg.equals(REAL_SENSORS)) { + useRealSensors = true; + System.out.println(REAL_SENSORS_DESC); + } else { + System.out.println("Invalid argument: " + arg); + printHelp(); + System.exit(1); } + i++; + } + } - private void printHelp() { - System.out.println("Usage:\n" - + HELP + ": " + HELP_DESC + "\n" - + REAL_SENSORS + ": " + REAL_SENSORS_DESC - ); - } + private void printHelp() { + System.out.println("Usage:\n" + + HELP + ": " + HELP_DESC + "\n" + + REAL_SENSORS + ": " + REAL_SENSORS_DESC + ); } + } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/Info.java b/src/org/rocketproplab/marginalstability/flightcomputer/Info.java index 7edd808..3fda0e1 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/Info.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/Info.java @@ -4,13 +4,13 @@ public enum Info { INIT_SUBSYSTEMS_START("Starting Subsystems."), FINISH_SUBSYSTEM_START("Subsystems started."), DONE_CREATING_SENSORS("Finished creating sensors."); - + private String description; - - Info(String description){ + + Info(String description) { this.description = description; } - + public String getDescription() { return this.description; } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/Main.java b/src/org/rocketproplab/marginalstability/flightcomputer/Main.java index 112d246..889e5a9 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/Main.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/Main.java @@ -1,10 +1,5 @@ package org.rocketproplab.marginalstability.flightcomputer; -import org.rocketproplab.marginalstability.flightcomputer.comm.PacketRouter; -import org.rocketproplab.marginalstability.flightcomputer.comm.PacketSources; -import org.rocketproplab.marginalstability.flightcomputer.comm.SCMPacket; -import org.rocketproplab.marginalstability.flightcomputer.subsystems.*; - /** * The main file contains the entry point to the software stack. It is * responsible for instantiating the @@ -44,12 +39,12 @@ * */ public class Main { - public static void main(String[] args) { - FlightComputer flightComputer = FlightComputer.create(args); - flightComputer.initHighLevelObjects(); + public static void main(String[] args) { + FlightComputer flightComputer = FlightComputer.create(args); + flightComputer.initHighLevelObjects(); // while(true) { // flightComputer.tick(); // } - } + } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/SensorProvider.java b/src/org/rocketproplab/marginalstability/flightcomputer/SensorProvider.java index 0fdc65f..3f5aff1 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/SensorProvider.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/SensorProvider.java @@ -9,47 +9,47 @@ */ public abstract class SensorProvider { - abstract LPS22HD getPressureSensor(); + abstract LPS22HD getPressureSensor(); - private static SensorProvider instance; + private static SensorProvider instance; - /** - * Create singleton SensorProvider. - * - * @param useRealSensors whether to use real sensors or simulators - * @return new SensorProvider instance - */ - public static SensorProvider create(boolean useRealSensors) { - if (instance != null) { - throw new RuntimeException("SensorProvider has already been created."); - } - if (useRealSensors) { - instance = new RealSensorProvider(); - } else { - instance = new SimulatorProvider(); - } - return instance; + /** + * Create singleton SensorProvider. + * + * @param useRealSensors whether to use real sensors or simulators + * @return new SensorProvider instance + */ + public static SensorProvider create(boolean useRealSensors) { + if (instance != null) { + throw new RuntimeException("SensorProvider has already been created."); } + if (useRealSensors) { + instance = new RealSensorProvider(); + } else { + instance = new SimulatorProvider(); + } + return instance; + } - /** - * SensorProvider that returns simulators - */ - private static class SimulatorProvider extends SensorProvider { - @Override - public LPS22HD getPressureSensor() { - // TODO: implement methods to get different simulators - throw new RuntimeException("Not implemented!"); - } + /** + * SensorProvider that returns simulators + */ + private static class SimulatorProvider extends SensorProvider { + @Override + public LPS22HD getPressureSensor() { + // TODO: implement methods to get different simulators + throw new RuntimeException("Not implemented!"); } + } - /** - * SensorProvider that returns real sensors - */ - private static class RealSensorProvider extends SensorProvider { - @Override - public LPS22HD getPressureSensor() { - // TODO: implement methods to get different real sensors - throw new RuntimeException("Not implemented!"); - } + /** + * SensorProvider that returns real sensors + */ + private static class RealSensorProvider extends SensorProvider { + @Override + public LPS22HD getPressureSensor() { + // TODO: implement methods to get different real sensors + throw new RuntimeException("Not implemented!"); } + } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/SettingSectionHeader.java b/src/org/rocketproplab/marginalstability/flightcomputer/SettingSectionHeader.java index e6cd8b4..de5e749 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/SettingSectionHeader.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/SettingSectionHeader.java @@ -1,11 +1,11 @@ package org.rocketproplab.marginalstability.flightcomputer; -import static java.lang.annotation.ElementType.FIELD; -import static java.lang.annotation.RetentionPolicy.RUNTIME; - import java.lang.annotation.Retention; import java.lang.annotation.Target; +import static java.lang.annotation.ElementType.FIELD; +import static java.lang.annotation.RetentionPolicy.RUNTIME; + @Retention(RUNTIME) @Target(FIELD) public @interface SettingSectionHeader { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/Settings.java b/src/org/rocketproplab/marginalstability/flightcomputer/Settings.java index c4f862c..a83d336 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/Settings.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/Settings.java @@ -31,11 +31,11 @@ public class Settings { */ @UserSetting(comment = "Time threshold needed to exceed to deploy the main chute", units = "s") public static double MAIN_CHUTE_PRESSURE_TIME_THRESHOLD = 10; // TODO: set time exceeding the threshold needed to - // deploy main chute + // deploy main chute - public static boolean[] ENGINE_ON_VALVE_STATES = { true, true, true, true, true }; + public static boolean[] ENGINE_ON_VALVE_STATES = {true, true, true, true, true}; - public static boolean[] ENGINE_ABORT_VALVE_STATES = { true, true, true, true, true }; + public static boolean[] ENGINE_ABORT_VALVE_STATES = {true, true, true, true, true}; // Unit conversions @@ -57,16 +57,16 @@ public class Settings { @SettingSectionHeader(name = "PT Quadratic Regression") @UserSetting(comment = "'a' constant for quadratic regression for pressure transducers", units = "hPa / V^2") - public static double[] A_PT_CONSTANTS = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, - 0.0 }; + public static double[] A_PT_CONSTANTS = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0}; @UserSetting(comment = "'b' constant for quadratic regression for pressure transducers", units = "hPa / V") - public static double[] B_PT_CONSTANTS = { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, - 1.0 }; + public static double[] B_PT_CONSTANTS = {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, + 1.0}; @UserSetting(comment = "'c' constant for quadratic regression for pressure transducers", units = "hPa") - public static double[] C_PT_CONSTANTS = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, - 0.0 }; + public static double[] C_PT_CONSTANTS = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, + 0.0}; @UserSetting(comment = "Phone number to text position to", units = "1xxxyyyyyyy") public static String PHONE_NUMBER = "13150001111"; @@ -78,15 +78,15 @@ public class Settings { @SettingSectionHeader(name = "LSM9DS1 settings") - public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_2G = 0.00006103; - public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_4G = 0.00012207; - public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_8G = 0.00024414; - public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_16G = 0.000732; - public static double LSM9DS1_SENSITIVITY_GYROSCOPE_245DPS = 0.00875; - public static double LSM9DS1_SENSITIVITY_GYROSCOPE_500DPS = 0.0175; - public static double LSM9DS1_SENSITIVITY_GYROSCOPE_2000DPS = 0.07; - public static double LSM9DS1_SENSITIVITY_MAGNETOMETER_4GAUSS = 0.00014; - public static double LSM9DS1_SENSITIVITY_MAGNETOMETER_8GAUSS = 0.00029; + public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_2G = 0.00006103; + public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_4G = 0.00012207; + public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_8G = 0.00024414; + public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_16G = 0.000732; + public static double LSM9DS1_SENSITIVITY_GYROSCOPE_245DPS = 0.00875; + public static double LSM9DS1_SENSITIVITY_GYROSCOPE_500DPS = 0.0175; + public static double LSM9DS1_SENSITIVITY_GYROSCOPE_2000DPS = 0.07; + public static double LSM9DS1_SENSITIVITY_MAGNETOMETER_4GAUSS = 0.00014; + public static double LSM9DS1_SENSITIVITY_MAGNETOMETER_8GAUSS = 0.00029; public static double LSM9DS1_SENSITIVITY_MAGNETOMETER_12GAUSS = 0.00043; public static double LSM9DS1_SENSITIVITY_MAGNETOMETER_16GAUSS = 0.00058; @@ -101,8 +101,8 @@ private static Set getSettingFields() { } public static String getConfigContents() { - String result = ""; - Set set = getSettingFields(); + String result = ""; + Set set = getSettingFields(); for (Field field : set) { result += fieldAsString(field) + "\n"; } @@ -114,8 +114,8 @@ public static String fieldAsString(Field field) { if (field.isAnnotationPresent(SettingSectionHeader.class)) { String sectionHeader = "# " + field.getAnnotation(SettingSectionHeader.class).name() + " |\n"; - int dashLength = sectionHeader.length() - 2; - String delimiter = "#" + new String(new char[dashLength]).replace('\0', '-') + "\n"; + int dashLength = sectionHeader.length() - 2; + String delimiter = "#" + new String(new char[dashLength]).replace('\0', '-') + "\n"; result += delimiter + sectionHeader + delimiter + "\n"; } @@ -168,7 +168,7 @@ protected static Set getUsefulLinesFromConfig(List config) { Set usefulLines = new HashSet<>(); for (String line : config) { String lineWithoutComment = line; - int commentStartIdx = line.indexOf('#'); + int commentStartIdx = line.indexOf('#'); if (commentStartIdx >= 0) { lineWithoutComment = line.substring(0, commentStartIdx); } @@ -182,7 +182,7 @@ protected static Set getUsefulLinesFromConfig(List config) { } protected static Map getFieldNameValueMap(List config) { - Set usefulLines = getUsefulLinesFromConfig(config); + Set usefulLines = getUsefulLinesFromConfig(config); Map fieldNameValueMap = new HashMap<>(); for (String line : usefulLines) { int equalsIndex = line.indexOf('='); @@ -191,16 +191,16 @@ protected static Map getFieldNameValueMap(List config) { continue; } String fieldName = line.substring(0, equalsIndex); - String value = line.substring(equalsIndex + 1); + String value = line.substring(equalsIndex + 1); fieldNameValueMap.put(fieldName.trim(), value); } return fieldNameValueMap; } protected static void setFieldDoubleArray(Field field, String line) - throws IllegalArgumentException, IllegalAccessException { + throws IllegalArgumentException, IllegalAccessException { line = line.trim().replace("[", "").replace("]", ""); - String[] newValues = line.split(","); + String[] newValues = line.split(","); double[] fieldValues = (double[]) field.get(null); if (newValues.length != fieldValues.length) { System.err.println("Array length mismatch: " + line); @@ -212,7 +212,7 @@ protected static void setFieldDoubleArray(Field field, String line) } protected static void setFieldDouble(Field field, String line) - throws IllegalArgumentException, IllegalAccessException { + throws IllegalArgumentException, IllegalAccessException { line = line.trim(); double value = Double.parseDouble(line); field.set(null, value); @@ -243,9 +243,9 @@ protected static void setFieldFromConfigLine(Field field, String line) { } public static boolean readSettingsFromConfig(List config, boolean checkOutOfDate) { - Set settingFields = getSettingFields(); + Set settingFields = getSettingFields(); Map fieldNameValueMap = getFieldNameValueMap(config); - boolean outOfDate = false; + boolean outOfDate = false; for (Field field : settingFields) { String fieldName = getNameFromField(field); if (fieldNameValueMap.containsKey(fieldName)) { @@ -268,8 +268,8 @@ private static String getSettingsFileLocation() { } public static void readSettings() { - String configFileLocation = getSettingsFileLocation(); - List lines = Collections.emptyList(); + String configFileLocation = getSettingsFileLocation(); + List lines = Collections.emptyList(); try { lines = Files.readAllLines(Paths.get(configFileLocation)); } catch (IOException e) { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/Time.java b/src/org/rocketproplab/marginalstability/flightcomputer/Time.java index bb76dd1..de79841 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/Time.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/Time.java @@ -3,16 +3,15 @@ /** * A class to get the current rocket time. At the moment its implementation * passed through to System.currentTimeMillis but this might change. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class Time { /** * Get the rocket time, this might change at some point in the future. This * value should be used for all interpolations. - * + * * @return the current rocket time */ public double getSystemTime() { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/UserSetting.java b/src/org/rocketproplab/marginalstability/flightcomputer/UserSetting.java index 0a64c3c..64e6cb4 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/UserSetting.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/UserSetting.java @@ -1,12 +1,12 @@ package org.rocketproplab.marginalstability.flightcomputer; -import static java.lang.annotation.ElementType.FIELD; -import static java.lang.annotation.RetentionPolicy.RUNTIME; - import java.lang.annotation.Documented; import java.lang.annotation.Retention; import java.lang.annotation.Target; +import static java.lang.annotation.ElementType.FIELD; +import static java.lang.annotation.RetentionPolicy.RUNTIME; + @Retention(RUNTIME) @Target(FIELD) @Documented @@ -18,18 +18,21 @@ public @interface UserSetting { /** * The name to use for the settings config file. If "" then the field name should be used. + * * @return the name to use for the settings file, "" if field name should be used */ String name() default ""; - + /** * The comment to display in the settings config file. "" will not be written to the file. + * * @return the comment for the settings file */ String comment(); - + /** * The units to display in the settings file. "" will not be written to the file. + * * @return the units for the settings file */ String units(); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/FramedSCM.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/FramedSCM.java index 57d6694..019cebf 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/FramedSCM.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/FramedSCM.java @@ -1,10 +1,10 @@ package org.rocketproplab.marginalstability.flightcomputer.comm; +import org.rocketproplab.marginalstability.flightcomputer.events.PacketListener; + import java.util.LinkedList; import java.util.Queue; -import org.rocketproplab.marginalstability.flightcomputer.events.PacketListener; - /** * A message to handle the framing of extra long SCM packets. The format for an * extra long SCM packet is as follows.
@@ -26,11 +26,11 @@ * @author Max Apodaca */ public class FramedSCM implements PacketListener { - private Queue outputQueue; - private String activeString; - private int frameLength; - private PacketRelay sCMOutput; - private FramedPacketProcessor framedPacketOutput; + private Queue outputQueue; + private String activeString; + private int frameLength; + private PacketRelay sCMOutput; + private FramedPacketProcessor framedPacketOutput; /** * Create a new SCM de-framer. SCMOutput is used to send replied to incoming SCM @@ -40,11 +40,11 @@ public class FramedSCM implements PacketListener { * @param framedOutput the callback to output framed packets to */ public FramedSCM(PacketRelay sCMOutput, FramedPacketProcessor framedOutput) { - this.outputQueue = new LinkedList(); - this.activeString = ""; - this.frameLength = -1; + this.outputQueue = new LinkedList(); + this.activeString = ""; + this.frameLength = -1; framedPacketOutput = framedOutput; - this.sCMOutput = sCMOutput; + this.sCMOutput = sCMOutput; } @Override @@ -73,15 +73,15 @@ public void onPacket(PacketDirection direction, SCMPacket packet) { * @return the packet to reply with */ protected SCMPacket processNextPacket(SCMPacket incomingPacket) { - boolean completed = (activeString.length() == frameLength); + boolean completed = (activeString.length() == frameLength); SCMPacket returnpacket = new SCMPacket(SCMPacketType.XB, " "); - String finalmessage = ""; + String finalmessage = ""; if (!incomingPacket.isValid()) { return null; } if (incomingPacket.getID() == SCMPacketType.XS) { returnpacket = processXSPacket(incomingPacket); - completed = false; + completed = false; } else if (incomingPacket.getID() == SCMPacketType.X0) { returnpacket = processX0Packet(incomingPacket); @@ -103,9 +103,9 @@ private SCMPacket processX0Packet(SCMPacket incomingPacket) { if (frameLength == -1) { String[] SCMmessagesplit = incomingPacket.getData().split("\\|"); activeString += SCMmessagesplit[0]; - frameLength = Integer.parseInt(activeString); + frameLength = Integer.parseInt(activeString); activeString = SCMmessagesplit[1]; - // TODO Similar to XS, where if the frameLength is still less than 0 or + // TODO Similar to XS, where if the frameLength is still less than 0 or // does not split into several indices } else if (lengthofframeleft < incomingPacket.getData().length()) { activeString += incomingPacket.getData().substring(0, lengthofframeleft); @@ -135,7 +135,7 @@ private SCMPacket processXSPacket(SCMPacket incomingPacket) { } else { String getint = incomingPacket.getData(); activeString = "" + Integer.parseInt(getint); - frameLength = -1; + frameLength = -1; } return new SCMPacket(SCMPacketType.XB, " "); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSPacket.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSPacket.java index 3e82323..2deba0c 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSPacket.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSPacket.java @@ -8,25 +8,25 @@ */ public class GPSPacket { - private static final String NEMA_DELIMITER = ","; - private static final int NEMA_PART_LENGTH = 15; - private static final int NEMA_TIME_INDEX = 1; - private static final int NEMA_LAT_INDEX = 2; - private static final int NEMA_LON_INDEX = 4; - private static final int NEMA_SV_COUNT_INDEX = 7; - private static final int NEMA_ALTITUDE_INDEX = 9; + private static final String NEMA_DELIMITER = ","; + private static final int NEMA_PART_LENGTH = 15; + private static final int NEMA_TIME_INDEX = 1; + private static final int NEMA_LAT_INDEX = 2; + private static final int NEMA_LON_INDEX = 4; + private static final int NEMA_SV_COUNT_INDEX = 7; + private static final int NEMA_ALTITUDE_INDEX = 9; private boolean valid; - private double latitude; - private double longitude; - private double altitude; - private double time; - private int sVCount; - private String nema; + private double latitude; + private double longitude; + private double altitude; + private double time; + private int sVCount; + private String nema; /** * Create a new GPS Packet based on the NEMA String - * + * * @param nEMA the nema to make the packet of */ public GPSPacket(String nEMA) { @@ -36,7 +36,7 @@ public GPSPacket(String nEMA) { /** * Internally parses the NEMA for the packet - * + * * @param nEMA the nema to assign this packet to */ private void parseNEMA(String nEMA) { @@ -51,17 +51,17 @@ private void parseNEMA(String nEMA) { } this.valid = true; - String timeString = nEMAParts[NEMA_TIME_INDEX]; - String latString = nEMAParts[NEMA_LAT_INDEX]; - String lonString = nEMAParts[NEMA_LON_INDEX]; - String sVCountString = nEMAParts[NEMA_SV_COUNT_INDEX]; + String timeString = nEMAParts[NEMA_TIME_INDEX]; + String latString = nEMAParts[NEMA_LAT_INDEX]; + String lonString = nEMAParts[NEMA_LON_INDEX]; + String sVCountString = nEMAParts[NEMA_SV_COUNT_INDEX]; String altitudeString = nEMAParts[NEMA_ALTITUDE_INDEX]; - this.time = Double.parseDouble(timeString); - this.latitude = Double.parseDouble(latString); + this.time = Double.parseDouble(timeString); + this.latitude = Double.parseDouble(latString); this.longitude = Double.parseDouble(lonString); - this.sVCount = Integer.parseInt(sVCountString); - this.altitude = Double.parseDouble(altitudeString); + this.sVCount = Integer.parseInt(sVCountString); + this.altitude = Double.parseDouble(altitudeString); } /** @@ -102,7 +102,7 @@ public double getTime() { /** * Used as debug information for how many satellite vehicles (SVs) are connected * to the GPS. - * + * * @return the number of satellite vehicles connected to the GPS */ public int getSVCount() { @@ -115,7 +115,7 @@ public boolean equals(Object o) { return false; } GPSPacket other = (GPSPacket) o; - boolean equal = this.valid == other.valid; + boolean equal = this.valid == other.valid; equal &= (this.latitude - other.latitude) < Settings.EQUALS_EPSILON; equal &= (this.longitude - other.longitude) < Settings.EQUALS_EPSILON; equal &= (this.altitude - other.altitude) < Settings.EQUALS_EPSILON; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSTransceiver.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSTransceiver.java index 4b5e157..6d20174 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSTransceiver.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSTransceiver.java @@ -1,23 +1,21 @@ package org.rocketproplab.marginalstability.flightcomputer.comm; import org.rocketproplab.marginalstability.flightcomputer.ErrorReporter; -import org.rocketproplab.marginalstability.flightcomputer.Errors; import org.rocketproplab.marginalstability.flightcomputer.events.SerialListener; /** * A class to handle the sending and receiving information from the GPS. It will * Listener to a serial port and every time a valid full NMEA packet is received * it will parse the packet and send it to the packet router. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class GPSTransceiver implements SerialListener { private PacketRouter router; /** * Create a new GPS Transceiver that - * + * * @param router the router to use to route packets */ public GPSTransceiver(PacketRouter router) { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketDirection.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketDirection.java index bf7733e..8761ad7 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketDirection.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketDirection.java @@ -2,18 +2,18 @@ /** * The different ways a packet can be transmitted, either sending or receiving - * @author Max Apodaca * + * @author Max Apodaca */ public enum PacketDirection { - /** - * The packet is being sent to the other component - */ - SEND, - - /** - * The packet is coming to the flight computer - */ - RECIVE + /** + * The packet is being sent to the other component + */ + SEND, + + /** + * The packet is coming to the flight computer + */ + RECIVE } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRelay.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRelay.java index 23823a5..f488cd7 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRelay.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRelay.java @@ -2,17 +2,17 @@ /** * This interface has the ability to send a packet to a given location - * @author Max Apodaca * + * @author Max Apodaca */ public interface PacketRelay { /** * Sends a packet to the associated listeners. - * + * * @param o the packet to send (must be of packet type) * @param source where the packet is coming from */ public void sendPacket(Object o, PacketSources source); - + } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRouter.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRouter.java index 6948545..d96e546 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRouter.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRouter.java @@ -1,12 +1,11 @@ package org.rocketproplab.marginalstability.flightcomputer.comm; -import java.util.ArrayList; -import java.util.HashMap; - import org.rocketproplab.marginalstability.flightcomputer.ErrorReporter; -import org.rocketproplab.marginalstability.flightcomputer.Errors; import org.rocketproplab.marginalstability.flightcomputer.events.PacketListener; +import java.util.ArrayList; +import java.util.HashMap; + /** * Routes packets of any type to their destination.
* The routing works by having a Map between the type and source of the packet @@ -19,9 +18,8 @@ * class of the object) and source. See * {@link #dispatchPacket(Object, PacketSources, PacketDirection)} for more * information. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class PacketRouter implements PacketRelay { @@ -41,7 +39,7 @@ public void sendPacket(Object o, PacketSources source) { /** * Send a packet to all of the receivers - * + * * @param o the packet which is being sent (must be of packet type) * @param source */ @@ -53,12 +51,12 @@ public void recivePacket(Object o, PacketSources source) { * Dispatch a packet with the given direction to all of the appropriate * listeners. The packet listeners are looked up based off of a combination * between the direction and class hash. - * + * * @param o The packet to be transmitted * @param source the sender of the packet * @param direction what direction the packet is being sent in */ - @SuppressWarnings({ "unchecked", "rawtypes" }) + @SuppressWarnings({"unchecked", "rawtypes"}) private void dispatchPacket(Object o, PacketSources source, PacketDirection direction) { try { LookupTuple lookup = new LookupTuple(o.getClass(), source); @@ -78,7 +76,7 @@ private void dispatchPacket(Object o, PacketSources source, PacketDirection dire /** * Add a listener for a specific type of packet. Note that the listeners are * mapped using the hash of the Class object associated with that packet. - * + * * @param listener the packet listener listening to this packet * @param type the class which will be hashed to make lookup easier * @param source what source to listen from @@ -94,9 +92,8 @@ public void addListener(PacketListener listener, Class type, PacketSources /** * A class to get a nice hash code for the lookup map - * - * @author Max Apodaca * + * @author Max Apodaca */ private class LookupTuple { @@ -104,7 +101,7 @@ private class LookupTuple { /** * Create a new LookupTuple for the type and source - * + * * @param type the type of packet to look for * @param source the origin of the packet */ diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketSources.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketSources.java index 6b9ad4f..2ceec21 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketSources.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketSources.java @@ -2,29 +2,28 @@ /** * The different places packets can go and come from. - * - * @author Max Apodaca * + * @author Max Apodaca */ public enum PacketSources { - /** - * The packet is coming from or going to the Engine Controller Unit (ECU) - */ - EngineControllerUnit, + /** + * The packet is coming from or going to the Engine Controller Unit (ECU) + */ + EngineControllerUnit, + + /** + * The packet is coming from or going to the command box + */ + CommandBox, - /** - * The packet is coming from or going to the command box - */ - CommandBox, + /** + * The packet is coming from or going to the GPS + */ + GPS, - /** - * The packet is coming from or going to the GPS - */ - GPS, - - /** - * This packet is coming from or going to the Auxiliary GPS - */ - AUX_GPS + /** + * This packet is coming from or going to the Auxiliary GPS + */ + AUX_GPS } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacket.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacket.java index a14299a..f713c59 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacket.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacket.java @@ -1,19 +1,18 @@ package org.rocketproplab.marginalstability.flightcomputer.comm; import org.rocketproplab.marginalstability.flightcomputer.ErrorReporter; -import org.rocketproplab.marginalstability.flightcomputer.Errors; /** * A packet for the SCMProtocol to convert between the object and string * representation.
* The Simple Checksum Messaging (SCM) protocol consists of three sections. The * id, data and checksum organized as a plaintext string.
- * + * *
  * {@code | Id | Data  | Checksum |}
  * {@code   AA , BBBBB ,    FF    ;}
  * 
- * + *

* An example of a heartbeat packet would be {@code HB,12345,81;} where the ID * is HB, data is 12345 and checksum is 81.
* The checksum is calculated by summing the char code of each character up the @@ -21,24 +20,23 @@ * a character sequence from 00 to 99 and then a semicolon is appended. See * {@link #calculateChecksum(String)} for implementation details of the checksum * algorithm. - * - * @author Daniel Walder, Max Apodaca * + * @author Daniel Walder, Max Apodaca */ public class SCMPacket { - public static final int LAST_THREE_CHARS = 3; - public static final int NUM_CHARS_PACKET = 12; + public static final int LAST_THREE_CHARS = 3; + public static final int NUM_CHARS_PACKET = 12; public static final int NUM_COMPONENTS_PACKET = 3; - public static final int DATA_LENGTH = 5; + public static final int DATA_LENGTH = 5; private SCMPacketType id; - private String data; - private boolean isValid; + private String data; + private boolean isValid; /** * Constructor that passes the packet into it's components - * + * * @param packet the packet to be processed */ public SCMPacket(String packet) { @@ -47,12 +45,12 @@ public SCMPacket(String packet) { /** * Create a new packet based off of the ID and data - * + * * @param id the id of the packet * @param data the data which the packet holds */ public SCMPacket(SCMPacketType id, String data) { - this.id = id; + this.id = id; this.data = data; this.validate(); } @@ -60,7 +58,7 @@ public SCMPacket(SCMPacketType id, String data) { /** * Takes the packet assigns its id and data to the instance variables Also calls * verifyChecksum to confirm packet accuracy - * + * * @param packet the received packet to work with */ private void parsepacket(String packet) { @@ -78,7 +76,7 @@ private void parsepacket(String packet) { checksum = Integer.parseInt(strChecksum); } catch (NumberFormatException exception) { ErrorReporter errorReporter = ErrorReporter.getInstance(); - String errorMsg = "Unable to parse checksum in " + packet; + String errorMsg = "Unable to parse checksum in " + packet; errorReporter.reportError(null, exception, errorMsg); this.isValid = false; return; @@ -89,7 +87,7 @@ private void parsepacket(String packet) { this.id = SCMPacketType.valueOf(packetComponents[0]); } catch (IllegalArgumentException illegalArg) { ErrorReporter errorReporter = ErrorReporter.getInstance(); - String errorMsg = "Got bad packet ID (" + packetComponents[0] + ")!"; + String errorMsg = "Got bad packet ID (" + packetComponents[0] + ")!"; errorReporter.reportError(null, illegalArg, errorMsg); } this.data = packetComponents[1]; @@ -123,7 +121,7 @@ private void validate() { /** * Helper method for verifyChecksum for calculating the strChecksum - * + * * @param packet the packet in question * @return the checksum of the packet */ @@ -143,7 +141,7 @@ private static int calculateChecksum(String packet) { /** * Gets the ID of this packet. Only valid if {@link SCMPacket#isValid()} returns * true. - * + * * @return the id of the packet */ public SCMPacketType getID() { @@ -153,7 +151,7 @@ public SCMPacketType getID() { /** * Get the data in this packet. Only valid if {@link SCMPacket#isValid()} * returns true. - * + * * @return the data in this packet */ public String getData() { @@ -162,7 +160,7 @@ public String getData() { /** * Get whether or not this packet is valid. If invalid nothing is guarantee. - * + * * @return if the data in the packet is valid */ public boolean isValid() { @@ -172,7 +170,7 @@ public boolean isValid() { /** * Encodes id and data into a packet string. Will attempt to encode even with an * invalid state. - * + * * @return the packet as String */ @Override diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacketType.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacketType.java index 321043d..d606994 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacketType.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacketType.java @@ -5,20 +5,20 @@ public enum SCMPacketType { * Change the state of the valves, each index in data is a 1 or 0 that * Specifies valve 0-4. */ - V0("Valve State"), - + V0("Valve State"), + /** * Change the state of the valves, each index in data is a 1 or 0 that * Specifies valve 5-7. */ V1("Valve State"), - - V2("Valve State"), - - V3("Valve State"), - + + V2("Valve State"), + + V3("Valve State"), + HB("HB"), // TODO fill this packet in - + /** * Position of the GPS x coordinate. Bits are hex integer value (m) @@ -99,12 +99,12 @@ public enum SCMPacketType { * Reading of pressure transducer 4. Bits are integer value (PSI) */ P4("Pressure Transducer 4"), - + /** * Reading of pressure transducer 5. Bits are integer value (PSI) */ P5("Pressure Transducer 5"), - + /** * Reading of pressure transducer 6. Bits are integer value (PSI) */ @@ -114,47 +114,47 @@ public enum SCMPacketType { * Reading of pressure transducer 7. Bits are integer value (PSI) */ P7("Pressure Transducer 7"), - + /** * Reading of pressure transducer 8. Bits are integer value (PSI) */ P8("Pressure Transducer 8"), - + /** * Reading of pressure transducer 9. Bits are integer value (PSI) */ P9("Pressure Transducer 9"), - + /** * Reading of pressure transducer 10. Bits are integer value (PSI) */ PA("Pressure Transducer 10"), - + /** * Reading of pressure transducer 11. Bits are integer value (PSI) */ PB("Pressure Transducer 11"), - + /** * Reading of pressure transducer 12. Bits are integer value (PSI) */ PC("Pressure Transducer 12"), - + /** * Reading of pressure transducer 13. Bits are integer value (PSI) */ PD("Pressure Transducer 13"), - + /** * Reading of pressure transducer 14. Bits are integer value (PSI) */ PE("Pressure Transducer 14"), - + /** * Reading of pressure transducer 15. Bits are integer value (PSI) */ PF("Pressure Transducer 15"), - + /** * Error. The bits are the error code */ @@ -164,37 +164,37 @@ public enum SCMPacketType { * Warning. The bits are the warning code */ WA("Warning"), VS("VS"), - + /** * Drogue Chute Deploy */ DD("Drogue Chute Deploy"), - + /** * Main Chute Deploy */ MD("Main Chute Deploy"), - + /** * A packet to indicate the start of an extra long transmission, @see {@link FramedSCM} */ XS("Start extra long transmission"), - + /** * Indicates data for the extra long transmission, @see {@link FramedSCM} */ X0("Extra long data frame zero"), - + /** * Indicates data for the extra long transmission, @see {@link FramedSCM} */ X1("Extra long data frame one"), - + /** * Acknowledges the receipt of the {@link #X0} packet */ XA("Extra long ack to X0"), - + /** * Acknowledges the receipt of the {@link #X1} packet */ @@ -205,7 +205,7 @@ public enum SCMPacketType { /** * Create a new SCMPacketType enum element with the appropriate name to print * when relevant - * + * * @param name the full name of the packet type */ SCMPacketType(String name) { @@ -214,6 +214,7 @@ public enum SCMPacketType { /** * Returns the human readable name of the packet type + * * @return the human readable name of this packet type */ public String getName() { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMTransceiver.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMTransceiver.java index e1bb4fd..0397810 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMTransceiver.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMTransceiver.java @@ -1,7 +1,6 @@ package org.rocketproplab.marginalstability.flightcomputer.comm; import org.rocketproplab.marginalstability.flightcomputer.ErrorReporter; -import org.rocketproplab.marginalstability.flightcomputer.Errors; import org.rocketproplab.marginalstability.flightcomputer.events.PacketListener; import org.rocketproplab.marginalstability.flightcomputer.events.SerialListener; import org.rocketproplab.marginalstability.flightcomputer.hal.SerialPort; @@ -13,27 +12,26 @@ * chunk it will notify the packet router of the new packet. It uses the * specified source for this as we can have multiple SCM packet sources. See * {@link PacketSources} for more info about packet sources. - * - * @author Max Apodaca, Antonio * + * @author Max Apodaca, Antonio */ public class SCMTransceiver implements SerialListener, PacketListener { - private SerialPort serialPort; - private PacketRouter router; + private SerialPort serialPort; + private PacketRouter router; private PacketSources source; /** * Create a new SCM Transceiver that will use this serial port to send and * receive data. - * + * * @param serialPort The serial port to send data to * @param router the router to use to route packets * @param source where the SCM is connected to */ public SCMTransceiver(SerialPort serialPort, PacketRouter router, PacketSources source) { this.serialPort = serialPort; - this.router = router; - this.source = source; + this.router = router; + this.source = source; } @Override diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/AbortCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/AbortCommand.java index 35c0a96..da44ebe 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/AbortCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/AbortCommand.java @@ -3,36 +3,36 @@ import org.rocketproplab.marginalstability.flightcomputer.subsystems.EngineSubsystem; import org.rocketproplab.marginalstability.flightcomputer.subsystems.Subsystem; -public class AbortCommand implements Command{ - private EngineSubsystem enginesubsystem; - - AbortCommand(EngineSubsystem enginesubsystem){ - this.enginesubsystem = enginesubsystem; - } - - @Override - public boolean isDone() { - return true; - } - - @Override - public void execute() { - enginesubsystem.deactivateEngine(); - } - - @Override - public void start() { - - } - - @Override - public void end() { - - } - - @Override - public Subsystem[] getDependencies() { - return new Subsystem[0]; - } +public class AbortCommand implements Command { + private EngineSubsystem enginesubsystem; + + AbortCommand(EngineSubsystem enginesubsystem) { + this.enginesubsystem = enginesubsystem; + } + + @Override + public boolean isDone() { + return true; + } + + @Override + public void execute() { + enginesubsystem.deactivateEngine(); + } + + @Override + public void start() { + + } + + @Override + public void end() { + + } + + @Override + public Subsystem[] getDependencies() { + return new Subsystem[0]; + } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/Command.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/Command.java index 741c60c..8dbe663 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/Command.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/Command.java @@ -5,12 +5,11 @@ /** * This is the super class for all commands. All commands will implement this * class. - * + *

* Basic capabilities of this class include executing, starting, and stopping * commands. Additionally, it can check whether the command is finished or not. - * - * @author Hemanth Battu, Enlil Odisho * + * @author Hemanth Battu, Enlil Odisho */ public interface Command { /** @@ -35,7 +34,7 @@ public interface Command { /** * Retrieves a list of dependencies - * + * * @return array of subsystems */ public Subsystem[] getDependencies(); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/HeartbeatCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/HeartbeatCommand.java index 76e4bc5..19dd4c0 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/HeartbeatCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/HeartbeatCommand.java @@ -9,31 +9,30 @@ * This is the Heartbeat Command class that implements the Command interface. * The main capabilities of this class includes checking the start time and * sending a periodic "heartbeat" signal every second. - * - * @author Hemanth Battu * + * @author Hemanth Battu */ public class HeartbeatCommand implements Command { private static final Subsystem[] EMPTY_ARRAY = {}; - private int HBcounter; - private double startTime; - private Time time; - private Telemetry telemetry; + private int HBcounter; + private double startTime; + private Time time; + private Telemetry telemetry; /** * Creates a new HeartbeatCommand object using Time and Telemetry objects. - * + * * @param time the Time object to use for checking time * @param telemetry the Telemetry object used to send heartbeat */ public HeartbeatCommand(Time time, Telemetry telemetry) { - this.time = time; + this.time = time; this.telemetry = telemetry; } /** * Setter method to set the start time. - * + * * @param startTime input to set start time with */ private void setStartTime(double startTime) { @@ -62,7 +61,7 @@ public void execute() { } } else { if (currentTime - - startTime >= ((HBcounter + 1) * (Settings.HEARTBEAT_THRESHOLD))) { + - startTime >= ((HBcounter + 1) * (Settings.HEARTBEAT_THRESHOLD))) { telemetry.sendHeartbeat(); HBcounter += 1; } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/LaunchCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/LaunchCommand.java index c8c1d34..c539fec 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/LaunchCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/LaunchCommand.java @@ -3,36 +3,36 @@ import org.rocketproplab.marginalstability.flightcomputer.subsystems.EngineSubsystem; import org.rocketproplab.marginalstability.flightcomputer.subsystems.Subsystem; -public class LaunchCommand implements Command{ - private EngineSubsystem enginesubsystem; - - LaunchCommand(EngineSubsystem enginesubsystem){ - this.enginesubsystem = enginesubsystem; - } - - @Override - public boolean isDone() { - return true; - } - - @Override - public void execute() { - enginesubsystem.activateEngine(); - } - - @Override - public void start() { - - } - - @Override - public void end() { - - } - - @Override - public Subsystem[] getDependencies() { - return new Subsystem [0]; - } +public class LaunchCommand implements Command { + private EngineSubsystem enginesubsystem; + + LaunchCommand(EngineSubsystem enginesubsystem) { + this.enginesubsystem = enginesubsystem; + } + + @Override + public boolean isDone() { + return true; + } + + @Override + public void execute() { + enginesubsystem.activateEngine(); + } + + @Override + public void start() { + + } + + @Override + public void end() { + + } + + @Override + public Subsystem[] getDependencies() { + return new Subsystem[0]; + } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenDrogueChuteCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenDrogueChuteCommand.java index 2e4e9c4..3802aaa 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenDrogueChuteCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenDrogueChuteCommand.java @@ -8,49 +8,51 @@ import org.rocketproplab.marginalstability.flightcomputer.subsystems.Subsystem; public class OpenDrogueChuteCommand implements Command { - private ParachuteSubsystem parachuteSubsystem; - private PacketRelay relay; - - private OpenDrogueChuteCommand(ParachuteSubsystem parachuteSubsystem, PacketRelay relay) { - this.parachuteSubsystem = parachuteSubsystem; - this.relay = relay; - } - - @Override - public boolean isDone() { - return true; - } - - @Override - public void execute() { - boolean success = parachuteSubsystem.attemptDrogueChuteOpen(); - relay.sendPacket(new SCMPacket( - SCMPacketType.DD, success? " 1" : " 0"), - PacketSources.CommandBox); - } - - @Override - public void start() { } - - @Override - public void end() { } - - @Override - public Subsystem[] getDependencies() { - return new Subsystem[] {parachuteSubsystem}; - } - - public static class OpenDrogueChuteFactory { - /** - * Get a new OpenDrogueChuteCommand - * - * @param parachuteSubsystem the ParachuteSubsystem this command will operate on - * @param relay the PacketRelay to send the success status packet through - * @return a new OpenDrogueChuteCommand - */ - public static OpenDrogueChuteCommand getOpenDrogueChuteCommand( - ParachuteSubsystem parachuteSubsystem, PacketRelay relay) { - return new OpenDrogueChuteCommand(parachuteSubsystem, relay); - } + private ParachuteSubsystem parachuteSubsystem; + private PacketRelay relay; + + private OpenDrogueChuteCommand(ParachuteSubsystem parachuteSubsystem, PacketRelay relay) { + this.parachuteSubsystem = parachuteSubsystem; + this.relay = relay; + } + + @Override + public boolean isDone() { + return true; + } + + @Override + public void execute() { + boolean success = parachuteSubsystem.attemptDrogueChuteOpen(); + relay.sendPacket(new SCMPacket( + SCMPacketType.DD, success ? " 1" : " 0"), + PacketSources.CommandBox); + } + + @Override + public void start() { + } + + @Override + public void end() { + } + + @Override + public Subsystem[] getDependencies() { + return new Subsystem[]{parachuteSubsystem}; + } + + public static class OpenDrogueChuteFactory { + /** + * Get a new OpenDrogueChuteCommand + * + * @param parachuteSubsystem the ParachuteSubsystem this command will operate on + * @param relay the PacketRelay to send the success status packet through + * @return a new OpenDrogueChuteCommand + */ + public static OpenDrogueChuteCommand getOpenDrogueChuteCommand( + ParachuteSubsystem parachuteSubsystem, PacketRelay relay) { + return new OpenDrogueChuteCommand(parachuteSubsystem, relay); } + } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenMainChuteCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenMainChuteCommand.java index 0f202ad..7a265d7 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenMainChuteCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenMainChuteCommand.java @@ -8,50 +8,52 @@ import org.rocketproplab.marginalstability.flightcomputer.subsystems.Subsystem; public class OpenMainChuteCommand implements Command { - private ParachuteSubsystem parachuteSubsystem; - private PacketRelay relay; - - private OpenMainChuteCommand(ParachuteSubsystem parachuteSubsystem, PacketRelay relay) { - this.parachuteSubsystem = parachuteSubsystem; - this.relay = relay; - } - - @Override - public boolean isDone() { - return true; - } - - @Override - public void execute() { - boolean success = parachuteSubsystem.attemptMainChuteOpen(); - relay.sendPacket(new SCMPacket( - SCMPacketType.MD, success? " 1" : " 0"), - PacketSources.CommandBox); - } - - @Override - public void start() { } - - @Override - public void end() { } - - @Override - public Subsystem[] getDependencies() { - return new Subsystem[] {parachuteSubsystem}; - } - - public static class OpenMainChuteFactory { - /** - * Get a new OpenMainChuteCommand - * - * @param parachuteSubsystem the ParachuteSubsystem this command will operate on - * @param relay the PacketRelay to send the success status packet through - * @return a new OpenMainChuteCommand - */ - public static OpenMainChuteCommand getOpenMainChuteCommand( - ParachuteSubsystem parachuteSubsystem, PacketRelay relay) { - return new OpenMainChuteCommand(parachuteSubsystem, relay); - } + private ParachuteSubsystem parachuteSubsystem; + private PacketRelay relay; + + private OpenMainChuteCommand(ParachuteSubsystem parachuteSubsystem, PacketRelay relay) { + this.parachuteSubsystem = parachuteSubsystem; + this.relay = relay; + } + + @Override + public boolean isDone() { + return true; + } + + @Override + public void execute() { + boolean success = parachuteSubsystem.attemptMainChuteOpen(); + relay.sendPacket(new SCMPacket( + SCMPacketType.MD, success ? " 1" : " 0"), + PacketSources.CommandBox); + } + + @Override + public void start() { + } + + @Override + public void end() { + } + + @Override + public Subsystem[] getDependencies() { + return new Subsystem[]{parachuteSubsystem}; + } + + public static class OpenMainChuteFactory { + /** + * Get a new OpenMainChuteCommand + * + * @param parachuteSubsystem the ParachuteSubsystem this command will operate on + * @param relay the PacketRelay to send the success status packet through + * @return a new OpenMainChuteCommand + */ + public static OpenMainChuteCommand getOpenMainChuteCommand( + ParachuteSubsystem parachuteSubsystem, PacketRelay relay) { + return new OpenMainChuteCommand(parachuteSubsystem, relay); } + } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/SetValveCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/SetValveCommand.java index 516df67..ff75d04 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/SetValveCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/SetValveCommand.java @@ -8,11 +8,11 @@ public class SetValveCommand implements Command { private SCMPacket scmpacket; - private Valves valves; + private Valves valves; SetValveCommand(SCMPacket scmpacket, Valves valves) { this.scmpacket = scmpacket; - this.valves = valves; + this.valves = valves; } @Override @@ -50,7 +50,7 @@ public Subsystem[] getDependencies() { private int getValveID() { int currentvalve = this.scmpacket.getID().ordinal(); int initialvalve = SCMPacketType.V0.ordinal(); - int valveindex = currentvalve - initialvalve; + int valveindex = currentvalve - initialvalve; return valveindex; } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/UpdateSettingCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/UpdateSettingCommand.java index 957102c..adbad11 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/UpdateSettingCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/UpdateSettingCommand.java @@ -6,31 +6,37 @@ import java.util.Collections; public class UpdateSettingCommand implements Command { - private final String setting; - - UpdateSettingCommand(String setting) { - this.setting = setting; - } - - public static UpdateSettingCommand getUpdateSettingCommand(String setting) { - return new UpdateSettingCommand(setting); - } - - @Override - public boolean isDone() { return true; } - - @Override - public void execute() { - Settings.readSettingsFromConfig(Collections.singletonList(setting)); - } - - @Override - public void start() { } - - @Override - public void end() { } - - @Override - public Subsystem[] getDependencies() { return new Subsystem[0]; } + private final String setting; + + UpdateSettingCommand(String setting) { + this.setting = setting; + } + + public static UpdateSettingCommand getUpdateSettingCommand(String setting) { + return new UpdateSettingCommand(setting); + } + + @Override + public boolean isDone() { + return true; + } + + @Override + public void execute() { + Settings.readSettingsFromConfig(Collections.singletonList(setting)); + } + + @Override + public void start() { + } + + @Override + public void end() { + } + + @Override + public Subsystem[] getDependencies() { + return new Subsystem[0]; + } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/events/EngineEventListener.java b/src/org/rocketproplab/marginalstability/flightcomputer/events/EngineEventListener.java index 1b83e63..b8badef 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/events/EngineEventListener.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/events/EngineEventListener.java @@ -14,7 +14,7 @@ public interface EngineEventListener { /** * Called when new engine data is received - * + * * @param type the type of data which was received * @param value the value of the data which was received */ @@ -22,15 +22,16 @@ public interface EngineEventListener { /** * The different types of data which relate to the engine - * - * @author Max Apodaca * + * @author Max Apodaca */ public enum EngineDataType { /** * Temperature of the engine bell */ Temperature - }; + } + + ; } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/events/FlightStateListener.java b/src/org/rocketproplab/marginalstability/flightcomputer/events/FlightStateListener.java index 9497805..9eaa514 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/events/FlightStateListener.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/events/FlightStateListener.java @@ -6,8 +6,9 @@ public interface FlightStateListener { /** * Called when the flight mode changes + * * @param newMode the new flight mode we are in */ public void onFlightModeChange(FlightMode newMode); - + } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/events/PacketListener.java b/src/org/rocketproplab/marginalstability/flightcomputer/events/PacketListener.java index 0090366..8a5cbe2 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/events/PacketListener.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/events/PacketListener.java @@ -4,14 +4,13 @@ /** * Listens for a particular type of packet in a particular direction - * - * @author Max Apodaca * * @param The type of packet to listen for (should be GPSPacket or * SCMPacket) + * @author Max Apodaca */ public interface PacketListener { - public void onPacket(PacketDirection direction, E packet); + public void onPacket(PacketDirection direction, E packet); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/events/ParachuteListener.java b/src/org/rocketproplab/marginalstability/flightcomputer/events/ParachuteListener.java index c35e815..3ac5a4f 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/events/ParachuteListener.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/events/ParachuteListener.java @@ -2,8 +2,8 @@ /** * A listener for changes in the parachute state. - * @author Max Apodaca * + * @author Max Apodaca */ public interface ParachuteListener { @@ -11,15 +11,15 @@ public interface ParachuteListener { * Called when the drogue chute opens */ public void onDrogueOpen(); - + /** * Called when the drogue chute is cut */ public void onDrougeCut(); - + /** * Called when the main chute opens. */ public void onMainChuteOpen(); - + } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/events/PositionListener.java b/src/org/rocketproplab/marginalstability/flightcomputer/events/PositionListener.java index 69c0cda..10a23f8 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/events/PositionListener.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/events/PositionListener.java @@ -4,15 +4,14 @@ /** * An interface for listening to new position estimations - * - * @author Max Apodaca * + * @author Max Apodaca */ public interface PositionListener { /** * Called when new estimate is available - * + * * @param positionEstimate the new position estimate */ public void onPositionEstimate(InterpolatingVector3 positionEstimate); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/events/SerialListener.java b/src/org/rocketproplab/marginalstability/flightcomputer/events/SerialListener.java index 0f32a92..f08e9ac 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/events/SerialListener.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/events/SerialListener.java @@ -3,15 +3,14 @@ /** * A listener for the serial port. It is notified when the serial port receives * a new message. - * - * @author Max Apodaca, Antonio * + * @author Max Apodaca, Antonio */ public interface SerialListener { - + /** * Called each time the serial port receives a string - * + * * @param data the data that was received */ public void onSerialData(String data); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/events/VelocityListener.java b/src/org/rocketproplab/marginalstability/flightcomputer/events/VelocityListener.java index 80d09ac..b8a264d 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/events/VelocityListener.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/events/VelocityListener.java @@ -4,16 +4,17 @@ /** * Listens for updates in the velocity - * @author Max Apodaca * + * @author Max Apodaca */ public interface VelocityListener { /** * Called when a new velocity measurement is recorded + * * @param velocity the velocity which was recorded - * @param time the time at which the measurement was recorded + * @param time the time at which the measurement was recorded */ public void onVelocityUpdate(Vector3 velocity, double time); - + } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/AccelGyroReading.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/AccelGyroReading.java index 4bb2c08..123628e 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/AccelGyroReading.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/AccelGyroReading.java @@ -6,15 +6,14 @@ * An AccelGyroReading is the accelerometer and gyroscope data read by an * IMU at an instant. It consists of an acceleration vector as well as a * rotation difference.
- * + *

* The rotation vector specified how many radians were rotated in the last * timestep in the local reference frame.
* The acceleration vector is the acceleration felt by the IMU in the local * reference frame in meters / second^2. If the IMU is lying flat on a table it * would read (0, 0, 9.81). - * - * @author Max Apodaca * + * @author Max Apodaca */ public class AccelGyroReading { @@ -23,18 +22,18 @@ public class AccelGyroReading { /** * Construct a new AccelGyroReading to store the acceleration and rotation. - * + * * @param acc * @param rotation */ public AccelGyroReading(Vector3 acc, Vector3 rotation) { - this.acc = acc; + this.acc = acc; this.rotation = rotation; } /** * Get the rotation delta in the given reference frame in radians. - * + * * @return the difference in rotation from the last reading. */ public Vector3 getXYZRotation() { @@ -43,7 +42,7 @@ public Vector3 getXYZRotation() { /** * Get the acceleration at the given sample time in m/s^2. - * + * * @return the acceleration in m/s^2 as a 3 component x y z vector */ public Vector3 getXYZAcceleration() { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/AccelerometerGyroscope.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/AccelerometerGyroscope.java index 8140984..53ecf74 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/AccelerometerGyroscope.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/AccelerometerGyroscope.java @@ -5,16 +5,15 @@ * this interface will give an iterable list of AccelGyroReadings. If hasNext * returns true there will be at least another accelerometer and gyroscope * reading. - * - * @author max * + * @author max */ public interface AccelerometerGyroscope { /** * Read the next accelerometer and gyroscope reading, returns null if * {@link #hasNext()} returns false. - * + * * @return the next accelerometer and gyroscope reading or null. */ public AccelGyroReading getNext(); @@ -22,7 +21,7 @@ public interface AccelerometerGyroscope { /** * Determines if there is another reading from the accelerometer/gyroscope * that can be read with {@link #getNext()} - * + * * @return true if {@link #getNext()} will return a new accelerometer and * gyroscope reading, false otherwise. */ diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/Barometer.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/Barometer.java index 7cf555e..84d36af 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/Barometer.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/Barometer.java @@ -3,7 +3,7 @@ public interface Barometer { /** * Get the pressure in hPa - * + * * @return get the pressure in hPa */ public double getPressure(); @@ -11,21 +11,21 @@ public interface Barometer { /** * Returns if the pressure is in a usable range. If the sensor is in too low or * too high air pressure the data we get might be garbage. - * + * * @return if the current pressure is in a usable range */ public boolean inUsableRange(); /** * Gets the time at which the last measurement was made - * + * * @return the time of the last measurements */ public double getLastMeasurementTime(); /** * Returns an instance to a standard samplable sensor - * + * * @return the standard samplable sensor */ public SamplableSensor getSamplable(); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/DummyPiCommandsImu.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/DummyPiCommandsImu.java index ecefaba..e53468a 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/DummyPiCommandsImu.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/DummyPiCommandsImu.java @@ -1,18 +1,18 @@ package org.rocketproplab.marginalstability.flightcomputer.hal; public class DummyPiCommandsImu { - - private byte altX; - private byte altY; - private byte alyZ; - - - /** - * This is for receiving packages. Basically a dummy pi command set. - * I loved it. - */ - public void DummyPiCommands() { - } + + private byte altX; + private byte altY; + private byte alyZ; + + + /** + * This is for receiving packages. Basically a dummy pi command set. + * I loved it. + */ + public void DummyPiCommands() { + } } /* * i2c has registers which store data generally for things like altitude it's diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LPS22HD.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LPS22HD.java index 4670a79..7007b2b 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LPS22HD.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LPS22HD.java @@ -1,51 +1,49 @@ package org.rocketproplab.marginalstability.flightcomputer.hal; -import java.io.IOException; - +import com.pi4j.io.i2c.I2CDevice; import org.rocketproplab.marginalstability.flightcomputer.ErrorReporter; import org.rocketproplab.marginalstability.flightcomputer.Errors; import org.rocketproplab.marginalstability.flightcomputer.Time; -import com.pi4j.io.i2c.I2CDevice; +import java.io.IOException; /** * The LPS22HD HAL implementation. Refer to the datasheet for specification https://www.st.com/resource/en/datasheet/lps22hd.pdf - * - * @author Clara Chun, Max Apodaca * + * @author Clara Chun, Max Apodaca */ public class LPS22HD implements Barometer, PollingSensor { private I2CDevice i2cDevice; - private double pressure; - private double sampleTime; - private Time clock; - - private static final byte ODR_25HZ = 0b00110000; - private static final byte LOW_PASS_ENABLE = 0b00001000; - private static final byte LOW_PASS_20TH = 0b00000100; - private static final byte KEEP_REGISTERS_SYCHONISED_BDU = 0b00000010; - private static final int CTRL_REG1 = 0x10; - private static final double MINIMUM_RANGE = 259; - private static final double MAXIMUM_RANGE = 1261; - private static final double ZERO_TIME = 0.0; - private static final double SCALING_FACTOR = 4096; - private static final int REG_PRESSURE_HIGH = 0x2A; - private static final int REG_PRESSURE_LOW = 0x29; - private static final int REG_PRESSURE_EXTRA_LOW = 0x28; + private double pressure; + private double sampleTime; + private Time clock; + + private static final byte ODR_25HZ = 0b00110000; + private static final byte LOW_PASS_ENABLE = 0b00001000; + private static final byte LOW_PASS_20TH = 0b00000100; + private static final byte KEEP_REGISTERS_SYCHONISED_BDU = 0b00000010; + private static final int CTRL_REG1 = 0x10; + private static final double MINIMUM_RANGE = 259; + private static final double MAXIMUM_RANGE = 1261; + private static final double ZERO_TIME = 0.0; + private static final double SCALING_FACTOR = 4096; + private static final int REG_PRESSURE_HIGH = 0x2A; + private static final int REG_PRESSURE_LOW = 0x29; + private static final int REG_PRESSURE_EXTRA_LOW = 0x28; /** * Create a new LPS22HD with the given i2cDevice and time. Time will be used to * determine the {@link #getLastMeasurementTime()} return value.
* The i2cDevice parameter is not checked for a valid address. - * + * * @param i2cDevice the device which should be used to communicate via i2c * @param time the time to use when reporting measurement time. */ public LPS22HD(I2CDevice i2cDevice, Time time) { this.i2cDevice = i2cDevice; - this.clock = time; + this.clock = time; } /** @@ -93,7 +91,7 @@ public void poll() { /** * Read the current pressure form the sensor using a one shot read method. - * + *

* MSB LSB Complete 24-bit word: | buffer[2] | buffer[1] | buffer[0] | * Registers: | 0x2A | 0x29 | 0x28 | */ @@ -101,7 +99,7 @@ private void readPressure() { // TODO Read at once so we don't read high on sample 1 and low on sample 2. As // in if the sample changes while we are reading. try { - byte[] buffer = { 0, 0, 0 }; + byte[] buffer = {0, 0, 0}; i2cDevice.read(REG_PRESSURE_EXTRA_LOW, buffer, 0, 3); // Out of range if MSB = 1 @@ -112,7 +110,7 @@ private void readPressure() { } int rawPressure = (Byte.toUnsignedInt(buffer[2]) << 16) + (Byte.toUnsignedInt(buffer[1]) << 8) - + Byte.toUnsignedInt(buffer[0]); + + Byte.toUnsignedInt(buffer[0]); pressure = rawPressure / (double) SCALING_FACTOR; } catch (IOException e) { ErrorReporter errorReporter = ErrorReporter.getInstance(); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1AccelGyro.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1AccelGyro.java index 18377ff..9e68d13 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1AccelGyro.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1AccelGyro.java @@ -1,23 +1,22 @@ package org.rocketproplab.marginalstability.flightcomputer.hal; -import java.io.IOException; -import java.nio.ByteBuffer; -import java.nio.ByteOrder; -import java.util.ArrayDeque; -import java.util.Arrays; - +import com.pi4j.io.i2c.I2CDevice; import org.rocketproplab.marginalstability.flightcomputer.ErrorReporter; import org.rocketproplab.marginalstability.flightcomputer.Errors; import org.rocketproplab.marginalstability.flightcomputer.Settings; import org.rocketproplab.marginalstability.flightcomputer.math.Vector3; -import com.pi4j.io.i2c.I2CDevice; +import java.io.IOException; +import java.nio.ByteBuffer; +import java.nio.ByteOrder; +import java.util.ArrayDeque; +import java.util.Arrays; /** * The HAL implementation for the LSM9DS1 accelerometer and gyroscope sensors. * Datasheet can be found here: https://www.st.com/resource/en/datasheet/lsm9ds1.pdf
- * + *

* Every time poll is called this sensor will acquire as many samples as * possible from the LSM9DS1's internal FIFO buffer. This is done by reading the * number of samples in the FIFO and then reading the FIFO output registers @@ -26,34 +25,33 @@ * {@link #getNext()} method. Whether or not the queue is empty can be read * using the {@link #hasNext()} method. It is recommended to call * {@link #hasNext()} before each call of {@link #getNext()}. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class LSM9DS1AccelGyro implements PollingSensor, AccelerometerGyroscope { - private static final int ODR_MASK = 0b111; - private static final int ODR_LSB_POS = 5; - private static final int ACCELEROMETER_SCALE_MASK = 0b11; + private static final int ODR_MASK = 0b111; + private static final int ODR_LSB_POS = 5; + private static final int ACCELEROMETER_SCALE_MASK = 0b11; private static final int ACCELEROMETER_SCALE_LSB_POS = 3; - private static final int GYRO_SCALE_MASK = 0b11; - private static final int GYRO_SCALE_LSB_POS = 3; - private static final int FIFO_EN_VAL_MASK = 0b1; - private static final int FIFO_EN_LSB_POS = 1; - private static final int FIFO_MODE_MASK = 0b111; - private static final int FIFO_MODE_LSB_POS = 5; - private static final int FIFO_THRESHOLD_MASK = 0b11111; - private static final int FIFO_THRESHOLD_LSB_POS = 0; - public static final int FIFO_THRESHOLD_MAX = 31; - public static final int FIFO_THRESHOLD_MIN = 0; - public static final int FIFO_OVERRUN_POS = 6; - public static final int FIFO_THRESHOLD_STATUS_POS = 7; - public static final int FIFO_SAMPLES_STORED_MASK = 0b111111; - - private static final int BYTES_PER_FIFO_LINE = 12; - + private static final int GYRO_SCALE_MASK = 0b11; + private static final int GYRO_SCALE_LSB_POS = 3; + private static final int FIFO_EN_VAL_MASK = 0b1; + private static final int FIFO_EN_LSB_POS = 1; + private static final int FIFO_MODE_MASK = 0b111; + private static final int FIFO_MODE_LSB_POS = 5; + private static final int FIFO_THRESHOLD_MASK = 0b11111; + private static final int FIFO_THRESHOLD_LSB_POS = 0; + public static final int FIFO_THRESHOLD_MAX = 31; + public static final int FIFO_THRESHOLD_MIN = 0; + public static final int FIFO_OVERRUN_POS = 6; + public static final int FIFO_THRESHOLD_STATUS_POS = 7; + public static final int FIFO_SAMPLES_STORED_MASK = 0b111111; + + private static final int BYTES_PER_FIFO_LINE = 12; + public static final double ACCELEROMETER_OUTPUT_TO_MPS_SQUARED = 9.81; // factor to multiply acc output by to - // convert sensor output to m/s^2 - private static final double ONE_DEGREE_IN_RADIANS = Math.PI / 180.0; + // convert sensor output to m/s^2 + private static final double ONE_DEGREE_IN_RADIANS = Math.PI / 180.0; /** * All the registers that can be found in the LSM9DS1 imu for the accelerometer @@ -120,7 +118,7 @@ public enum Registers { /** * Read the address of a register, this is not necessarily the same as the * ordinal and should be used for I2C access. - * + * * @return the I2C address of the register. */ public int getAddress() { @@ -165,6 +163,7 @@ public int getValueLSBPos() { return ACCELEROMETER_SCALE_LSB_POS; } } + /** * The current accelerometer scale the sensor is set to. * Initialize to default value as specified in sensor datasheet. @@ -191,6 +190,7 @@ public int getValueLSBPos() { return GYRO_SCALE_LSB_POS; } } + /** * The current gyroscope scale the sensor is set to. * Initialize to default value as specified in sensor datasheet. @@ -225,13 +225,13 @@ public int getValueLSBPos() { } } - private I2CDevice i2c; + private I2CDevice i2c; private ArrayDeque samples = new ArrayDeque<>(); /** * Create a new LSM9DS1AccelGyro on the given {@link I2CDevice}. There is no * validation for the {@link I2CDevice} address. - * + * * @param device the device to use for I2C communication */ public LSM9DS1AccelGyro(I2CDevice device) { @@ -240,7 +240,7 @@ public LSM9DS1AccelGyro(I2CDevice device) { /** * Sets the output data rate of the sensor - * + * * @throws IOException if unable to read */ public void setODR(ODR odr) throws IOException { @@ -249,7 +249,7 @@ public void setODR(ODR odr) throws IOException { /** * Sets the scale of the accelerometer - * + * * @param scale the scale of the accelerometer data * @throws IOException if we are unable to access the i2c device */ @@ -257,9 +257,10 @@ public void setAccelerometerScale(AccelerometerScale scale) throws IOException { modifyRegister(Registers.CTRL_REG6_XL, scale); accelScale = scale; } - + /** * Returns the scale of the accelerometer + * * @return the set accelerometer scale */ public AccelerometerScale getAccelerometerScale() { @@ -268,7 +269,7 @@ public AccelerometerScale getAccelerometerScale() { /** * Sets the scale of the Gyroscope - * + * * @param scale the scale of the gyroscope data * @throws IOException if we are unable to access the i2c device */ @@ -276,9 +277,10 @@ public void setGyroscopeScale(GyroScale scale) throws IOException { modifyRegister(Registers.CTRL_REG1_G, scale); gyroScale = scale; } - + /** * Returns the scale of the gyroscope + * * @return the set gyroscope scale */ public GyroScale getGyroscopeScale() { @@ -287,19 +289,19 @@ public GyroScale getGyroscopeScale() { /** * Enable or disable the FIFO by setting CTRL_REG9 - * + * * @param enabled whether or not to enable the fifo * @throws IOException if we are unable to access the i2c device */ public void setFIFOEnabled(boolean enabled) throws IOException { int registerValue = this.i2c.read(Registers.CTRL_REG9.getAddress()); - int result = mask(registerValue, enabled ? 1 : 0, FIFO_EN_LSB_POS, FIFO_EN_VAL_MASK); + int result = mask(registerValue, enabled ? 1 : 0, FIFO_EN_LSB_POS, FIFO_EN_VAL_MASK); this.i2c.write(Registers.CTRL_REG9.getAddress(), (byte) result); } /** * Set the FIFOMode to the new mode - * + * * @param mode the new FIFOMode to use * @throws IOException if we are unable to access the i2c device */ @@ -309,7 +311,7 @@ public void setFIFOMode(FIFOMode mode) throws IOException { /** * Set the threshold at which we should signal that the FIFO is full. - * + * * @param threshold the number of samples at which we start signaling * @throws IOException if we are unable to access the i2c device */ @@ -321,51 +323,51 @@ public void setFIFOThreshold(int threshold) throws IOException { threshold = FIFO_THRESHOLD_MIN; } int registerValue = this.i2c.read(Registers.FIFO_CTRL.getAddress()); - int result = mask(registerValue, threshold, FIFO_THRESHOLD_LSB_POS, FIFO_THRESHOLD_MASK); + int result = mask(registerValue, threshold, FIFO_THRESHOLD_LSB_POS, FIFO_THRESHOLD_MASK); this.i2c.write(Registers.FIFO_CTRL.getAddress(), (byte) result); } /** * Returns if the FIFO buffer's data has been exceeded. This means that data was * lost. - * + * * @return if the FIFO overflowed * @throws IOException if we are unable to access the i2c device */ public boolean hasFIFOOverrun() throws IOException { int fifoSRCValue = this.i2c.read(Registers.FIFO_SRC.getAddress()); - int masked = (1 << FIFO_OVERRUN_POS) & fifoSRCValue; + int masked = (1 << FIFO_OVERRUN_POS) & fifoSRCValue; return masked != 0; } /** * Are we at the FIFO threshold yet. See {@link #setFIFOThreshold(int)} on how * to set the threshold. - * + * * @return if we are at the FIFO threshold * @throws IOException if we are unable to access the i2c device */ public boolean isFIFOThresholdReached() throws IOException { int fifoSRCValue = this.i2c.read(Registers.FIFO_SRC.getAddress()); - int masked = (1 << FIFO_THRESHOLD_STATUS_POS) & fifoSRCValue; + int masked = (1 << FIFO_THRESHOLD_STATUS_POS) & fifoSRCValue; return masked != 0; } /** * Read how many samples are in the FIFO at the current time. - * + * * @return the number of samples in the FIFO * @throws IOException if we are unable to access the i2c device */ public int getSamplesInFIFO() throws IOException { int fifoSRCValue = this.i2c.read(Registers.FIFO_SRC.getAddress()); - int masked = FIFO_SAMPLES_STORED_MASK & fifoSRCValue; + int masked = FIFO_SAMPLES_STORED_MASK & fifoSRCValue; return masked; } /** * Write a register value to a register. - * + * * @param register the register to write to * @param value the value to write, uses all of the values in * {@link RegisterValue} @@ -373,7 +375,7 @@ public int getSamplesInFIFO() throws IOException { */ private void modifyRegister(Registers register, RegisterValue value) throws IOException { int registerValue = this.i2c.read(register.getAddress()); - int result = mask(registerValue, value.ordinal(), value.getValueLSBPos(), value.getValueMask()); + int result = mask(registerValue, value.ordinal(), value.getValueLSBPos(), value.getValueMask()); this.i2c.write(register.getAddress(), (byte) result); } @@ -385,7 +387,7 @@ private void modifyRegister(Registers register, RegisterValue value) throws IOEx * anding with toMask.
*
* Note: No values in newData are masked out. - * + * * @param toMask the value to mask * @param newData the value to replace the masked areas of to mask * @param lsbPos how far to the left the masked value is in toMask @@ -393,9 +395,9 @@ private void modifyRegister(Registers register, RegisterValue value) throws IOEx * @return combination of toMask and newData combined based on valueMask */ private int mask(int toMask, int newData, int lsbPos, int valueMask) { - int mask = valueMask << lsbPos; + int mask = valueMask << lsbPos; int notMask = ~mask; - int result = newData << lsbPos | (toMask & notMask); + int result = newData << lsbPos | (toMask & notMask); return result; } @@ -422,9 +424,9 @@ private void readFromSensor() { if (samplesInFIFO == 0) { return; } - int dataLength = samplesInFIFO * BYTES_PER_FIFO_LINE; - byte[] data = new byte[dataLength]; - int samplesRead = this.i2c.read(Registers.OUT_X_L_G.getAddress(), data, 0, dataLength); + int dataLength = samplesInFIFO * BYTES_PER_FIFO_LINE; + byte[] data = new byte[dataLength]; + int samplesRead = this.i2c.read(Registers.OUT_X_L_G.getAddress(), data, 0, dataLength); this.parseReadings(data, samplesRead); } catch (IOException e) { ErrorReporter errorReporter = ErrorReporter.getInstance(); @@ -437,16 +439,16 @@ private void readFromSensor() { * Take the raw data read and split it into chunks of BYTES_PER_FIFO_LINE bytes * to correspond to each IMU reading. Then feed those into * {@link #buildReading(byte[])}. - * + * * @param data the raw data to parse * @param bytesRead how many bytes were read. */ private void parseReadings(byte[] data, int bytesRead) { int samplesRead = bytesRead / BYTES_PER_FIFO_LINE; for (int i = 0; i < samplesRead; i++) { - int start = i * BYTES_PER_FIFO_LINE; - int end = (i + 1) * BYTES_PER_FIFO_LINE; - byte[] samples = Arrays.copyOfRange(data, start, end); + int start = i * BYTES_PER_FIFO_LINE; + int end = (i + 1) * BYTES_PER_FIFO_LINE; + byte[] samples = Arrays.copyOfRange(data, start, end); AccelGyroReading reading = this.buildReading(samples); this.samples.add(reading); } @@ -455,7 +457,7 @@ private void parseReadings(byte[] data, int bytesRead) { /** * Parse a set of BYTES_PER_FIFO_LINE bytes into an AccelGyroReading.
* Use range to normalize to m/s^2 - * + * * @param data the set of six bytes representing a reading * @return the AccelGyroReading which the six bytes belong to. */ @@ -465,12 +467,12 @@ public AccelGyroReading buildReading(byte[] data) { int xGyro = results[0]; int yGyro = results[1]; int zGyro = results[2]; - int xAcc = results[3]; - int yAcc = results[4]; - int zAcc = results[5]; + int xAcc = results[3]; + int yAcc = results[4]; + int zAcc = results[5]; Vector3 gyroVec = computeAngularAcceleration(xGyro, yGyro, zGyro); - Vector3 accVec = computeAcceleration(xAcc, yAcc, zAcc); + Vector3 accVec = computeAcceleration(xAcc, yAcc, zAcc); return new AccelGyroReading(accVec, gyroVec); } @@ -478,7 +480,7 @@ public AccelGyroReading buildReading(byte[] data) { * Converts the input bytes to shorts where it assumes that the first byte of * the tuple is less significant.
* The array looks like {@code [L,H,L,H, ..., L, H]}. - * + * * @param data byte array of little-endian shorts * @return array of the shorts */ @@ -500,9 +502,10 @@ public AccelGyroReading getNext() { public boolean hasNext() { return !samples.isEmpty(); } - + /** * Converts accelerometer readings to m/s^2. Uses the current accelerometer scale setting. + * * @param accX x-axis reading from accelerometer * @param accY y-axis reading from accelerometer * @param accZ z-axis reading from accelerometer @@ -511,35 +514,36 @@ public boolean hasNext() { public Vector3 computeAcceleration(int accX, int accY, int accZ) { // Get the accelerometer sensitivity. double sensitivity; - switch(accelScale) { - case G_2: - sensitivity = Settings.LSM9DS1_SENSITIVITY_ACCELEROMETER_2G; - break; - case G_4: - sensitivity = Settings.LSM9DS1_SENSITIVITY_ACCELEROMETER_4G; - break; - case G_8: - sensitivity = Settings.LSM9DS1_SENSITIVITY_ACCELEROMETER_8G; - break; - case G_16: - sensitivity = Settings.LSM9DS1_SENSITIVITY_ACCELEROMETER_16G; - break; - default: - throw new IllegalStateException("Sensor has an unknown accelerometer scale."); + switch (accelScale) { + case G_2: + sensitivity = Settings.LSM9DS1_SENSITIVITY_ACCELEROMETER_2G; + break; + case G_4: + sensitivity = Settings.LSM9DS1_SENSITIVITY_ACCELEROMETER_4G; + break; + case G_8: + sensitivity = Settings.LSM9DS1_SENSITIVITY_ACCELEROMETER_8G; + break; + case G_16: + sensitivity = Settings.LSM9DS1_SENSITIVITY_ACCELEROMETER_16G; + break; + default: + throw new IllegalStateException("Sensor has an unknown accelerometer scale."); } - + // This factor converts accelerometer readings to m/s^2 double conversionFactor = sensitivity * ACCELEROMETER_OUTPUT_TO_MPS_SQUARED; - + return new Vector3( - accX * conversionFactor, - accY * conversionFactor, - accZ * conversionFactor + accX * conversionFactor, + accY * conversionFactor, + accZ * conversionFactor ); } - + /** * Converts gyroscope readings to radians per second. Uses the current gyroscope scale setting. + * * @param gyroX x-axis reading from gyroscope * @param gyroY y-axis reading from gyroscope * @param gyroZ z-axis reading from gyroscope @@ -548,27 +552,27 @@ public Vector3 computeAcceleration(int accX, int accY, int accZ) { public Vector3 computeAngularAcceleration(int gyroX, int gyroY, int gyroZ) { // Get the gyroscope sensitivity. double sensitivity; - switch(gyroScale) { - case DPS_245: - sensitivity = Settings.LSM9DS1_SENSITIVITY_GYROSCOPE_245DPS; - break; - case DPS_500: - sensitivity = Settings.LSM9DS1_SENSITIVITY_GYROSCOPE_500DPS; - break; - case DPS_2000: - sensitivity = Settings.LSM9DS1_SENSITIVITY_GYROSCOPE_2000DPS; - break; - default: - throw new IllegalStateException("Sensor has an unknown gyroscope scale."); + switch (gyroScale) { + case DPS_245: + sensitivity = Settings.LSM9DS1_SENSITIVITY_GYROSCOPE_245DPS; + break; + case DPS_500: + sensitivity = Settings.LSM9DS1_SENSITIVITY_GYROSCOPE_500DPS; + break; + case DPS_2000: + sensitivity = Settings.LSM9DS1_SENSITIVITY_GYROSCOPE_2000DPS; + break; + default: + throw new IllegalStateException("Sensor has an unknown gyroscope scale."); } - + // This factor converts gyroscope readings to radians per second double conversionFactor = sensitivity * ONE_DEGREE_IN_RADIANS; - + return new Vector3( - gyroX * conversionFactor, - gyroY * conversionFactor, - gyroZ * conversionFactor + gyroX * conversionFactor, + gyroY * conversionFactor, + gyroZ * conversionFactor ); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1Mag.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1Mag.java index cb3fd16..bf8ca86 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1Mag.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1Mag.java @@ -1,48 +1,46 @@ package org.rocketproplab.marginalstability.flightcomputer.hal; -import java.io.IOException; -import java.nio.ByteBuffer; -import java.nio.ByteOrder; -import java.util.ArrayDeque; - +import com.pi4j.io.i2c.I2CDevice; import org.rocketproplab.marginalstability.flightcomputer.ErrorReporter; import org.rocketproplab.marginalstability.flightcomputer.Errors; import org.rocketproplab.marginalstability.flightcomputer.Settings; import org.rocketproplab.marginalstability.flightcomputer.math.Vector3; -import com.pi4j.io.i2c.I2CDevice; +import java.io.IOException; +import java.nio.ByteBuffer; +import java.nio.ByteOrder; +import java.util.ArrayDeque; /** * The HAL implementation for the LSM9DS1 magnetometer sensor. Datasheet can be * found here: https://www.st.com/resource/en/datasheet/lsm9ds1.pdf
- * + *

* Every time poll is called, this sensor will acquire 1 sample from the LSM9DS1 * magnetometer registers. Each sample gets put into a queue which can be accessed * with the {@link #getNext()} method. Whether or not the queue is empty can be * read using the {@link #hasNext()} method. It is recommended to call * {@link #hasNext()} before each call of {@link #getNext()}. - * - * @author Enlil Odisho * + * @author Enlil Odisho */ public class LSM9DS1Mag implements PollingSensor, Magnetometer { - private static final int ODR_MASK = 0b111; - private static final int ODR_LSB_POS = 2; - private static final int SCALE_MASK = 0b11; - private static final int SCALE_LSB_POS = 5; - private static final int MODE_MASK = 0b11; - private static final int MODE_LSB_POS = 0; - private static final int PERFORMANCE_MASK = 0b11; - private static final int PERFORMANCE_XY_LSB_POS = 5; - private static final int PERFORMANCE_Z_LSB_POS = 2; - private static final int TEMP_COMPENSATE_MASK = 0b1; - private static final int TEMP_COMPENSATE_POS = 7; - private static final int BLOCK_DATA_UPDATE_MASK = 0b1; - private static final int BLOCK_DATA_UPDATE_POS = 6; - private static final int NEW_XYZ_DATA_AVAILABLE_POS = 3; - + private static final int ODR_MASK = 0b111; + private static final int ODR_LSB_POS = 2; + private static final int SCALE_MASK = 0b11; + private static final int SCALE_LSB_POS = 5; + private static final int MODE_MASK = 0b11; + private static final int MODE_LSB_POS = 0; + private static final int PERFORMANCE_MASK = 0b11; + private static final int PERFORMANCE_XY_LSB_POS = 5; + private static final int PERFORMANCE_Z_LSB_POS = 2; + private static final int TEMP_COMPENSATE_MASK = 0b1; + private static final int TEMP_COMPENSATE_POS = 7; + private static final int BLOCK_DATA_UPDATE_MASK = 0b1; + private static final int BLOCK_DATA_UPDATE_POS = 6; + private static final int NEW_XYZ_DATA_AVAILABLE_POS = 3; + private static final int BYTES_PER_SAMPLE = 6; - private static final int BITS_PER_BYTE = 8; + private static final int BITS_PER_BYTE = 8; /** * All the registers that can be found in the LSM9DS1 imu for the magnetometer @@ -72,24 +70,26 @@ public enum Registers { INT_SRC_M(0x31), INT_THS_L(0x32), INT_THS_H(0x33); - + final int address; - + Registers(int address) { this.address = address; } - + /** * Read the address of a register, this is not necessarily the same as the * ordinal and should be used for I2C access. - * + * * @return the I2C address of the register. */ public int getAddress() { return this.address; } - }; - + } + + ; + public enum ODR implements RegisterValue { ODR_0_625, ODR_1_25, @@ -109,9 +109,9 @@ public int getValueMask() { public int getValueLSBPos() { return ODR_LSB_POS; } - + } - + public enum SCALE implements RegisterValue { GAUSS_4, GAUSS_8, @@ -128,17 +128,18 @@ public int getValueLSBPos() { return SCALE_LSB_POS; } } + /** * The current scale the magnetometer is set to. * Initialized to the default value that was specified in the datasheet. */ private SCALE scale = SCALE.GAUSS_4; - + public enum MODE implements RegisterValue { CONTINUOUS_CONVERSION, SINGLE_CONVERSION, POWER_DOWN; - + @Override public int getValueMask() { return MODE_MASK; @@ -149,13 +150,13 @@ public int getValueLSBPos() { return MODE_LSB_POS; } } - + public enum PERFORMANCE_XY implements RegisterValue { LOW, MEDIUM, HIGH, ULTRA; - + @Override public int getValueMask() { return PERFORMANCE_MASK; @@ -166,13 +167,13 @@ public int getValueLSBPos() { return PERFORMANCE_XY_LSB_POS; } } - + public enum PERFORMANCE_Z implements RegisterValue { LOW, MEDIUM, HIGH, ULTRA; - + @Override public int getValueMask() { return PERFORMANCE_MASK; @@ -183,33 +184,33 @@ public int getValueLSBPos() { return PERFORMANCE_Z_LSB_POS; } } - + private I2CDevice i2c; private ArrayDeque samples = new ArrayDeque<>(); - + /** * Create a new LSM9DS1Mag on the given {@link I2CDevice}. There is no * validation for the {@link I2CDevice} address. - * + * * @param device the device to use for the I2C communication */ public LSM9DS1Mag(I2CDevice device) { this.i2c = device; } - + /** * Sets the output data rate of the sensor - * + * * @param odr the rate to set sensor to * @throws IOException if we are unable to access the i2c device */ public void setODR(ODR odr) throws IOException { modifyRegister(Registers.CTRL_REG1_M, odr); } - + /** * Sets the scale of the sensor - * + * * @param newScale the scale of the magnetometer data * @throws IOException if we are unable to access the i2c device */ @@ -217,84 +218,84 @@ public void setScale(SCALE newScale) throws IOException { modifyRegister(Registers.CTRL_REG2_M, newScale); scale = newScale; } - + /** * Returns the scale of the magnetometer. + * * @return the set magnetometer scale */ - public SCALE getScale() - { + public SCALE getScale() { return scale; } - + /** * Sets the operating mode of the magnetometer sensor - * + * * @param mode Operating mode of sensor * @throws IOException if we are unable to access the i2c device */ public void setMode(MODE mode) throws IOException { modifyRegister(Registers.CTRL_REG3_M, mode); } - + /** * Sets the performance of the sensor for x and y magnetometer data - * + * * @param performance the performance of the magnetometer sensor for xy data * @throws IOException if we are unable to access the i2c device */ public void setXYPerformance(PERFORMANCE_XY performance) throws IOException { modifyRegister(Registers.CTRL_REG1_M, performance); } - + /** * Sets the performance of the sensor for z magnetometer data - * + * * @param performance the performance of the magnetometer sensor for z data * @throws IOException if we are unable to access the i2c device */ public void setZPerformance(PERFORMANCE_Z performance) throws IOException { modifyRegister(Registers.CTRL_REG4_M, performance); } - + /** * Enable or disable temperature compensation for magnetometer sensor - * + * * @param enabled whether or not to enable temperature compensation * @throws IOException if we are unable to access the i2c device */ public void setTemperatureCompensationEnabled(boolean enabled) throws IOException { int registerValue = this.i2c.read(Registers.CTRL_REG1_M.getAddress()); - int result = mask(registerValue, enabled ? 1 : 0, TEMP_COMPENSATE_POS, TEMP_COMPENSATE_MASK); + int result = mask(registerValue, enabled ? 1 : 0, TEMP_COMPENSATE_POS, TEMP_COMPENSATE_MASK); this.i2c.write(Registers.CTRL_REG1_M.getAddress(), (byte) result); } - + /** * Whether or not to block the magnetic data from updating until all LSB and * MSB are read for the current sample. - * + * * @param enabled whether or not to enable BDU feature * @throws IOException if we are unable to access the i2c device */ public void setBlockDataUpdateUntilAllReadEnabled(boolean enabled) throws IOException { int registerValue = this.i2c.read(Registers.CTRL_REG5_M.getAddress()); - int result = mask(registerValue, enabled ? 1 : 0, BLOCK_DATA_UPDATE_POS, BLOCK_DATA_UPDATE_MASK); + int result = mask(registerValue, enabled ? 1 : 0, BLOCK_DATA_UPDATE_POS, BLOCK_DATA_UPDATE_MASK); this.i2c.write(Registers.CTRL_REG5_M.getAddress(), (byte) result); } - + /** * @return whether new x/y/z data is available or not. * @throws IOException if we are unable to access the i2c device */ public boolean isNewXYZDataAvailable() throws IOException { int statusRegValue = this.i2c.read(Registers.STATUS_REG_M.getAddress()); - int masked = (1 << NEW_XYZ_DATA_AVAILABLE_POS) & statusRegValue; + int masked = (1 << NEW_XYZ_DATA_AVAILABLE_POS) & statusRegValue; return masked != 0; } - + /** * Write a register value to a register. - * + * * @param register the register to write to * @param value the value to write, uses all of the values in * {@link RegisterValue} @@ -302,10 +303,10 @@ public boolean isNewXYZDataAvailable() throws IOException { */ private void modifyRegister(Registers register, RegisterValue value) throws IOException { int registerValue = this.i2c.read(register.getAddress()); - int result = mask(registerValue, value.ordinal(), value.getValueLSBPos(), value.getValueMask()); + int result = mask(registerValue, value.ordinal(), value.getValueLSBPos(), value.getValueMask()); this.i2c.write(register.getAddress(), (byte) result); } - + /** * Masks the value in toMask with the given parameters. newData is the data to * replace the masked bits. LSBPos is how many bits to the left newData is in @@ -314,7 +315,7 @@ private void modifyRegister(Registers register, RegisterValue value) throws IOEx * anding with toMask.
*
* Note: No values in newData are masked out. - * + * * @param toMask the value to mask * @param newData the value to replace the masked areas of to mask * @param lsbPos how far to the left the masked value is in toMask @@ -322,17 +323,17 @@ private void modifyRegister(Registers register, RegisterValue value) throws IOEx * @return combination of toMask and newData combined based on valueMask */ private int mask(int toMask, int newData, int lsbPos, int valueMask) { - int mask = valueMask << lsbPos; + int mask = valueMask << lsbPos; int notMask = ~mask; - int result = newData << lsbPos | (toMask & notMask); + int result = newData << lsbPos | (toMask & notMask); return result; } - + @Override public void poll() { this.readFromSensor(); } - + /** * Read one sample from the sensor. This method will read the sample by * reading BYTES_PER_SAMPLE number of bytes from the register OUT_X_L_M. @@ -343,46 +344,46 @@ private void readFromSensor() { return; } int dataLength = BYTES_PER_SAMPLE; - byte[] data = new byte[dataLength]; - int bytesRead = this.i2c.read(Registers.OUT_X_L_M.getAddress(), data, 0, dataLength); + byte[] data = new byte[dataLength]; + int bytesRead = this.i2c.read(Registers.OUT_X_L_M.getAddress(), data, 0, dataLength); if (bytesRead != BYTES_PER_SAMPLE) { ErrorReporter errorReporter = ErrorReporter.getInstance(); String errorMsg = "Incorrect number of bytes for magnetometer read from IMU."; errorReporter.reportError(Errors.IMU_IO_ERROR, errorMsg); return; } - MagReading reading = this.buildReading(data); + MagReading reading = this.buildReading(data); this.samples.add(reading); - } catch(IOException e) { + } catch (IOException e) { ErrorReporter errorReporter = ErrorReporter.getInstance(); String errorMsg = "Unable to read from IMU IO Exception"; errorReporter.reportError(Errors.IMU_IO_ERROR, e, errorMsg); } } - + /** * Parse a set of BYTES_PER_SAMPLE bytes into an MagReading. * Normalzie to gauss - * + * * @param data the set of six bytes representing a reading * @return the MagReading which the six bytes belong to */ public MagReading buildReading(byte[] data) { int[] results = this.getData(data); - + int xMag = results[0]; int yMag = results[1]; int zMag = results[2]; - + Vector3 magVec = computeMagneticField(xMag, yMag, zMag); return new MagReading(magVec); } - + /** * Converts the input bytes to shorts where it assumes that the first byte of * the tuple is less significant.
* The array looks like {@code [L,H,L,H, ..., L, H]}. - * + * * @param data byte array of little-endian shorts * @return array of the shorts */ @@ -394,7 +395,7 @@ private int[] getData(byte[] data) { } return results; } - + @Override public MagReading getNext() { return samples.pollFirst(); @@ -404,9 +405,10 @@ public MagReading getNext() { public boolean hasNext() { return !samples.isEmpty(); } - + /** * Converts magnetometer readings to gauss. Uses the current magnetometer scale setting. + * * @param magX x-axis reading from magnetometer * @param magY y-axis reading from magnetometer * @param magZ z-axis reading from magnetometer @@ -415,28 +417,28 @@ public boolean hasNext() { public Vector3 computeMagneticField(int magX, int magY, int magZ) { // Get the sensitivity of the sensor double sensitivity; - switch(scale) { - case GAUSS_4: - sensitivity = Settings.LSM9DS1_SENSITIVITY_MAGNETOMETER_4GAUSS; - break; - case GAUSS_8: - sensitivity = Settings.LSM9DS1_SENSITIVITY_MAGNETOMETER_8GAUSS; - break; - case GAUSS_12: - sensitivity = Settings.LSM9DS1_SENSITIVITY_MAGNETOMETER_12GAUSS; - break; - case GAUSS_16: - sensitivity = Settings.LSM9DS1_SENSITIVITY_MAGNETOMETER_16GAUSS; - break; - default: - throw new IllegalStateException("Sensor has an unknown scale."); + switch (scale) { + case GAUSS_4: + sensitivity = Settings.LSM9DS1_SENSITIVITY_MAGNETOMETER_4GAUSS; + break; + case GAUSS_8: + sensitivity = Settings.LSM9DS1_SENSITIVITY_MAGNETOMETER_8GAUSS; + break; + case GAUSS_12: + sensitivity = Settings.LSM9DS1_SENSITIVITY_MAGNETOMETER_12GAUSS; + break; + case GAUSS_16: + sensitivity = Settings.LSM9DS1_SENSITIVITY_MAGNETOMETER_16GAUSS; + break; + default: + throw new IllegalStateException("Sensor has an unknown scale."); } - + // Compute magnetic field in gauss return new Vector3( - magX * sensitivity, - magY * sensitivity, - magZ * sensitivity); + magX * sensitivity, + magY * sensitivity, + magZ * sensitivity); } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX14830.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX14830.java index 9ea745f..a721a13 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX14830.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX14830.java @@ -1,29 +1,26 @@ package org.rocketproplab.marginalstability.flightcomputer.hal; -import java.io.IOException; -import java.nio.charset.Charset; - +import com.pi4j.io.spi.SpiDevice; import org.rocketproplab.marginalstability.flightcomputer.ErrorReporter; import org.rocketproplab.marginalstability.flightcomputer.Errors; import org.rocketproplab.marginalstability.flightcomputer.Settings; -import com.pi4j.io.spi.SpiDevice; +import java.io.IOException; +import java.nio.charset.Charset; /** * A class that implements the SPI protocol for the MAX14830, it contains the * code to emit serial port events to any listeners listening to ports provided * by the MAX14830. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class MAX14830 implements PollingSensor { /** * The list of ports which we can access on the MAX14830 - * - * @author Max Apodaca * + * @author Max Apodaca */ public enum Port { UART0, @@ -34,9 +31,8 @@ public enum Port { /** * The list of registers found on the MAX14830 - * - * @author Max Apodaca * + * @author Max Apodaca */ public enum Registers { // FIFO DATA @@ -104,33 +100,33 @@ public byte address() { private static final String CHARSET = "US-ASCII"; - private static final int UART_SELECT_LSB_IDX = 5; - private static final byte WRITE = -0x80; - private static final int BYTE_MSB_VALUE = 128; - private static final int BITS_PER_BYTE = 8; + private static final int UART_SELECT_LSB_IDX = 5; + private static final byte WRITE = -0x80; + private static final int BYTE_MSB_VALUE = 128; + private static final int BITS_PER_BYTE = 8; private static final int TX_BUFFER_SIZE = 128; - private SpiDevice spi; - private StringBuffer[] uartBufferArray; + private SpiDevice spi; + private StringBuffer[] uartBufferArray; private SerialPortAdapter[] serialPortArray; - private int[] txFifoLengths; - private Charset charset; + private int[] txFifoLengths; + private Charset charset; /** * Create the MAX14830 and initialize the event handlers with * {@link SerialPortAdapter}. TODO Use chipselect via gpio - * + * * @param spi the Spi device to use, no validation is done */ public MAX14830(SpiDevice spi) { - this.spi = spi; + this.spi = spi; this.uartBufferArray = new StringBuffer[Port.values().length]; this.serialPortArray = new SerialPortAdapter[Port.values().length]; - this.txFifoLengths = new int[Port.values().length]; + this.txFifoLengths = new int[Port.values().length]; for (int i = 0; i < Port.values().length; i++) { this.uartBufferArray[i] = new StringBuffer(); - this.txFifoLengths[i] = TX_BUFFER_SIZE; + this.txFifoLengths[i] = TX_BUFFER_SIZE; final Port port = Port.values()[i]; this.serialPortArray[i] = new SerialPortAdapter(message -> this.writeToPort(port, message)); } @@ -140,28 +136,28 @@ public MAX14830(SpiDevice spi) { /** * Read the length of the transmit buffer for a given port. This will return how * many bytes can currently be written. - * + * * @param port which of the four uart channels to read from * @return the number of free bytes in the FIFO buffer * @throws IOException if we are unable to access /dev/spix.x via Pi4J */ protected int getTXBufferLen(Port port) throws IOException { - int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; - byte command = (byte) (uartSelect | Registers.TxFIFOLvl.address()); + int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; + byte command = (byte) (uartSelect | Registers.TxFIFOLvl.address()); return this.readRegister(command); } /** * Read the receive buffer length for a given port. This reports the number of * bytes in the receive buffer that can be currently read. - * + * * @param port which of the four uart channels to read for. * @return the number of bytes that can be read from the given FIFO buffer. * @throws IOException if we are unable to access /dev/spix.x via Pi4J */ protected int getRXBufferLen(Port port) throws IOException { - int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; - byte command = (byte) (uartSelect | Registers.RxFIFOLvl.address()); + int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; + byte command = (byte) (uartSelect | Registers.RxFIFOLvl.address()); return this.readRegister(command); } @@ -179,13 +175,13 @@ protected int getRXBufferLen(Port port) throws IOException { * above 0x1F (31) are currently not supported as they are read in a different * way. * - * + * * @param command the command to write * @return -1 on failure or the value of the register * @throws IOException if we are unable to access /dev/spix.x via Pi4J */ private int readRegister(byte command) throws IOException { - byte[] data = { command, 0 }; + byte[] data = {command, 0}; byte[] readData = this.spi.write(data); if (readData.length < 2) { return -1; @@ -204,7 +200,7 @@ private int readRegister(byte command) throws IOException { * {@link #getTXBufferLen(Port)} and therefore it is possible to loose data if * too many bytes are sent.. If there are too few bytes in the * {@link #uartBufferArray} then the remaining bytes are written. - * + * * @param port Which UART channel to use * @param charCount how many bytes to write at most * @return how many bytes were actually written. @@ -217,10 +213,10 @@ protected int writeToTxFifo(Port port, int charCount) throws IOException { String first = stringBuffer.substring(0, readCount); stringBuffer.delete(0, readCount); - int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; - byte command = (byte) (uartSelect | WRITE | Registers.THR.address()); - byte[] data = first.getBytes(this.charset); - byte[] toWrite = new byte[data.length + 1]; + int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; + byte command = (byte) (uartSelect | WRITE | Registers.THR.address()); + byte[] data = first.getBytes(this.charset); + byte[] toWrite = new byte[data.length + 1]; toWrite[0] = command; System.arraycopy(data, 0, toWrite, 1, data.length); this.spi.write(toWrite); @@ -230,16 +226,16 @@ protected int writeToTxFifo(Port port, int charCount) throws IOException { /** * Try to read from the RX FIFO buffer for the specified UART channel. This * method does not check if the buffer actually has enough data. - * + * * @param port which channel to read from * @param charCount how many characters to read * @return the characters as a byte stream. * @throws IOException if we are unable to access /dev/spix.x via Pi4J */ protected byte[] readFromRxFifo(Port port, int charCount) throws IOException { - int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; - byte command = (byte) (uartSelect | Registers.RHR.address()); - byte[] zeros = new byte[charCount + 1]; + int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; + byte command = (byte) (uartSelect | Registers.RHR.address()); + byte[] zeros = new byte[charCount + 1]; zeros[0] = command; return this.spi.write(zeros); } @@ -247,7 +243,7 @@ protected byte[] readFromRxFifo(Port port, int charCount) throws IOException { /** * Get a serial port interface compatible representation of the given port. This * can be used as any other serial port would be. - * + * * @param port which UART interface to use * @return the serial port created for the UART interface. */ @@ -257,7 +253,7 @@ public SerialPort getPort(Port port) { /** * Queue the string to be written to the specified port as soon as possible. - * + * * @param port which UART interface to write to * @param data the string to write. Will wait until previous stirngs have been * written. @@ -269,7 +265,7 @@ public void writeToPort(Port port, String data) { /** * Get the string buffer acting as a queue for the given port. - * + * * @param port which UART buffer to select. * @return the string buffer acting as a queue */ @@ -284,7 +280,7 @@ private StringBuffer selectBuffer(Port port) { * The length is cached to prevent unnecessary calls to * {@link #getTXBufferLen(Port)}. If we see that there is enough space from the * last call to {@link #getTXBufferLen(Port)} we write to it. - * + * * @param port Which port to select * @param length How many characters to write, must be >= 0 * @throws IOException if we are unable to access /dev/spix.x via Pi4J @@ -293,7 +289,7 @@ private void writeToPort(Port port, int length) throws IOException { int spaceLeft = TX_BUFFER_SIZE - this.txFifoLengths[port.ordinal()]; if (spaceLeft < length) { int txBufferLen = this.getTXBufferLen(port); - spaceLeft = TX_BUFFER_SIZE - txBufferLen; + spaceLeft = TX_BUFFER_SIZE - txBufferLen; this.txFifoLengths[port.ordinal()] = txBufferLen; } @@ -306,17 +302,17 @@ private void writeToPort(Port port, int length) throws IOException { /** * Read from the given port and call the SerilPort callbacks. Length must be * smaller or equal to the number of bytes in the RX FIFO. - * + * * @param port which port to read * @param length how many bytes to read, passed directly to * {@link #readFromRxFifo(Port, int)} * @throws IOException if we are unable to access /dev/spix.x via Pi4J */ private void readFromPort(Port port, int length) throws IOException { - byte[] byteMessage = this.readFromRxFifo(port, length); - String unprocessedMessage = new String(byteMessage, this.charset); - String message = unprocessedMessage.substring(1); - SerialPortAdapter serialPort = this.serialPortArray[port.ordinal()]; + byte[] byteMessage = this.readFromRxFifo(port, length); + String unprocessedMessage = new String(byteMessage, this.charset); + String message = unprocessedMessage.substring(1); + SerialPortAdapter serialPort = this.serialPortArray[port.ordinal()]; serialPort.newMessage(message); } @@ -325,13 +321,13 @@ private void readFromPort(Port port, int length) throws IOException { * the data.
* Then check if we have data to receive in the RX buffer. If so receive it and * emit events. - * + * * @param port which UART port to read * @throws IOException if we are unable to access /dev/spix.x via Pi4J */ private void pollPort(Port port) throws IOException { StringBuffer buffer = this.selectBuffer(port); - int length = buffer.length(); + int length = buffer.length(); if (length != 0) { this.writeToPort(port, length); } @@ -363,8 +359,8 @@ public void poll() { * {@link Settings#MAX14830_F_REF}. All math is integer math so fREF must be an * integer multiple of 16 * BaudRate or the actual baud rate will differ from the * requested. - * - * @param port the UART channel to use + * + * @param port the UART channel to use * @param baudrate the baud rate in baud * @throws IOException if we are unable to access /dev/spix.x via Pi4J */ @@ -374,11 +370,11 @@ public void setBaudRate(Port port, int baudrate) throws IOException { if (baudrate > 0) { d = Settings.MAX14830_F_REF / (16 * baudrate); } - int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; - byte command = (byte) (uartSelect | WRITE | Registers.BRGConfig.address()); - byte leastSignificantBits = (byte) (d & 0xFF); - byte mostSignificantBits = (byte) ((d >> BITS_PER_BYTE) & 0xFF); - byte[] data = { command, 0, leastSignificantBits, mostSignificantBits }; + int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; + byte command = (byte) (uartSelect | WRITE | Registers.BRGConfig.address()); + byte leastSignificantBits = (byte) (d & 0xFF); + byte mostSignificantBits = (byte) ((d >> BITS_PER_BYTE) & 0xFF); + byte[] data = {command, 0, leastSignificantBits, mostSignificantBits}; this.spi.write(data); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX31856.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX31856.java index 2932cde..ed2a4f8 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX31856.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX31856.java @@ -1,27 +1,25 @@ package org.rocketproplab.marginalstability.flightcomputer.hal; -import java.io.IOException; - +import com.pi4j.io.spi.SpiDevice; import org.rocketproplab.marginalstability.flightcomputer.Time; -import com.pi4j.io.spi.SpiDevice; +import java.io.IOException; /** * Implements SPI protocol for the MAX31856, contains code to read and quantify * linearized thermocouple temperature data. - * - * @author Rudy Thurston * + * @author Rudy Thurston */ public class MAX31856 implements Thermocouple, PollingSensor { - private SpiDevice spi; - private double temp; - private long sampleTime; - private Time clock; + private SpiDevice spi; + private double temp; + private long sampleTime; + private Time clock; - private static final byte REG_TC_TEMP = 0x0C; - private static final double ZERO_TIME = 0.0; + private static final byte REG_TC_TEMP = 0x0C; + private static final double ZERO_TIME = 0.0; private static final double SCALING_FACTOR = 128.0; private static final double MINIMUM_RANGE = -200.0; private static final double MAXIMUM_RANGE = 1372.0; @@ -30,14 +28,14 @@ public class MAX31856 implements Thermocouple, PollingSensor { /** * Create instance of MAX31856 with given SpiDevice. Time will be used to * determine the {@link #getLastMeasurementTime()} return value. - * - * @param spi SpiDevice communicating with MAX31856, no validation check - * @param time the time to use when reporting measurement time. + * + * @param spi SpiDevice communicating with MAX31856, no validation check + * @param time the time to use when reporting measurement time. */ public MAX31856(SpiDevice spi, Time time) { - this.spi = spi; - this.clock = time; - this.temp = TEMP_ERROR; + this.spi = spi; + this.clock = time; + this.temp = TEMP_ERROR; } @Override @@ -53,7 +51,7 @@ public double getLastMeasurementTime() { return ZERO_TIME; } } - + @Override public boolean inUsableRange() { if ((temp >= MINIMUM_RANGE) && (temp <= MAXIMUM_RANGE)) { @@ -78,53 +76,53 @@ public void poll() { * Read the linearized thermocouple temperature from the sensor using a * multi-byte read. Read/Write register memory map, * https://datasheets.maximintegrated.com/en/ds/MAX31856.pdf - * + *

* 0x0C (readData[1]) : | Sign | 2^10 | 2^9 | 2^8 | 2^7 | 2^6 | 2^5 | 2^4 | * 0x0D (readData[2]) : | 2^3 | 2^2 | 2^1 | 2^0 | 2^-1| 2^-2| 2^-3| 2^-4| * 0x0E (readData[3]) : | 2^-5 | 2^-6 | 2^-7| X | X | X | X | X | - * + * * @throws IOException */ private void readTemp() throws IOException { - byte[] data = {REG_TC_TEMP, 0, 0, 0}; - byte[] readData = this.spi.write(data); - if (readData.length < 4) { - return; - } - - // Perform 2's complement if rawData is negative - byte sign = 0; - byte mask = (byte) 0b10000000; - if ((readData[1] & mask) != 0) { - sign = 1; - readData[1] = (byte)~readData[1]; - readData[2] = (byte)~readData[2]; - readData[3] = (byte)~readData[3]; - } - - // Store 24 bit temperature read into integer placeholder - int rawData = (Byte.toUnsignedInt(readData[1])<<16) + - (Byte.toUnsignedInt(readData[2])<<8) + - Byte.toUnsignedInt(readData[3]) + sign; - - // Returns magnitude of temperature read with correct sign - temp = tempCalc(rawData) * Math.pow(-1, sign); + byte[] data = {REG_TC_TEMP, 0, 0, 0}; + byte[] readData = this.spi.write(data); + if (readData.length < 4) { + return; + } + + // Perform 2's complement if rawData is negative + byte sign = 0; + byte mask = (byte) 0b10000000; + if ((readData[1] & mask) != 0) { + sign = 1; + readData[1] = (byte) ~readData[1]; + readData[2] = (byte) ~readData[2]; + readData[3] = (byte) ~readData[3]; + } + + // Store 24 bit temperature read into integer placeholder + int rawData = (Byte.toUnsignedInt(readData[1]) << 16) + + (Byte.toUnsignedInt(readData[2]) << 8) + + Byte.toUnsignedInt(readData[3]) + sign; + + // Returns magnitude of temperature read with correct sign + temp = tempCalc(rawData) * Math.pow(-1, sign); } - + /** * Calculates magnitude of temperature from raw thermocouple read. - * + *

* data : | X | X | X | X | X | X | X | X | - * | 0 | 2^10 | 2^9 | 2^8 | 2^7 | 2^6 | 2^5 | 2^4 | - * | 2^3 | 2^2 | 2^1 | 2^0 | 2^-1| 2^-2| 2^-3| 2^-4| - * | 2^-5 | 2^-6 | 2^-7| X | X | X | X | X | - * + * | 0 | 2^10 | 2^9 | 2^8 | 2^7 | 2^6 | 2^5 | 2^4 | + * | 2^3 | 2^2 | 2^1 | 2^0 | 2^-1| 2^-2| 2^-3| 2^-4| + * | 2^-5 | 2^-6 | 2^-7| X | X | X | X | X | + * * @param data the 24 bit thermocouple read * @return Magnitude of linearized temperature */ private double tempCalc(int data) { - data = data >>> 5; - return data/SCALING_FACTOR; + data = data >>> 5; + return data / SCALING_FACTOR; } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/MagReading.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/MagReading.java index 77c80c2..821a0f1 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/MagReading.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/MagReading.java @@ -8,23 +8,22 @@ * strength of the magnetic field at the current location. * Note that the magnetic field vector from the magnetometer is in the body * frame (measured x, y, and z are relative to the orientation of the sensor). - * - * @author Enlil Odisho * + * @author Enlil Odisho */ public class MagReading { - + private Vector3 magField; - + /** * Construct a new MagReading to store the magnetic field vector. - * + * * @param magField the magnetic field vector measured from the IMU */ public MagReading(Vector3 magField) { this.magField = magField; } - + /** * @return the magnetic field vector */ diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/Magnetometer.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/Magnetometer.java index 0ea563f..e606a5c 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/Magnetometer.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/Magnetometer.java @@ -4,16 +4,15 @@ * An interface for a magnetometer sensor. A sensor implementing this interface * will give an iterable list of MagReadings. If hasNext returns true there will * be at least another magnetometer reading. - * - * @author max * + * @author max */ public interface Magnetometer { /** * Read the next magnetometer reading, returns null if {@link #hasNext()} * returns false. - * + * * @return the next magnetometer reading or null. */ public MagReading getNext(); @@ -21,7 +20,7 @@ public interface Magnetometer { /** * Determines if there is another reading from the magnetometer that can be * read with {@link #getNext()} - * + * * @return true if {@link #getNext()} will return a new magnetometer reading, * false otherwise. */ diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/PollingGroup.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/PollingGroup.java index adf7f18..df0c69a 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/PollingGroup.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/PollingGroup.java @@ -5,9 +5,8 @@ * to poll a gyroscope and magnetometer on the same chip.
*
* Each time the group is polled each sensor gets polled in series. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class PollingGroup implements PollingSensor { @@ -15,7 +14,7 @@ public class PollingGroup implements PollingSensor { /** * Create a new polling group for the given set of sensors. - * + * * @param pollingSensors the sensors to poll simultaneously */ public PollingGroup(PollingSensor... pollingSensors) { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/PollingSensor.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/PollingSensor.java index adeb3a7..6ef7f94 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/PollingSensor.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/PollingSensor.java @@ -2,9 +2,8 @@ /** * A sensor that can be polled. - * - * @author Max Apodaca * + * @author Max Apodaca */ public interface PollingSensor { /** diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/RegisterValue.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/RegisterValue.java index e3a6316..3c506b5 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/RegisterValue.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/RegisterValue.java @@ -5,9 +5,8 @@ * {@link #getValueMask()} returns a bitmask of what section of the register * should be read and the {@link #getValueLSBPos()} method returns how many bits * to the left of the LSB the LSB of the value is. - * - * @author Max Apodaca * + * @author Max Apodaca */ public interface RegisterValue { @@ -16,7 +15,7 @@ public interface RegisterValue { * cover the specified value.
* For instance a register with three values aabbbccc would mean that value a * has a mask of 0b11000000; - * + * * @return the mask for this value for its register */ public int getValueMask(); @@ -28,9 +27,9 @@ public interface RegisterValue { * value b would be 3 as the LSB of b is three bits to the left of the LSB of * the register as a whole. The LSBPos of c would be 0 and the LSBPos of a would * be 6. - * + * * @return how many bits to the left of the register's LSB the LSB of the value - * is + * is */ public int getValueLSBPos(); @@ -45,9 +44,9 @@ public interface RegisterValue { * must be ordered correctly to yield a correct return value for ordinal. If the * enum has 2 members A_0 and A_1 and A_0 should have value 0 then A_0 must be * the first element in the enum. - * + * * @return the value of this value */ public int ordinal(); - + } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SamplableSensor.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SamplableSensor.java index 7d393c3..0b52cab 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SamplableSensor.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SamplableSensor.java @@ -2,16 +2,15 @@ /** * Sensor that exposes a standardized samplable interface - * - * @author Max * * @param The type that the sensor returns + * @author Max */ public interface SamplableSensor { /** * If the sensor has new data to sample - * + * * @return if the sensor has new data */ public boolean hasNewData(); @@ -19,7 +18,7 @@ public interface SamplableSensor { /** * Get the next datum from the sensor. This can either be a queue or the latest * measurement. - * + * * @return The next datum */ public E getNewData(); @@ -27,7 +26,7 @@ public interface SamplableSensor { /** * Return when the datum that was last returned by {@link #getNewData()} was * captured. - * + * * @return the capture time of the datum returned by {@link #getNewData()} */ public double getLastSampleTime(); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SaraSMSSender.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SaraSMSSender.java index fe5382a..6038ad2 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SaraSMSSender.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SaraSMSSender.java @@ -4,60 +4,58 @@ import org.rocketproplab.marginalstability.flightcomputer.comm.PacketRouter; import org.rocketproplab.marginalstability.flightcomputer.comm.PacketSources; import org.rocketproplab.marginalstability.flightcomputer.events.SerialListener; -import org.rocketproplab.marginalstability.flightcomputer.hal.*; -import java.util.*; public class SaraSMSSender implements SMSSender, SerialListener { - - SerialPort saraSerialPort; - String phoneNumber; - String at; - String message; - int messageIndex; - private PacketRouter router; - GPSPacket packet; - - public SaraSMSSender(SerialPort saraSerialPort) { - this.saraSerialPort = saraSerialPort; - messageIndex = 0; - router = new PacketRouter(); //should this be set to a specific packet router? - - saraSerialPort.write("AT\n"); - saraSerialPort.write("AT+CMGF=1\n"); - } - - @Override - public void sendTextMessage(String number, String data) { - //TODO: Add in a listener that would allow us to check if the AT - //is on, if it's been switched the SMS mode, and if the message - //was sent. - if (number.length() != 11 || data.length() > 160) { - throw new IllegalArgumentException(); - } else { - saraSerialPort.write("AT+CMGS=\"+" + number + "\"\n"); - saraSerialPort.write(data + "\r\n"); - } - } - - public void getGPSInfo() { - saraSerialPort.write("AT+UGPS=1\n"); //turns the gps on. - saraSerialPort.write("AT+UGGGA?\r\n"); - } - - @Override //this re - public void onSerialData(String data) { - int index = data.indexOf(","); - String subData = data.substring(index+1); - - packet = new GPSPacket(subData); - router.recivePacket(packet, PacketSources.AUX_GPS); - //should this throw an error if null data is sent? - //or should it just be thrown to the wayside? - // - } - - //we need to figure out a way to send a message to the - //sara, but so taht it can differentiate between texting - // and not texting - + + SerialPort saraSerialPort; + String phoneNumber; + String at; + String message; + int messageIndex; + private PacketRouter router; + GPSPacket packet; + + public SaraSMSSender(SerialPort saraSerialPort) { + this.saraSerialPort = saraSerialPort; + messageIndex = 0; + router = new PacketRouter(); //should this be set to a specific packet router? + + saraSerialPort.write("AT\n"); + saraSerialPort.write("AT+CMGF=1\n"); + } + + @Override + public void sendTextMessage(String number, String data) { + //TODO: Add in a listener that would allow us to check if the AT + //is on, if it's been switched the SMS mode, and if the message + //was sent. + if (number.length() != 11 || data.length() > 160) { + throw new IllegalArgumentException(); + } else { + saraSerialPort.write("AT+CMGS=\"+" + number + "\"\n"); + saraSerialPort.write(data + "\r\n"); + } + } + + public void getGPSInfo() { + saraSerialPort.write("AT+UGPS=1\n"); //turns the gps on. + saraSerialPort.write("AT+UGGGA?\r\n"); + } + + @Override //this re + public void onSerialData(String data) { + int index = data.indexOf(","); + String subData = data.substring(index + 1); + + packet = new GPSPacket(subData); + router.recivePacket(packet, PacketSources.AUX_GPS); + //should this throw an error if null data is sent? + //or should it just be thrown to the wayside? + // + } + + //we need to figure out a way to send a message to the + //sara, but so taht it can differentiate between texting + // and not texting + } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SensorPoller.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SensorPoller.java index 9ff9f71..ce39df8 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SensorPoller.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SensorPoller.java @@ -2,34 +2,33 @@ /** * A class to poll a {@link PollingSensor} at a fixed rate. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class SensorPoller { - private double pollingRate; - private double nextPollTime; - private boolean hasPolled; + private double pollingRate; + private double nextPollTime; + private boolean hasPolled; private PollingSensor sensor; /** * Initialize a sensor poller that will poll the given sensor every rate * seconds. - * + * * @param sensor the sensor to poll * @param rate the rate at which to poll in seconds */ public SensorPoller(PollingSensor sensor, double rate) { - this.pollingRate = rate; + this.pollingRate = rate; this.nextPollTime = -Double.MAX_VALUE; - this.hasPolled = false; - this.sensor = sensor; + this.hasPolled = false; + this.sensor = sensor; } /** * Update the poller, if enough time has passed the sensor will be polled. - * + * * @param time the current time in seconds */ public void update(double time) { @@ -40,13 +39,13 @@ public void update(double time) { if (!this.hasPolled) { this.nextPollTime = time + this.pollingRate; - this.hasPolled = true; + this.hasPolled = true; } } /** * Determine if we should poll the sensor at this time - * + * * @param time the current time * @return if the sensor needs to be polled */ diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPort.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPort.java index 56e6cf6..8a9460c 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPort.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPort.java @@ -3,17 +3,19 @@ import org.rocketproplab.marginalstability.flightcomputer.events.SerialListener; public interface SerialPort { - - /** - * Register a serial port as a listener - * @param listener the listener to register - */ - public void registerListener(SerialListener listener); - /** - * Send data over serial port - * @param data the string to send - */ - public void write(String data); + /** + * Register a serial port as a listener + * + * @param listener the listener to register + */ + public void registerListener(SerialListener listener); + + /** + * Send data over serial port + * + * @param data the string to send + */ + public void write(String data); } \ No newline at end of file diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPortAdapter.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPortAdapter.java index d9fe673..cb6676a 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPortAdapter.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPortAdapter.java @@ -1,23 +1,22 @@ package org.rocketproplab.marginalstability.flightcomputer.hal; +import org.rocketproplab.marginalstability.flightcomputer.events.SerialListener; + import java.util.HashSet; import java.util.Set; -import org.rocketproplab.marginalstability.flightcomputer.events.SerialListener; - /** * A relay for a serial port. Simply buffers a message without any processing. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class SerialPortAdapter implements SerialPort { private Set listeners; - private SerialListener writeListener; + private SerialListener writeListener; public SerialPortAdapter(SerialListener writeListener) { - this.listeners = new HashSet<>(); + this.listeners = new HashSet<>(); this.writeListener = writeListener; } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/Solenoid.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/Solenoid.java index 016ba55..03b707a 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/Solenoid.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/Solenoid.java @@ -2,21 +2,20 @@ /** * An on off style solenoid that can be used for a variety of purposes - * - * @author Max Apodaca * + * @author Max Apodaca */ public interface Solenoid { /** * Gets if the solenoid is currently in an active state - * + * * @return if the solenoid is active */ public boolean isActive(); /** * Sets the state of the solenoid, either active or not - * + * * @param active whether or not the solenoid is active */ public void set(boolean active); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/Thermocouple.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/Thermocouple.java index e257456..8f281fd 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/Thermocouple.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/Thermocouple.java @@ -3,21 +3,21 @@ public interface Thermocouple { /** * Get the temperature in celsius - * + * * @return the temperature in celsius */ public double getTemperature(); /** * Gets the time at which the last measurement was made - * + * * @return the time of the last measurements */ public double getLastMeasurementTime(); - + /** * Checks if temperature is within logical bounds of the sensor - * + * * @return if temperature is in usable range */ public boolean inUsableRange(); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/TimeBasedSensorSampler.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/TimeBasedSensorSampler.java index 86a44af..62d1cc9 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/TimeBasedSensorSampler.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/TimeBasedSensorSampler.java @@ -3,10 +3,9 @@ /** * Provides checks for the given samplable sensor to allow sampling every time * new data exists. - * - * @author Max * * @param The type which the sensor returns + * @author Max */ public class TimeBasedSensorSampler implements SamplableSensor { @@ -14,16 +13,15 @@ public class TimeBasedSensorSampler implements SamplableSensor { /** * A free function, see {@link #getLastMeasurementTime()} for details. - * - * @author Max * + * @author Max */ public interface LastReadTimeFunction { /** * Get the last time a sample was captured with the guarantees from * {@link SamplableSensor#getLastSampleTime()}. - * + * * @return The time the last measurement was taken. */ public double getLastMeasurementTime(); @@ -31,10 +29,9 @@ public interface LastReadTimeFunction { /** * A free function, see {@link #getNewData()} for details. - * - * @author Max * * @param The type of data returned + * @author Max */ public interface GetNewDataFunction { @@ -42,33 +39,33 @@ public interface GetNewDataFunction { * Get the new datum, this can either be a queue or the most recent one but * should be the same as the time returned in * {@link LastReadTimeFunction#getLastMeasurementTime()}. - * + * * @return The new datum */ public E getNewData(); } private GetNewDataFunction newDataFunction; - private LastReadTimeFunction lastReadTimeFunction; - private double lastTime; - private boolean firstRequest; + private LastReadTimeFunction lastReadTimeFunction; + private double lastTime; + private boolean firstRequest; /** * Create a new sampler the samples the given data function - * + * * @param newDataFunction used to get the latest datum * @param lastReadTimeFunction used to get the time of the latest datum */ public TimeBasedSensorSampler(GetNewDataFunction newDataFunction, LastReadTimeFunction lastReadTimeFunction) { - this.newDataFunction = newDataFunction; + this.newDataFunction = newDataFunction; this.lastReadTimeFunction = lastReadTimeFunction; - this.lastTime = 0; - this.firstRequest = true; + this.lastTime = 0; + this.firstRequest = true; } @Override public boolean hasNewData() { - double lastRead = this.lastReadTimeFunction.getLastMeasurementTime() - lastTime; + double lastRead = this.lastReadTimeFunction.getLastMeasurementTime() - lastTime; boolean hasReachedTime = lastRead > EPSILON; return this.firstRequest || hasReachedTime; } @@ -76,7 +73,7 @@ public boolean hasNewData() { @Override public E getNewData() { this.firstRequest = false; - this.lastTime = this.lastReadTimeFunction.getLastMeasurementTime(); + this.lastTime = this.lastReadTimeFunction.getLastMeasurementTime(); return this.newDataFunction.getNewData(); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/Valves.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/Valves.java index a67de1a..0677042 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/Valves.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/Valves.java @@ -1,5 +1,5 @@ package org.rocketproplab.marginalstability.flightcomputer.hal; public interface Valves { - public void setValve(int index, boolean active) ; + public void setValve(int index, boolean active); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/looper/DurationRequiredEvent.java b/src/org/rocketproplab/marginalstability/flightcomputer/looper/DurationRequiredEvent.java index dcaba10..51cf5f0 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/looper/DurationRequiredEvent.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/looper/DurationRequiredEvent.java @@ -10,12 +10,12 @@ */ public class DurationRequiredEvent extends GenericEvent { private final double durationTrue; - private double sinceTrueTime; + private double sinceTrueTime; public DurationRequiredEvent( double durationTrue, EventCondition condition, EventCallback callback, Time time) { super(condition, callback, time); - this.durationTrue = durationTrue; + this.durationTrue = durationTrue; this.sinceTrueTime = Double.NaN; } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/looper/GenericEvent.java b/src/org/rocketproplab/marginalstability/flightcomputer/looper/GenericEvent.java index aa9049a..42ba2b6 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/looper/GenericEvent.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/looper/GenericEvent.java @@ -10,8 +10,8 @@ */ public class GenericEvent implements EventCallback, EventCondition { private final EventCondition condition; - private final EventCallback callback; - private final Time time; + private final EventCallback callback; + private final Time time; public GenericEvent(EventCondition condition, EventCallback callback, Time time) { this.condition = condition; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java b/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java index b082365..0a3b79a 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java @@ -21,12 +21,12 @@ * @author Chi Chow, Enlil Odisho */ public class Looper { - private final Time time; + private final Time time; private final HashMap callbackMap; /** * List storing all commands that are running. */ - private final ArrayList active; + private final ArrayList active; /** * List storing all commands awaiting execution. diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/looper/ScheduledConditionEvent.java b/src/org/rocketproplab/marginalstability/flightcomputer/looper/ScheduledConditionEvent.java index 73f6cec..a4d1e5f 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/looper/ScheduledConditionEvent.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/looper/ScheduledConditionEvent.java @@ -14,7 +14,7 @@ public class ScheduledConditionEvent extends GenericEvent { public ScheduledConditionEvent( double interval, EventCondition condition, EventCallback callback, Time time) { super(condition, callback, time); - this.interval = interval; + this.interval = interval; this.lastInvoked = Double.NaN; } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/math/InterpolatingVector3.java b/src/org/rocketproplab/marginalstability/flightcomputer/math/InterpolatingVector3.java index 231474d..b4e60d9 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/math/InterpolatingVector3.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/math/InterpolatingVector3.java @@ -4,6 +4,7 @@ public interface InterpolatingVector3 { /** * Gets the interpolated vector at the given time + * * @param time the time to get the vector at * @return the best guess vector at the given time */ diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/math/Quaternion.java b/src/org/rocketproplab/marginalstability/flightcomputer/math/Quaternion.java index 8efaa60..60bebe1 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/math/Quaternion.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/math/Quaternion.java @@ -2,9 +2,8 @@ /** * Quaternion class. - * - * @author Enlil Odisho * + * @author Enlil Odisho */ public class Quaternion { @@ -29,7 +28,7 @@ public Quaternion(double w, double x, double y, double z) { /** * Adds two quaternions together. - * + * * @param other Quaternion to add to this quaternion. * @return Result of addition. */ @@ -44,7 +43,7 @@ public Quaternion add(Quaternion other) { /** * Subtracts another quaternion from this quaternion. - * + * * @param other The quaternion to subtract. * @return Result of subtraction. */ @@ -59,22 +58,22 @@ public Quaternion subtract(Quaternion other) { /** * Multiplies this quaternion with another quaternion. - * + * * @param other Quaternion to multiply with this quaternion. * @return Result of multiplication. */ public Quaternion multiply(Quaternion other) { Quaternion result = new Quaternion(); - result.w = this.w*other.w - this.x*other.x - this.y*other.y - this.z*other.z; - result.x = this.w*other.x + this.x*other.w + this.y*other.z - this.z*other.y; - result.y = this.w*other.y - this.x*other.z + this.y*other.w + this.z*other.x; - result.z = this.w*other.z + this.x*other.y - this.y*other.x + this.z*other.w; + result.w = this.w * other.w - this.x * other.x - this.y * other.y - this.z * other.z; + result.x = this.w * other.x + this.x * other.w + this.y * other.z - this.z * other.y; + result.y = this.w * other.y - this.x * other.z + this.y * other.w + this.z * other.x; + result.z = this.w * other.z + this.x * other.y - this.y * other.x + this.z * other.w; return result; } /** * Scale this quaternion by multiplying it with a scalar. - * + * * @param scalar to multiply with quaternion. * @return Result of multiplication. */ @@ -104,15 +103,15 @@ public Quaternion conjugate() { */ public Quaternion inverse() { double magnitude = this.getMagnitude(); - return this.conjugate().multiply(1.0 / (magnitude*magnitude)); + return this.conjugate().multiply(1.0 / (magnitude * magnitude)); } /** * @return the magnitude of this quaternion */ public double getMagnitude() { - return Math.sqrt(this.w*this.w + this.x*this.x + this.y*this.y + - this.z*this.z); + return Math.sqrt(this.w * this.w + this.x * this.x + this.y * this.y + + this.z * this.z); } /** @@ -149,11 +148,11 @@ public boolean equals(Object other) { return false; } final double EQUAL_TOLERANCE = 0.00001; // TODO may need adjusting - Quaternion otherQuaternion = (Quaternion) other; + Quaternion otherQuaternion = (Quaternion) other; return (Math.abs(this.w - otherQuaternion.w) < EQUAL_TOLERANCE) && - (Math.abs(this.x - otherQuaternion.x) < EQUAL_TOLERANCE) && - (Math.abs(this.y - otherQuaternion.y) < EQUAL_TOLERANCE) && - (Math.abs(this.z - otherQuaternion.z) < EQUAL_TOLERANCE); + (Math.abs(this.x - otherQuaternion.x) < EQUAL_TOLERANCE) && + (Math.abs(this.y - otherQuaternion.y) < EQUAL_TOLERANCE) && + (Math.abs(this.z - otherQuaternion.z) < EQUAL_TOLERANCE); } @Override diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticArray.java b/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticArray.java index bc9bb10..60ac1fb 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticArray.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticArray.java @@ -3,9 +3,8 @@ /** * Array to place statistics into that returns only statistical values. It * provides support for validators to determine if the contained data is valid. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class StatisticArray { @@ -15,7 +14,7 @@ public class StatisticArray { public interface StatisticValidator { /** * Returns if the statistic array is valid - * + * * @param array the current state of the array * @return true if the array is valid */ @@ -23,19 +22,19 @@ public interface StatisticValidator { } private TimedRingBuffer samples; - private StatisticValidator validator; + private StatisticValidator validator; /** * Create a new empty array */ public StatisticArray(int maxCount) { - this.samples = new TimedRingBuffer<>(maxCount); + this.samples = new TimedRingBuffer<>(maxCount); this.validator = array -> true; } /** * Adds a sample to the array - * + * * @param sample the sample to add * @param time the time when the sample was taken */ @@ -45,7 +44,7 @@ public void addSample(double sample, double time) { /** * Returns the mean of the previous samples. For zero samples zero is returned. - * + * * @return the mean of the previous samples */ public double getMean() { @@ -55,7 +54,7 @@ public double getMean() { /** * Returns the mean for the samples taken in the previous seconds - * + * * @param previousSeconds how many seconds to look back * @return the mean of the samples */ @@ -65,7 +64,7 @@ public double getMean(double previousSeconds) { /** * Returns the mean of the last N samples - * + * * @param lastN how many samples to look at * @return the mean of the samples, 0 if lastN is negative */ @@ -79,13 +78,13 @@ public double getMean(int lastN) { /** * implementation of the mean algorithm used by both {@link #getMean(int)} and * {@link #getMean(double)}. - * + * * @param iterator the iterator to grab the samples from * @return the mean of the samples returned by the iterator */ private double getMean(TimedRingBuffer.RingBufferIterator iterator) { - double sum = 0; - int sampleCount = 0; + double sum = 0; + int sampleCount = 0; for (double sample : iterator) { sum += sample; sampleCount++; @@ -98,15 +97,15 @@ private double getMean(TimedRingBuffer.RingBufferIterator iterator) { /** * Returns the variance of the inserted samples. Variance is given by - * + * *

    *       Sum (x_i - x_mean)^2
    * S^2 = --------------------
    *              n - 1
    * 
- * + *

* For fewer than two samples 0 is returned. - * + * * @return the variance of the samples */ public double getVariance() { @@ -117,12 +116,12 @@ public double getVariance() { /** * Returns the variance for samples taken within the last previousSeconds. See * {@link #getVariance()} for details. - * + * * @param previousSeconds the time to look back in * @return the variance of the samples taken in the previous seconds */ public double getVariance(double previousSeconds) { - double mean = this.getMean(previousSeconds); + double mean = this.getMean(previousSeconds); TimedRingBuffer.RingBufferIterator iterator = this.samples.get(previousSeconds); return this.getVariance(mean, iterator); } @@ -130,7 +129,7 @@ public double getVariance(double previousSeconds) { /** * Returns the variance for the last n samples. See {@link #getVariance()} for * details. - * + * * @param lastN how many samples to look at * @return the variance of the previous n samples */ @@ -144,19 +143,19 @@ public double getVariance(int lastN) { /** * Inner implementation constant to all three types of variance calculation - * + * * @param mean the mean of the sample set * @param iterator the iterator to get the samples * @return the variance of the samples */ private double getVariance(double mean, TimedRingBuffer.RingBufferIterator iterator) { - double sumSquared = 0; - int samplesCounted = 0; + double sumSquared = 0; + int samplesCounted = 0; for (double sample : iterator) { sumSquared += Math.pow(sample - mean, 2); samplesCounted++; } - if(samplesCounted < 2) { + if (samplesCounted < 2) { return 0; } double variance = sumSquared / (samplesCounted - 1); @@ -165,7 +164,7 @@ private double getVariance(double mean, TimedRingBuffer.RingBufferIterat /** * Get the number of samples which are contained in this array - * + * * @return the number of samples in this array */ public int getNumberOfSamples() { @@ -174,7 +173,7 @@ public int getNumberOfSamples() { /** * Returns if the array is valid. The default validator always returns true. - * + * * @return if the array is valid */ public boolean isValid() { @@ -183,7 +182,7 @@ public boolean isValid() { /** * Sets the validator to use for data validation. Must not be null. - * + * * @param validator the new validator to use */ public void setValidator(StatisticValidator validator) { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticReporter.java b/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticReporter.java index 403d15d..a181baa 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticReporter.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticReporter.java @@ -8,23 +8,22 @@ /** * A Class to report statistics to the telemetry subsystem. - * - * @author Max * + * @author Max */ public class StatisticReporter implements EventCallback { - private Telemetry telemetry; - private SCMPacketType meanType; - private SCMPacketType varianceType; - private StatisticArray array; + private Telemetry telemetry; + private SCMPacketType meanType; + private SCMPacketType varianceType; + private StatisticArray array; private SamplableSensor sensor; - private double lookbackTime; - private boolean reportVaraince; + private double lookbackTime; + private boolean reportVaraince; /** * Create a new reporter which only reports the mean - * + * * @param sensor what sensor to report * @param telem the telemetry to log to * @param meanType the packet type to use for the mean @@ -35,26 +34,26 @@ public StatisticReporter(SamplableSensor sensor, Telemetry telem, SCMPac /** * Create a new reporter which logs both mean and variance - * + * * @param sensor what sensor to report * @param telem the telemetry to log to * @param meanType the packet type to use for the mean * @param varianceType the packet type to use for the variance */ public StatisticReporter(SamplableSensor sensor, Telemetry telem, SCMPacketType meanType, - SCMPacketType varianceType) { + SCMPacketType varianceType) { this(sensor, telem, meanType, true, varianceType); } private StatisticReporter(SamplableSensor sensor, Telemetry telem, SCMPacketType meanType, - boolean reportVariance, SCMPacketType varianceType) { - this.telemetry = telem; - this.meanType = meanType; - this.array = new StatisticArray(1); - this.sensor = sensor; - this.lookbackTime = -1; + boolean reportVariance, SCMPacketType varianceType) { + this.telemetry = telem; + this.meanType = meanType; + this.array = new StatisticArray(1); + this.sensor = sensor; + this.lookbackTime = -1; this.reportVaraince = reportVariance; - this.varianceType = varianceType; + this.varianceType = varianceType; } /** @@ -99,7 +98,7 @@ public void sample() { /** * Should we call sample, useful for looper constructions with * {@link org.rocketproplab.marginalstability.flightcomputer.looper.Looper#emitIf()} - * + * * @return if data is ready to be sampled */ public boolean shouldSample() { @@ -108,7 +107,7 @@ public boolean shouldSample() { /** * Set the maximum number of samples to store. - * + * * @param size the number of samples to store */ public void setWindowSize(int size) { @@ -118,7 +117,7 @@ public void setWindowSize(int size) { /** * Set the amount of time to look back, by default all samples up to the maximum * count are used. - * + * * @param time how far to look back in seconds */ public void setLookbackTime(double time) { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/math/TimedRingBuffer.java b/src/org/rocketproplab/marginalstability/flightcomputer/math/TimedRingBuffer.java index 3f4255e..bb69a0a 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/math/TimedRingBuffer.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/math/TimedRingBuffer.java @@ -7,19 +7,17 @@ /** * A ring buffer that allows you to iterate based on time - * - * @author Max Apodaca * * @param The type which the buffer is of + * @author Max Apodaca */ public class TimedRingBuffer implements Iterable { /** * An iterator for the ring buffer, will iterate section of ring buffer in * increasing add time. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class RingBufferIterator implements Iterator, Iterable { private Iterator sublistIterator; @@ -28,12 +26,12 @@ public class RingBufferIterator implements Iterator, Iterable { /** * Create a new ring buffer iterator that will iterate the first iterator then * the second - * + * * @param sublistIterator first iterator to iterate * @param nextSublistIterator next iterator to iterate */ private RingBufferIterator(Iterator sublistIterator, Iterator nextSublistIterator) { - this.sublistIterator = sublistIterator; + this.sublistIterator = sublistIterator; this.nextSublistIterator = nextSublistIterator; } @@ -59,26 +57,26 @@ public Iterator iterator() { } - private int capacity; - private int insertPointer; + private int capacity; + private int insertPointer; private ArrayList elements; - private double[] times; + private double[] times; /** * Create a new timed ring buffer with the given capacity - * + * * @param capacity how many elements to store at most */ public TimedRingBuffer(int capacity) { - this.capacity = capacity; + this.capacity = capacity; this.insertPointer = 0; - this.elements = new ArrayList(capacity); - this.times = new double[capacity]; + this.elements = new ArrayList(capacity); + this.times = new double[capacity]; } /** * Add a new element to the buffer and specifies the time - * + * * @param value the element to add * @param time the time at which the element was added, must be greater than or * equal to the previous time @@ -96,7 +94,7 @@ public void add(E value, double time) { /** * Get how many elements are in the buffer - * + * * @return the number of elements in the buffer */ public int size() { @@ -105,23 +103,23 @@ public int size() { /** * Get an iterator for the whole buffer. Iterates in increasing time - * + * * @return an iterator for the whole buffer */ public RingBufferIterator get() { if (this.size() < this.capacity) { return new RingBufferIterator(this.elements.iterator(), Collections.emptyIterator()); } - int elementsSize = this.elements.size(); - List sublistA = this.elements.subList(this.insertPointer, elementsSize); - List sublistB = this.elements.subList(0, this.insertPointer); - RingBufferIterator result = new RingBufferIterator(sublistA.iterator(), sublistB.iterator()); + int elementsSize = this.elements.size(); + List sublistA = this.elements.subList(this.insertPointer, elementsSize); + List sublistB = this.elements.subList(0, this.insertPointer); + RingBufferIterator result = new RingBufferIterator(sublistA.iterator(), sublistB.iterator()); return result; } /** * Takes the mathematical definition of modulo so that -1 mod 5 = 4 - * + * * @param numerator the numerator in the modulo division * @param divisor the divisor in the modulo division * @return numerator modulo divisor @@ -138,12 +136,12 @@ private int trueMod(int numerator, int divisor) { * Get the most recent n elements from the ring buffer. If n is larger than the * number of elements all the elements are returned. The elements are iterated * in increasing order of time. - * + *

* Returns size if n > size. - * - * @throws IndexOutOfBoundsException if n < 0. + * * @param n the number of elements to get * @return an iterator for the most recent n elements + * @throws IndexOutOfBoundsException if n < 0. */ public RingBufferIterator get(int n) { if (n < 0) { @@ -156,7 +154,7 @@ public RingBufferIterator get(int n) { return new RingBufferIterator(Collections.emptyIterator(), Collections.emptyIterator()); } int start = this.trueMod(this.insertPointer - n, this.capacity); - int end = this.insertPointer; + int end = this.insertPointer; if (start < end) { List sublistA = this.elements.subList(start, end); return new RingBufferIterator(sublistA.iterator(), Collections.emptyIterator()); @@ -169,16 +167,16 @@ public RingBufferIterator get(int n) { /** * Get an iterator for the elements within the last pastTime seconds. - * + * * @param pastTime how far in the past to look * @return an iterator for the elements added within the last pastTime seconds. */ public RingBufferIterator get(double pastTime) { - int numberToGet = 1; - double firstTime = this.times[this.trueMod(this.insertPointer - 1, this.capacity)]; + int numberToGet = 1; + double firstTime = this.times[this.trueMod(this.insertPointer - 1, this.capacity)]; for (numberToGet = 1; numberToGet < this.size(); numberToGet++) { - int index = this.insertPointer - numberToGet - 1; - int modIndex = this.trueMod(index, this.capacity); + int index = this.insertPointer - numberToGet - 1; + int modIndex = this.trueMod(index, this.capacity); double timeDelta = firstTime - this.times[modIndex]; if (timeDelta > pastTime) { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/math/Vector3.java b/src/org/rocketproplab/marginalstability/flightcomputer/math/Vector3.java index 84a564a..d063d18 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/math/Vector3.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/math/Vector3.java @@ -4,9 +4,8 @@ /** * A vector class - * - * @author Max Apodaca * + * @author Max Apodaca */ public class Vector3 { @@ -54,8 +53,8 @@ public boolean equals(Object other) { } Vector3 otherVector = (Vector3) other; return (Math.abs(this.x - otherVector.x) < Settings.EQUALS_EPSILON) && - (Math.abs(this.y - otherVector.y) < Settings.EQUALS_EPSILON) && - (Math.abs(this.z - otherVector.z) < Settings.EQUALS_EPSILON); + (Math.abs(this.y - otherVector.y) < Settings.EQUALS_EPSILON) && + (Math.abs(this.z - otherVector.z) < Settings.EQUALS_EPSILON); } @Override diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/mockPi4J/DummyGpioPinImpl.java b/src/org/rocketproplab/marginalstability/flightcomputer/mockPi4J/DummyGpioPinImpl.java index 7d2b910..4140f83 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/mockPi4J/DummyGpioPinImpl.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/mockPi4J/DummyGpioPinImpl.java @@ -1,206 +1,200 @@ package org.rocketproplab.marginalstability.flightcomputer.mockPi4J; +import com.pi4j.io.gpio.*; +import com.pi4j.io.gpio.event.GpioPinListener; + import java.util.Collection; import java.util.List; import java.util.Map; -import com.pi4j.io.gpio.GpioPin; -import com.pi4j.io.gpio.GpioPinShutdown; -import com.pi4j.io.gpio.GpioProvider; -import com.pi4j.io.gpio.Pin; -import com.pi4j.io.gpio.PinMode; -import com.pi4j.io.gpio.PinPullResistance; -import com.pi4j.io.gpio.PinState; -import com.pi4j.io.gpio.event.GpioPinListener; +public class DummyGpioPinImpl implements GpioPin { + + @Override + public void addListener(GpioPinListener... arg0) { + + } + + @Override + public void addListener(List arg0) { + + } + + @Override + public void clearProperties() { + + } + + @Override + public void export(PinMode arg0) { + + } + + @Override + public void export(PinMode arg0, PinState arg1) { + + } + + public PinState getState() { + return null; + } + + @Override + public Collection getListeners() { + return null; + } + + @Override + public PinMode getMode() { + return null; + } + + @Override + public String getName() { + return null; + } + + @Override + public Pin getPin() { + return null; + } + + @Override + public Map getProperties() { + return null; + } + + @Override + public String getProperty(String arg0) { + return null; + } + + @Override + public String getProperty(String arg0, String arg1) { + return null; + } + + @Override + public GpioProvider getProvider() { + return null; + } + + @Override + public PinPullResistance getPullResistance() { + return null; + } + + @Override + public GpioPinShutdown getShutdownOptions() { + return null; + } + + @Override + public Object getTag() { + return null; + } + + @Override + public boolean hasListener(GpioPinListener... arg0) { + return false; + } + + @Override + public boolean hasProperty(String arg0) { + return false; + } + + @Override + public boolean isExported() { + return false; + } + + @Override + public boolean isMode(PinMode arg0) { + return false; + } + + @Override + public boolean isPullResistance(PinPullResistance arg0) { + return false; + } + + @Override + public void removeAllListeners() { + + } + + @Override + public void removeListener(GpioPinListener... arg0) { + + } + + @Override + public void removeListener(List arg0) { + + } + + @Override + public void removeProperty(String arg0) { + + } + + @Override + public void setMode(PinMode arg0) { + + } + + @Override + public void setName(String arg0) { + + } + + @Override + public void setProperty(String arg0, String arg1) { + + } + + @Override + public void setPullResistance(PinPullResistance arg0) { + + } + + @Override + public void setShutdownOptions(GpioPinShutdown arg0) { + + } + + @Override + public void setShutdownOptions(Boolean arg0) { + + } + + @Override + public void setShutdownOptions(Boolean arg0, PinState arg1) { + + } + + @Override + public void setShutdownOptions(Boolean arg0, PinState arg1, PinPullResistance arg2) { + + } + + @Override + public void setShutdownOptions(Boolean arg0, PinState arg1, PinPullResistance arg2, PinMode arg3) { + + } + + @Override + public void setTag(Object arg0) { + + } + + @Override + public void unexport() { + + } + + public void setState(PinState solenoidState) { -public class DummyGpioPinImpl implements GpioPin{ - - @Override - public void addListener(GpioPinListener... arg0) { - - } - - @Override - public void addListener(List arg0) { - - } - - @Override - public void clearProperties() { - - } - - @Override - public void export(PinMode arg0) { - - } - - @Override - public void export(PinMode arg0, PinState arg1) { - - } - - public PinState getState() { - return null; - } - - @Override - public Collection getListeners() { - return null; - } - - @Override - public PinMode getMode() { - return null; - } - - @Override - public String getName() { - return null; - } - - @Override - public Pin getPin() { - return null; - } - - @Override - public Map getProperties() { - return null; - } - - @Override - public String getProperty(String arg0) { - return null; - } - - @Override - public String getProperty(String arg0, String arg1) { - return null; - } - - @Override - public GpioProvider getProvider() { - return null; - } - - @Override - public PinPullResistance getPullResistance() { - return null; - } - - @Override - public GpioPinShutdown getShutdownOptions() { - return null; - } - - @Override - public Object getTag() { - return null; - } - - @Override - public boolean hasListener(GpioPinListener... arg0) { - return false; - } - - @Override - public boolean hasProperty(String arg0) { - return false; - } - - @Override - public boolean isExported() { - return false; - } - - @Override - public boolean isMode(PinMode arg0) { - return false; - } - - @Override - public boolean isPullResistance(PinPullResistance arg0) { - return false; - } - - @Override - public void removeAllListeners() { - - } - - @Override - public void removeListener(GpioPinListener... arg0) { - - } - - @Override - public void removeListener(List arg0) { - - } - - @Override - public void removeProperty(String arg0) { - - } - - @Override - public void setMode(PinMode arg0) { - - } - - @Override - public void setName(String arg0) { - - } - - @Override - public void setProperty(String arg0, String arg1) { - - } - - @Override - public void setPullResistance(PinPullResistance arg0) { - - } - - @Override - public void setShutdownOptions(GpioPinShutdown arg0) { - - } - - @Override - public void setShutdownOptions(Boolean arg0) { - - } - - @Override - public void setShutdownOptions(Boolean arg0, PinState arg1) { - - } - - @Override - public void setShutdownOptions(Boolean arg0, PinState arg1, PinPullResistance arg2) { - - } - - @Override - public void setShutdownOptions(Boolean arg0, PinState arg1, PinPullResistance arg2, PinMode arg3) { - - } - - @Override - public void setTag(Object arg0) { - - } - - @Override - public void unexport() { - - } - - public void setState(PinState solenoidState) { - - } + } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/EngineSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/EngineSubsystem.java index 6b68314..b47906f 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/EngineSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/EngineSubsystem.java @@ -1,50 +1,51 @@ package org.rocketproplab.marginalstability.flightcomputer.subsystems; -import java.util.HashSet; -import java.util.Set; - import org.rocketproplab.marginalstability.flightcomputer.Settings; import org.rocketproplab.marginalstability.flightcomputer.events.EngineEventListener; import org.rocketproplab.marginalstability.flightcomputer.hal.Valves; +import java.util.HashSet; +import java.util.Set; + public class EngineSubsystem { - private Valves valves; - private Set listeners; - - EngineSubsystem(Valves valves){ - this.valves = valves; - this.listeners = new HashSet<>(); - } - public void activateEngine() { - this.setValveBasedOnSettings(Settings.ENGINE_ON_VALVE_STATES); - this.notifyEngineActivation(); - } - - public void deactivateEngine() { - this.setValveBasedOnSettings(Settings.ENGINE_ABORT_VALVE_STATES); - this.notifyEngineDeactivation(); - } - - private void setValveBasedOnSettings(boolean[] EngineValveStates) { - for (int index = 0; index < EngineValveStates.length; index++) { - valves.setValve(index, EngineValveStates[index]); - } - } - - private void notifyEngineActivation() { - for(EngineEventListener listener : this.listeners) { - listener.onEngineActivation(); - } - } - - private void notifyEngineDeactivation() { - for(EngineEventListener listener : this.listeners) { - listener.onEngineShutdown(); - } - } - - public void registerEngineListener(EngineEventListener listener) { - this.listeners.add(listener); - } - + private Valves valves; + private Set listeners; + + EngineSubsystem(Valves valves) { + this.valves = valves; + this.listeners = new HashSet<>(); + } + + public void activateEngine() { + this.setValveBasedOnSettings(Settings.ENGINE_ON_VALVE_STATES); + this.notifyEngineActivation(); + } + + public void deactivateEngine() { + this.setValveBasedOnSettings(Settings.ENGINE_ABORT_VALVE_STATES); + this.notifyEngineDeactivation(); + } + + private void setValveBasedOnSettings(boolean[] EngineValveStates) { + for (int index = 0; index < EngineValveStates.length; index++) { + valves.setValve(index, EngineValveStates[index]); + } + } + + private void notifyEngineActivation() { + for (EngineEventListener listener : this.listeners) { + listener.onEngineActivation(); + } + } + + private void notifyEngineDeactivation() { + for (EngineEventListener listener : this.listeners) { + listener.onEngineShutdown(); + } + } + + public void registerEngineListener(EngineEventListener listener) { + this.listeners.add(listener); + } + } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/GPSMessageSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/GPSMessageSubsystem.java index 764adfd..6c857a6 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/GPSMessageSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/GPSMessageSubsystem.java @@ -4,48 +4,47 @@ import org.rocketproplab.marginalstability.flightcomputer.comm.GPSPacket; import org.rocketproplab.marginalstability.flightcomputer.comm.PacketDirection; import org.rocketproplab.marginalstability.flightcomputer.events.PacketListener; -import org.rocketproplab.marginalstability.flightcomputer.tracking.FlightMode; import org.rocketproplab.marginalstability.flightcomputer.tracking.FlightState; public class GPSMessageSubsystem implements PacketListener { - - String message; - double lastTime; - double thisTime; - GPSPacket packet; - FlightState currentState; - - private static final double TIME_BETWEEN = 0; - - public GPSMessageSubsystem() { - lastTime = 0; - thisTime = 0; - currentState = new FlightState(); - } - - public String createMessage() { - double latitude = this.packet.getLatitude(); - double longitude = this.packet.getLongitude(); - - message = "The longitude is: " + longitude + "\nThe latitude" - + " is: " + latitude; - - return message; - // how do we get message into string(data) if the phone number - //is passed in the method call and we don't necessarily have - //the phone number yet? - } - - @Override - public void onPacket(PacketDirection direction, Object packet) { - if (direction == PacketDirection.RECIVE) { - //should include, but i can't test with that in - //&& currentState.getFlightMode() == FlightMode.Landed - thisTime = (new Time()).getSystemTime(); - if (thisTime - lastTime > TIME_BETWEEN) { - this.packet = (GPSPacket)packet; - } - } - } + + String message; + double lastTime; + double thisTime; + GPSPacket packet; + FlightState currentState; + + private static final double TIME_BETWEEN = 0; + + public GPSMessageSubsystem() { + lastTime = 0; + thisTime = 0; + currentState = new FlightState(); + } + + public String createMessage() { + double latitude = this.packet.getLatitude(); + double longitude = this.packet.getLongitude(); + + message = "The longitude is: " + longitude + "\nThe latitude" + + " is: " + latitude; + + return message; + // how do we get message into string(data) if the phone number + //is passed in the method call and we don't necessarily have + //the phone number yet? + } + + @Override + public void onPacket(PacketDirection direction, Object packet) { + if (direction == PacketDirection.RECIVE) { + //should include, but i can't test with that in + //&& currentState.getFlightMode() == FlightMode.Landed + thisTime = (new Time()).getSystemTime(); + if (thisTime - lastTime > TIME_BETWEEN) { + this.packet = (GPSPacket) packet; + } + } + } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/LandedSMSSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/LandedSMSSubsystem.java index ce81d7f..d6c6137 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/LandedSMSSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/LandedSMSSubsystem.java @@ -15,13 +15,13 @@ */ public class LandedSMSSubsystem implements Subsystem, FlightStateListener, PacketListener { - public static final double SMS_INTERVAL = 15.0; // Interval to SMS, in seconds - private static final String SMS_FORMAT = "Landed! https://www.google.com/maps/place/%f+%f"; + public static final double SMS_INTERVAL = 15.0; // Interval to SMS, in seconds + private static final String SMS_FORMAT = "Landed! https://www.google.com/maps/place/%f+%f"; - private String phoneNumber; + private String phoneNumber; private SMSSender smsSender; - private GPSPacket lastPacket = null; + private GPSPacket lastPacket = null; private FlightMode flightMode = null; /** @@ -32,7 +32,7 @@ public class LandedSMSSubsystem */ public LandedSMSSubsystem(String phoneNumber, SMSSender smsSender) { this.phoneNumber = phoneNumber; - this.smsSender = smsSender; + this.smsSender = smsSender; } @Override diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java index 5d70977..a81e698 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java @@ -23,151 +23,151 @@ public class ParachuteSubsystem implements FlightStateListener, PositionListener, Subsystem { - private static final String MAIN_CHUTE_TAG = "MainChute"; - - private Solenoid mainChute; - private Solenoid drogueChute; - private InterpolatingVector3 position; - private Time time; - private Barometer barometer; - private Looper looper; - - private List parachuteListeners; - - /** - * Create a new parachute subsystem - * - * @param mainChute the solenoid to deploy the main chute - * @param drogueChute the solenoid to deploy the drogue chute - * @param time the rocket time - */ - public ParachuteSubsystem(Solenoid mainChute, Solenoid drogueChute, - Time time, Barometer barometer) { - this.mainChute = mainChute; - this.drogueChute = drogueChute; - this.time = time; - this.barometer = barometer; - this.parachuteListeners = new ArrayList<>(); - } - - /** - * Register drogue chute and main chute open conditions as - * events in the provided Looper. - * - * @param looper to register events to - */ - @Override - public void prepare(Looper looper) { - this.looper = looper; - } - - /** - * Determine whether the flight mode should trigger the drogue chute to open. - * - * @param flightMode FlightMode to test - * @return whether the drogue chute should open - */ - private boolean shouldDrogueChuteOpenByFlightMode(FlightMode flightMode) { - return flightMode.ordinal() >= FlightMode.Apogee.ordinal(); - } - - private boolean shouldMainChuteOpenByPressure() { - Vector3 currentPos = this.position.getAt(time.getSystemTime()); - boolean b1 = currentPos.getZ() < Settings.MAIN_CHUTE_HEIGHT; - boolean b2 = barometer.getPressure() < Settings.MAIN_CHUTE_PRESSURE; - return b1 && b2; + private static final String MAIN_CHUTE_TAG = "MainChute"; + + private Solenoid mainChute; + private Solenoid drogueChute; + private InterpolatingVector3 position; + private Time time; + private Barometer barometer; + private Looper looper; + + private List parachuteListeners; + + /** + * Create a new parachute subsystem + * + * @param mainChute the solenoid to deploy the main chute + * @param drogueChute the solenoid to deploy the drogue chute + * @param time the rocket time + */ + public ParachuteSubsystem(Solenoid mainChute, Solenoid drogueChute, + Time time, Barometer barometer) { + this.mainChute = mainChute; + this.drogueChute = drogueChute; + this.time = time; + this.barometer = barometer; + this.parachuteListeners = new ArrayList<>(); + } + + /** + * Register drogue chute and main chute open conditions as + * events in the provided Looper. + * + * @param looper to register events to + */ + @Override + public void prepare(Looper looper) { + this.looper = looper; + } + + /** + * Determine whether the flight mode should trigger the drogue chute to open. + * + * @param flightMode FlightMode to test + * @return whether the drogue chute should open + */ + private boolean shouldDrogueChuteOpenByFlightMode(FlightMode flightMode) { + return flightMode.ordinal() >= FlightMode.Apogee.ordinal(); + } + + private boolean shouldMainChuteOpenByPressure() { + Vector3 currentPos = this.position.getAt(time.getSystemTime()); + boolean b1 = currentPos.getZ() < Settings.MAIN_CHUTE_HEIGHT; + boolean b2 = barometer.getPressure() < Settings.MAIN_CHUTE_PRESSURE; + return b1 && b2; // return currentPos.getZ() < Settings.MAIN_CHUTE_HEIGHT && // barometer.getPressure() >= Settings.MAIN_CHUTE_PRESSURE; + } + + private boolean shouldMainChuteCheckPressure(FlightMode flightMode) { + return this.position != null && flightMode == FlightMode.Falling; + } + + /** + * Set drogueChute to active and + * emit drogue chute open event to all listeners. + */ + private void drogueChuteOpen() { + boolean wasActive = drogueChute.isActive(); + drogueChute.set(true); + if (!wasActive) { + for (ParachuteListener listener : parachuteListeners) { + listener.onDrogueOpen(); + } } - - private boolean shouldMainChuteCheckPressure(FlightMode flightMode) { - return this.position != null && flightMode == FlightMode.Falling; - } - - /** - * Set drogueChute to active and - * emit drogue chute open event to all listeners. - */ - private void drogueChuteOpen() { - boolean wasActive = drogueChute.isActive(); - drogueChute.set(true); - if (!wasActive) { - for (ParachuteListener listener : parachuteListeners) { - listener.onDrogueOpen(); - } - } + } + + /** + * Set mainChute to active and + * emit main chute open event to all listeners. + */ + private void mainChuteOpen() { + // remove main chute open event from Looper + if (this.looper.removeEvent(MAIN_CHUTE_TAG) == null) { + // TODO: Log that main chute was deployed because of pressure } - /** - * Set mainChute to active and - * emit main chute open event to all listeners. - */ - private void mainChuteOpen() { - // remove main chute open event from Looper - if (this.looper.removeEvent(MAIN_CHUTE_TAG) == null) { - // TODO: Log that main chute was deployed because of pressure - } - - boolean wasActive = mainChute.isActive(); - mainChute.set(true); - if (!wasActive) { - for (ParachuteListener listener : parachuteListeners) { - listener.onMainChuteOpen(); - } - } + boolean wasActive = mainChute.isActive(); + mainChute.set(true); + if (!wasActive) { + for (ParachuteListener listener : parachuteListeners) { + listener.onMainChuteOpen(); + } } - - /** - * Attempt to open the main chute - * - * @return if the deployment was successful - */ - public boolean attemptMainChuteOpen() { + } + + /** + * Attempt to open the main chute + * + * @return if the deployment was successful + */ + public boolean attemptMainChuteOpen() { /* TODO: Find a better way to check if the drogue chute is currently open, and if the main chute deployed successfully */ - if (drogueChute.isActive()) - mainChuteOpen(); - else { - return false; - } - - return mainChute.isActive(); - } - - /** - * Attempt to open the drogue chute - * - * @return if the deployment was successful - */ - public boolean attemptDrogueChuteOpen() { - drogueChuteOpen(); - - // TODO: Find a better way to check if the drogue chute deployed successfully - return drogueChute.isActive(); - } - - @Override - public void onFlightModeChange(FlightMode newMode) { - if (shouldDrogueChuteOpenByFlightMode(newMode)) { - drogueChuteOpen(); - } - if (shouldMainChuteCheckPressure(newMode)) { - looper.emitOnceIf(MAIN_CHUTE_TAG, Settings.MAIN_CHUTE_PRESSURE_TIME_THRESHOLD, - this::shouldMainChuteOpenByPressure, (tag, from) -> mainChuteOpen()); - } + if (drogueChute.isActive()) + mainChuteOpen(); + else { + return false; } - @Override - public void onPositionEstimate(InterpolatingVector3 positionEstimate) { - this.position = positionEstimate; + return mainChute.isActive(); + } + + /** + * Attempt to open the drogue chute + * + * @return if the deployment was successful + */ + public boolean attemptDrogueChuteOpen() { + drogueChuteOpen(); + + // TODO: Find a better way to check if the drogue chute deployed successfully + return drogueChute.isActive(); + } + + @Override + public void onFlightModeChange(FlightMode newMode) { + if (shouldDrogueChuteOpenByFlightMode(newMode)) { + drogueChuteOpen(); } - - /** - * Add a ParachuteListener to emit parachute changes - * - * @param parachuteListener ParachuteListener to emit callbacks to - */ - public void addParachuteListener(ParachuteListener parachuteListener) { - parachuteListeners.add(parachuteListener); + if (shouldMainChuteCheckPressure(newMode)) { + looper.emitOnceIf(MAIN_CHUTE_TAG, Settings.MAIN_CHUTE_PRESSURE_TIME_THRESHOLD, + this::shouldMainChuteOpenByPressure, (tag, from) -> mainChuteOpen()); } + } + + @Override + public void onPositionEstimate(InterpolatingVector3 positionEstimate) { + this.position = positionEstimate; + } + + /** + * Add a ParachuteListener to emit parachute changes + * + * @param parachuteListener ParachuteListener to emit callbacks to + */ + public void addParachuteListener(ParachuteListener parachuteListener) { + parachuteListeners.add(parachuteListener); + } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SensorSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SensorSubsystem.java index cc59392..6422fae 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SensorSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SensorSubsystem.java @@ -1,23 +1,22 @@ package org.rocketproplab.marginalstability.flightcomputer.subsystems; -import java.util.ArrayList; -import java.util.Collections; -import java.util.List; - import org.rocketproplab.marginalstability.flightcomputer.Time; import org.rocketproplab.marginalstability.flightcomputer.hal.PollingSensor; import org.rocketproplab.marginalstability.flightcomputer.hal.SensorPoller; import org.rocketproplab.marginalstability.flightcomputer.looper.Looper; +import java.util.ArrayList; +import java.util.Collections; +import java.util.List; + /** * A subsystem to handle ticking the sensors at a fixed rate. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class SensorSubsystem implements Subsystem { private List sensorPollers; - private Time time; + private Time time; /** * Create the subsystem using the given time. @@ -26,7 +25,7 @@ public class SensorSubsystem implements Subsystem { */ public SensorSubsystem(Time time) { this.sensorPollers = Collections.synchronizedList(new ArrayList<>()); - this.time = time; + this.time = time; } @Override diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/StatsSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/StatsSubsystem.java index cfb60ac..da3a31f 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/StatsSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/StatsSubsystem.java @@ -1,27 +1,26 @@ package org.rocketproplab.marginalstability.flightcomputer.subsystems; -import java.util.ArrayList; -import java.util.List; - import org.rocketproplab.marginalstability.flightcomputer.looper.Looper; import org.rocketproplab.marginalstability.flightcomputer.math.StatisticReporter; +import java.util.ArrayList; +import java.util.List; + /** * Subsystem that contains all of the sensors that are only used to provide * statistics, also listens for events to provide statistics. - * + *

* Contains all the Thermocouple Sensors, the Barometer, and the Pressure * Transducer Subsystem. Listens for parachute deployment, state change, and * navigation updates. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class StatsSubsystem implements Subsystem { private List reporters; - private Telemetry telemetry; - private Looper looper; + private Telemetry telemetry; + private Looper looper; public StatsSubsystem(Telemetry telemetry) { this.reporters = new ArrayList<>(); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Subsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Subsystem.java index 2ba749b..b40a1b3 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Subsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Subsystem.java @@ -4,9 +4,8 @@ /** * The basic super class of a subsystem. - * - * @author Max Apodaca, Chi Chow * + * @author Max Apodaca, Chi Chow */ public interface Subsystem { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java index a66df7d..0752c36 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java @@ -1,63 +1,61 @@ package org.rocketproplab.marginalstability.flightcomputer.subsystems; -import java.util.logging.Level; -import java.util.logging.Logger; - import org.rocketproplab.marginalstability.flightcomputer.Errors; import org.rocketproplab.marginalstability.flightcomputer.Info; import org.rocketproplab.marginalstability.flightcomputer.comm.PacketRelay; -import org.rocketproplab.marginalstability.flightcomputer.comm.PacketRouter; import org.rocketproplab.marginalstability.flightcomputer.comm.PacketSources; import org.rocketproplab.marginalstability.flightcomputer.comm.SCMPacket; import org.rocketproplab.marginalstability.flightcomputer.comm.SCMPacketType; +import java.util.logging.Level; +import java.util.logging.Logger; + /** * A reporter for telemetry. It will sends the packet periodically to the * Command Box with the information given. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class Telemetry { - public static final int BASE_10 = 10; - public static final int BASE_16 = 16; + public static final int BASE_10 = 10; + public static final int BASE_16 = 16; public static final int MAX_PACKET_BASE_10 = (int) Math.round(Math.pow(BASE_10, SCMPacket.DATA_LENGTH)) - 1; public static final int MAX_PACKET_BASE_16 = (int) Math.round(Math.pow(BASE_16, SCMPacket.DATA_LENGTH)) - 1; public static final int MIN_PACKET_BASE_10 = (int) -Math.round(Math.pow(BASE_10, SCMPacket.DATA_LENGTH - 1)) + 1; public static final int MIN_PACKET_BASE_16 = (int) -Math.round(Math.pow(BASE_16, SCMPacket.DATA_LENGTH - 1)) + 1; - public static final String INFINITY = "INF "; - public static final String NEG_INFINITY = "-INF "; - private static final String INT_FORMAT = "%0" + SCMPacket.DATA_LENGTH + "d"; - private static final String HEX_FORMAT = "%0" + SCMPacket.DATA_LENGTH + "x"; + public static final String INFINITY = "INF "; + public static final String NEG_INFINITY = "-INF "; + private static final String INT_FORMAT = "%0" + SCMPacket.DATA_LENGTH + "d"; + private static final String HEX_FORMAT = "%0" + SCMPacket.DATA_LENGTH + "x"; private static final String DOUBLE_FORMAT = "%0" + SCMPacket.DATA_LENGTH + "f"; - private Logger logger; + private Logger logger; private PacketRelay relay; /** * Creates a new telemetry subsystem that logs to the given logger and uses the * given packet reply to send its packets. - * + * * @param logger the logger to use for info output * @param relay the relay to use for sending packets */ public Telemetry(Logger logger, PacketRelay relay) { this.logger = logger; - this.relay = relay; + this.relay = relay; } /** * Reports a double to the command box - * + * * @param type the packet type to send with the double * @param data the double to send */ public void reportTelemetry(SCMPacketType type, double data) { String dataString = String.format(DOUBLE_FORMAT, data).toUpperCase(); - int toPrint = Math.min(dataString.length(), SCMPacket.DATA_LENGTH); - int padLen = (SCMPacket.DATA_LENGTH - toPrint); + int toPrint = Math.min(dataString.length(), SCMPacket.DATA_LENGTH); + int padLen = (SCMPacket.DATA_LENGTH - toPrint); dataString = dataString.substring(0, toPrint); if (padLen > 0) { @@ -76,7 +74,7 @@ public void reportTelemetry(SCMPacketType type, double data) { /** * Reports an integer to the command box in base 16 to allow for greater data to * be set. - * + * * @param type the data type to send * @param data the data to send, must fit in 5 characters */ @@ -88,7 +86,7 @@ public void reportTelemetryHex(SCMPacketType type, int data) { /** * Reports an integer to the command box. If greater than max then infinity is * sent. - * + * * @param type the type of data to send * @param data the data to be sent, must fit in 5 character */ @@ -99,7 +97,7 @@ public void reportTelemetry(SCMPacketType type, int data) { /** * Internally report the integer value using the given constraints - * + * * @param type the type of packet to send * @param data the integer to be sent * @param format the format string to print this integer @@ -119,7 +117,7 @@ private void reportTelemetry(SCMPacketType type, int data, String format, int ma /** * Send the error to the Command Box - * + * * @param error the error to inform the command box of */ public void reportError(Errors error) { @@ -135,8 +133,8 @@ public void logInfo(Info info) { * Send the heartbeat to the command box */ public void sendHeartbeat() { - String dataString = "00000"; - SCMPacket packet = new SCMPacket(SCMPacketType.HB, dataString); + String dataString = "00000"; + SCMPacket packet = new SCMPacket(SCMPacketType.HB, dataString); this.relay.sendPacket(packet, PacketSources.CommandBox); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java index bcec3d7..f5091a3 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java @@ -1,102 +1,96 @@ package org.rocketproplab.marginalstability.flightcomputer.subsystems; -import org.rocketproplab.marginalstability.flightcomputer.Settings; -import org.rocketproplab.marginalstability.flightcomputer.comm.PacketDirection; -import org.rocketproplab.marginalstability.flightcomputer.comm.PacketRelay; -import org.rocketproplab.marginalstability.flightcomputer.comm.PacketRouter; -import org.rocketproplab.marginalstability.flightcomputer.comm.PacketSources; -import org.rocketproplab.marginalstability.flightcomputer.comm.SCMPacket; -import org.rocketproplab.marginalstability.flightcomputer.comm.SCMPacketType; +import org.rocketproplab.marginalstability.flightcomputer.comm.*; import org.rocketproplab.marginalstability.flightcomputer.events.PacketListener; /* - * * - * - * + * + * + * * @author Clara Chun * */ public class ValveStateSubsystem implements PacketListener { - - private SCMPacket packet; - private int[] valveStates = {-1, -1, -1, -1, -1, -1, -1, -1}; - private String data; - private SCMPacketType id; - private PacketRelay relay; - - public ValveStateSubsystem(PacketRelay relay) { - this.relay = relay; - } - - public void onPacket(PacketDirection direction, SCMPacket packet) { - this.packet = packet; - this.data = packet.getData(); - this.id = packet.getID(); - setStates(); - } - - private void setStates() { - int trackArray = 0; //the value we're starting at on the valveStates array - int maxNum = 5; //what number to end at on the array - int trackString = 0; //what position on the data string we're at. - if (id == SCMPacketType.V1) { - trackArray = 5; - maxNum = 8; - } - - while (trackArray < maxNum) { - if (data.substring(trackString, trackString + 1).equals("0")) { - valveStates[trackArray] = 0; - } else if (data.substring(trackString, trackString + 1).equals("1")) { - valveStates[trackArray] = 1; - } else { - //TODO: report as error if occurs - valveStates[trackArray] = -1; - } - trackString++; - trackArray++; - } - sendPacket(id); - } - - public void setValve(int valve, int state) { - valveStates[valve - 1] = state; - sendPacket(valve); - } - - private void sendPacket(int valve) { - if (valve < 5) { - sendPacket(SCMPacketType.V0); - } else { - sendPacket(SCMPacketType.V1); - } - } - - private void sendPacket(SCMPacketType type) { - SCMPacketType id = type; - String data = ""; - SCMPacket packet; - - int endValue = 5; //value on the valveStates array to stop at when creating a data string - int beginValue = 0; // value on the valveStates array to begin at when creating a data string - if (id == SCMPacketType.V1) { - endValue = 8; - beginValue = 5; - } - for (; beginValue < endValue; beginValue++) { - if (valveStates[beginValue] == -1) { - return; - } - data += "" + valveStates[beginValue]; - } - if (id == SCMPacketType.V1) { - data += "00"; - } - - packet = new SCMPacket(id, data); - this.relay.sendPacket(packet, PacketSources.EngineControllerUnit); - } - - + + private SCMPacket packet; + private int[] valveStates = {-1, -1, -1, -1, -1, -1, -1, -1}; + private String data; + private SCMPacketType id; + private PacketRelay relay; + + public ValveStateSubsystem(PacketRelay relay) { + this.relay = relay; + } + + public void onPacket(PacketDirection direction, SCMPacket packet) { + this.packet = packet; + this.data = packet.getData(); + this.id = packet.getID(); + setStates(); + } + + private void setStates() { + int trackArray = 0; //the value we're starting at on the valveStates array + int maxNum = 5; //what number to end at on the array + int trackString = 0; //what position on the data string we're at. + if (id == SCMPacketType.V1) { + trackArray = 5; + maxNum = 8; + } + + while (trackArray < maxNum) { + if (data.substring(trackString, trackString + 1).equals("0")) { + valveStates[trackArray] = 0; + } else if (data.substring(trackString, trackString + 1).equals("1")) { + valveStates[trackArray] = 1; + } else { + //TODO: report as error if occurs + valveStates[trackArray] = -1; + } + trackString++; + trackArray++; + } + sendPacket(id); + } + + public void setValve(int valve, int state) { + valveStates[valve - 1] = state; + sendPacket(valve); + } + + private void sendPacket(int valve) { + if (valve < 5) { + sendPacket(SCMPacketType.V0); + } else { + sendPacket(SCMPacketType.V1); + } + } + + private void sendPacket(SCMPacketType type) { + SCMPacketType id = type; + String data = ""; + SCMPacket packet; + + int endValue = 5; //value on the valveStates array to stop at when creating a data string + int beginValue = 0; // value on the valveStates array to begin at when creating a data string + if (id == SCMPacketType.V1) { + endValue = 8; + beginValue = 5; + } + for (; beginValue < endValue; beginValue++) { + if (valveStates[beginValue] == -1) { + return; + } + data += "" + valveStates[beginValue]; + } + if (id == SCMPacketType.V1) { + data += "00"; + } + + packet = new SCMPacket(id, data); + this.relay.sendPacket(packet, PacketSources.EngineControllerUnit); + } + + } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/tracking/FlightMode.java b/src/org/rocketproplab/marginalstability/flightcomputer/tracking/FlightMode.java index 0971de4..3a13d3b 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/tracking/FlightMode.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/tracking/FlightMode.java @@ -2,9 +2,8 @@ /** * The different states which the rocket can be in while flying - * - * @author Max Apodaca * + * @author Max Apodaca */ public enum FlightMode { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/tracking/FlightState.java b/src/org/rocketproplab/marginalstability/flightcomputer/tracking/FlightState.java index 90f21fb..115ea24 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/tracking/FlightState.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/tracking/FlightState.java @@ -8,23 +8,22 @@ /** * A class that keeps track of the flight state of the rocket. - * + *

* It looks at different characteristics to determine which flight mode we are * in. - * + *

* We look at the engine activation and shutdown to determine if we are burning * or coasting. - * + *

* We look at the velocity updates to determine if we are in apogee, falling or * landed. - * + *

* We look at the parachute deploying to determine if we are in descending. - * - * @author Max Apodaca * + * @author Max Apodaca */ public class FlightState - implements EngineEventListener, VelocityListener, ParachuteListener { + implements EngineEventListener, VelocityListener, ParachuteListener { private FlightMode currentFlightMode; @@ -37,7 +36,7 @@ public FlightState() { /** * Get the current flight mode which the rocket is in. - * + * * @return the current flight mode */ public FlightMode getFlightMode() { @@ -63,7 +62,7 @@ public void onVelocityUpdate(Vector3 velocity, double time) { /** * Checks if the rocket should transition into the apogee state - * + * * @param velocity the current velocity */ private void checkForApogee(Vector3 velocity) { @@ -78,11 +77,11 @@ private void checkForApogee(Vector3 velocity) { /** * Checks if the rocket should transition from apogee to falling - * + * * @param velocity the current velocity */ private void checkForFalling(Vector3 velocity) { - boolean isApogee = this.currentFlightMode == FlightMode.Apogee; + boolean isApogee = this.currentFlightMode == FlightMode.Apogee; boolean isCoasting = this.currentFlightMode == FlightMode.Coasting; if (!(isApogee || isCoasting)) { return; @@ -95,7 +94,7 @@ private void checkForFalling(Vector3 velocity) { /** * Checks if the rocket should transition into the landed state - * + * * @param velocity the current velocity */ private void checkForLanded(Vector3 velocity) { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/tracking/VelocityCalculator.java b/src/org/rocketproplab/marginalstability/flightcomputer/tracking/VelocityCalculator.java index 4085cf7..f62caad 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/tracking/VelocityCalculator.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/tracking/VelocityCalculator.java @@ -13,9 +13,9 @@ public void onVelocityUpdate(Vector3 velocity, double time) { } public static Vector3 getVelocity(GPSPacket prevGPSPacket, - GPSPacket curGPSPacket) { + GPSPacket curGPSPacket) { double deltaLat = curGPSPacket.getLatitude() - prevGPSPacket.getLatitude(); - double deltaLon = curGPSPacket.getLongitude() - prevGPSPacket.getLongitude(); + double deltaLon = curGPSPacket.getLongitude() - prevGPSPacket.getLongitude(); double deltaTime = curGPSPacket.getTime() - prevGPSPacket.getTime(); double angVelocityX = deltaLon / deltaTime; double angVelocityY = deltaLat / deltaTime; From 528f8e30ce40f7be70ec1536336907f6a9c84525 Mon Sep 17 00:00:00 2001 From: Chi Chow Date: Sat, 17 Apr 2021 13:16:35 -0700 Subject: [PATCH 6/7] "Reformat Code" button V2 --- .../flightcomputer/ErrorReporter.java | 2 +- .../flightcomputer/FlightComputer.java | 2 +- .../flightcomputer/Settings.java | 24 ++++----- .../flightcomputer/comm/FramedSCM.java | 18 +++---- .../flightcomputer/comm/GPSPacket.java | 18 +++---- .../flightcomputer/comm/GPSTransceiver.java | 2 +- .../flightcomputer/comm/PacketRouter.java | 2 +- .../flightcomputer/comm/SCMPacket.java | 6 +-- .../flightcomputer/comm/SCMTransceiver.java | 6 +-- .../commands/HeartbeatCommand.java | 2 +- .../commands/OpenDrogueChuteCommand.java | 2 +- .../commands/OpenMainChuteCommand.java | 2 +- .../commands/SetValveCommand.java | 6 +-- .../flightcomputer/hal/AccelGyroReading.java | 2 +- .../flightcomputer/hal/LPS22HD.java | 6 +-- .../flightcomputer/hal/LSM9DS1AccelGyro.java | 40 +++++++------- .../flightcomputer/hal/LSM9DS1Mag.java | 24 ++++----- .../flightcomputer/hal/MAX14830.java | 54 +++++++++---------- .../flightcomputer/hal/MAX31856.java | 8 +-- .../flightcomputer/hal/SMSSender.java | 2 +- .../flightcomputer/hal/SaraSMSSender.java | 6 +-- .../flightcomputer/hal/Sensor.java | 2 +- .../flightcomputer/hal/SensorPoller.java | 8 +-- .../flightcomputer/hal/SerialPortAdapter.java | 2 +- .../hal/TimeBasedSensorSampler.java | 10 ++-- .../looper/DurationRequiredEvent.java | 2 +- .../flightcomputer/looper/GenericEvent.java | 4 +- .../flightcomputer/looper/Looper.java | 14 ++--- .../looper/ScheduledConditionEvent.java | 2 +- .../flightcomputer/math/Quaternion.java | 2 +- .../flightcomputer/math/StatisticArray.java | 12 ++--- .../math/StatisticReporter.java | 12 ++--- .../flightcomputer/math/TimedRingBuffer.java | 26 ++++----- .../subsystems/EngineSubsystem.java | 2 +- .../subsystems/GPSMessageSubsystem.java | 6 +-- .../subsystems/LandedSMSSubsystem.java | 2 +- .../subsystems/ParachuteSubsystem.java | 12 ++--- .../subsystems/SCMCommandSubsystem.java | 4 +- .../subsystems/SensorSubsystem.java | 2 +- .../flightcomputer/subsystems/Telemetry.java | 10 ++-- .../subsystems/ValveStateSubsystem.java | 20 +++---- .../flightcomputer/tracking/FlightState.java | 2 +- .../tracking/VelocityCalculator.java | 14 ++--- 43 files changed, 202 insertions(+), 202 deletions(-) diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/ErrorReporter.java b/src/org/rocketproplab/marginalstability/flightcomputer/ErrorReporter.java index aee71b7..7d0fef8 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/ErrorReporter.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/ErrorReporter.java @@ -61,7 +61,7 @@ public ErrorReporter() { * @param telemetry the telemetry object to use to send telemetry. */ public ErrorReporter(PrintStream stream, Telemetry telemetry) { - this.stream = stream; + this.stream = stream; this.telemetry = telemetry; } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java b/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java index d9bec09..d59fab0 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java @@ -58,7 +58,7 @@ public static FlightComputer create() { * @param args arguments to configure FlightComputer settings */ private FlightComputer(String[] args) { - this.time = new Time(); + this.time = new Time(); this.looper = new Looper(this.time); initWithArgs(args); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/Settings.java b/src/org/rocketproplab/marginalstability/flightcomputer/Settings.java index a83d336..5ca1676 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/Settings.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/Settings.java @@ -101,8 +101,8 @@ private static Set getSettingFields() { } public static String getConfigContents() { - String result = ""; - Set set = getSettingFields(); + String result = ""; + Set set = getSettingFields(); for (Field field : set) { result += fieldAsString(field) + "\n"; } @@ -114,8 +114,8 @@ public static String fieldAsString(Field field) { if (field.isAnnotationPresent(SettingSectionHeader.class)) { String sectionHeader = "# " + field.getAnnotation(SettingSectionHeader.class).name() + " |\n"; - int dashLength = sectionHeader.length() - 2; - String delimiter = "#" + new String(new char[dashLength]).replace('\0', '-') + "\n"; + int dashLength = sectionHeader.length() - 2; + String delimiter = "#" + new String(new char[dashLength]).replace('\0', '-') + "\n"; result += delimiter + sectionHeader + delimiter + "\n"; } @@ -168,7 +168,7 @@ protected static Set getUsefulLinesFromConfig(List config) { Set usefulLines = new HashSet<>(); for (String line : config) { String lineWithoutComment = line; - int commentStartIdx = line.indexOf('#'); + int commentStartIdx = line.indexOf('#'); if (commentStartIdx >= 0) { lineWithoutComment = line.substring(0, commentStartIdx); } @@ -182,7 +182,7 @@ protected static Set getUsefulLinesFromConfig(List config) { } protected static Map getFieldNameValueMap(List config) { - Set usefulLines = getUsefulLinesFromConfig(config); + Set usefulLines = getUsefulLinesFromConfig(config); Map fieldNameValueMap = new HashMap<>(); for (String line : usefulLines) { int equalsIndex = line.indexOf('='); @@ -191,7 +191,7 @@ protected static Map getFieldNameValueMap(List config) { continue; } String fieldName = line.substring(0, equalsIndex); - String value = line.substring(equalsIndex + 1); + String value = line.substring(equalsIndex + 1); fieldNameValueMap.put(fieldName.trim(), value); } return fieldNameValueMap; @@ -200,7 +200,7 @@ protected static Map getFieldNameValueMap(List config) { protected static void setFieldDoubleArray(Field field, String line) throws IllegalArgumentException, IllegalAccessException { line = line.trim().replace("[", "").replace("]", ""); - String[] newValues = line.split(","); + String[] newValues = line.split(","); double[] fieldValues = (double[]) field.get(null); if (newValues.length != fieldValues.length) { System.err.println("Array length mismatch: " + line); @@ -243,9 +243,9 @@ protected static void setFieldFromConfigLine(Field field, String line) { } public static boolean readSettingsFromConfig(List config, boolean checkOutOfDate) { - Set settingFields = getSettingFields(); + Set settingFields = getSettingFields(); Map fieldNameValueMap = getFieldNameValueMap(config); - boolean outOfDate = false; + boolean outOfDate = false; for (Field field : settingFields) { String fieldName = getNameFromField(field); if (fieldNameValueMap.containsKey(fieldName)) { @@ -268,8 +268,8 @@ private static String getSettingsFileLocation() { } public static void readSettings() { - String configFileLocation = getSettingsFileLocation(); - List lines = Collections.emptyList(); + String configFileLocation = getSettingsFileLocation(); + List lines = Collections.emptyList(); try { lines = Files.readAllLines(Paths.get(configFileLocation)); } catch (IOException e) { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/FramedSCM.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/FramedSCM.java index 019cebf..adaf6f3 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/FramedSCM.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/FramedSCM.java @@ -40,11 +40,11 @@ public class FramedSCM implements PacketListener { * @param framedOutput the callback to output framed packets to */ public FramedSCM(PacketRelay sCMOutput, FramedPacketProcessor framedOutput) { - this.outputQueue = new LinkedList(); - this.activeString = ""; - this.frameLength = -1; + this.outputQueue = new LinkedList(); + this.activeString = ""; + this.frameLength = -1; framedPacketOutput = framedOutput; - this.sCMOutput = sCMOutput; + this.sCMOutput = sCMOutput; } @Override @@ -73,15 +73,15 @@ public void onPacket(PacketDirection direction, SCMPacket packet) { * @return the packet to reply with */ protected SCMPacket processNextPacket(SCMPacket incomingPacket) { - boolean completed = (activeString.length() == frameLength); + boolean completed = (activeString.length() == frameLength); SCMPacket returnpacket = new SCMPacket(SCMPacketType.XB, " "); - String finalmessage = ""; + String finalmessage = ""; if (!incomingPacket.isValid()) { return null; } if (incomingPacket.getID() == SCMPacketType.XS) { returnpacket = processXSPacket(incomingPacket); - completed = false; + completed = false; } else if (incomingPacket.getID() == SCMPacketType.X0) { returnpacket = processX0Packet(incomingPacket); @@ -103,7 +103,7 @@ private SCMPacket processX0Packet(SCMPacket incomingPacket) { if (frameLength == -1) { String[] SCMmessagesplit = incomingPacket.getData().split("\\|"); activeString += SCMmessagesplit[0]; - frameLength = Integer.parseInt(activeString); + frameLength = Integer.parseInt(activeString); activeString = SCMmessagesplit[1]; // TODO Similar to XS, where if the frameLength is still less than 0 or // does not split into several indices @@ -135,7 +135,7 @@ private SCMPacket processXSPacket(SCMPacket incomingPacket) { } else { String getint = incomingPacket.getData(); activeString = "" + Integer.parseInt(getint); - frameLength = -1; + frameLength = -1; } return new SCMPacket(SCMPacketType.XB, " "); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSPacket.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSPacket.java index 2deba0c..dcdc33c 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSPacket.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSPacket.java @@ -51,17 +51,17 @@ private void parseNEMA(String nEMA) { } this.valid = true; - String timeString = nEMAParts[NEMA_TIME_INDEX]; - String latString = nEMAParts[NEMA_LAT_INDEX]; - String lonString = nEMAParts[NEMA_LON_INDEX]; - String sVCountString = nEMAParts[NEMA_SV_COUNT_INDEX]; + String timeString = nEMAParts[NEMA_TIME_INDEX]; + String latString = nEMAParts[NEMA_LAT_INDEX]; + String lonString = nEMAParts[NEMA_LON_INDEX]; + String sVCountString = nEMAParts[NEMA_SV_COUNT_INDEX]; String altitudeString = nEMAParts[NEMA_ALTITUDE_INDEX]; - this.time = Double.parseDouble(timeString); - this.latitude = Double.parseDouble(latString); + this.time = Double.parseDouble(timeString); + this.latitude = Double.parseDouble(latString); this.longitude = Double.parseDouble(lonString); - this.sVCount = Integer.parseInt(sVCountString); - this.altitude = Double.parseDouble(altitudeString); + this.sVCount = Integer.parseInt(sVCountString); + this.altitude = Double.parseDouble(altitudeString); } /** @@ -115,7 +115,7 @@ public boolean equals(Object o) { return false; } GPSPacket other = (GPSPacket) o; - boolean equal = this.valid == other.valid; + boolean equal = this.valid == other.valid; equal &= (this.latitude - other.latitude) < Settings.EQUALS_EPSILON; equal &= (this.longitude - other.longitude) < Settings.EQUALS_EPSILON; equal &= (this.altitude - other.altitude) < Settings.EQUALS_EPSILON; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSTransceiver.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSTransceiver.java index 6d20174..b78a571 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSTransceiver.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSTransceiver.java @@ -29,7 +29,7 @@ public void onSerialData(String data) { router.recivePacket(packet, PacketSources.GPS); } else { ErrorReporter errorReporter = ErrorReporter.getInstance(); - String errorMsg = "Got invalid packet " + data + "!\""; + String errorMsg = "Got invalid packet " + data + "!\""; errorReporter.reportError(errorMsg); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRouter.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRouter.java index d96e546..cda00fc 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRouter.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/PacketRouter.java @@ -67,7 +67,7 @@ private void dispatchPacket(Object o, PacketSources source, PacketDirection dire } } catch (ClassCastException classExecption) { ErrorReporter errorReporter = ErrorReporter.getInstance(); - String errorMsg = "Packet " + o + " is not of suitable type"; + String errorMsg = "Packet " + o + " is not of suitable type"; errorReporter.reportError(null, classExecption, errorMsg); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacket.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacket.java index f713c59..c75a944 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacket.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacket.java @@ -50,7 +50,7 @@ public SCMPacket(String packet) { * @param data the data which the packet holds */ public SCMPacket(SCMPacketType id, String data) { - this.id = id; + this.id = id; this.data = data; this.validate(); } @@ -76,7 +76,7 @@ private void parsepacket(String packet) { checksum = Integer.parseInt(strChecksum); } catch (NumberFormatException exception) { ErrorReporter errorReporter = ErrorReporter.getInstance(); - String errorMsg = "Unable to parse checksum in " + packet; + String errorMsg = "Unable to parse checksum in " + packet; errorReporter.reportError(null, exception, errorMsg); this.isValid = false; return; @@ -87,7 +87,7 @@ private void parsepacket(String packet) { this.id = SCMPacketType.valueOf(packetComponents[0]); } catch (IllegalArgumentException illegalArg) { ErrorReporter errorReporter = ErrorReporter.getInstance(); - String errorMsg = "Got bad packet ID (" + packetComponents[0] + ")!"; + String errorMsg = "Got bad packet ID (" + packetComponents[0] + ")!"; errorReporter.reportError(null, illegalArg, errorMsg); } this.data = packetComponents[1]; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMTransceiver.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMTransceiver.java index 0397810..ef7a2ae 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMTransceiver.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMTransceiver.java @@ -30,8 +30,8 @@ public class SCMTransceiver implements SerialListener, PacketListener */ public SCMTransceiver(SerialPort serialPort, PacketRouter router, PacketSources source) { this.serialPort = serialPort; - this.router = router; - this.source = source; + this.router = router; + this.source = source; } @Override @@ -41,7 +41,7 @@ public void onSerialData(String data) { router.recivePacket(packet, this.source); } else { ErrorReporter errorReporter = ErrorReporter.getInstance(); - String errorMsg = "Got invalid packet " + data + "!"; + String errorMsg = "Got invalid packet " + data + "!"; errorReporter.reportError(null, null, errorMsg); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/HeartbeatCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/HeartbeatCommand.java index 19dd4c0..235f2f8 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/HeartbeatCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/HeartbeatCommand.java @@ -26,7 +26,7 @@ public class HeartbeatCommand implements Command { * @param telemetry the Telemetry object used to send heartbeat */ public HeartbeatCommand(Time time, Telemetry telemetry) { - this.time = time; + this.time = time; this.telemetry = telemetry; } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenDrogueChuteCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenDrogueChuteCommand.java index 3802aaa..3f2ccb6 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenDrogueChuteCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenDrogueChuteCommand.java @@ -13,7 +13,7 @@ public class OpenDrogueChuteCommand implements Command { private OpenDrogueChuteCommand(ParachuteSubsystem parachuteSubsystem, PacketRelay relay) { this.parachuteSubsystem = parachuteSubsystem; - this.relay = relay; + this.relay = relay; } @Override diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenMainChuteCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenMainChuteCommand.java index 7a265d7..ec73b58 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenMainChuteCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenMainChuteCommand.java @@ -13,7 +13,7 @@ public class OpenMainChuteCommand implements Command { private OpenMainChuteCommand(ParachuteSubsystem parachuteSubsystem, PacketRelay relay) { this.parachuteSubsystem = parachuteSubsystem; - this.relay = relay; + this.relay = relay; } @Override diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/SetValveCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/SetValveCommand.java index ff75d04..22b92f7 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/SetValveCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/SetValveCommand.java @@ -12,7 +12,7 @@ public class SetValveCommand implements Command { SetValveCommand(SCMPacket scmpacket, Valves valves) { this.scmpacket = scmpacket; - this.valves = valves; + this.valves = valves; } @Override @@ -27,7 +27,7 @@ public void execute() { valves.setValve(getValveID(), valveState); } catch (IllegalArgumentException dataOnOffException) { ErrorReporter errorReporter = ErrorReporter.getInstance(); - String errorMsg = "Data from SCMPacket was not On or Off. Data was actually: " + scmpacket.getData(); + String errorMsg = "Data from SCMPacket was not On or Off. Data was actually: " + scmpacket.getData(); errorReporter.reportError(null, dataOnOffException, errorMsg); } } @@ -50,7 +50,7 @@ public Subsystem[] getDependencies() { private int getValveID() { int currentvalve = this.scmpacket.getID().ordinal(); int initialvalve = SCMPacketType.V0.ordinal(); - int valveindex = currentvalve - initialvalve; + int valveindex = currentvalve - initialvalve; return valveindex; } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/AccelGyroReading.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/AccelGyroReading.java index 123628e..cd66622 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/AccelGyroReading.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/AccelGyroReading.java @@ -27,7 +27,7 @@ public class AccelGyroReading { * @param rotation */ public AccelGyroReading(Vector3 acc, Vector3 rotation) { - this.acc = acc; + this.acc = acc; this.rotation = rotation; } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LPS22HD.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LPS22HD.java index 7007b2b..99db910 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LPS22HD.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LPS22HD.java @@ -43,7 +43,7 @@ public class LPS22HD implements Barometer, PollingSensor { */ public LPS22HD(I2CDevice i2cDevice, Time time) { this.i2cDevice = i2cDevice; - this.clock = time; + this.clock = time; } /** @@ -56,7 +56,7 @@ public void init() { i2cDevice.write(CTRL_REG1, (byte) (ODR_25HZ | LOW_PASS_ENABLE | LOW_PASS_20TH | KEEP_REGISTERS_SYCHONISED_BDU)); } catch (IOException e) { ErrorReporter errorReporter = ErrorReporter.getInstance(); - String errorMsg = "Unable to write from i2cDevice IO Exception"; + String errorMsg = "Unable to write from i2cDevice IO Exception"; errorReporter.reportError(Errors.LPS22HD_INITIALIZATION_ERROR, e, errorMsg); } } @@ -114,7 +114,7 @@ private void readPressure() { pressure = rawPressure / (double) SCALING_FACTOR; } catch (IOException e) { ErrorReporter errorReporter = ErrorReporter.getInstance(); - String errorMsg = "Unable to read Pressure from i2cDevice IO Exception"; + String errorMsg = "Unable to read Pressure from i2cDevice IO Exception"; errorReporter.reportError(Errors.LPS22HD_PRESSURE_IO_ERROR, e, errorMsg); } sampleTime = clock.getSystemTime(); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1AccelGyro.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1AccelGyro.java index 9e68d13..0e9e937 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1AccelGyro.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1AccelGyro.java @@ -295,7 +295,7 @@ public GyroScale getGyroscopeScale() { */ public void setFIFOEnabled(boolean enabled) throws IOException { int registerValue = this.i2c.read(Registers.CTRL_REG9.getAddress()); - int result = mask(registerValue, enabled ? 1 : 0, FIFO_EN_LSB_POS, FIFO_EN_VAL_MASK); + int result = mask(registerValue, enabled ? 1 : 0, FIFO_EN_LSB_POS, FIFO_EN_VAL_MASK); this.i2c.write(Registers.CTRL_REG9.getAddress(), (byte) result); } @@ -323,7 +323,7 @@ public void setFIFOThreshold(int threshold) throws IOException { threshold = FIFO_THRESHOLD_MIN; } int registerValue = this.i2c.read(Registers.FIFO_CTRL.getAddress()); - int result = mask(registerValue, threshold, FIFO_THRESHOLD_LSB_POS, FIFO_THRESHOLD_MASK); + int result = mask(registerValue, threshold, FIFO_THRESHOLD_LSB_POS, FIFO_THRESHOLD_MASK); this.i2c.write(Registers.FIFO_CTRL.getAddress(), (byte) result); } @@ -336,7 +336,7 @@ public void setFIFOThreshold(int threshold) throws IOException { */ public boolean hasFIFOOverrun() throws IOException { int fifoSRCValue = this.i2c.read(Registers.FIFO_SRC.getAddress()); - int masked = (1 << FIFO_OVERRUN_POS) & fifoSRCValue; + int masked = (1 << FIFO_OVERRUN_POS) & fifoSRCValue; return masked != 0; } @@ -349,7 +349,7 @@ public boolean hasFIFOOverrun() throws IOException { */ public boolean isFIFOThresholdReached() throws IOException { int fifoSRCValue = this.i2c.read(Registers.FIFO_SRC.getAddress()); - int masked = (1 << FIFO_THRESHOLD_STATUS_POS) & fifoSRCValue; + int masked = (1 << FIFO_THRESHOLD_STATUS_POS) & fifoSRCValue; return masked != 0; } @@ -361,7 +361,7 @@ public boolean isFIFOThresholdReached() throws IOException { */ public int getSamplesInFIFO() throws IOException { int fifoSRCValue = this.i2c.read(Registers.FIFO_SRC.getAddress()); - int masked = FIFO_SAMPLES_STORED_MASK & fifoSRCValue; + int masked = FIFO_SAMPLES_STORED_MASK & fifoSRCValue; return masked; } @@ -375,7 +375,7 @@ public int getSamplesInFIFO() throws IOException { */ private void modifyRegister(Registers register, RegisterValue value) throws IOException { int registerValue = this.i2c.read(register.getAddress()); - int result = mask(registerValue, value.ordinal(), value.getValueLSBPos(), value.getValueMask()); + int result = mask(registerValue, value.ordinal(), value.getValueLSBPos(), value.getValueMask()); this.i2c.write(register.getAddress(), (byte) result); } @@ -395,9 +395,9 @@ private void modifyRegister(Registers register, RegisterValue value) throws IOEx * @return combination of toMask and newData combined based on valueMask */ private int mask(int toMask, int newData, int lsbPos, int valueMask) { - int mask = valueMask << lsbPos; + int mask = valueMask << lsbPos; int notMask = ~mask; - int result = newData << lsbPos | (toMask & notMask); + int result = newData << lsbPos | (toMask & notMask); return result; } @@ -424,13 +424,13 @@ private void readFromSensor() { if (samplesInFIFO == 0) { return; } - int dataLength = samplesInFIFO * BYTES_PER_FIFO_LINE; - byte[] data = new byte[dataLength]; - int samplesRead = this.i2c.read(Registers.OUT_X_L_G.getAddress(), data, 0, dataLength); + int dataLength = samplesInFIFO * BYTES_PER_FIFO_LINE; + byte[] data = new byte[dataLength]; + int samplesRead = this.i2c.read(Registers.OUT_X_L_G.getAddress(), data, 0, dataLength); this.parseReadings(data, samplesRead); } catch (IOException e) { ErrorReporter errorReporter = ErrorReporter.getInstance(); - String errorMsg = "Unable to read from IMU IO Exception"; + String errorMsg = "Unable to read from IMU IO Exception"; errorReporter.reportError(Errors.IMU_IO_ERROR, e, errorMsg); } } @@ -446,9 +446,9 @@ private void readFromSensor() { private void parseReadings(byte[] data, int bytesRead) { int samplesRead = bytesRead / BYTES_PER_FIFO_LINE; for (int i = 0; i < samplesRead; i++) { - int start = i * BYTES_PER_FIFO_LINE; - int end = (i + 1) * BYTES_PER_FIFO_LINE; - byte[] samples = Arrays.copyOfRange(data, start, end); + int start = i * BYTES_PER_FIFO_LINE; + int end = (i + 1) * BYTES_PER_FIFO_LINE; + byte[] samples = Arrays.copyOfRange(data, start, end); AccelGyroReading reading = this.buildReading(samples); this.samples.add(reading); } @@ -467,12 +467,12 @@ public AccelGyroReading buildReading(byte[] data) { int xGyro = results[0]; int yGyro = results[1]; int zGyro = results[2]; - int xAcc = results[3]; - int yAcc = results[4]; - int zAcc = results[5]; + int xAcc = results[3]; + int yAcc = results[4]; + int zAcc = results[5]; Vector3 gyroVec = computeAngularAcceleration(xGyro, yGyro, zGyro); - Vector3 accVec = computeAcceleration(xAcc, yAcc, zAcc); + Vector3 accVec = computeAcceleration(xAcc, yAcc, zAcc); return new AccelGyroReading(accVec, gyroVec); } @@ -486,7 +486,7 @@ public AccelGyroReading buildReading(byte[] data) { */ private int[] getData(byte[] data) { ByteBuffer byteBuffer = ByteBuffer.wrap(data).order(ByteOrder.LITTLE_ENDIAN); - int[] results = new int[data.length / 2]; + int[] results = new int[data.length / 2]; for (int i = 0; i < data.length / 2; i++) { results[i] = byteBuffer.getShort(i * 2); // i * 2 = index of low byte } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1Mag.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1Mag.java index bf8ca86..4a061ee 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1Mag.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1Mag.java @@ -266,7 +266,7 @@ public void setZPerformance(PERFORMANCE_Z performance) throws IOException { */ public void setTemperatureCompensationEnabled(boolean enabled) throws IOException { int registerValue = this.i2c.read(Registers.CTRL_REG1_M.getAddress()); - int result = mask(registerValue, enabled ? 1 : 0, TEMP_COMPENSATE_POS, TEMP_COMPENSATE_MASK); + int result = mask(registerValue, enabled ? 1 : 0, TEMP_COMPENSATE_POS, TEMP_COMPENSATE_MASK); this.i2c.write(Registers.CTRL_REG1_M.getAddress(), (byte) result); } @@ -279,7 +279,7 @@ public void setTemperatureCompensationEnabled(boolean enabled) throws IOExceptio */ public void setBlockDataUpdateUntilAllReadEnabled(boolean enabled) throws IOException { int registerValue = this.i2c.read(Registers.CTRL_REG5_M.getAddress()); - int result = mask(registerValue, enabled ? 1 : 0, BLOCK_DATA_UPDATE_POS, BLOCK_DATA_UPDATE_MASK); + int result = mask(registerValue, enabled ? 1 : 0, BLOCK_DATA_UPDATE_POS, BLOCK_DATA_UPDATE_MASK); this.i2c.write(Registers.CTRL_REG5_M.getAddress(), (byte) result); } @@ -289,7 +289,7 @@ public void setBlockDataUpdateUntilAllReadEnabled(boolean enabled) throws IOExce */ public boolean isNewXYZDataAvailable() throws IOException { int statusRegValue = this.i2c.read(Registers.STATUS_REG_M.getAddress()); - int masked = (1 << NEW_XYZ_DATA_AVAILABLE_POS) & statusRegValue; + int masked = (1 << NEW_XYZ_DATA_AVAILABLE_POS) & statusRegValue; return masked != 0; } @@ -303,7 +303,7 @@ public boolean isNewXYZDataAvailable() throws IOException { */ private void modifyRegister(Registers register, RegisterValue value) throws IOException { int registerValue = this.i2c.read(register.getAddress()); - int result = mask(registerValue, value.ordinal(), value.getValueLSBPos(), value.getValueMask()); + int result = mask(registerValue, value.ordinal(), value.getValueLSBPos(), value.getValueMask()); this.i2c.write(register.getAddress(), (byte) result); } @@ -323,9 +323,9 @@ private void modifyRegister(Registers register, RegisterValue value) throws IOEx * @return combination of toMask and newData combined based on valueMask */ private int mask(int toMask, int newData, int lsbPos, int valueMask) { - int mask = valueMask << lsbPos; + int mask = valueMask << lsbPos; int notMask = ~mask; - int result = newData << lsbPos | (toMask & notMask); + int result = newData << lsbPos | (toMask & notMask); return result; } @@ -343,12 +343,12 @@ private void readFromSensor() { if (!isNewXYZDataAvailable()) { return; } - int dataLength = BYTES_PER_SAMPLE; - byte[] data = new byte[dataLength]; - int bytesRead = this.i2c.read(Registers.OUT_X_L_M.getAddress(), data, 0, dataLength); + int dataLength = BYTES_PER_SAMPLE; + byte[] data = new byte[dataLength]; + int bytesRead = this.i2c.read(Registers.OUT_X_L_M.getAddress(), data, 0, dataLength); if (bytesRead != BYTES_PER_SAMPLE) { ErrorReporter errorReporter = ErrorReporter.getInstance(); - String errorMsg = "Incorrect number of bytes for magnetometer read from IMU."; + String errorMsg = "Incorrect number of bytes for magnetometer read from IMU."; errorReporter.reportError(Errors.IMU_IO_ERROR, errorMsg); return; } @@ -356,7 +356,7 @@ private void readFromSensor() { this.samples.add(reading); } catch (IOException e) { ErrorReporter errorReporter = ErrorReporter.getInstance(); - String errorMsg = "Unable to read from IMU IO Exception"; + String errorMsg = "Unable to read from IMU IO Exception"; errorReporter.reportError(Errors.IMU_IO_ERROR, e, errorMsg); } } @@ -389,7 +389,7 @@ public MagReading buildReading(byte[] data) { */ private int[] getData(byte[] data) { ByteBuffer byteBuffer = ByteBuffer.wrap(data).order(ByteOrder.LITTLE_ENDIAN); - int[] results = new int[data.length / 2]; + int[] results = new int[data.length / 2]; for (int i = 0; i < data.length / 2; i++) { results[i] = byteBuffer.getShort(i * 2); // i * 2 = index of low byte } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX14830.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX14830.java index a721a13..bec59ed 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX14830.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX14830.java @@ -120,13 +120,13 @@ public byte address() { * @param spi the Spi device to use, no validation is done */ public MAX14830(SpiDevice spi) { - this.spi = spi; + this.spi = spi; this.uartBufferArray = new StringBuffer[Port.values().length]; this.serialPortArray = new SerialPortAdapter[Port.values().length]; - this.txFifoLengths = new int[Port.values().length]; + this.txFifoLengths = new int[Port.values().length]; for (int i = 0; i < Port.values().length; i++) { this.uartBufferArray[i] = new StringBuffer(); - this.txFifoLengths[i] = TX_BUFFER_SIZE; + this.txFifoLengths[i] = TX_BUFFER_SIZE; final Port port = Port.values()[i]; this.serialPortArray[i] = new SerialPortAdapter(message -> this.writeToPort(port, message)); } @@ -142,8 +142,8 @@ public MAX14830(SpiDevice spi) { * @throws IOException if we are unable to access /dev/spix.x via Pi4J */ protected int getTXBufferLen(Port port) throws IOException { - int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; - byte command = (byte) (uartSelect | Registers.TxFIFOLvl.address()); + int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; + byte command = (byte) (uartSelect | Registers.TxFIFOLvl.address()); return this.readRegister(command); } @@ -156,8 +156,8 @@ protected int getTXBufferLen(Port port) throws IOException { * @throws IOException if we are unable to access /dev/spix.x via Pi4J */ protected int getRXBufferLen(Port port) throws IOException { - int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; - byte command = (byte) (uartSelect | Registers.RxFIFOLvl.address()); + int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; + byte command = (byte) (uartSelect | Registers.RxFIFOLvl.address()); return this.readRegister(command); } @@ -181,7 +181,7 @@ protected int getRXBufferLen(Port port) throws IOException { * @throws IOException if we are unable to access /dev/spix.x via Pi4J */ private int readRegister(byte command) throws IOException { - byte[] data = {command, 0}; + byte[] data = {command, 0}; byte[] readData = this.spi.write(data); if (readData.length < 2) { return -1; @@ -213,10 +213,10 @@ protected int writeToTxFifo(Port port, int charCount) throws IOException { String first = stringBuffer.substring(0, readCount); stringBuffer.delete(0, readCount); - int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; - byte command = (byte) (uartSelect | WRITE | Registers.THR.address()); - byte[] data = first.getBytes(this.charset); - byte[] toWrite = new byte[data.length + 1]; + int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; + byte command = (byte) (uartSelect | WRITE | Registers.THR.address()); + byte[] data = first.getBytes(this.charset); + byte[] toWrite = new byte[data.length + 1]; toWrite[0] = command; System.arraycopy(data, 0, toWrite, 1, data.length); this.spi.write(toWrite); @@ -233,9 +233,9 @@ protected int writeToTxFifo(Port port, int charCount) throws IOException { * @throws IOException if we are unable to access /dev/spix.x via Pi4J */ protected byte[] readFromRxFifo(Port port, int charCount) throws IOException { - int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; - byte command = (byte) (uartSelect | Registers.RHR.address()); - byte[] zeros = new byte[charCount + 1]; + int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; + byte command = (byte) (uartSelect | Registers.RHR.address()); + byte[] zeros = new byte[charCount + 1]; zeros[0] = command; return this.spi.write(zeros); } @@ -289,7 +289,7 @@ private void writeToPort(Port port, int length) throws IOException { int spaceLeft = TX_BUFFER_SIZE - this.txFifoLengths[port.ordinal()]; if (spaceLeft < length) { int txBufferLen = this.getTXBufferLen(port); - spaceLeft = TX_BUFFER_SIZE - txBufferLen; + spaceLeft = TX_BUFFER_SIZE - txBufferLen; this.txFifoLengths[port.ordinal()] = txBufferLen; } @@ -309,10 +309,10 @@ private void writeToPort(Port port, int length) throws IOException { * @throws IOException if we are unable to access /dev/spix.x via Pi4J */ private void readFromPort(Port port, int length) throws IOException { - byte[] byteMessage = this.readFromRxFifo(port, length); - String unprocessedMessage = new String(byteMessage, this.charset); - String message = unprocessedMessage.substring(1); - SerialPortAdapter serialPort = this.serialPortArray[port.ordinal()]; + byte[] byteMessage = this.readFromRxFifo(port, length); + String unprocessedMessage = new String(byteMessage, this.charset); + String message = unprocessedMessage.substring(1); + SerialPortAdapter serialPort = this.serialPortArray[port.ordinal()]; serialPort.newMessage(message); } @@ -327,7 +327,7 @@ private void readFromPort(Port port, int length) throws IOException { */ private void pollPort(Port port) throws IOException { StringBuffer buffer = this.selectBuffer(port); - int length = buffer.length(); + int length = buffer.length(); if (length != 0) { this.writeToPort(port, length); } @@ -345,7 +345,7 @@ public void poll() { } } catch (IOException e) { ErrorReporter errorReporter = ErrorReporter.getInstance(); - String errorMsg = "Unable to access /dev/spix.x via Pi4J"; + String errorMsg = "Unable to access /dev/spix.x via Pi4J"; errorReporter.reportError(Errors.MAX14830_IO_ERROR, e, errorMsg); } @@ -370,11 +370,11 @@ public void setBaudRate(Port port, int baudrate) throws IOException { if (baudrate > 0) { d = Settings.MAX14830_F_REF / (16 * baudrate); } - int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; - byte command = (byte) (uartSelect | WRITE | Registers.BRGConfig.address()); - byte leastSignificantBits = (byte) (d & 0xFF); - byte mostSignificantBits = (byte) ((d >> BITS_PER_BYTE) & 0xFF); - byte[] data = {command, 0, leastSignificantBits, mostSignificantBits}; + int uartSelect = port.ordinal() << UART_SELECT_LSB_IDX; + byte command = (byte) (uartSelect | WRITE | Registers.BRGConfig.address()); + byte leastSignificantBits = (byte) (d & 0xFF); + byte mostSignificantBits = (byte) ((d >> BITS_PER_BYTE) & 0xFF); + byte[] data = {command, 0, leastSignificantBits, mostSignificantBits}; this.spi.write(data); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX31856.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX31856.java index ed2a4f8..482c802 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX31856.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX31856.java @@ -33,9 +33,9 @@ public class MAX31856 implements Thermocouple, PollingSensor { * @param time the time to use when reporting measurement time. */ public MAX31856(SpiDevice spi, Time time) { - this.spi = spi; + this.spi = spi; this.clock = time; - this.temp = TEMP_ERROR; + this.temp = TEMP_ERROR; } @Override @@ -84,7 +84,7 @@ public void poll() { * @throws IOException */ private void readTemp() throws IOException { - byte[] data = {REG_TC_TEMP, 0, 0, 0}; + byte[] data = {REG_TC_TEMP, 0, 0, 0}; byte[] readData = this.spi.write(data); if (readData.length < 4) { return; @@ -94,7 +94,7 @@ private void readTemp() throws IOException { byte sign = 0; byte mask = (byte) 0b10000000; if ((readData[1] & mask) != 0) { - sign = 1; + sign = 1; readData[1] = (byte) ~readData[1]; readData[2] = (byte) ~readData[2]; readData[3] = (byte) ~readData[3]; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SMSSender.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SMSSender.java index 9fdbfd4..f52c248 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SMSSender.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SMSSender.java @@ -1,5 +1,5 @@ package org.rocketproplab.marginalstability.flightcomputer.hal; public interface SMSSender { - void sendTextMessage(String number, String message); + void sendTextMessage(String number, String message); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SaraSMSSender.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SaraSMSSender.java index 6038ad2..1ed5ff0 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SaraSMSSender.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SaraSMSSender.java @@ -17,8 +17,8 @@ public class SaraSMSSender implements SMSSender, SerialListener { public SaraSMSSender(SerialPort saraSerialPort) { this.saraSerialPort = saraSerialPort; - messageIndex = 0; - router = new PacketRouter(); //should this be set to a specific packet router? + messageIndex = 0; + router = new PacketRouter(); //should this be set to a specific packet router? saraSerialPort.write("AT\n"); saraSerialPort.write("AT+CMGF=1\n"); @@ -44,7 +44,7 @@ public void getGPSInfo() { @Override //this re public void onSerialData(String data) { - int index = data.indexOf(","); + int index = data.indexOf(","); String subData = data.substring(index + 1); packet = new GPSPacket(subData); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/Sensor.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/Sensor.java index 8e1bb43..4ba0f3e 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/Sensor.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/Sensor.java @@ -1,5 +1,5 @@ package org.rocketproplab.marginalstability.flightcomputer.hal; public interface Sensor { - public void init(); + public void init(); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SensorPoller.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SensorPoller.java index ce39df8..d87854a 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SensorPoller.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SensorPoller.java @@ -20,10 +20,10 @@ public class SensorPoller { * @param rate the rate at which to poll in seconds */ public SensorPoller(PollingSensor sensor, double rate) { - this.pollingRate = rate; + this.pollingRate = rate; this.nextPollTime = -Double.MAX_VALUE; - this.hasPolled = false; - this.sensor = sensor; + this.hasPolled = false; + this.sensor = sensor; } /** @@ -39,7 +39,7 @@ public void update(double time) { if (!this.hasPolled) { this.nextPollTime = time + this.pollingRate; - this.hasPolled = true; + this.hasPolled = true; } } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPortAdapter.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPortAdapter.java index cb6676a..2be307f 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPortAdapter.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPortAdapter.java @@ -16,7 +16,7 @@ public class SerialPortAdapter implements SerialPort { private SerialListener writeListener; public SerialPortAdapter(SerialListener writeListener) { - this.listeners = new HashSet<>(); + this.listeners = new HashSet<>(); this.writeListener = writeListener; } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/TimeBasedSensorSampler.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/TimeBasedSensorSampler.java index 62d1cc9..f7b7e31 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/TimeBasedSensorSampler.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/TimeBasedSensorSampler.java @@ -57,15 +57,15 @@ public interface GetNewDataFunction { * @param lastReadTimeFunction used to get the time of the latest datum */ public TimeBasedSensorSampler(GetNewDataFunction newDataFunction, LastReadTimeFunction lastReadTimeFunction) { - this.newDataFunction = newDataFunction; + this.newDataFunction = newDataFunction; this.lastReadTimeFunction = lastReadTimeFunction; - this.lastTime = 0; - this.firstRequest = true; + this.lastTime = 0; + this.firstRequest = true; } @Override public boolean hasNewData() { - double lastRead = this.lastReadTimeFunction.getLastMeasurementTime() - lastTime; + double lastRead = this.lastReadTimeFunction.getLastMeasurementTime() - lastTime; boolean hasReachedTime = lastRead > EPSILON; return this.firstRequest || hasReachedTime; } @@ -73,7 +73,7 @@ public boolean hasNewData() { @Override public E getNewData() { this.firstRequest = false; - this.lastTime = this.lastReadTimeFunction.getLastMeasurementTime(); + this.lastTime = this.lastReadTimeFunction.getLastMeasurementTime(); return this.newDataFunction.getNewData(); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/looper/DurationRequiredEvent.java b/src/org/rocketproplab/marginalstability/flightcomputer/looper/DurationRequiredEvent.java index 51cf5f0..6c90768 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/looper/DurationRequiredEvent.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/looper/DurationRequiredEvent.java @@ -15,7 +15,7 @@ public class DurationRequiredEvent extends GenericEvent { public DurationRequiredEvent( double durationTrue, EventCondition condition, EventCallback callback, Time time) { super(condition, callback, time); - this.durationTrue = durationTrue; + this.durationTrue = durationTrue; this.sinceTrueTime = Double.NaN; } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/looper/GenericEvent.java b/src/org/rocketproplab/marginalstability/flightcomputer/looper/GenericEvent.java index 42ba2b6..9703741 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/looper/GenericEvent.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/looper/GenericEvent.java @@ -15,8 +15,8 @@ public class GenericEvent implements EventCallback, EventCondition { public GenericEvent(EventCondition condition, EventCallback callback, Time time) { this.condition = condition; - this.callback = callback; - this.time = time; + this.callback = callback; + this.time = time; } @Override diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java b/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java index 0a3b79a..90cf813 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java @@ -45,10 +45,10 @@ public class Looper { * @param time the time all events in this Looper will use. */ public Looper(Time time) { - this.time = time; - callbackMap = new HashMap<>(); - active = new ArrayList<>(); - queue = new ArrayList<>(); + this.time = time; + callbackMap = new HashMap<>(); + active = new ArrayList<>(); + queue = new ArrayList<>(); busySubsystems = new HashMap<>(); } @@ -72,8 +72,8 @@ private void handleEvents(LooperErrorListener errorListener) { Iterator> entryIterator = callbackMap.entrySet().iterator(); while (entryIterator.hasNext()) { Map.Entry entry = entryIterator.next(); - Object tag = entry.getKey(); - GenericEvent event = entry.getValue(); + Object tag = entry.getKey(); + GenericEvent event = entry.getValue(); try { if (event.shouldEmit()) { event.onLooperCallback(tag, this); @@ -103,7 +103,7 @@ private void handleCommands() { Iterator queueIterator = queue.iterator(); while (queueIterator.hasNext()) { // Get next command in queue and it's dependencies. - Command command = queueIterator.next(); + Command command = queueIterator.next(); List dependencies = Arrays.asList(command.getDependencies()); // Check if command has no dependencies that are in-use. diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/looper/ScheduledConditionEvent.java b/src/org/rocketproplab/marginalstability/flightcomputer/looper/ScheduledConditionEvent.java index a4d1e5f..73f6cec 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/looper/ScheduledConditionEvent.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/looper/ScheduledConditionEvent.java @@ -14,7 +14,7 @@ public class ScheduledConditionEvent extends GenericEvent { public ScheduledConditionEvent( double interval, EventCondition condition, EventCallback callback, Time time) { super(condition, callback, time); - this.interval = interval; + this.interval = interval; this.lastInvoked = Double.NaN; } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/math/Quaternion.java b/src/org/rocketproplab/marginalstability/flightcomputer/math/Quaternion.java index 60bebe1..7125da8 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/math/Quaternion.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/math/Quaternion.java @@ -148,7 +148,7 @@ public boolean equals(Object other) { return false; } final double EQUAL_TOLERANCE = 0.00001; // TODO may need adjusting - Quaternion otherQuaternion = (Quaternion) other; + Quaternion otherQuaternion = (Quaternion) other; return (Math.abs(this.w - otherQuaternion.w) < EQUAL_TOLERANCE) && (Math.abs(this.x - otherQuaternion.x) < EQUAL_TOLERANCE) && (Math.abs(this.y - otherQuaternion.y) < EQUAL_TOLERANCE) && diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticArray.java b/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticArray.java index 60ac1fb..0b7c425 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticArray.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticArray.java @@ -28,7 +28,7 @@ public interface StatisticValidator { * Create a new empty array */ public StatisticArray(int maxCount) { - this.samples = new TimedRingBuffer<>(maxCount); + this.samples = new TimedRingBuffer<>(maxCount); this.validator = array -> true; } @@ -83,8 +83,8 @@ public double getMean(int lastN) { * @return the mean of the samples returned by the iterator */ private double getMean(TimedRingBuffer.RingBufferIterator iterator) { - double sum = 0; - int sampleCount = 0; + double sum = 0; + int sampleCount = 0; for (double sample : iterator) { sum += sample; sampleCount++; @@ -121,7 +121,7 @@ public double getVariance() { * @return the variance of the samples taken in the previous seconds */ public double getVariance(double previousSeconds) { - double mean = this.getMean(previousSeconds); + double mean = this.getMean(previousSeconds); TimedRingBuffer.RingBufferIterator iterator = this.samples.get(previousSeconds); return this.getVariance(mean, iterator); } @@ -149,8 +149,8 @@ public double getVariance(int lastN) { * @return the variance of the samples */ private double getVariance(double mean, TimedRingBuffer.RingBufferIterator iterator) { - double sumSquared = 0; - int samplesCounted = 0; + double sumSquared = 0; + int samplesCounted = 0; for (double sample : iterator) { sumSquared += Math.pow(sample - mean, 2); samplesCounted++; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticReporter.java b/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticReporter.java index a181baa..8ae77ef 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticReporter.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticReporter.java @@ -47,13 +47,13 @@ public StatisticReporter(SamplableSensor sensor, Telemetry telem, SCMPac private StatisticReporter(SamplableSensor sensor, Telemetry telem, SCMPacketType meanType, boolean reportVariance, SCMPacketType varianceType) { - this.telemetry = telem; - this.meanType = meanType; - this.array = new StatisticArray(1); - this.sensor = sensor; - this.lookbackTime = -1; + this.telemetry = telem; + this.meanType = meanType; + this.array = new StatisticArray(1); + this.sensor = sensor; + this.lookbackTime = -1; this.reportVaraince = reportVariance; - this.varianceType = varianceType; + this.varianceType = varianceType; } /** diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/math/TimedRingBuffer.java b/src/org/rocketproplab/marginalstability/flightcomputer/math/TimedRingBuffer.java index bb69a0a..2ae0695 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/math/TimedRingBuffer.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/math/TimedRingBuffer.java @@ -31,7 +31,7 @@ public class RingBufferIterator implements Iterator, Iterable { * @param nextSublistIterator next iterator to iterate */ private RingBufferIterator(Iterator sublistIterator, Iterator nextSublistIterator) { - this.sublistIterator = sublistIterator; + this.sublistIterator = sublistIterator; this.nextSublistIterator = nextSublistIterator; } @@ -68,10 +68,10 @@ public Iterator iterator() { * @param capacity how many elements to store at most */ public TimedRingBuffer(int capacity) { - this.capacity = capacity; + this.capacity = capacity; this.insertPointer = 0; - this.elements = new ArrayList(capacity); - this.times = new double[capacity]; + this.elements = new ArrayList(capacity); + this.times = new double[capacity]; } /** @@ -110,10 +110,10 @@ public RingBufferIterator get() { if (this.size() < this.capacity) { return new RingBufferIterator(this.elements.iterator(), Collections.emptyIterator()); } - int elementsSize = this.elements.size(); - List sublistA = this.elements.subList(this.insertPointer, elementsSize); - List sublistB = this.elements.subList(0, this.insertPointer); - RingBufferIterator result = new RingBufferIterator(sublistA.iterator(), sublistB.iterator()); + int elementsSize = this.elements.size(); + List sublistA = this.elements.subList(this.insertPointer, elementsSize); + List sublistB = this.elements.subList(0, this.insertPointer); + RingBufferIterator result = new RingBufferIterator(sublistA.iterator(), sublistB.iterator()); return result; } @@ -154,7 +154,7 @@ public RingBufferIterator get(int n) { return new RingBufferIterator(Collections.emptyIterator(), Collections.emptyIterator()); } int start = this.trueMod(this.insertPointer - n, this.capacity); - int end = this.insertPointer; + int end = this.insertPointer; if (start < end) { List sublistA = this.elements.subList(start, end); return new RingBufferIterator(sublistA.iterator(), Collections.emptyIterator()); @@ -172,11 +172,11 @@ public RingBufferIterator get(int n) { * @return an iterator for the elements added within the last pastTime seconds. */ public RingBufferIterator get(double pastTime) { - int numberToGet = 1; - double firstTime = this.times[this.trueMod(this.insertPointer - 1, this.capacity)]; + int numberToGet = 1; + double firstTime = this.times[this.trueMod(this.insertPointer - 1, this.capacity)]; for (numberToGet = 1; numberToGet < this.size(); numberToGet++) { - int index = this.insertPointer - numberToGet - 1; - int modIndex = this.trueMod(index, this.capacity); + int index = this.insertPointer - numberToGet - 1; + int modIndex = this.trueMod(index, this.capacity); double timeDelta = firstTime - this.times[modIndex]; if (timeDelta > pastTime) { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/EngineSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/EngineSubsystem.java index b47906f..406d9c2 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/EngineSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/EngineSubsystem.java @@ -12,7 +12,7 @@ public class EngineSubsystem { private Set listeners; EngineSubsystem(Valves valves) { - this.valves = valves; + this.valves = valves; this.listeners = new HashSet<>(); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/GPSMessageSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/GPSMessageSubsystem.java index 6c857a6..6069b72 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/GPSMessageSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/GPSMessageSubsystem.java @@ -17,13 +17,13 @@ public class GPSMessageSubsystem implements PacketListener { private static final double TIME_BETWEEN = 0; public GPSMessageSubsystem() { - lastTime = 0; - thisTime = 0; + lastTime = 0; + thisTime = 0; currentState = new FlightState(); } public String createMessage() { - double latitude = this.packet.getLatitude(); + double latitude = this.packet.getLatitude(); double longitude = this.packet.getLongitude(); message = "The longitude is: " + longitude + "\nThe latitude" diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/LandedSMSSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/LandedSMSSubsystem.java index d6c6137..7adb3c7 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/LandedSMSSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/LandedSMSSubsystem.java @@ -32,7 +32,7 @@ public class LandedSMSSubsystem */ public LandedSMSSubsystem(String phoneNumber, SMSSender smsSender) { this.phoneNumber = phoneNumber; - this.smsSender = smsSender; + this.smsSender = smsSender; } @Override diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java index a81e698..2024aae 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java @@ -43,10 +43,10 @@ public class ParachuteSubsystem */ public ParachuteSubsystem(Solenoid mainChute, Solenoid drogueChute, Time time, Barometer barometer) { - this.mainChute = mainChute; - this.drogueChute = drogueChute; - this.time = time; - this.barometer = barometer; + this.mainChute = mainChute; + this.drogueChute = drogueChute; + this.time = time; + this.barometer = barometer; this.parachuteListeners = new ArrayList<>(); } @@ -73,8 +73,8 @@ private boolean shouldDrogueChuteOpenByFlightMode(FlightMode flightMode) { private boolean shouldMainChuteOpenByPressure() { Vector3 currentPos = this.position.getAt(time.getSystemTime()); - boolean b1 = currentPos.getZ() < Settings.MAIN_CHUTE_HEIGHT; - boolean b2 = barometer.getPressure() < Settings.MAIN_CHUTE_PRESSURE; + boolean b1 = currentPos.getZ() < Settings.MAIN_CHUTE_HEIGHT; + boolean b2 = barometer.getPressure() < Settings.MAIN_CHUTE_PRESSURE; return b1 && b2; // return currentPos.getZ() < Settings.MAIN_CHUTE_HEIGHT && // barometer.getPressure() >= Settings.MAIN_CHUTE_PRESSURE; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SCMCommandSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SCMCommandSubsystem.java index 61ec12b..efc4f84 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SCMCommandSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SCMCommandSubsystem.java @@ -36,7 +36,7 @@ public class SCMCommandSubsystem implements Subsystem, * Creates a new SCMCommandSubsystem */ public SCMCommandSubsystem() { - SCMMap = new HashMap<>(); + SCMMap = new HashMap<>(); framedSCMMap = new HashMap<>(); } @@ -88,7 +88,7 @@ public void onPacket(PacketDirection direction, SCMPacket packet) { */ @Override public void processFramedPacket(String framedPacket) { - String data = extractFramedSCMData(framedPacket); + String data = extractFramedSCMData(framedPacket); FramedSCMCommandFactory factory = framedSCMMap.get(data); if (factory != null) { Command commandToSchedule = factory.getCommandByFramedSCM(data); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SensorSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SensorSubsystem.java index 6422fae..a31e9b4 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SensorSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SensorSubsystem.java @@ -25,7 +25,7 @@ public class SensorSubsystem implements Subsystem { */ public SensorSubsystem(Time time) { this.sensorPollers = Collections.synchronizedList(new ArrayList<>()); - this.time = time; + this.time = time; } @Override diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java index 0752c36..54b876d 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java @@ -43,7 +43,7 @@ public class Telemetry { */ public Telemetry(Logger logger, PacketRelay relay) { this.logger = logger; - this.relay = relay; + this.relay = relay; } /** @@ -54,8 +54,8 @@ public Telemetry(Logger logger, PacketRelay relay) { */ public void reportTelemetry(SCMPacketType type, double data) { String dataString = String.format(DOUBLE_FORMAT, data).toUpperCase(); - int toPrint = Math.min(dataString.length(), SCMPacket.DATA_LENGTH); - int padLen = (SCMPacket.DATA_LENGTH - toPrint); + int toPrint = Math.min(dataString.length(), SCMPacket.DATA_LENGTH); + int padLen = (SCMPacket.DATA_LENGTH - toPrint); dataString = dataString.substring(0, toPrint); if (padLen > 0) { @@ -133,8 +133,8 @@ public void logInfo(Info info) { * Send the heartbeat to the command box */ public void sendHeartbeat() { - String dataString = "00000"; - SCMPacket packet = new SCMPacket(SCMPacketType.HB, dataString); + String dataString = "00000"; + SCMPacket packet = new SCMPacket(SCMPacketType.HB, dataString); this.relay.sendPacket(packet, PacketSources.CommandBox); } diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java index f5091a3..30db2b3 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java @@ -25,18 +25,18 @@ public ValveStateSubsystem(PacketRelay relay) { public void onPacket(PacketDirection direction, SCMPacket packet) { this.packet = packet; - this.data = packet.getData(); - this.id = packet.getID(); + this.data = packet.getData(); + this.id = packet.getID(); setStates(); } private void setStates() { - int trackArray = 0; //the value we're starting at on the valveStates array - int maxNum = 5; //what number to end at on the array + int trackArray = 0; //the value we're starting at on the valveStates array + int maxNum = 5; //what number to end at on the array int trackString = 0; //what position on the data string we're at. if (id == SCMPacketType.V1) { trackArray = 5; - maxNum = 8; + maxNum = 8; } while (trackArray < maxNum) { @@ -68,14 +68,14 @@ private void sendPacket(int valve) { } private void sendPacket(SCMPacketType type) { - SCMPacketType id = type; - String data = ""; - SCMPacket packet; + SCMPacketType id = type; + String data = ""; + SCMPacket packet; - int endValue = 5; //value on the valveStates array to stop at when creating a data string + int endValue = 5; //value on the valveStates array to stop at when creating a data string int beginValue = 0; // value on the valveStates array to begin at when creating a data string if (id == SCMPacketType.V1) { - endValue = 8; + endValue = 8; beginValue = 5; } for (; beginValue < endValue; beginValue++) { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/tracking/FlightState.java b/src/org/rocketproplab/marginalstability/flightcomputer/tracking/FlightState.java index 115ea24..0c5ad45 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/tracking/FlightState.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/tracking/FlightState.java @@ -81,7 +81,7 @@ private void checkForApogee(Vector3 velocity) { * @param velocity the current velocity */ private void checkForFalling(Vector3 velocity) { - boolean isApogee = this.currentFlightMode == FlightMode.Apogee; + boolean isApogee = this.currentFlightMode == FlightMode.Apogee; boolean isCoasting = this.currentFlightMode == FlightMode.Coasting; if (!(isApogee || isCoasting)) { return; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/tracking/VelocityCalculator.java b/src/org/rocketproplab/marginalstability/flightcomputer/tracking/VelocityCalculator.java index f62caad..c8042f3 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/tracking/VelocityCalculator.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/tracking/VelocityCalculator.java @@ -14,15 +14,15 @@ public void onVelocityUpdate(Vector3 velocity, double time) { public static Vector3 getVelocity(GPSPacket prevGPSPacket, GPSPacket curGPSPacket) { - double deltaLat = curGPSPacket.getLatitude() - prevGPSPacket.getLatitude(); - double deltaLon = curGPSPacket.getLongitude() - prevGPSPacket.getLongitude(); - double deltaTime = curGPSPacket.getTime() - prevGPSPacket.getTime(); + double deltaLat = curGPSPacket.getLatitude() - prevGPSPacket.getLatitude(); + double deltaLon = curGPSPacket.getLongitude() - prevGPSPacket.getLongitude(); + double deltaTime = curGPSPacket.getTime() - prevGPSPacket.getTime(); double angVelocityX = deltaLon / deltaTime; double angVelocityY = deltaLat / deltaTime; - int radiusEarth = 6378100; - double velocityX = angVelocityX * radiusEarth; - double velocityY = angVelocityY * radiusEarth; - double velocityZ = curGPSPacket.getAltitude() - prevGPSPacket.getAltitude(); + int radiusEarth = 6378100; + double velocityX = angVelocityX * radiusEarth; + double velocityY = angVelocityY * radiusEarth; + double velocityZ = curGPSPacket.getAltitude() - prevGPSPacket.getAltitude(); return new Vector3(velocityX, velocityY, velocityZ); } From c26b1f5ef4c156f375575ceca85a05f4e62e4641 Mon Sep 17 00:00:00 2001 From: Chi Chow Date: Sat, 17 Apr 2021 16:18:40 -0700 Subject: [PATCH 7/7] Align field declarations (in addition to variables and assignments) --- .../flightcomputer/ErrorReporter.java | 2 +- .../flightcomputer/FlightComputer.java | 10 ++--- .../flightcomputer/Settings.java | 18 ++++----- .../flightcomputer/comm/FramedSCM.java | 8 ++-- .../flightcomputer/comm/GPSPacket.java | 26 ++++++------- .../flightcomputer/comm/SCMPacket.java | 10 ++--- .../flightcomputer/comm/SCMTransceiver.java | 4 +- .../commands/HeartbeatCommand.java | 8 ++-- .../commands/OpenDrogueChuteCommand.java | 2 +- .../commands/OpenMainChuteCommand.java | 2 +- .../commands/SetValveCommand.java | 2 +- .../flightcomputer/hal/LPS22HD.java | 32 ++++++++-------- .../flightcomputer/hal/LSM9DS1AccelGyro.java | 38 +++++++++---------- .../flightcomputer/hal/LSM9DS1Mag.java | 30 +++++++-------- .../flightcomputer/hal/MAX14830.java | 16 ++++---- .../flightcomputer/hal/MAX31856.java | 16 ++++---- .../flightcomputer/hal/SaraSMSSender.java | 8 ++-- .../flightcomputer/hal/SensorPoller.java | 6 +-- .../flightcomputer/hal/SerialPortAdapter.java | 2 +- .../hal/TimeBasedSensorSampler.java | 6 +-- .../looper/DurationRequiredEvent.java | 2 +- .../flightcomputer/looper/GenericEvent.java | 4 +- .../flightcomputer/looper/Looper.java | 4 +- .../flightcomputer/math/StatisticArray.java | 2 +- .../math/StatisticReporter.java | 12 +++--- .../flightcomputer/math/TimedRingBuffer.java | 6 +-- .../subsystems/EngineSubsystem.java | 2 +- .../subsystems/GPSMessageSubsystem.java | 8 ++-- .../subsystems/LandedSMSSubsystem.java | 8 ++-- .../subsystems/ParachuteSubsystem.java | 10 ++--- .../subsystems/SensorSubsystem.java | 2 +- .../subsystems/StatsSubsystem.java | 4 +- .../flightcomputer/subsystems/Telemetry.java | 14 +++---- .../subsystems/ValveStateSubsystem.java | 8 ++-- 34 files changed, 166 insertions(+), 166 deletions(-) diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/ErrorReporter.java b/src/org/rocketproplab/marginalstability/flightcomputer/ErrorReporter.java index 7d0fef8..fbe000c 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/ErrorReporter.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/ErrorReporter.java @@ -43,7 +43,7 @@ public static void setInstance(ErrorReporter reporter) { } private PrintStream stream; - private Telemetry telemetry; + private Telemetry telemetry; /** * No arg constructor that should print to stderr and not send telemetry. diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java b/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java index d59fab0..4d50e84 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/FlightComputer.java @@ -45,7 +45,7 @@ public static FlightComputer create() { private final Looper looper; private PacketRouter packetRouter = new PacketRouter(); - private Telemetry telemetry = new Telemetry(Logger.getLogger("Telemetry"), packetRouter); + private Telemetry telemetry = new Telemetry(Logger.getLogger("Telemetry"), packetRouter); /** * Providers to provide singleton objects to higher level management objects. @@ -132,7 +132,7 @@ public void tick() { * Builder class to create FlightComputer objects with more customization. */ public static class Builder { - private Telemetry telemetry; + private Telemetry telemetry; private final FlightComputer fc; /** @@ -182,9 +182,9 @@ private static class ParseCmdLine { * CLI argument names and descriptions */ private static final String - HELP = "--help", - HELP_DESC = "print help menu", - REAL_SENSORS = "--real-sensors", + HELP = "--help", + HELP_DESC = "print help menu", + REAL_SENSORS = "--real-sensors", REAL_SENSORS_DESC = "use real sensors"; /** diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/Settings.java b/src/org/rocketproplab/marginalstability/flightcomputer/Settings.java index 5ca1676..204414b 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/Settings.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/Settings.java @@ -78,15 +78,15 @@ public class Settings { @SettingSectionHeader(name = "LSM9DS1 settings") - public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_2G = 0.00006103; - public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_4G = 0.00012207; - public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_8G = 0.00024414; - public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_16G = 0.000732; - public static double LSM9DS1_SENSITIVITY_GYROSCOPE_245DPS = 0.00875; - public static double LSM9DS1_SENSITIVITY_GYROSCOPE_500DPS = 0.0175; - public static double LSM9DS1_SENSITIVITY_GYROSCOPE_2000DPS = 0.07; - public static double LSM9DS1_SENSITIVITY_MAGNETOMETER_4GAUSS = 0.00014; - public static double LSM9DS1_SENSITIVITY_MAGNETOMETER_8GAUSS = 0.00029; + public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_2G = 0.00006103; + public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_4G = 0.00012207; + public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_8G = 0.00024414; + public static double LSM9DS1_SENSITIVITY_ACCELEROMETER_16G = 0.000732; + public static double LSM9DS1_SENSITIVITY_GYROSCOPE_245DPS = 0.00875; + public static double LSM9DS1_SENSITIVITY_GYROSCOPE_500DPS = 0.0175; + public static double LSM9DS1_SENSITIVITY_GYROSCOPE_2000DPS = 0.07; + public static double LSM9DS1_SENSITIVITY_MAGNETOMETER_4GAUSS = 0.00014; + public static double LSM9DS1_SENSITIVITY_MAGNETOMETER_8GAUSS = 0.00029; public static double LSM9DS1_SENSITIVITY_MAGNETOMETER_12GAUSS = 0.00043; public static double LSM9DS1_SENSITIVITY_MAGNETOMETER_16GAUSS = 0.00058; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/FramedSCM.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/FramedSCM.java index adaf6f3..564253c 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/FramedSCM.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/FramedSCM.java @@ -26,10 +26,10 @@ * @author Max Apodaca */ public class FramedSCM implements PacketListener { - private Queue outputQueue; - private String activeString; - private int frameLength; - private PacketRelay sCMOutput; + private Queue outputQueue; + private String activeString; + private int frameLength; + private PacketRelay sCMOutput; private FramedPacketProcessor framedPacketOutput; /** diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSPacket.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSPacket.java index dcdc33c..08ad3be 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSPacket.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/GPSPacket.java @@ -8,21 +8,21 @@ */ public class GPSPacket { - private static final String NEMA_DELIMITER = ","; - private static final int NEMA_PART_LENGTH = 15; - private static final int NEMA_TIME_INDEX = 1; - private static final int NEMA_LAT_INDEX = 2; - private static final int NEMA_LON_INDEX = 4; - private static final int NEMA_SV_COUNT_INDEX = 7; - private static final int NEMA_ALTITUDE_INDEX = 9; + private static final String NEMA_DELIMITER = ","; + private static final int NEMA_PART_LENGTH = 15; + private static final int NEMA_TIME_INDEX = 1; + private static final int NEMA_LAT_INDEX = 2; + private static final int NEMA_LON_INDEX = 4; + private static final int NEMA_SV_COUNT_INDEX = 7; + private static final int NEMA_ALTITUDE_INDEX = 9; private boolean valid; - private double latitude; - private double longitude; - private double altitude; - private double time; - private int sVCount; - private String nema; + private double latitude; + private double longitude; + private double altitude; + private double time; + private int sVCount; + private String nema; /** * Create a new GPS Packet based on the NEMA String diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacket.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacket.java index c75a944..d9b02b6 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacket.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMPacket.java @@ -25,14 +25,14 @@ */ public class SCMPacket { - public static final int LAST_THREE_CHARS = 3; - public static final int NUM_CHARS_PACKET = 12; + public static final int LAST_THREE_CHARS = 3; + public static final int NUM_CHARS_PACKET = 12; public static final int NUM_COMPONENTS_PACKET = 3; - public static final int DATA_LENGTH = 5; + public static final int DATA_LENGTH = 5; private SCMPacketType id; - private String data; - private boolean isValid; + private String data; + private boolean isValid; /** * Constructor that passes the packet into it's components diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMTransceiver.java b/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMTransceiver.java index ef7a2ae..5fc531c 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMTransceiver.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/comm/SCMTransceiver.java @@ -16,8 +16,8 @@ * @author Max Apodaca, Antonio */ public class SCMTransceiver implements SerialListener, PacketListener { - private SerialPort serialPort; - private PacketRouter router; + private SerialPort serialPort; + private PacketRouter router; private PacketSources source; /** diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/HeartbeatCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/HeartbeatCommand.java index 235f2f8..29e3525 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/HeartbeatCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/HeartbeatCommand.java @@ -14,10 +14,10 @@ */ public class HeartbeatCommand implements Command { private static final Subsystem[] EMPTY_ARRAY = {}; - private int HBcounter; - private double startTime; - private Time time; - private Telemetry telemetry; + private int HBcounter; + private double startTime; + private Time time; + private Telemetry telemetry; /** * Creates a new HeartbeatCommand object using Time and Telemetry objects. diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenDrogueChuteCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenDrogueChuteCommand.java index 3f2ccb6..1271586 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenDrogueChuteCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenDrogueChuteCommand.java @@ -9,7 +9,7 @@ public class OpenDrogueChuteCommand implements Command { private ParachuteSubsystem parachuteSubsystem; - private PacketRelay relay; + private PacketRelay relay; private OpenDrogueChuteCommand(ParachuteSubsystem parachuteSubsystem, PacketRelay relay) { this.parachuteSubsystem = parachuteSubsystem; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenMainChuteCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenMainChuteCommand.java index ec73b58..1002569 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenMainChuteCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/OpenMainChuteCommand.java @@ -9,7 +9,7 @@ public class OpenMainChuteCommand implements Command { private ParachuteSubsystem parachuteSubsystem; - private PacketRelay relay; + private PacketRelay relay; private OpenMainChuteCommand(ParachuteSubsystem parachuteSubsystem, PacketRelay relay) { this.parachuteSubsystem = parachuteSubsystem; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/commands/SetValveCommand.java b/src/org/rocketproplab/marginalstability/flightcomputer/commands/SetValveCommand.java index 22b92f7..fa9d046 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/commands/SetValveCommand.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/commands/SetValveCommand.java @@ -8,7 +8,7 @@ public class SetValveCommand implements Command { private SCMPacket scmpacket; - private Valves valves; + private Valves valves; SetValveCommand(SCMPacket scmpacket, Valves valves) { this.scmpacket = scmpacket; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LPS22HD.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LPS22HD.java index 99db910..9957604 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LPS22HD.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LPS22HD.java @@ -16,22 +16,22 @@ public class LPS22HD implements Barometer, PollingSensor { private I2CDevice i2cDevice; - private double pressure; - private double sampleTime; - private Time clock; - - private static final byte ODR_25HZ = 0b00110000; - private static final byte LOW_PASS_ENABLE = 0b00001000; - private static final byte LOW_PASS_20TH = 0b00000100; - private static final byte KEEP_REGISTERS_SYCHONISED_BDU = 0b00000010; - private static final int CTRL_REG1 = 0x10; - private static final double MINIMUM_RANGE = 259; - private static final double MAXIMUM_RANGE = 1261; - private static final double ZERO_TIME = 0.0; - private static final double SCALING_FACTOR = 4096; - private static final int REG_PRESSURE_HIGH = 0x2A; - private static final int REG_PRESSURE_LOW = 0x29; - private static final int REG_PRESSURE_EXTRA_LOW = 0x28; + private double pressure; + private double sampleTime; + private Time clock; + + private static final byte ODR_25HZ = 0b00110000; + private static final byte LOW_PASS_ENABLE = 0b00001000; + private static final byte LOW_PASS_20TH = 0b00000100; + private static final byte KEEP_REGISTERS_SYCHONISED_BDU = 0b00000010; + private static final int CTRL_REG1 = 0x10; + private static final double MINIMUM_RANGE = 259; + private static final double MAXIMUM_RANGE = 1261; + private static final double ZERO_TIME = 0.0; + private static final double SCALING_FACTOR = 4096; + private static final int REG_PRESSURE_HIGH = 0x2A; + private static final int REG_PRESSURE_LOW = 0x29; + private static final int REG_PRESSURE_EXTRA_LOW = 0x28; /** * Create a new LPS22HD with the given i2cDevice and time. Time will be used to diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1AccelGyro.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1AccelGyro.java index 0e9e937..7097fb1 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1AccelGyro.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1AccelGyro.java @@ -29,29 +29,29 @@ * @author Max Apodaca */ public class LSM9DS1AccelGyro implements PollingSensor, AccelerometerGyroscope { - private static final int ODR_MASK = 0b111; - private static final int ODR_LSB_POS = 5; - private static final int ACCELEROMETER_SCALE_MASK = 0b11; + private static final int ODR_MASK = 0b111; + private static final int ODR_LSB_POS = 5; + private static final int ACCELEROMETER_SCALE_MASK = 0b11; private static final int ACCELEROMETER_SCALE_LSB_POS = 3; - private static final int GYRO_SCALE_MASK = 0b11; - private static final int GYRO_SCALE_LSB_POS = 3; - private static final int FIFO_EN_VAL_MASK = 0b1; - private static final int FIFO_EN_LSB_POS = 1; - private static final int FIFO_MODE_MASK = 0b111; - private static final int FIFO_MODE_LSB_POS = 5; - private static final int FIFO_THRESHOLD_MASK = 0b11111; - private static final int FIFO_THRESHOLD_LSB_POS = 0; - public static final int FIFO_THRESHOLD_MAX = 31; - public static final int FIFO_THRESHOLD_MIN = 0; - public static final int FIFO_OVERRUN_POS = 6; - public static final int FIFO_THRESHOLD_STATUS_POS = 7; - public static final int FIFO_SAMPLES_STORED_MASK = 0b111111; + private static final int GYRO_SCALE_MASK = 0b11; + private static final int GYRO_SCALE_LSB_POS = 3; + private static final int FIFO_EN_VAL_MASK = 0b1; + private static final int FIFO_EN_LSB_POS = 1; + private static final int FIFO_MODE_MASK = 0b111; + private static final int FIFO_MODE_LSB_POS = 5; + private static final int FIFO_THRESHOLD_MASK = 0b11111; + private static final int FIFO_THRESHOLD_LSB_POS = 0; + public static final int FIFO_THRESHOLD_MAX = 31; + public static final int FIFO_THRESHOLD_MIN = 0; + public static final int FIFO_OVERRUN_POS = 6; + public static final int FIFO_THRESHOLD_STATUS_POS = 7; + public static final int FIFO_SAMPLES_STORED_MASK = 0b111111; private static final int BYTES_PER_FIFO_LINE = 12; - public static final double ACCELEROMETER_OUTPUT_TO_MPS_SQUARED = 9.81; // factor to multiply acc output by to + public static final double ACCELEROMETER_OUTPUT_TO_MPS_SQUARED = 9.81; // factor to multiply acc output by to // convert sensor output to m/s^2 - private static final double ONE_DEGREE_IN_RADIANS = Math.PI / 180.0; + private static final double ONE_DEGREE_IN_RADIANS = Math.PI / 180.0; /** * All the registers that can be found in the LSM9DS1 imu for the accelerometer @@ -225,7 +225,7 @@ public int getValueLSBPos() { } } - private I2CDevice i2c; + private I2CDevice i2c; private ArrayDeque samples = new ArrayDeque<>(); /** diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1Mag.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1Mag.java index 4a061ee..b2d9d42 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1Mag.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/LSM9DS1Mag.java @@ -24,23 +24,23 @@ * @author Enlil Odisho */ public class LSM9DS1Mag implements PollingSensor, Magnetometer { - private static final int ODR_MASK = 0b111; - private static final int ODR_LSB_POS = 2; - private static final int SCALE_MASK = 0b11; - private static final int SCALE_LSB_POS = 5; - private static final int MODE_MASK = 0b11; - private static final int MODE_LSB_POS = 0; - private static final int PERFORMANCE_MASK = 0b11; - private static final int PERFORMANCE_XY_LSB_POS = 5; - private static final int PERFORMANCE_Z_LSB_POS = 2; - private static final int TEMP_COMPENSATE_MASK = 0b1; - private static final int TEMP_COMPENSATE_POS = 7; - private static final int BLOCK_DATA_UPDATE_MASK = 0b1; - private static final int BLOCK_DATA_UPDATE_POS = 6; + private static final int ODR_MASK = 0b111; + private static final int ODR_LSB_POS = 2; + private static final int SCALE_MASK = 0b11; + private static final int SCALE_LSB_POS = 5; + private static final int MODE_MASK = 0b11; + private static final int MODE_LSB_POS = 0; + private static final int PERFORMANCE_MASK = 0b11; + private static final int PERFORMANCE_XY_LSB_POS = 5; + private static final int PERFORMANCE_Z_LSB_POS = 2; + private static final int TEMP_COMPENSATE_MASK = 0b1; + private static final int TEMP_COMPENSATE_POS = 7; + private static final int BLOCK_DATA_UPDATE_MASK = 0b1; + private static final int BLOCK_DATA_UPDATE_POS = 6; private static final int NEW_XYZ_DATA_AVAILABLE_POS = 3; private static final int BYTES_PER_SAMPLE = 6; - private static final int BITS_PER_BYTE = 8; + private static final int BITS_PER_BYTE = 8; /** * All the registers that can be found in the LSM9DS1 imu for the magnetometer @@ -185,7 +185,7 @@ public int getValueLSBPos() { } } - private I2CDevice i2c; + private I2CDevice i2c; private ArrayDeque samples = new ArrayDeque<>(); /** diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX14830.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX14830.java index bec59ed..5ba4886 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX14830.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX14830.java @@ -100,18 +100,18 @@ public byte address() { private static final String CHARSET = "US-ASCII"; - private static final int UART_SELECT_LSB_IDX = 5; - private static final byte WRITE = -0x80; - private static final int BYTE_MSB_VALUE = 128; - private static final int BITS_PER_BYTE = 8; + private static final int UART_SELECT_LSB_IDX = 5; + private static final byte WRITE = -0x80; + private static final int BYTE_MSB_VALUE = 128; + private static final int BITS_PER_BYTE = 8; private static final int TX_BUFFER_SIZE = 128; - private SpiDevice spi; - private StringBuffer[] uartBufferArray; + private SpiDevice spi; + private StringBuffer[] uartBufferArray; private SerialPortAdapter[] serialPortArray; - private int[] txFifoLengths; - private Charset charset; + private int[] txFifoLengths; + private Charset charset; /** * Create the MAX14830 and initialize the event handlers with diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX31856.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX31856.java index 482c802..7f4ae58 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX31856.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/MAX31856.java @@ -14,16 +14,16 @@ public class MAX31856 implements Thermocouple, PollingSensor { private SpiDevice spi; - private double temp; - private long sampleTime; - private Time clock; + private double temp; + private long sampleTime; + private Time clock; - private static final byte REG_TC_TEMP = 0x0C; - private static final double ZERO_TIME = 0.0; + private static final byte REG_TC_TEMP = 0x0C; + private static final double ZERO_TIME = 0.0; private static final double SCALING_FACTOR = 128.0; - private static final double MINIMUM_RANGE = -200.0; - private static final double MAXIMUM_RANGE = 1372.0; - private static final double TEMP_ERROR = 2048.0; + private static final double MINIMUM_RANGE = -200.0; + private static final double MAXIMUM_RANGE = 1372.0; + private static final double TEMP_ERROR = 2048.0; /** * Create instance of MAX31856 with given SpiDevice. Time will be used to diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SaraSMSSender.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SaraSMSSender.java index 1ed5ff0..efbe218 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SaraSMSSender.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SaraSMSSender.java @@ -8,10 +8,10 @@ public class SaraSMSSender implements SMSSender, SerialListener { SerialPort saraSerialPort; - String phoneNumber; - String at; - String message; - int messageIndex; + String phoneNumber; + String at; + String message; + int messageIndex; private PacketRouter router; GPSPacket packet; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SensorPoller.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SensorPoller.java index d87854a..684068f 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SensorPoller.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SensorPoller.java @@ -7,9 +7,9 @@ */ public class SensorPoller { - private double pollingRate; - private double nextPollTime; - private boolean hasPolled; + private double pollingRate; + private double nextPollTime; + private boolean hasPolled; private PollingSensor sensor; /** diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPortAdapter.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPortAdapter.java index 2be307f..6214d82 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPortAdapter.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/SerialPortAdapter.java @@ -13,7 +13,7 @@ public class SerialPortAdapter implements SerialPort { private Set listeners; - private SerialListener writeListener; + private SerialListener writeListener; public SerialPortAdapter(SerialListener writeListener) { this.listeners = new HashSet<>(); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/hal/TimeBasedSensorSampler.java b/src/org/rocketproplab/marginalstability/flightcomputer/hal/TimeBasedSensorSampler.java index f7b7e31..799a109 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/hal/TimeBasedSensorSampler.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/hal/TimeBasedSensorSampler.java @@ -46,9 +46,9 @@ public interface GetNewDataFunction { } private GetNewDataFunction newDataFunction; - private LastReadTimeFunction lastReadTimeFunction; - private double lastTime; - private boolean firstRequest; + private LastReadTimeFunction lastReadTimeFunction; + private double lastTime; + private boolean firstRequest; /** * Create a new sampler the samples the given data function diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/looper/DurationRequiredEvent.java b/src/org/rocketproplab/marginalstability/flightcomputer/looper/DurationRequiredEvent.java index 6c90768..dcaba10 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/looper/DurationRequiredEvent.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/looper/DurationRequiredEvent.java @@ -10,7 +10,7 @@ */ public class DurationRequiredEvent extends GenericEvent { private final double durationTrue; - private double sinceTrueTime; + private double sinceTrueTime; public DurationRequiredEvent( double durationTrue, EventCondition condition, EventCallback callback, Time time) { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/looper/GenericEvent.java b/src/org/rocketproplab/marginalstability/flightcomputer/looper/GenericEvent.java index 9703741..d35bdc8 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/looper/GenericEvent.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/looper/GenericEvent.java @@ -10,8 +10,8 @@ */ public class GenericEvent implements EventCallback, EventCondition { private final EventCondition condition; - private final EventCallback callback; - private final Time time; + private final EventCallback callback; + private final Time time; public GenericEvent(EventCondition condition, EventCallback callback, Time time) { this.condition = condition; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java b/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java index 90cf813..bb3ffe5 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/looper/Looper.java @@ -21,12 +21,12 @@ * @author Chi Chow, Enlil Odisho */ public class Looper { - private final Time time; + private final Time time; private final HashMap callbackMap; /** * List storing all commands that are running. */ - private final ArrayList active; + private final ArrayList active; /** * List storing all commands awaiting execution. diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticArray.java b/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticArray.java index 0b7c425..149d355 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticArray.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticArray.java @@ -22,7 +22,7 @@ public interface StatisticValidator { } private TimedRingBuffer samples; - private StatisticValidator validator; + private StatisticValidator validator; /** * Create a new empty array diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticReporter.java b/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticReporter.java index 8ae77ef..0987145 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticReporter.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/math/StatisticReporter.java @@ -13,13 +13,13 @@ */ public class StatisticReporter implements EventCallback { - private Telemetry telemetry; - private SCMPacketType meanType; - private SCMPacketType varianceType; - private StatisticArray array; + private Telemetry telemetry; + private SCMPacketType meanType; + private SCMPacketType varianceType; + private StatisticArray array; private SamplableSensor sensor; - private double lookbackTime; - private boolean reportVaraince; + private double lookbackTime; + private boolean reportVaraince; /** * Create a new reporter which only reports the mean diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/math/TimedRingBuffer.java b/src/org/rocketproplab/marginalstability/flightcomputer/math/TimedRingBuffer.java index 2ae0695..9c27680 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/math/TimedRingBuffer.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/math/TimedRingBuffer.java @@ -57,10 +57,10 @@ public Iterator iterator() { } - private int capacity; - private int insertPointer; + private int capacity; + private int insertPointer; private ArrayList elements; - private double[] times; + private double[] times; /** * Create a new timed ring buffer with the given capacity diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/EngineSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/EngineSubsystem.java index 406d9c2..71171e0 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/EngineSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/EngineSubsystem.java @@ -8,7 +8,7 @@ import java.util.Set; public class EngineSubsystem { - private Valves valves; + private Valves valves; private Set listeners; EngineSubsystem(Valves valves) { diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/GPSMessageSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/GPSMessageSubsystem.java index 6069b72..3c98150 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/GPSMessageSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/GPSMessageSubsystem.java @@ -8,10 +8,10 @@ public class GPSMessageSubsystem implements PacketListener { - String message; - double lastTime; - double thisTime; - GPSPacket packet; + String message; + double lastTime; + double thisTime; + GPSPacket packet; FlightState currentState; private static final double TIME_BETWEEN = 0; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/LandedSMSSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/LandedSMSSubsystem.java index 7adb3c7..ce81d7f 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/LandedSMSSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/LandedSMSSubsystem.java @@ -15,13 +15,13 @@ */ public class LandedSMSSubsystem implements Subsystem, FlightStateListener, PacketListener { - public static final double SMS_INTERVAL = 15.0; // Interval to SMS, in seconds - private static final String SMS_FORMAT = "Landed! https://www.google.com/maps/place/%f+%f"; + public static final double SMS_INTERVAL = 15.0; // Interval to SMS, in seconds + private static final String SMS_FORMAT = "Landed! https://www.google.com/maps/place/%f+%f"; - private String phoneNumber; + private String phoneNumber; private SMSSender smsSender; - private GPSPacket lastPacket = null; + private GPSPacket lastPacket = null; private FlightMode flightMode = null; /** diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java index 2024aae..9114e36 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ParachuteSubsystem.java @@ -25,12 +25,12 @@ public class ParachuteSubsystem private static final String MAIN_CHUTE_TAG = "MainChute"; - private Solenoid mainChute; - private Solenoid drogueChute; + private Solenoid mainChute; + private Solenoid drogueChute; private InterpolatingVector3 position; - private Time time; - private Barometer barometer; - private Looper looper; + private Time time; + private Barometer barometer; + private Looper looper; private List parachuteListeners; diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SensorSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SensorSubsystem.java index a31e9b4..a912bde 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SensorSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/SensorSubsystem.java @@ -16,7 +16,7 @@ */ public class SensorSubsystem implements Subsystem { private List sensorPollers; - private Time time; + private Time time; /** * Create the subsystem using the given time. diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/StatsSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/StatsSubsystem.java index da3a31f..d346d3a 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/StatsSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/StatsSubsystem.java @@ -19,8 +19,8 @@ public class StatsSubsystem implements Subsystem { private List reporters; - private Telemetry telemetry; - private Looper looper; + private Telemetry telemetry; + private Looper looper; public StatsSubsystem(Telemetry telemetry) { this.reporters = new ArrayList<>(); diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java index 54b876d..8f85396 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/Telemetry.java @@ -17,21 +17,21 @@ * @author Max Apodaca */ public class Telemetry { - public static final int BASE_10 = 10; - public static final int BASE_16 = 16; + public static final int BASE_10 = 10; + public static final int BASE_16 = 16; public static final int MAX_PACKET_BASE_10 = (int) Math.round(Math.pow(BASE_10, SCMPacket.DATA_LENGTH)) - 1; public static final int MAX_PACKET_BASE_16 = (int) Math.round(Math.pow(BASE_16, SCMPacket.DATA_LENGTH)) - 1; public static final int MIN_PACKET_BASE_10 = (int) -Math.round(Math.pow(BASE_10, SCMPacket.DATA_LENGTH - 1)) + 1; public static final int MIN_PACKET_BASE_16 = (int) -Math.round(Math.pow(BASE_16, SCMPacket.DATA_LENGTH - 1)) + 1; - public static final String INFINITY = "INF "; - public static final String NEG_INFINITY = "-INF "; - private static final String INT_FORMAT = "%0" + SCMPacket.DATA_LENGTH + "d"; - private static final String HEX_FORMAT = "%0" + SCMPacket.DATA_LENGTH + "x"; + public static final String INFINITY = "INF "; + public static final String NEG_INFINITY = "-INF "; + private static final String INT_FORMAT = "%0" + SCMPacket.DATA_LENGTH + "d"; + private static final String HEX_FORMAT = "%0" + SCMPacket.DATA_LENGTH + "x"; private static final String DOUBLE_FORMAT = "%0" + SCMPacket.DATA_LENGTH + "f"; - private Logger logger; + private Logger logger; private PacketRelay relay; /** diff --git a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java index 30db2b3..0c5bbb8 100644 --- a/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java +++ b/src/org/rocketproplab/marginalstability/flightcomputer/subsystems/ValveStateSubsystem.java @@ -13,11 +13,11 @@ */ public class ValveStateSubsystem implements PacketListener { - private SCMPacket packet; - private int[] valveStates = {-1, -1, -1, -1, -1, -1, -1, -1}; - private String data; + private SCMPacket packet; + private int[] valveStates = {-1, -1, -1, -1, -1, -1, -1, -1}; + private String data; private SCMPacketType id; - private PacketRelay relay; + private PacketRelay relay; public ValveStateSubsystem(PacketRelay relay) { this.relay = relay;