From 9b710806255af6de343bb45ab888aaa1fc34eaec Mon Sep 17 00:00:00 2001 From: Duy-Nguyen Ta Date: Fri, 8 Jun 2012 20:08:53 +0000 Subject: [PATCH] Visual ISAM gui with global vars --- matlab/examples/VisualISAMGenerateData.m | 50 +++ matlab/examples/VisualISAMGlobalVars.m | 7 + matlab/examples/VisualISAMInitOptions.m | 22 ++ matlab/examples/VisualISAMInitialize.m | 28 ++ matlab/examples/VisualISAMPlot.m | 42 +++ matlab/examples/VisualISAMStep.m | 46 +++ matlab/examples/VisualISAM_gui.fig | Bin 0 -> 9609 bytes matlab/examples/VisualISAM_gui.m | 393 +++++++++++++++++++++++ 8 files changed, 588 insertions(+) create mode 100644 matlab/examples/VisualISAMGenerateData.m create mode 100644 matlab/examples/VisualISAMGlobalVars.m create mode 100644 matlab/examples/VisualISAMInitOptions.m create mode 100644 matlab/examples/VisualISAMInitialize.m create mode 100644 matlab/examples/VisualISAMPlot.m create mode 100644 matlab/examples/VisualISAMStep.m create mode 100644 matlab/examples/VisualISAM_gui.fig create mode 100644 matlab/examples/VisualISAM_gui.m diff --git a/matlab/examples/VisualISAMGenerateData.m b/matlab/examples/VisualISAMGenerateData.m new file mode 100644 index 000000000..7ab135168 --- /dev/null +++ b/matlab/examples/VisualISAMGenerateData.m @@ -0,0 +1,50 @@ +VisualISAMGlobalVars +sprintf('vData...') + +%% Generate simulated data +points = {}; +if TRIANGLE % Create a triangle target, just 3 points on a plane + nPoints = 3; + r = 10; + for j=1:nPoints + theta = (j-1)*2*pi/nPoints; + points{j} = gtsamPoint3([r*cos(theta), r*sin(theta), 0]'); + end +else % 3D landmarks as vertices of a cube + nPoints = 8; + points = {gtsamPoint3([10 10 10]'),... + gtsamPoint3([-10 10 10]'),... + gtsamPoint3([-10 -10 10]'),... + gtsamPoint3([10 -10 10]'),... + gtsamPoint3([10 10 -10]'),... + gtsamPoint3([-10 10 -10]'),... + gtsamPoint3([-10 -10 -10]'),... + gtsamPoint3([10 -10 -10]')}; +end + +%% Create camera cameras on a circle around the triangle +height = 10; r = 40; +K = gtsamCal3_S2(500,500,0,640/2,480/2); +cameras = {}; +for i=1:NCAMERAS + theta = (i-1)*2*pi/NCAMERAS; + t = gtsamPoint3([r*cos(theta), r*sin(theta), height]'); + cameras{i} = gtsamSimpleCamera_lookat(t, gtsamPoint3, gtsamPoint3([0,0,1]'), K); + if SHOW_IMAGES % show images + figure(2+i);clf;hold on + set(2+i,'NumberTitle','off','Name',sprintf('Camera %d',i)); + for j=1:nPoints + zij = cameras{i}.project(points{j}); + plot(zij.x,zij.y,'*'); + axis([1 640 1 480]); + end + end +end +odometry = cameras{1}.pose.between(cameras{2}.pose); + + +%% Set Noise parameters +poseNoise = gtsamSharedNoiseModel_Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]'); +odometryNoise = gtsamSharedNoiseModel_Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]'); +pointNoise = gtsamSharedNoiseModel_Sigma(3, 0.1); +measurementNoise = gtsamSharedNoiseModel_Sigma(2, 1.0); \ No newline at end of file diff --git a/matlab/examples/VisualISAMGlobalVars.m b/matlab/examples/VisualISAMGlobalVars.m new file mode 100644 index 000000000..2438a9ea0 --- /dev/null +++ b/matlab/examples/VisualISAMGlobalVars.m @@ -0,0 +1,7 @@ +global TRIANGLE NCAMERAS SHOW_IMAGES +global HARD_CONSTRAINT POINT_PRIORS BATCH_INIT REORDER_INTERVAL ALWAYS_RELINEARIZE +global SAVE_GRAPH PRINT_STATS DRAW_INTERVAL CAMERA_INTERVAL DRAW_TRUE_POSES +global SAVE_FIGURES SAVE_GRAPHS +global nPoints points K cameras odometry +global poseNoise pointNoise odometryNoise measurementNoise +global frame_i isam newFactors initialEstimates result diff --git a/matlab/examples/VisualISAMInitOptions.m b/matlab/examples/VisualISAMInitOptions.m new file mode 100644 index 000000000..a9ef09bb5 --- /dev/null +++ b/matlab/examples/VisualISAMInitOptions.m @@ -0,0 +1,22 @@ +VisualISAMGlobalVars + +%% Data Options +TRIANGLE = true; +NCAMERAS = 20; +SHOW_IMAGES = false; + +%% iSAM Options +HARD_CONSTRAINT = false; +POINT_PRIORS = false; +BATCH_INIT = true; +REORDER_INTERVAL=10; +ALWAYS_RELINEARIZE = false; + +%% Display Options +SAVE_GRAPH = false; +PRINT_STATS = true; +DRAW_INTERVAL = 4; +CAMERA_INTERVAL = 1; +DRAW_TRUE_POSES = false; +SAVE_FIGURES = false; +SAVE_GRAPHS = false; \ No newline at end of file diff --git a/matlab/examples/VisualISAMInitialize.m b/matlab/examples/VisualISAMInitialize.m new file mode 100644 index 000000000..ae48f3531 --- /dev/null +++ b/matlab/examples/VisualISAMInitialize.m @@ -0,0 +1,28 @@ +VisualISAMGlobalVars + +%% Initialize iSAM +isam = visualSLAMISAM(REORDER_INTERVAL); +newFactors = visualSLAMGraph; +initialEstimates = visualSLAMValues; +i1 = symbol('x',1); +camera1 = cameras{1}; +pose1 = camera1.pose; +if HARD_CONSTRAINT % add hard constraint + newFactors.addPoseConstraint(i1,pose1); +else + newFactors.addPosePrior(i1,pose1, poseNoise); +end +initialEstimates.insertPose(i1,pose1); +% Add visual measurement factors from first pose +for j=1:nPoints + jj = symbol('l',j); + if POINT_PRIORS % add point priors + newFactors.addPointPrior(jj, points{j}, pointNoise); + end + zij = camera1.project(points{j}); + newFactors.addMeasurement(zij, measurementNoise, i1, jj, K); + initialEstimates.insertPoint(jj, points{j}); +end + +frame_i = 1 +cla; \ No newline at end of file diff --git a/matlab/examples/VisualISAMPlot.m b/matlab/examples/VisualISAMPlot.m new file mode 100644 index 000000000..549c3ac37 --- /dev/null +++ b/matlab/examples/VisualISAMPlot.m @@ -0,0 +1,42 @@ +VisualISAMGlobalVars + +if (frame_i<2) + sprintf('Cannot plot the first frame') + return +end + +%% Plot results +tic +% h=figure(2);clf +% set(1,'NumberTitle','off','Name','Visual iSAM'); +cla; +hold on; +sprintf('Computing marginals and plotting. Please wait...') +for j=1:size(points,2) + P = isam.marginalCovariance(symbol('l',j)); + point_j = result.point(symbol('l',j)); + plot3(point_j.x, point_j.y, point_j.z,'marker','o'); + covarianceEllipse3D([point_j.x;point_j.y;point_j.z],P); +end +for ii=1:CAMERA_INTERVAL:frame_i + P = isam.marginalCovariance(symbol('x',ii)); + pose_ii = result.pose(symbol('x',ii)); + plotPose3(pose_ii,P,10); + if DRAW_TRUE_POSES % show ground truth + plotPose3(cameras{ii}.pose,0.001*eye(6),10); + end +end +axis([-40 40 -40 40 -10 20]);axis equal +view(3) +colormap('hot') +sprintf('Done!') + +% figure(2); +t=toc; +if DRAW_INTERVAL~=NCAMERAS, plot(frame_i,t,'b.'); end +if SAVE_FIGURES + print(h,'-dpng',sprintf('VisualiSAM%03d.png',frame_i)); +end +if SAVE_GRAPHS + isam.saveGraph(sprintf('VisualiSAM%03d.dot',frame_i)); +end diff --git a/matlab/examples/VisualISAMStep.m b/matlab/examples/VisualISAMStep.m new file mode 100644 index 000000000..7c86e3ce1 --- /dev/null +++ b/matlab/examples/VisualISAMStep.m @@ -0,0 +1,46 @@ +VisualISAMGlobalVars + +%% Add odometry +newFactors.addOdometry(symbol('x',frame_i-1), symbol('x',frame_i), odometry, odometryNoise); + +%% Add visual measurement factors +for j=1:nPoints + zij = cameras{frame_i}.project(points{j}); + newFactors.addMeasurement(zij, measurementNoise, symbol('x',frame_i), symbol('l',j), K); +end + +%% Initial estimates for the new pose. Also initialize points while in the first frame. +%TODO: this might be suboptimal since "result" is not the fully optimized result +if (frame_i==2), prevPose = cameras{1}.pose; +else, prevPose = result.pose(symbol('x',frame_i-1)); end +initialEstimates.insertPose(symbol('x',frame_i), prevPose.compose(odometry)); + +%% Update ISAM +if BATCH_INIT & (frame_i==2) % Do a full optimize for first two poses + initialEstimates + fullyOptimized = newFactors.optimize(initialEstimates) + initialEstimates = fullyOptimized; +end +% figure(1);tic; +isam.update(newFactors, initialEstimates); +% t=toc; plot(frame_i,t,'r.'); tic +result = isam.estimate(); +% t=toc; plot(frame_i,t,'g.'); +if ALWAYS_RELINEARIZE % re-linearize + isam.reorder_relinearize(); +end + + +if SAVE_GRAPH + isam.saveGraph(sprintf('VisualiSAM.dot',frame_i)); +end +if PRINT_STATS + isam.printStats(); +end +if mod(frame_i,DRAW_INTERVAL)==0 + VisualISAMPlot +end + +%% Reset newFactors and initialEstimates to prepare for the next update +newFactors = visualSLAMGraph; +initialEstimates = visualSLAMValues; \ No newline at end of file diff --git a/matlab/examples/VisualISAM_gui.fig b/matlab/examples/VisualISAM_gui.fig new file mode 100644 index 0000000000000000000000000000000000000000..e01fc121404c65aa02fc01446d26a9da945f4241 GIT binary patch literal 9609 zcma*NcTf|~^FK@#5NU!GDFLZUmlkS3nsg9p(m_BvK}zTX(xeJX?_FuqdypDBNbf;f zfY5sa2|wT8&wtNf&(6)w?d|N%-p=gq?Q2d;;jN~^D^@W9AyzGgxBT{wE_QsZx-QmU z_U@jpQvdc8)x<^lSQS0(ti9~sv%0%Uv8s4FvZ{N#v9bbLg~g?WM5KhpSzihXzhwRY zOI_?Z|07&AEsB3DiGMsK`+z~qok?tFG4Q*1%*}2AYbYKuI7~}t8)v^*ZOQ!4WRliY z@hkOCku?+EwbQ|?hQ(}ug?$h%SU#JQjuOTaPVgoINbvdR&u>5J`lt>V0(=Lg)vnkv zIG1W`&ByV1n7f11+w|u+zpK)sey8`r-t&GUP!W^;<^;2=xcxqsAtLfvvx~~(6$r$h z^&#>#gf>kcMU^zI`a(@%eYQMFW-QO>6dzxwCm+f##<8$V`o}p|uKQ`t{{jfl zJO}ywmZFgDGnP=kcx_-7hOm4p__yO&Ws()(Lt?+P%r=T+Y&nN3xFbnksl}kQt z5fkwiyP?x!6_Z(tA+N$ttEh|mz_W*iABDtRROIZH;$PVC8h;oG=j7q3!+x@l*Jpo9cmUQE1I6emp?V?k2PZA?wWSTj`zYP4RHzAaAz9 z=$28MzMWp0p`AhcY5P-Y#`gactaIDla}y1_yM%{h7V!qrBFc2%Nw<~tt_$tgRkdhn zYV@1>6?Y2@1%WO!jJlM@{DrOy#3UQadm-$vhrciOYk_)>hX++BKpzM1dNWW_xK*=l z$-M8k9?JJWS{;mkzojBCk3SO+&#OBq-aRNJGCh6_1X{dCR^8o-3R#UGN2jbi#_LF8 z654;R*N`D%>DT5KKH6Y)I31F_S?ri{xI;#hjT%Tve!TJ>nUkJiVU5truG%Vv1;lo7 zi($UF&>4=Llcv3T^2t-4mCiZIs)jk@=c#+#r8rbF(Q<^#Rwt0mbuOh04-G8WTTL70 z$+6anntVh>&>B-_!qpO49Sh<8;x;4X2wNQpQ~NXmUZ>{pN*~W!G1yZ)8#f~HZr(aq z(&lf%t6|gGrWP*25=aRHT|kev4q}0}5R`iSQ zoB<~(D&mNBvI&Kp``T_$vhNx1L5#1|W|CNCq=4m>v2Q(v$-w(;Q>Fiut-Q|j%-3lh zVrsRxn=OJ8xdz2k+;t7(PMUX!IxHIe35RLKS0h4ZPM53^PAi#~e};nm(XY3BRj+HV zGnO>gI^{kD)y!Y(N+yKv`)j|MZx>$50tBc{hlFRhS!m;GEP=P(QXO68P=0rf8Ah=%n5h(s;l;@^L+S`xnJ6&!MhE*dBg|+`hVjP zuxQC#|IoeHj7|G(!Ry{>By--|cgASmzs!sfdEAf{AXKHQ@J3NlvDVxTz$%ejbdRtC zK|XB%@vZ6zn)in`>x5*jHSXh!FPzga$SxlT1l$7%-LGJsWyM)--Mte`z{(8lGffMlwMNMJx$fo==3`**Y4q(2U4Dmj~l(Q!hj{59*M4tS6iqCJo)SERSzSc7H);qM4jkhs`G z>G&aXb+-aS8SMjWFF4x`n}9I_^)HkgAy-5{nA~a41=tVfmyaHO zS#(&i%3g-;W^l`|Kpq}-5OlH^%i;NKaI_mPxi*1x8`!I|QFVC^G8XrNgT~zr&6?6> zxty1y<%mfCQZftC;BG7SHBp=F&>dOzzhlOy4HGT9R+;<)2^?L~EhRMA%KrIavR&z< zzJBf*S9?uRgfS=q?LB=mo)tn1CDjZAny!+P1mms(Qhb*n4rFW1McaIro|-G~9=Z>I zX{V2EzgVB%NeqCE#Of@Sz;=Q9EW{=Au2v><^KZi>A~*sEWhMg5)YsJRxHhlH7K>2CmMTkN@O&#B(J6 zJ`L~7<*ne@$MJT^n%eE8a-RFr#$oX_pEq{!Jo~zxs495}Fsjw0y%T@0P6mmhVkj)G z0&}?r61KYscC+so0JjUH;)CNyD_b2}M9e%t%$|1#`x>lMinkDf-Rj-gFlNJ}WmeWP zI1il54~GVPLT_9pdz{RYf+B3+mG(I>dz&jFKP%Xz=$6)+Zw&c7TK?U`{fN^gC5ofT z_0nbJAQ4>2Mra+JY&vh$FE4-G^P!UD6+GB>@yC+tes%ZHJ6Y3@L^*~8RwV3}rcZbl z7Sw5cM%-RzJ+)_v;364fDNynWpr5qLBI*lzxcWCh$xV@-ca7D7iZJ#0xFrF2Jr7xqh?vQQl< z*<;V+!&ZTD?^EyTe)tY3SOAM|HEX+Nq&`MoBg&;QCpnq%Uly52h$a53E343HS_ZeA zt)_Izfl$Gl7tK}M6m2Ef-GJ7O7NV(h+BY)Ctl_yV_l4^~v=a~9WWKc@=+J51g_gO5 z#0#Hd>HHnfv*&l7qXcEQ3aEnXx6&Gy5pB6DuO@Kfupt+9J9dSaf=d38rDb_AKdL{; z8{5XJp3iajDJ(P;=X|Qy`YQ>i{+u8SC zMD60C7^!1w0vn&aGVk0yElYPZ=FBS$*K@hjegn-ugKyUqpphW>O|ALa#L)K8_)x`{ z`?s1m={84U9IN)V1NIes_u+9V}qifGlHp6`$?Fqsj1dVrF?xXUl3^P2We`$*BW%j zK7BYm3npksW4E`w={(Af@y}e@K$g|u9i<5Pg&|pY2pPwN^eN4J zH~Y^9Bk`v;Cc@d73?eOQ%{nd^?)`lC%D8Lp$!on2Cq(|*B(b@($vT^@^rmu-Ts)$i z@HqW%0X26y4pH{xGFkz$7Wo|!X7mp*M$LD#BmU$0u z&{o!U=S}4h#z&jThaAP6zq|&KEe0?ODYu#0uL(cuwhjwZC5E!hcjfi1q$TRkAp&*v zz#i?uwX@qJGpNiEMENWGuWg~y_0m`uDoVhe!}>!WK32b$%KSq;fTwu7T>2#jP&|4| z=DL;)kLH|NE&rZ)HL^U`>nq{D=F*ApDs9x&hI@9|%30#uo6eW`*S~t;3=ijc*~zF8 zY>WU1A^I8%7`BjL^}yF7X%tJcxN?5w>BmmX6Dp4E8)fO1m`oEDQc>T zX`ZgccIVNJdBAHbDfX&K2_+*9=jY^uvk3@+2iNIzxvljV)Tei5vrt}QjmF`ewym1* z0?b0(OXkJc`9+O)OxA+TOKEqWC+G^?WTXWS3iytazRKB$`U#>-p$!R@>M=f;h|c5{!x1f?*ApV^gr6mLNt*&q*b3tzNszuRY!_yHN0s|b)++6P3;jC zc6>7XaHYxZ=@&K*y$u(e4YrmQk%OGl&cTK;Hy4`~H^=F>`Cr*h#=${YV;BrOvxOrs zYR}u?y@T_m!7`tJ0!F%GgrKux5j{dS*1s*M0wpoY#``Y_4g=x{v$X37{XZ0O`MACLNerP@Khun%J9v>d%ow4Aw^ z8VbIi5q;f%r_@{$Mf?I_4U(U`HSGLzMAXu7L_NJqLR=u-5X)B)8&`ihtZN)GZr4f4 zmu3W!y>m8?9d1icbb&#EzIb_wux-oqO7;z?I+)_SpXAS(g;jUq`{$2lt)+)OikrFj z_<4~$FK&nKW=~E7EYMmqBAr@lHNa<}y0vEj-w=_2>I%gBw|5V;*{ZiT24S46oh)Tl3JO(VcA-sKofmM866e~e6sC?cyE)!jq=FCK&1}VT!Thq-W8Ge6 z$daDMH$Tmmm)fMwV)wB(i z+zRddE7Pnm&Q6`~y@wvIZ!u=`ynz2SQ+7*-8XJk;4Tuf4_*k~i>7Di8opvcoE&9HG zo#;%Mp5Pqt!$V8s@_uQ1dll71JL?S0ElpU0?TzO;C%&v!7-)=hPWd?2$dvq_eKCG& z$Mpbx&%=3E?4{Uz&vA0%rN76N7gvF* zMcS*2wXYX1R}|GuSBq_1gD?6`NwcH*G%ooB;tDE9C7f2qm0WM!QAkr)ap#$aA(fL+A*qLZ z86`!nwIgG4DwP}mjb?UF<< zsoblah_U^n+kJIggjVYtM`$E{xb>OXbeRM`EfAo$O(T$&xZwU76f0+Om$CTjS+O?X z?PRy^<&6|+ZO!x3{$JDndWK&Pt9De)InU9;-mxm19&P|h<_|726)l1^3yNdRSi|Q-lqflPLNcd!NDxAkL}7!$CeCp z{=%$SSr}zY1JH9p=u%GU0r@UVhTKc+o!CYI*SM701>y!%T-h>`mVCC#oCpD->Y2EY z;9-ByIOn<3@Y^C^zbl)PDp3yjCE07V>?-l;sjn zKs%2E&Fx8jy{_j7dL&}{f@BEaqy0?#_TA+Mcc)J2_0UDO_(@JvA6;*6?(|zo@v^Sh zn(xIH;LtE5cRFms(Ply-C~pOPyES48&XY+rF7tR-_V|Z>zw=Lh1ltu`j9{doepw;> z#dN^7@}>HXS(9MQc_kdm3I(Xk2+QmquVc6hbS%D8VvK^;Fi9qA#~D<98l{$aH9Dye zJ1kS5t%`(WkJ0}?$$w#Ntfey}PoIm|j*Ie;P2cTaxaluclBe*mA9>uTga-~q+BZob z7^*Kf=*xAKOC+*LdR~E0sxsy0O(G4MR6+IcQnkh~USF+TMb ze3wFo&y&xx48&oJOp1TYJt|LZAA&4wqm$Vm`oV4d*q{5U^VRg6l}bi_ut_|!n%;H$ z%aTn5ooDcV``G(4y_27Tu3U0qYPSU2Dee{7YE!v$mT)e_eD+Ze*A1Ay?0ee-RN3rb zuWImJ#F*MVOAWB^`Gos;PR_p_7ILx!1O{Gp~ZVwD!(;Ds=*7*;1>g5xgz z8$+S~XhFmxy%LNuIpNc#oKNj|=1eR^TZKLMT_m|jP>5)ro9?k(Dc4a;lUDCJ3)om; z#^>vAS~0$7sSJncRPtvHw+s6(Bi6B53==_?{%*fXg%vs@E(hjr2Rv_kWBW@=#y=ha z@ehqSyDRbut6{(Vo=)hiMo#NhI>?riE<3`=-LuUV8zu`5kNn8z6g#zF?)N5JeCk|< z#lGw8`h$AyC8a~YQ0HX=7(b-XO&s&B8t`vNFkYHa0Fs&oe9&XtO$+$-=ZLeN#ePb{ z%@w9D%e8CVCKn_Ge$`1oaX+UJ2TUA{MSj$1)3(+`j>Xfix9^&Pn%GO&p^fzLhPSFu zIOm_7oXNKyzi4yAN=E#5%yD?3 z-&T5mz$q40d@(Tv(zxFWRGK0^$;U2wpZ-lnQqRFT5+hQv8Ao{=%pr?dzo$3bu17_J zQD+lb$!njCjJwJwg`6gZ=cho^xf)AE5oghD52}tgFz1eYc_ksK*ddgcn&9u=z%Fw! ze`wZ-tj7IaTF7|ch8@}g;`Jgeq!iQj5DGtwr1CeHxX)G@^2g!6Qs|Z;Hs`-T2sRhM z)LY%({SWam(fJoYG@1|utRds1c2R)g+ zu_8L^gj@_wFbTCFS1_62euq!wIC=jOh$dP4Wk%2{6y6bZzINN`b4&ROKhXXgNfE_m zAr%{A;E}EUW*wr9?{2M`=St|KEQehb6|62I`lmPSeV@0w*uh&DQuEDuanu3b?Ip`G z^8 z=Tq{Df;;%O!2N>6wTez8mQ<#J{@eZma{czZHAMus!cvs1m!n=g3b0 z4MGu_)9f2>mzpQ%$dXkl2Eh4g=;cgr!wy}lI-$$5oy$?YR*r7=hHvi+Hg2vS%x^jN zZm7bTTvF|(RMf58sw&kud|ZM2iR%6jEW_;4h)3~dj|$b6>8_GY>N6cxNX5goBzskm zlZ;W4dnBOing>o6`{aa{rUOfVUk(Z1K<~TLUq6zy+_(r3!!YGZcMsB=cB4NEe*-Y& zg`YatW_)ZfL@{nXOH4DP7lL8mz5dNG=^-!foZ4#SV;PPmnt8`UM#5moczYn(q-Mu> ztR9dYJZ~_@k~Ax`D?aY%oD3ImykVUu>DRSbj_0NSKI%zn1b6FOrfzNvPxWrJ6B-J%oV-n|x`2CVgK&us8HR z6`=~u*|AM#27?tK{bR0^pP(BDAH?1JP!plpfSJ{fy_sANmND^Nhp(npxw}M}Rqod2 zNRhDZOl*be@=q0}3ZBS}B%4Nf`&P1T7Z#33d*lW29| z&pgM92x4MXeK_xVNa@}4lVAT?wLS6D-rhByTQT4wi&0qT9G zWPDl~p|)K0JVKbGw7}H^&)aRk+TO&5liZexas_zQvN?XIY?gFI!P<=*LrNiC8-pZF zrfECU)kwY7I157Eb>_%<%4pWw;tQw#h&>d;dDdZ9KpggvjaHnEyOs1g0k5uKdc3~N zQy21j$)2737C8=&gfUy2ZQHk2^@Qdh-fa0(<*kNBPkeZkm)#Qu()orsCz+rS9#SFP zIdhYD>TW{n1eg7UyV(nWh&o9gQlg#F-W zonu@ljDK#xE=@_T7QPnyKAO}<+=M$7gtBOYcP(s>-7+ybgokGyOw@Gwrgs;!uh#)| zs&eAYS#1d=CwqPH8{@H6iaXZ>V+U`WtTC8)>B~}7lBDv6B-i1YdyO?Trxt2xPVhWa zgtJ>=Zuv0o(x=hV{a&M!SvudpJ%<&p|Id$QRn6t0jz7M2_FW;J1A}CV{7o&xU;1}` z`0Rb9FIibZM}W1^-aPip-}f z8UcRLNAop>SaZ4?4aqUAioz}S#_UzXvb-DavP+_1{;Zm8@h+z0Rdr@PnvdL4Gfqn*$IxBHB7zb*{s97_2{@nC6}=+m^z5mKUlyOoW-rN!t8e8T?K zT`A>)BjPOYlHKnoT2kQTk#4&jtCX!=G?H@bO`Ob*@q$xJv~;;@QjE2+FoohOp@bZf zAJ#Mq9_yoU-9;x1Kfi@1q7n7I9&)C$|D3gS&H#?q5l=dFxQmbeV(LorhCDTl0JX77E=E{w@n%b<{C=Cgye z2DtV>$I@_;(f@FtL!+^OjWA6Jzbm1OrpKaHnn4zq{43|b4W{~SY)J$1G%d8;Vy-IC zZ$NyXjTUwoGq+X>7dDTX`!wocM4Kr&GrE{lsCYJc8#~ounVSbsi`D(4hBNr*`JW%` zg=~xBT6k+7zam_eG#T++C})2^jrw)`^r4tW_8E!i zXu>Abgz^ENd;ml|*)(6UUd$>x4*|DDtC67NNzlS^ zkEVfhTJtd{X5Qr8(PspndbgS+$J;#9{;Tj;l_dlG`2~WTnyKDEk$h1(b7@T_r{Rhv%0gP0DfeT`L?xt8EJk7+U}hjpW|Q^q zGs5n3**B|ZVPecygK?@%$kXGABZXXBM5Apv$BCBs)7R7Qi2DI0oYA$xq^e5e)KYuLOQ9Elu>O%Lp#4zRlkoRU zMaRc|5s-Hj%5h<0V5`g;lx3cq8QMNO5s6?r65(Y5Yi)F*g0Ft0!6$Cx{*`(YkJh|S zw|oCA%s#7+X{WvU1< zsQd56R}R|qGG^0yMAGrwShpnXbtJ|lFyxB9+BfkoS+8^DOz@i+MebWv(3vm)SnDeF z!I(!1T4T{Soiu=RHcc-y%DN=>JN}{!nht{uQUF92fs@2043L%-6CRiUeV^(1SD_)< zhZ$qqJ@PaWWs0W3rr7(ljhS_WJ+&{on|CXsEpgTr~(<_{p2~rr=?cJ zjJ8KwTxIaRobdwJNM&=jzGA`8%#H$2{ixDP7NZC90TnNPn9w8G``tthI}ZahUV<2E z-QC6++8n(6!QaggkE``(F$2w+Sr+};qT{9Y>;8L!wB1wZ7k3Xw;nj5KBtr%0`MD!F z#s+hcwv>W~lpkfi6AAnNysw=hPiL6IvVT<{7@R$>=)MuvT>m>DSMV4>iv?2daq7$X z-^a-+J|3qOCo%o(+GEml;kQFVM@&bOMlAi=yvMHRNsmE~SdVuPS&vo^e~)VqbID>e>YA3kMF;s@JBGb&=Oa< z>*1GRG8&8&51LH(A}fElS^kfEcp?0s;GbUNZiql2om}5h5X<%N;t*mC`ChYHmkowV zZm%&})`^w;wyVew2tpw4vh&VA29HmmB>z9m{RnEFXy@KlmhGy>_ux(