From f56e1c3d50586df7c15c1f8decb99424a4f26871 Mon Sep 17 00:00:00 2001 From: Austin Rohlfing <rohlfing@iastate.edu> Date: Thu, 31 May 2018 21:11:09 -0500 Subject: [PATCH] Resolve "Add LQR Control to Simulink" --- controls/documentation/LQR_Design.md | 129 + controls/documentation/SimulinkModel.md | 70 +- controls/model/Quadcopter_Model.slx | Bin 0 -> 77520 bytes controls/model/Quadcopter_Model_R2015_A.mdl | 17773 ---------------- controls/model/Quadcopter_Model_R2016_A.slx | Bin 40651 -> 0 bytes controls/model/Quadcopter_Model_R2016_B.slx | Bin 70974 -> 0 bytes controls/model/improved_lqr.m | 22 + controls/model/initial_lqr.m | 8 + controls/model/linearization.m | 130 + controls/model/lqr_err.m | 19 + controls/model/modelParameters.m | 260 +- controls/model/repeated_opt.m | 29 + controls/model/rich_params.m | 389 + controls/model/run_once.m | 33 + controls/model/test_improved_lqr.m | 4 + controls/model/test_model.slx | Bin 163681 -> 0 bytes controls/model/test_model_R2015A.mdl | 12432 ----------- controls/model/test_model_R2015Ax.slx | Bin 44942 -> 0 bytes controls/model/weights_modern.mat | Bin 0 -> 405 bytes controls/model/weights_old_quad.mat | Bin 0 -> 404 bytes controls/model/weights_rich.mat | Bin 0 -> 336 bytes documentation/images/simulink_lqr_control.png | Bin 0 -> 94296 bytes documentation/images/simulink_lqr_sensor.png | Bin 0 -> 79787 bytes documentation/images/simulink_lqr_top.png | Bin 0 -> 84585 bytes 24 files changed, 951 insertions(+), 30347 deletions(-) create mode 100644 controls/documentation/LQR_Design.md create mode 100644 controls/model/Quadcopter_Model.slx delete mode 100644 controls/model/Quadcopter_Model_R2015_A.mdl delete mode 100644 controls/model/Quadcopter_Model_R2016_A.slx delete mode 100644 controls/model/Quadcopter_Model_R2016_B.slx create mode 100644 controls/model/improved_lqr.m create mode 100644 controls/model/initial_lqr.m create mode 100644 controls/model/linearization.m create mode 100644 controls/model/lqr_err.m create mode 100644 controls/model/repeated_opt.m create mode 100644 controls/model/rich_params.m create mode 100644 controls/model/run_once.m create mode 100644 controls/model/test_improved_lqr.m delete mode 100644 controls/model/test_model.slx delete mode 100644 controls/model/test_model_R2015A.mdl delete mode 100644 controls/model/test_model_R2015Ax.slx create mode 100644 controls/model/weights_modern.mat create mode 100644 controls/model/weights_old_quad.mat create mode 100644 controls/model/weights_rich.mat create mode 100644 documentation/images/simulink_lqr_control.png create mode 100644 documentation/images/simulink_lqr_sensor.png create mode 100644 documentation/images/simulink_lqr_top.png diff --git a/controls/documentation/LQR_Design.md b/controls/documentation/LQR_Design.md new file mode 100644 index 000000000..cb1b773fa --- /dev/null +++ b/controls/documentation/LQR_Design.md @@ -0,0 +1,129 @@ +# LQR Control + +This document describes the MATLAB and Simulink implementation +for designing an LQR controller for our quadcopter platform. +This work is almost entirely based on Matt Rich's graduate thesis ([Model development, system identification, and control of a quadrotor helicopter][model_dev]), +specifically sections 4.1, 4.2 (for the nonlinear model), 7.3 (initial LQR control), +and 7.4 (improved LQR control). + +## 1 Theory + +### 1.1 Nonlinear Model + +The nonlinear model for the quadcopter is described at a high level in section 4.1, +with individual components further separated and defined in section 4.2. The definition +is given in the form of $`\dot \Lambda = f(\Lambda)`$ where $`\Lambda`$ is the state vector. +Technically, this is also a function of rotor force and torque. + +There are 12 state variables: three linear velocities ($`u`$, $`v`$, $`w`$), +three rotational velocities ($`p`$, $`q`$, $`r`$), hree dimesions for location ($`x`$, $`y`$, $`z`$), +and three Euler angles ($`\phi`$, $`\theta`$, $`\psi`$). + +### 1.2 Linearization + +The linearization for this system is performed around the only equilibrium we have, which is hovering in a constant +position. This means that every state variable is $`0`$ except for possibly the $`z`$ position, but we set that to +$`0`$ as well because it does not affect the linearization. The equilibrium command inputs are also zero except for +$`u_T`$ (as some non-zero throttle is required to maintain altitude). + +### 1.3 LQR Controller + +LQR (Linear Quadratic Regulator) control is designed to minimize a given cost function, which is given as +```math +J = \int_0^\infty x^T Q x + u^T R u dt +``` +where $`x`$ is the error between the state and the equilibrium state, and $`u`$ is the difference between the command +at time $`t`$ and the equilibrium input. + +## 2 Implementation + +### 2.1 Nonlinear Model and Linearization + +The nonlinear model, as described in section 4.1, is implemented in MATLAB in `model/linearization.m` with symbolic variables for +states and commands. Setting all other values to zero, the equilibrium throttle input is found using this model with a binary search +for the correct command value. The $`A`$ and $`B`$ state-space matrices are determined with symbolic differentiation, so the linearization +is automatically updated if the model is improved (or simplified) or if the equilibrium point is manually changed. + +### 2.2 LQR Controller + +Matt Rich describes two different weighting schemes for the matrices $`Q`$ and $`R`$. The first makes each of these matrices diagonal +(and $`N = 0`$), so the controller tries to separately minimize each of the state variables. The MATLAB function in `model/initial_lqr.m` +computes this controller when given the state-space matrices $`A`$ and $`B`$, as well as vectors for state values and command values. +These vectors should correpsond to approximately the maximum allowable value for each state or command (for example, you might set +the 10th value of the state weights to $`\frac \pi 6`$ if you don't want the quad to pitch more than about $`30^o`$). + +Rich also gives a weighting scheme broken down by what he refers to as subsystems, of which there are four: altitude, lateral, +longitudinal, and direction. The matrix $`Q`$ then ends up block diagonal (after permutation to make subsystems adjacent). +The logic behind this is that, for example, if the quad is too far to the right, rolling leftward should reduce the cost rather than +increase it, because that is the action required to return to equilibrium. Given the $`c`$ and $`d`$ matrices Rich defines in 7.4.2, +the matlab function in `improved_lqr.m` will construct the corresponding controller for this weighting style. Unfortunately, this design +has never flown successfully in simulation. + +### 2.3 Automated Optimization of LQR Weights + +Due to a lack of controls knowledge and intuition in our team, we implemented a MATLAB script to pick weights for the diagonally-weighted +LQR controller design. The script `repeated_opt.m` picks a random set of weights, then uses MATLAB's included contstrained minimization function +(`fmincon()`) to search for weights that reduce the actual error when run through the Simulink simulation of the nonlinear model (recall that +the controller itself was built with only the linearization, so it doesn't represent extreme angles and speeds well). This process is repeated, +and each set of weights is stored in a file along with a error score (lower implies a better controller). + +The function passed to `fmincon()` is `lqr_err()`, which transforms inputs from a subset of the weights to the full weight list and calls the function +to create the LQR $`K`$ matrix. We assume the lateral and longitudinal weights should be the same, which reduces the dimension of the space for the +minimization to search to 11 instead of 16. Internally, `lqr_err()` calls `run_once()`, which simply runs the Simulink model and returns the +error between state and setpoint as the output. + +Warning: The LQR controller designed as above (or in any way) has not been tested on our quadcopter. The simulation is a good place to verify that +the control conceptually works, but don't assume that it will necessarily act the same way on the quad. + +### 2.4 C Implementation + +The existing PID controller on the quad is run on the [computation graph][ctrl_graph], which only currently handles scalar values. An implementation +for matrix constants and matrix multiplication blocks is available on the branch `53-add-lqr-controller-to-c`, but the controller itself is not +finished or connected. To implement the LQR controller (or any sort of state-feedback style controller) on the quad, either this implementation +needs to be finished or an entirely new implementation needs to replace the computation graph. + +## 3 Errata to "Model Development..." + +Like any 150-page technical work, Rich's thesis contains its share of mistakes and errors. Most are minor typos or inconsistencies that largely +have no impact on the readability or usability of the work. There are a few points, however, that deserve note here to clarify discrepencies +should anyone want to replicate his work again. + +In section 4.3.1, gravity in the body reference frame should depend on $`\phi`$ rather than $`\psi`$ (roll affects the direction of gravity, but yaw shouldn't). +The actual vector of graviational force should be +```math +^BG = \begin{bmatrix} +-mg\sin(\theta)\\ +mg\cos(\theta)\sin(\phi)\\ +mg\cos(\theta)\cos(\phi)\\ +\end{bmatrix} +``` + +In section 4.6, the outputs of the camera model should be defined as +```math +Y_c[n] = \begin{bmatrix} +x(nT_c - \tau_c)\\ +\vdots\\ +\psi(nT_c - \tau_c)\\ +\end{bmatrix} +``` +As written in the original, the actual period was dependent on both the period variable $`T_c`$ and the latency $`\tau_c`$. +This model is not required for designing a controller, but is necessary if creating a simulation that includes inputs from the camera system. + +In section 7.3.1, the list of weights that Rich chose for his test are missing for $`u`$, $`v`$, $`w`$, $`p`$, $`q`$, and $`r`$, and aren't +exactly clear for the rest. This was one of the reason for the automated weight testing MATLAB script. + +In sections 7.4.2.3 and 7.4.2.4, the $`c`$ matrices should be +```math +c_{\text{alt}} = c_{\text{dir}} = \begin{bmatrix} +1 & 0\\ +0 & \sqrt{10}\\ +0 & 0 +\end{bmatrix} +``` +in order to create the block-diagonal $`Q`$ given in 7.4.2.4. Also note that this $`Q`$ should be symmetric. The third +value in the top row of the lateral block is $`0.02`$, and the element symmetric from this one should be $`0.02`$ as +well, not $`0.2`$. As written, $`Q`$ cannot be used in MATLAB to genenerate a LQR controller because it isn't +positive semidefinite. + +[model_dev]: http://lib.dr.iastate.edu/cgi/viewcontent.cgi?article=3777&context=etd +[ctrl_graph]: ../../quad/src/computation_graph/README.md diff --git a/controls/documentation/SimulinkModel.md b/controls/documentation/SimulinkModel.md index 5deb8593a..796fd09d3 100644 --- a/controls/documentation/SimulinkModel.md +++ b/controls/documentation/SimulinkModel.md @@ -2,7 +2,7 @@ This documentation is about the Simulink model of the quadcopter found in `controls/model/`. Specifically, the description and images are from the file -[`Quadcopter_Model_R2015A.mdl`](../model/Quadcopter_Model_R2015_A.mdl). +[`Quadcopter_Model.slx`](../model/Quadcopter_Model.slx). ## 1 Top Level @@ -28,29 +28,60 @@ The variables used at the top level of the model are as follows: - $`\frac{d^Bv_0}{dt}`$ - Time derivative of velocity in quadcopter reference frame - $`^Bg`$ - Gravity in quadcopter reference frame -The three components are further discussed in the sections below : +The three components are further discussed in the sections below. + +### 1.2 Switches + +The top level also contains two toggle swtiches that change the operation of the simulation. +The left switch toggles between using exact and noisy values for the controls. The +switch that this toggle controls appears directly above it in the model, and its output is used +for all but on of the Control System inputs. The right toggle switch changes the simulation from +using the LQR controller to using the PID, or from PID to LQR. The components that this directly affects +are all in the Control System block. ## 2 Control System ![Control System Simulink Model][control_sys] -The two central components of the Control System are the Controller and the +The three central components of the Control System are the two controllers and the Signal Mixer. ### 2.1 Variables The variables used in the controls system not listed above are enumerated below: - $`u_T`$ - Controller output for thrust -- $`u_A`$ - Controller output for "ailerons", used to control pitch -- $`u_E`$ - Controller output for "elevators", used to control roll +- $`u_A`$ - Controller output for "ailerons", used to control roll +- $`u_E`$ - Controller output for "elevators", used to control pitch - $`u_R`$ - Controller output for "rudder", used to control yaw -### 2.2 Controller -The controller contains the actual PIDs for each element of the setpoint, -and outputs control values to the signal mixer. - -<!---TODO ADR make new doc or write more about controller---> - -### 2.3 Signal Mixer +### 2.2 Controllers +There are two separate controllers implemented in this subsystem, a PID controller and an LQR controller. + +### 2.2.1 PID Controller +This controller contains the actual PIDs for each element of the setpoint, +and outputs control values to the signal mixer. The inputs to the signal mixer are +values for thrust, aileron, throttle, and rudder. Inside the PID Controller block +are four sets of nested PIDS, one for each of the output commands. For example, +the $`u_A`$ output is determined by state variables $`y`$, $`v`$, $`\phi`$, and, $`p`$ +(i.e. lateral position, lateral velocity, roll, and roll rate). + +### 2.2.2 LQR Controller +LQR is a state-feedback controller (currently without an observer) that generates +command outputs directly from the state estimation provided by the sensors. +The details of the controller and how it is designed can be found in the +[`LQR_Design.md`](LQR_Design.md) documentation. + +### 2.3 Equilibrium inputs +The result of either controller is added to the equilibrium input before being +passed to the signal mixer. Equilibrium for this system is when the quadcopter +is hovering, so $`u_T`$ must be non-zero (all the other commands are zero, however). +This correction is required for the LQR controller to work. Though not strictly necessary +for the PID controller, not correcting for equilibrium input would initially respond +very slowly as the throttle PID loop accumulated its error integration. + +### 2.4 Signal Mixer +Because the output of the controllers is in a style more fit for airplanes or helicopters +than a quadrotor, we need to convert the control result values to something meaningful +to control our flight with. The Signal Mixer is simply a $`4 \times 4`$ matrix that is multiplied by the vector $`\begin{pmatrix}u_T & u_A & u_E & u_R\end{pmatrix}^\top`$ to produce a vector of PWM commands for the motor. As such, each row of the matrix corresponds to one @@ -65,9 +96,11 @@ S = \left(\begin{array}{rrrr} ``` For example, the fourth column is $`\begin{pmatrix}-1 & 1 & 1 & -1\end{pmatrix}^\top`$, so when the controller commands a positive rudder (i.e. positive change in yaw), -the speed of rotors 1 and 4 decrease and 2 and 3 increase. +the speed of rotors 1 and 4 decrease and 2 and 3 increase. -<!---TODO ADR The matrix is copied from MATLAB, but that example can't be right---> +When comparing different research or implementations, be careful to compare signal mixing +matrices. Everyone has their own scheme for number the rotors and orienting the quad, +but the signal mixer should give enough information to determine the rotor configuration. ## 3 Actuation ![Actuation Simulink Model][act_sys] @@ -127,6 +160,9 @@ phase), sample, quantize, and delay their readings. Without these, the Simulink model would only be good to prove math, and would not actually provide valuable insight into the physical system. +The 3D Graphical Simulation block can be opened to geive a simple visualization of +the quad's flight. + ### 4.1 Variables There are no new quantities that haven't already been explained in a previous section. @@ -135,8 +171,8 @@ A good resource to better understand the mathematical process of this model can in Matthew Rich's 2012 thesis, [Model development, system identification, and control of a quadrotor helicopter][model_dev]. -[top_level]: ../../documentation/images/simulink_top_level.png -[control_sys]: ../../documentation/images/simulink_control_sys.png +[top_level]: ../../documentation/images/simulink_lqr_top.png +[control_sys]: ../../documentation/images/simulink_lqr_control.png [act_sys]: ../../documentation/images/simulink_act_sys.png -[sensor_sys]: ../../documentation/images/simulink_sensor_sys.png +[sensor_sys]: ../../documentation/images/simulink_lqr_sensor.png [model_dev]: http://lib.dr.iastate.edu/cgi/viewcontent.cgi?article=3777&context=etd diff --git a/controls/model/Quadcopter_Model.slx b/controls/model/Quadcopter_Model.slx new file mode 100644 index 0000000000000000000000000000000000000000..e7f7ad3500d97b1b851d355dcadb8fac2467ade9 GIT binary patch literal 77520 zcmb@sV~{RE*Dct#ZQFMD)3*DxZQHhO+qUh~cK2!9r)}T!elam|-<gPs`(rX{M^<HJ zWY)^H_l~NSr6>amh6V%#1O@a*J62Xx#AWXl3<&7qpCSBfwXn5hbT>8nS25Tcx&S|b z!F|XH{gM?DCSqq`BKmhqZ)Ry@N=Kw<W9VXL?_|qEq$r{;CC|Y|M<n88YUpBWLS%2p zL-fnllt|9dlZc6#h?$A!-@(RA#KOePMf87I(n0?{%YO>6lpNx}3i02yN6wX+g8dQ` zntL|@1Z-)q<q*wruOWs^e#3*(0JK)w&~%+}BqZdpqq>zX6Gi<p>=nTWPyT~qi~AnA zL8W{`dW{7FHC(gl?@OM4|I7XTeGWK~;Ew>%gHbQ389LlpP7<xOy3#!?1~?s$?CAiV z#;<pCWx}zeicn99{a$&W#Rx2OuB}2}glA0$Np36z#%uBrjQgMreL>`Lk<xm&HO*Tu z->Kw#(n#}dz28N}E6C$X=FKAy21lMJ=;pJu$EAbM+N~y2<wva2KJL~1C*{-Xs=SdO zdejch#`o{7%6k~8pHjwwZDmSpZt#=^Jfd#8?UlyoefrH$Ja<x?Bypyzm2E|LOU5+v z<;1WSNqJ22Ji;F=Lw=Iv@Csh{e+Uq~?{kQs3C45EHa3JPGB=vA2vfQueR0g%PBv`~ zZP_`TKGcRR$YvY3P(*XN49y!8L?$Ffq`Ba6lmtJ9EMT_P;+IOWQNg+9WkIF=E9~H~ zkCEeZ7p85bs}GOHCg!IUi++1Zh$ozLQuF?GAdUj1)gn!;P_JP`buMUi%$Qt;Qw#Oa zBZ#J4Ps_`$nR+FXt4<p+mm$cVR-u*8lnyWTO}p95&HThqy%hBWyrg{UP2=BDK&EYP zkBu3qr?j0O^VFYK8_fm%cA?MNyT;urH9(|XhZ*=*(o&48Jba_Ro8YOV+2UpDj3W$= zcBMNW2%xapRHTd}h5aMO(`HzJ8)%BEG{i)7#aHJS+0PQzkGFRA!q1Rbn&?r|!%)Q@ zIc$2vcHHvuD}s6)xt(lxoc5jZ)G_BL6ZYF&a9dEt@r`Qyi}#yie~a32Hg>Nhr!~s@ z{Yz!*XZh#h%k}*yp8D&@r{pIe^J}*xVs!&zRreyh>xxHF;`cbuU<47KBH`M6|KA^6 zwvqB6;e;pVeg7Mbh9)(=mc{6Hpd1(27-2>ccza-v!}fu_UO;CrWY`N(pn$E&-KjA1 zy(?~JTAXgkV;hqo7MBqIAYUCqhZbSp>h2_8wDc_QPwb=bQpeSYiUR-`!Yml%KVk6; z_&;HBXbc3x!DO@tWF!v(We|Fg9ry}D8v+4LL6sl4u!K2s3TgzZ7UD-i_il(qG7FMs z98z`X`ivNs`49wd7)SJrpESn|xElP<Gw=^RD<yjmRbv5BE0q92l|OirUx+V~0B;tr z-~~UH<A-(-vMN97uNdem3ZMws0uRXLLKLP^qPvkKxUhqRX*7uPoX?}bKuDZitnF-+ ztc=-(9c<JDH9)99y#oU=VtDvWM*FNr$mT|ZBhWGN*Ni$o6l4O#oOi?v1x$nJh-cSe zmF|Mdb3tPKgh^h&Q~)kYR`OO!;tsxMGVWm{k~G1hUI>rBp};2Imd5}+HgAuGuW>>B zA9ALHHc0;7fMso_y}2Jas*?tTvmZf0fY;j~^sx-9-~%>PzynT3U{a^xiS-^d=c5CW z1b^rL)?h&YR;=LSIM^|1dN%>wGPS!95Rid4x2)p-og>Ho<;dIKWf9|lE8PtO1cdu< z)oo2(3{4DO3>l5>olF&->>W&<Tr5qU89Z!le3f<WgNe|-Xv5rLExO&rZJ!ebYA2dp z*PA#&+UYZcfYmPh39Vdpm;S=fa_4woAD2xTYl1;Csad5G^AJ-3jkYFOr5Co((C8El z@RWhkwgkbk8z?nQtLTyI;CgU$fgF<k8Nj8^zNHcIKCJ>Xo_bMa;k|=7o~Y#@cmB3= z>oEF^z5<d6+1f+FL!D;c!U<bBi;zzXicec<r{)12WJXgAa>7`G9_`;y?kWqaW`wwx zy&6b)uIexrKVFzrQeAs0iQ~<kQ@9&{KX0{WPpQI3hg_Zu=l)~4bYx9mAbH1~k|#~M z6)-Nk2TSIA8|WENNWe*(A`vnx!UA9HAtK4rD_3-G9>uuR9`>b~{V5+=rWzxdU1qTQ zM&v{*w8h!E@L_Zb=!|w9jNP9^efIAXlQbhP#O0BxK$M(Ygon@t0fk(z)4T@I<++DS zR2(a4XY{w=H^&hc_<8t0)BgbfH#avY{K}*MIFb0r5B~qojjj9tn;p}5A$d?{II(&Z z)47r>h!B?ZI$k82V<3t~o&_>DwD7b}e$9rAz*74D)1Rw5UP{+tnncUx55scwq*J7G zo{RXY^L;5=OF>{1)HpApg^M$rKJU6$wN3+DWHDF7iHh>o$!6vQ%4s5zFpllcSr(7k zvVi>ksFQ|G!s)cNS+BCNWd<1`$kLLt!lz#+;)chG8U4y7p1<*!G@Hv-qf}xgiRtST z7J7e#FOCUYI-9=~g63E$z=Yhdg$M_;uG;4OC%Xy%8-MJ6s$IrE+>8H=;{OZ3n1_q0 zowKFA-GAIvH*N|chzUu|zcjO#UZFT_TzZXR`AdUBuz>!YEy$m744uJV{(6G?Vl?JJ zEYI6qCc+dfsK!mseiP-oed-!02y_EN!n`tslR2V`X1XS~yxJZ0Z5}mx#kezsA>_OS z?J^Foi4Ci3{VlN6O<b-5(ngA0DW~%4rw6QQ7fNFrOWa4mPiaMof+fi_>-eKZQM>KB zKkfqbzp*j0#Q4Lb0s(#hdtJf!-?6z^xY`=o8Cu#fIM|tQdxWa1_`d=Q16n{9i3<Wq zL*t3yd0dniC1a8j7!nbvsfCouO33h-#McI(BS02WOCS(RM9EG9kasyxUpPN!-|}u| zd%N9vyXScGPSNL32+p_73yzD(NlA?Z_&dy@>hxz7aA<DzjP<mk7}9$P`JPEhNq@Zj zk~W#KwG$H?R|l^xu^><EXSzGhkrtNy6P2NrZDG6+sX~lfbnD>9IMgD?c2U^FuyBQ1 z8V+00Z(P}O(a}ro3jR=5>A@>x%}^As;kcS7yPQrnTanzT>X_orMb`v19sho_No{wG zEK#JmeeO?^_Fe1uYSiC7JZ%hKoP9D?R(#wUL=X^ewl=?cWjhs+QO@rblrl4}q09`7 z34Wh~#hVT~`o)Y$GEuMF_|^ZwT$7=VUqnBH%zA>d)Lg<a4i5eT*g723@#<gGSe$X^ zd6p=PWnh5m89>8FhRRmq)nLsowM-dy$;B`Iu)WUA#NG@eY*_+zHtv0<dN8t!6#zq- zININDWKPv6iW}J2+(?S;#G3QonXG*n^j}R$uH@<{nczOzNTGmJp_csH>|d!$LqkDv z!heP<r<Wu9XZNQ=&c(s0NbCN@!D<f-lAScZ;zyK&v6RC6_x<HZ%L8++TPHW7&4;jl zi<T5b(LPvvNgpQMR=eh9LBx71yAq|jIUP!%V8M_=+~g3?zVb6woYm6IEcMkRi^tS_ zyFJ#+W{OFETFH6kb)0*krCEK7?a7OLEe?a?ma<|&VCgPQJ|VuT8o!R&z7p&yaJA)= zUXj6(O4-B*hB<?LYEdfkSFf7Ak<o#iU*GKXm3BMTe0ehmwz4iH8iyfRo4OB8<nb}* z2~V(waD=~6KlgECIX_D5f;xW>()|r51+0<Trir0}#jBCom{A>V4DUa;nMp*AGf|L| z@>Eeof=wz^cU+rOcrI*fLo^&NX{>~9KGOZACts@S^>)48ohoVKua0$&jHkD0O6o%n z(~e)Sj;u>Ullx-3+$xp5>R?!qoFT{A*yOH3CjIgDa9R}kG*RoaZ^Xv)S6=UO44**U zT_=4~MaI{+EMRwObf1QX25uok5>A|ymG@(~1~h7TXy^d*=C@iva4$bNR*POwOK)y; zZ0wBd%Fb9AKvSk-0}TX(b!kkXso@n#eP?kf?(bG<YKv9u*7g&7J#(qK5z2vd<L;-P z^DXUMHNyd&j)cNZa;=M!J0~DeP!hGz#Kc5Y1f75TPUphA)|J4m#3nW=2+l`SQ`L0u znNwGz*hm<((aCr5g;-nbFZDIJxZr76V%`pG6jf7TV4%%VHX%lOIoQeRsTgsBh2ftm z@1VL9Cmp!Z!ft)`<6hY~jN;6U^U5g7)xir}`_p5a+|&$z5=?WmFdQbzt?0xom&DCv zIzs<8_N5d&c@;%P!Sb$)TE&|UV?f{RI$t+9ys<|ROZ`KR{oE;Wt$I&)Rn+i)*IFB4 zr7$=nE#c4A8`^V}{#ELyFp;U6+N!uS#oPNk&tJ#+U{imw<%cWqyY@lRN<Fq8>D}0% z(fX&ikaC177{2;@Mu9{rI>XVp6w*XJW5X)S4^*L1uN=$sbM-BA9K%4@cv042PO;pF zC(#<Rb>M+T1$X=#GhP%$m25>+)Z{y}A3|+lp7;0HT>ws*cF$|SI>3$!)&N(*rj#b` z>!$ywj(Ld=!9>X7z+0RXx}Z)E&@n)NgUxzVslc*U&6EVizvJz`O3Pa$tI3>bt@F?T z2-Ws;yt!q}`-uq#*!<kXBO@;_MdA_#mOeeH4-|_4Xp%-Ch3X7wJ6@)L^}goDKT|aY z2eh<1nDnSshJno8YJILZEVcn*VPiXjaPMNc0yo9foBGh3n!Z@U!RH9_mjY_c3=NrY zpl-2V6QC9C1!YyI+~9%;cNkvRs_h3BZ?=}VY9a@|H!yRYtp;kY*JIJD2F!XLbk9a@ zMF9jVroR%O3!#L6oOT}i*d*-jZ@|?#+pQaD3#&eXsEk=z?Z-1_)B4R~x_+yYAT2!P z-E~}j<4j=$4r=4#;))qF6lh(3s)Yx8Jh3=$Z_97W!o%s^Ag`^i3dk!s(}f_{3O)HZ zNkBW4rm%5B8bnnTvsc-6y$MEMp*Jb=6Mtt?ehhmk@u)+NrIiPFAUX)CVYZy2Eg8S$ ztLES7aYGv<Cq+lo_Hqk3>AZ}ML|1l}uP*d{>8DeBvAvJruh<I{{Y8<wiGBCktQnwt z8FStE(?zIBNq|RyrL3t_Ky+FVPb;D+q-^G<vLeqNMYs?^iZ$cTeojIV4>=H#wY|8w zVhR+}Mp(nb#C6upGi|+cAs5$Zig0tHpt|$5c<xq;o4&Efci(IYBOsYHS9jj~32fw4 zv;IqsLZ^z`p`)F~`BWanAn)kNq)Clj{S7+1UsMMS00sP83RJYcp(O<#A({DXhnE;R z_XPlsLFK#_{bGY!N;k@P!^Fgd21)@^nQ~H)e+_p}J3A%X>oqE=wql<}WD{i+YGq-) z1l{L%yI%7CU|xHag4V`lZa@0Iw7YT7N9FuJg3_d>9CUN;h$IoER^Vhf|Don>_T2_g za?WDRx4pHg0A2a!#fJmlS~wQ5eOXO%XJC|)l49a7>kX#AG(A0wlacWmZbB~4TT<7u z+d2NmF6sMQDvj~69>UPsLj#eB?x9zB;v@Yp$%Izv;KNYEqd`>|8)oP8XiK|hnnU2T zUjsM<21cZTlicD?cz0ajq|ca{nevHitzUJ_K4mt?EG)KHLLx<br33{<W4|A_Z{-{z zEsni)_ru@6K>qW(jMqpwRXPtb)6Rvgg;mlv8($ppRuv#d53%0%pGM)SC939ortLQ? z5O-G}U_l|BA5#J!!GO8$hYMPO_$+sOd%FxREv5CTBnUppCrt-CdQ8|)|2$ANw=ze* z=3}aowZQT5akOaC+;^7H*`Tt|o)Oy9*^voFU<P&A0EL!2SdY4;Kb<<V!p_)H<NQP> z<qi5;v&l7}So2=8<u9WDh&>7PWuk`ibBzk;joZrh+F?3{FMaqpSFi_qC-!0bC;G&x ze8zW@Jjdr^=x%lf1{y}z{fmt2m&v-hr6x0)!MBG)fgth|v+lVS+n8IA?WU@75kT!> z13ZdK&Qsb|Kovf!;<rJ*=>T59o_`$1uI}bWkZ>VpAXmVo4oQ;9(UH-s!s@mE&|Lew zqSmqwIQe9%aH+-s6j(rTI_D~yVUmd9Z!e`Qpy3pLY#<p<6TI7-40Vt1a7qJjVsZwC zI<E(`-v=C7zuh;T<H}6a_8r}rSJ55b&*BMfgQShP`StteUGQ(LaI-TE)O@0?t+4~A ziIEaiiP_lEQ#k`51y64*Q;-sM;6N7a)S-3=yW@|w9TJPh<cY)3h2z}c*Htmt-u!KB zZA+m6zOuG7>l*y;_SP83p(^0#wBm&(9Cv0E6f!r?d!Q0vBu3V4p}krBcvRV*!75P) zs=t&(#{6!jdhPl<GXAVRN&Bqcmuqy5TS%p(1W2`eeS~28)%O+`8_&5DDSRND3xlW# zo;PM^Yd`+Bnww9EQ)A0+HHkB-{Cht5{XRmv8ogGpA0A8Qn)K}gBn7)=mDOaMnR<-N zws6;*#F0T7N;sL?YV}%x;9=(Cmc~%Y=v#APXi@T|@M&cjp%<vNFLa72O>s;jUWvG} z!u<6*{;m0@hPSn~aN1suAAq91D~5L6cC1fjZP$0P(kU`JED2A;%~@Frwee^1pr(g9 zx{KDd3C8{uUg2zTX?vocj)4NQQ--cklb$rR>iXuU*)6id#WD4fPRvNR(9qDZszZ3m zD1QCqAPs{R9C=4g=D0Zd3W~ix!LZV?hqTA|dnJM<k|5_`Chx(Xa@W$t${L`jCeAZd z2(csap&+6FrE)@_*YoBzd+PygHlF<(<^hc3q@*utg9FvefGu#XqWQAW%Em?qk3n%G zqIdtRM`dnqE`F;?wabXa(0qLSXT8~oh@%Ifnv#;lge7ZCv(s+NVhxdRML$vJY+U4w zj)R9nQd}YmDZAx1f-RLr3*Ld0(#b{8C7yi{z|-pJ91L`gJG`F&+h6}NjlHb*1!KOv zvH~tzj^suL+2WCO1Xp%z^0SBmv<5AJ4!?W-D7gVG-tYPGtP<8|6{Hlp<B80}!_yX) zPc;OZ&H!TNNKvLkUi>ImdV**QvH$%23->4NRZd=R|8OO)UW{Q^b1wJttTDBY?CC*$ znytUGHkFJCo=nPB)$1T@Yub!&q)w}La*O~<pkG4aLCbglTMu);yEJHS&bzh4CaY5G zl3>qE|8A>N|0DA0LIAo!rNk8bFBn8uWhL~x&C^EWIi#!+N^q?_p`XMj_2a`N7Y44j zwl=J4QS2BLP%$AQ7?IH+BUCRfBv<c_(&hl&3F6bbP=8h}+ju9abXgEx3t%bj?DBLx zSHFK-G4+1?4H`TN-K!%Bv_*E%{Y?nydaAZuPmkl97q_t=BkdThXc-)dxD@q}k7jTT z{5|wCH?nv82?YhE&KBlRFG~2%${}UDXcw2-5tu{x@Ep7~WPIPmp~mn|G{$3Z_KVM~ zd19PfqBpNwR>H^*tQ!UIAb~A}^~<p|tjT*U1e)PYmlkyg!?o$-{Q>!ss9+6wl&06L zs&muqu*lW}ge9z`JENbqyBgKW;kcw2=iHzTbVNB-3&s(c=ESK4MO&8gIHN42>?!xD z$84)Oa9etEx_gH0bH&I0wUyuKv~*3oqmk%U4CJ~mPEP=781Brz7)t*Lvx5ST5-?0< zuWqDktMw~04~KYO5qj<jL#ZZ@8SFbI5l}`UvDcm?_M2+*v11{fAa~#u^j1aHZEm2s zPj3P%7OyGlAZ$>$77@3n=Yn!x{N+9O;!!|uk6+V=cUh#}bm-I3k?1dBk~Z^m<L2?d z+*kCI1H(`n$78-S2CxU%o`gwGFzGubNq{oJVHIGA^$qUxG2NpAA#8F@<|C$97eih$ z>3XAi@}*uZ$?dy+$&pi`%Ii=3b~3gvUg~$q7Bk6?I`D@Eb69~asVC%vH06Ptc)>3? zSaYdDT_H;0Ukht(reY`j$ARaF0KAqrF{sTn$T?unuDcQ#uBwMPBsOw0?nA4-DYk)Q ztgmh<GNd%8Tv$Wa^-GJW9E-cb{=mrs6UH-ino|@XSt-^dqM!@jvQ1AoWC_%p9)Ebp zcYyzO1CP$Y;ONuDiAy?uN#EUvOypNeIJ<$)Z8i!}j9mDIzstxc>`RlnG)KWMg-F}N z-KiZVn8bk!zZR-j0zq<uL#4C5#yL<lTzqMXna*Prkz@FcSr0BuCAQ8&OA8+*s^wnb z!CMgRgaej!!-R@t_V+>eUCZua)1wB_kI5@zoV?tzEJ;VwdxlC&gNvWB5voN=>qq9w z`-vGMlm&DKiV|}9Hd+I_%9U#n!43Z*qV#l>3h%ZQKM=1DuHXIkqIG2N$DYw^f0+BO zS^4T00BHrag*TJHZDDDNk-?}4vNP<Tm;YHtJFayvf{AAwNCP^`3>OK2Flf|Zu4l4D zPsLe^%OA;xHs3&^kRI$Gxn|Xyj{??47=U*m!|11XdTb9rXR-b3Noi(<0~v7}I}1;6 zEO;Xj22MPG)ty211JWDY+K)=W4<aR-j+*iU{kHDIq{_(P!agy(w1j%NM}{S^cv`DC z)7~X0D}T{kuF_k-?V#e6la+;YYpU#c$9}v7>QjxFC;dr-pWr^9zSZODtelFFhVW|0 zGI#ahmNIm;`D-9;y3K<dC<Ry>7>wZJ%md$}nH0s+++Ub*m#JuDX}Bb<hdY$+>hBS- zwaeWjo?R-<`5Ba^1|yIkzA-L$w<*m5Vaas4Pm9_Hj%)|C7XLim)bHP-fqg6=o(Lzw zR=b-$Jr-QbKUYmm(+)boAna5_U1pMQjrxNVHx2`d_Ysci#t25uzbk2OvoYAq&VrZi z4z}>(F<Z#j(W)4rZ+y;c1rc#}wsdCM{lyFrsdhsNBRjjg<SDYaxS*u8+Q)$;Hm%6t zyz64Y*~aaioS7v;W=eAh7S7Mp8Jte1(2PpKzu4*%5|AvQX1ky374)X<2HhoofZ;p* zltHAxJWN1>>FC$xj2hhx)GdtIxnEyf@&wR70tD&6UH(is>dId{2)uT?^iofvmF4A< z!F_mR!T5Zy2`!4j+)vlkq@uT+`4h#qQH)ijKgn?dGEND=y#Wnogd;a-t+J*cZu$7J zIlhh4(MyX%dcjAMTEiRS6qK3@k;vuJdIT77km)`uj^q9r22%N`e71294wP%JuKIsX zMe=AA=nF*PevXK?r5l-#GTuZ%t7~4K5>XoLrJKa9IjiW;EEn7L|JutGij|uZ^706i z?@q?SRVK8D5^R8hum5T8v?N2XxDTt*;nYL0VyId+^}=X~$O24V|LDy?xkSklKJ{Pp z*Zlwp6*74a48e#I;!Id>gM^;0SFASrUjHBBpqn5m2iHI0Ea0D!{4-}uTUQ%PJ8MQG z6I+k}QLsh-$=JUP&6yZ%Jq(?k3_Xnv9v@ACKm>>wfQ&eZPJoQW|LrJ<9k7x_1~2mx zRhkbL<v~jI0;Le<BxfdRq3PslCglL5Kmz@@aQA;aFZ2Ju^BUSq_ZLqA0fk7y0Ac?Z zUK@L3YZFUDb0<UF|LC88do8^;#ha);ef_}ePICDsA~F5~UBz6B*f!2;G?M<?XEHH+ z6eJVf2Lr(ZT0YqNd}*)71!{bRKq)cF&Wn^o*^aHdxVYH(=>GZez@&NcOM-BGe4)2h z-&X##K#LEyxPPhDbZb7e``Z2L_i@LF|GH)CicIEZ6p>5KuhxD3DWWQY_7TqCr3HAn zfA6+4^mzOGcwCb2P(36c`s~$yg%jb7Bc8{VX}`OB-(>fS-z@`P>`?%{y>Qo`wZ5+E z>~yNCo3^`!os@%r>|Y{_-7brXp6W#WvBElhqqMfS6tg@t-QU=rq6gcb{iVO!?|#EF ze$t5`l^h5RpR>VzKC<j=NYsBAx}8!ELg6UB=YcO|zCiKY554Z&@?{#(Me1waaLJ0d z5B4I$Hnt)H1jvL=+P!mo`uXz3Zau9DeHGaz2X+qE7dDfL9(N%Ue^%ou)~{Ck%2d?$ zYSYa;a_=r#{ZnR82pJn~XSMsgzx5wQJ@ZFY7OxCG1Cf9gSJH&@@(GB8Hk1)W80DO` zpsvjfk-plz9e&v=h?mArVX2nKOKYu#)daX@AxK~kS?s*rXdCiD&j%67rX;L52ByKb zNvs><%^~&LUj0<Tv-zrTtGVgCYU5&Ye5<$4|C2}%S3#g}YJ$Opjw$6j;COUu86NIv zm%g|qK{NDV`C2)OX;R0FcX!4u6+xXsI9^x3wSOp#T|bawkiXEbf~i;^Yki~N(m4H? zI%keHNqNNnmah9LN?Z~M;UF%I$1gF-e;y53@2{5}cCHuWX0b28g-adqt5R|yG;vKt z;$}#>(!64Ox`c2Uq&%GdEM7KG7Ul(;t>iHZe#0AlL9%hk)(H`f$}%3FYya#Zt{eBn z_A)o5EESI-$-z`Sa{EnxQpr&B&bi*rI^*|tu2_M7vc}!W&vT<w)-t!~a{18syF4@9 z*x4xqtQCe=TXnUY;YT3hwAo!mHq~Uk8=|=atg+IJH`}V%%hxENH$XPFF%yC%??CjX z>z2x00*{+z5f0S41L9VEC-6|2&DYvo%?+|FFw#0}&(b=19q2bXeyMZ9kEduf-#p(6 zoH!EfRfpegv&8{H%AFj}XDZa9W`8NF-G8(L@GtB4p8S&dbH&e>A$uBMt*wcp^P(E8 zUr0}w?s}&Ik3+W`xL>Ot%+;tUsVE5pWZC&4jgTa&0LoqN9JSmyfz7`j&zW^JJhUf_ zV2LLrB9b=K&Jo{#`3H6-KwrJNuuuFE_CE&OZwL|Y)_T#tznS>H9X-ArZu^ICmiFfm zA(!@F00=*C4oC>QpIm(2TwxsX9lH+Sr`lLQd+Gacw|joCU+eSUT(9~2Fa7X8+<XyX zyFYArh~YGro-L66C;ahvuOH<TgW3Cc!?&k|i1J|)<-<$+fjmCWJfElWXT26~{d@x* z7Y-rgock}>)2CO%Mqju2FHESI6yN=?tYZszK33p*c0i1f0Qh)`;i>(>x#7e7F!SU> zem-mj2~@W0Y~q*?u)}u%!6#>r`J=-vkVElH_3(}EvYm&5eZ1P?Yy1Aw(Vp@5$Is9W z)Q^Ik&)4BTRepUup=|iE&jcT{hW+;2=@N=G2(H$_<muas@hq!ezgYg@2Lj!5GpT(e zvjW2!?6BsL-?IoM7EO0g-#G5Bv>R~M30<@hJ>j5&rS1cNOmVh>(}~#5hysjQlaI)R zK)LY<!wwkr!I6UGU5(!t@Pw7>v%ng1B8xxj>tS#?stv}Ujh{_*!)F|`hZQpKnad!J zR>tk~&wG&tL^kh{_3N?-(yX|PiVZ>Yo^eEHRIxh(+jgHNOEzgAGGg<3w&BX&=Wc$4 zp*~U)4%BE&3!_3rXTF$3wfP1HMO=hps@aCg-*#Ud9r8U#(9{S0_~7SkkMl6Gk;KNb z*75RqHLcD&{<r|aXl1!QPG3SwO~W07_L{cIQ_TWDEC{`*SW>0e5ieLGOhu<0GBEeV ziepH|NCRS%4TSL*Asou^_U|)J<`#gM(3rjJQTZSl&r4Ax)SM%q+^!fF&8nyZC9*OJ zVvu7(0e;--FzhI-N1!C~0+qmiCp_a9n>Qh;(1DAnT2^EYELaj|-iIaLtO3ptLILe7 zbU(ImIlwPH<|~AID!-TPwg}F)mpQRs13sSc3po$lD(fvCi-b6}co1+vueNK0SFo6g z2|?&fw)M{R_Amvi_rc2eX3JsP$_16U2Ss?d164MCeh_xk3+6k4bed!pSK*KXrUG<M zA~Uat^wbq|cspQ>LLwR4oU%m3NsYXmW)msrPuXmdQm-EJ1m?EnW6`4T_dzYZ>~vB( z6WG65?6`N+ARMxmI+Ha;F~WlbYz|Y|qERD|Vfe+oj&dHZ4Vb)YN@vaxTeq3dF3o5y z?$mC908C%keI0Gjh@B`bby1rNZ2!(KYj<>G>h2W!Bi<|ouc|kt(n6TzZIfNtM!OSL z+v=I$Qg{6eA!o9TTZS^A?sqvz_6Vns36aw`5@mm>iv5xPNV7=@PCh*2E&}3Yz9oKm zaU!7}UumYl`#Cu(fRyWH?{u3EkNHFA{mepaaWwNK+n@Eunf=+mM>9j$)O|Vfpl=@X ze92vpZD*rjM87WSZ(vt63fG2s1Qvt5_`-q|?01`A{IjV%pj4%>Xs_D^++V(RJ|D~V zK}mz+lGnm{Me*~y|I!g<+!ej`FY@U_;KC`sdFMgp_ph6k7D<v(&kQ};FC_+;1MV{Q zP}lo;#NjY*<!Wu}0&wHD+X!>9#O$fj(es5OR2n&<AB^cT>gr~VMR$W^X(WljPNleZ zI6uH`(*pgz%Cs{QCtsW(6kRMfTwX3`pKK5`2RQL!oSDmsx+Tp)a%ve7Gc%TE>55~7 zm|Y7oX%(D?r5Bq_1THu;YwBbXRqUz7Z9)X&*&_wQ_`i&f1=qmS6@P4N*evX{xuFn* zHX}SwfIILuyxQaG!}HrU%RMn3;Y4;Br&V+*6xB9k3p$)2o^hTSjZbe3;B5oVVE+Y- z7dOl_VkG$)==&#~X=jkn>0D570J9%_srZ#x_>!;g<)9CgS(c4-@K1nH(Gv>t8B$4g z7e(*dPS?n(?{zWjM*RHSSc-t4bPfCHqIO+@6S#(S`;z-KfyVUnc*hb`=Ja)gST6#E z{j324)(pxc8LikA#;@h!E0(*WM~EDU2NhdEz)BzDp*3TTYZ0D|#L>W*T!XU1o;hM4 zp)Q|Tu?!u~szU4`RW5lS3&j2#Lqrf8thjVqzu?>ZtheY*zsTHz-*=cFN|PS9EclIR z0o7U0BW1*Aeo9B(k#rAGOQx8CFhFW3#Dep#%#i`)W8Ibyqvs>M>$iGpDpNb~${F4j zCeR7dXRN)HeO5K?racZsF_B1+Q5duEY-83mW68u#L_tRI#*W`jFExs9GEi&+AuTb= z-6HaPCPPcnNoZw$gZ^q{P<E1tYg(9vvWpD1UD_sEkcG=-d5c=Qqz?XJnPjmj3xU;V zb(S|lJNiz!zjIjjE2agvPg)T$1mf}uQJ$DF*@LqU!b$?j-xX+K(JSSdNJJC;^891W zVz4DcD2Sx+O{?G1rK+Rd?e(g{zzH>CnqN0gPZ>hUl3o(o=mxX;-uPa{yA@j0@4c%@ z+=HYeh>Ui<j-LY~(4Sufz0{Z?e}-0|H&Sjbt$$((cRnmOy=%<)j*;^GiN47Or@|J< zj-tE;sZ7Klom))9Pc}qm4~;05Ph&T8z&j^u#^9(f-?z8whIMW^nHSBGbM(0262%p6 z0r#Y1VPcf5dp#Sk3|R3Z7efG4=3YLWH)?vg{`7BS4pHG>Oz*WWM;sVQtrok6!))G% zZeU&wFd6-u)(ZE$4eHFNzWd>vBa!>M&VR`b=J=$zx*>6Tvc3A}3c$b9FPJmM%FkMa zLZGkaz8nwu19px>6$mTw9h$MaW7gXUN{-QOovdN3D?TfNRairZ%V~Vu8bXlOH~2HL z`1)Rku>H94S<{=TB<P=*pN)hRVQ^oNk#92LXMOGA5a8N|0?nDs<O-oe4S<oxiJ7;> z;eD7B9(1>jwubQhYWDgguMUCE*^zXRm%#0sTzBQ5jpH)zce^#uPdk6lE0!<R#)Ivu zON&TX83E$_5Rz<8LM;&JKatC3b2&Ev-xWNLhLmLNWtosU-Tb-v$kcDsM6>yK*-UyW zR~3yqEBx?!d}N_0$ce9yDb|d&p2rs+ys#ujvPS$b1f6r|9&-RHPAQ*qpU{!dM_1rp zknS<c{sjr&Xr?roh$mA^;fv&k3nC-7A)ibBEJ?nT7O(tQNur*YXlOk*%J3~RktNr8 zP?Tz&jI4MNL~1g+l?t0U6BWbk{4z-vf7~r_Yz~=)P0&rTdOChhmIsUH!TsyUvQX%Q zt?&T$xVSLg{0w~LLp*281+OjAx3E9;@;-#n7m|XRTTWd>8Wc)!T~s^<R+1)jr(6Be zH(%1me<S!~`(8)^LOS@+qPDE+@DfX!&jOJWepyE7%<U9qQRy_2hOs07+0^=_NeUCH z5lKmIxTFQTN0bBI#F7tui1vX%HS=b+VY?;o9~KG*(xO`@2*?QJ*AD;fbY2^a>;rg5 zPVW+1s1atQjrj-)YjSc;zllJZ*pACQc;%8~Q$K=AIbISX5s+DmOnMcLuv<llZod2C zSB40a@EW#oA)$6NxSSjH9tX>CczGT+5jb_hgGC*Zd<}G!Pwu2+k@7jZxqBiXk-#3J z<42b}-J{C!e$sOyU(CA>Ag$-&KmGf8MPj%+QeI#u5QAJ|xPy^B%aL)7a)2e|MIVh< zpo*ZK4>&1r;EcH*i=JB|?ylFMQD4Eo*@C~MSzxh`Qi^NR8|QoG^{_~JF0HM65yH(l z@nX%~eP?R>2SbF5j<{Hi_C47kRPI;5rLZ_j257SZpg%c33?N@t2b5w>I5&TEA0_$w zKj()Xy@E#0Shxb~1jsaEDZ?VzUaWN--PS>9lHt}yXlUCmI9n&Bi~ZlFd@@F^h#J!h zn0kbUa|?orrqN5X)(T)@`d<R*+jd3#%mrCb%|-Dh=K6EPiJtnu$FKcou*UIMmpgni zTJ{``wu}rZx>#o954JD=RPcdkh!+{X4~Q#zni5QiYs41P>CiqGh^?B!Wns3(@Lp<& zJ`<#C@{)O-cC(T@VV2YX*%o{mV>CnJ5j|HM^3$vVzvE&mAQ{sZZVHJDS?9b<hUU_< zRM<CwA2LSBYhZ!C`z1LX2<GsKfZ*i7NoPXZiq59nAbq;;t22{4YD`{%p)*A1tt}#L zPODFsE$kR2qm7Q`0h|m$%uHYz_(Xb&Y|*lXFvRxI6H7=n<DPK^C~yudp=&G$vMu|@ z;v8O@P^h#dvWq`WZr?R@9Uz`R&H)cYMG1-x!)U?PJG8JO8wrs#jTP5fqzK&OZp#o+ zQ*eQ>hN$;LnlUPAAI1yUOaohEt=T{}Hkcx#Dmh{8iUq!@AdrOvlnONPBu1!Ps`%-I z&R}zl1WC-EpuM5VBco_1Gd@^mCBxVc8@GL2Q<&F)<#NmHYx+xyKxs@>#}jp)t|DT~ z2W_0$uq3X=g@oi)kM`8gG{ia|KW+aQNnVCKVtFmG#arWr6|yiuNA7|m<2i5cR|d8C zxJ;Nu(PA#y2a(Nqp{@qb^aE*rjc10>CdIo{+kPXd4Df*qZMS0Go@Ro7Gm%#r{4DXm z6gm1xEaF?R3Ow+)(TSoYireh&g(7aIFKCBFI_5^B3?v40^TFp5*Bvm4a@fUJ?T7p| z`zdAt7Q+RW58&=O^Vr>>Onix%A6HAy@orGszF0^_VQ_<)i4Utd(6k#FWHyO0rOzTs zV~6D?`E?k;C(6UnFo(m7Jjb)U*}^@io4{fhUNxN5ODe>aM&PuALqB%kts|U}x~`I6 z^Cl(>r&t<;iZ7Rx>Kq!X=!9*SdjMnJ&1H%saA1gNk4393MRHC7Xdz*(BJs#`QA0=1 zgna$uKTVr1_KiRp6ZASU|2<hOoq2F@5JUP<&gSr2BW4Z%m6O?H1d9%JQ*C{GvWYT$ zqzomPznh}4h3!xD^jZ5(E8;T>Q_`?I)QeGrAeYIa&kC{Ig@`hun@!uy4w$4!SWUVT zJ2W<I<fC0W(hQqyxTX(gOvJ{}R!D>h+%U9>aX)UN!@UykpH7}qvOM7)&pb;VjZBAg z(iqaVq5$0Abkwi34#p^7OeQq675fuV_6{zKZMrzIX~2$h5m^}HIBA=9L;zI$J?)Pd zN2b1@{?}dsu=T4@z*Evz=!E-J4spmU=@~4{Y$;--L~8?iPCL~?ZVAvU>|>Y|hLXg2 z(AOz*5Ugvyx%(7iz$>@Ox`<u7KVgi=scd*t>Xsi$DQ&iPwaVM1)+tL?YNuoGBWDD| zI4-kQx@m=!6*=$b#?SsX;`pPP*!;rBNPdz>G#B+%iH|jt1Gs(AJBJL$EzhwHOb&qx zVR;?;Fj31q!~xb55(JS6tkMYIMv7&ZJm7T=(vw1aT*X(MA3R`Ff6FUCFXH322zo@x zan=%SrhT`MOGL2#`dMM3<W~999}`iCqpMWu4>1(9g@n!3oC~=0!>4X%PiRpe^OTXA zz=?z!f41WpID}q}8or1&w;vabogLIpBEg^SPrpcdG`;eOn<<aPidZadElr6zQh~NY z5BUvg@%l>R;=MXaO>@KRK041(8OVn0bBR#aW(qO`iUOb9Z3rYpEK*HDPbj3#p667s z@U^&9eDbG#?K9FZsmOzA1#GiF$$O4bvn9y^gm&soj?legS1o-8BOp_}fQ;;FM|Roc zn9|C0#RY6Tnh*qkx){i@<}uXd=oG)3*sq>@CCa~_Xr2?O2jY9}S~iH%;kwYLAhN*2 zw-C)5-!2*9g5RO36T&S8P3EDPC)qG-b72?jn^F5&48LYMbgecnyDN8FxK?VMJP4>o z1IOJXR80UWl@Ze|gau1HYkwwC3*3^a*`Y5E9?#^MI=}V;OIKtPK985H)E`oAe4w_j zK_)~TlZq6yC&8)X<VjiC01d1gn^6-{_B1r<B(hp<t+g5q!sRC&XT{Z>F?v7Kk!y|E zzc>_NObJv4lCGC(ilk2YVl&n=znmH~7K?NV@Ts9XAF8#)^-O<>OVpmbIz=CNJ@I*H zd{!gX5a^=@Gnx$_kq+&-<vBd$0}#G_+)ovH4xryKf#JGzzs9*pe*7NZ89x`EipKl@ zePz_F6~<nS+|(ZkjB}hC6aHjA^0ukwzF^7u*ylWP_vzyMHy!;JZL?T_(VVFU*g3HE z0=}Eq)>1@S8FpAbr4In<<0@b5;{DM&gj+gMJmVImr^6?3Eh_${v-TUQX_w_IMU)s< z%T~8t;PG`li1o{ISXeV^HIh@p9$iCx^Z=g=Oz3$9%qgV>3U;I(j$aiGbh+w{`~ZEI zY?WMm8wAsB6~SN>!**fRlrADt(A@ZxhNH<~v>P_ag#@4lM`Q!gwa{eL-TlJJL5pVG z!~_y~$Ilhw{k;o;*+5RywKbO*A78n(#Gq~D!JU%n)&W1CRI~<G#=(jKfrj~WRwj52 z-&d1~!Rsgk&V1|b`Z33};kh1>qSj}t#&$W~xNAs~*L>3lLLE7$d3?=z+g2iP?PM*l zaFG=-7X*bf)W<Y8Lp<tT${n=sjTFzup`Zn4E?^~g4_bYpY&(!PyqTbAR=U?S4VDO8 zhil673Z><DmR6W8X|-m9Eya~ZI;(m;!S4Br1AttZWdxHCw)$K)rMmx!|0LqZ80N7P zPL<2AVG%K5kaei<B?ul7fvP8y2}yd8D-z0;^Li56bE|B7nH(x2WvUJ<+4mKF!tnZN z{1rZZoa8*~Qw9ubBmoyXop}!%-+w>IT51GoU6HLrYyQEINes-5$-``)9JC{#)oF08 z1=8j$8MK3yi*=tTuTDKIQ?@B>5k*O&@~5D(A^_B$gZ7I-DqI#3b8y^YAOCTX2Zq-y zqhr}TRjtL}+*uO0wBy2v`6G$g@od3W4<D_`FPe{LZ_z>Xu18U;LFo>DX|mT1gq+_l zSK#GM)U9Znco(ft)vHk<^aE=e&~sDp69c@Xh(;XNCvUs(469MjLe|iz_^=yUS360E zwt*M+DXf|Cz`Yq&s@0%aRCg@g3VtVs8TDE`IU-DEY;R7~XRELzSa!-(dPJ+LO*+!z zZ)Z>!;a?65o;n6b)qw>m*Ww7OQ2IvjRl7|g0tl^49>mhVb2;OUjLUAJwJUjnrQT8D z;lIOd;&1tG4~HI)IUzYQ*Loc&tY~cQJN~x7b+Ee9N~O<cXQKAyxv9+S*hP_1fdUm@ zLfaVLICE$jz%E9tkvE5vQ}6_~&_k{kwz+uIL^D&Eo6E|eoOGgtrnEg`B*}+f;EX+t zJ)c7~oYoFl(a@-MrfP3neV=vx)3#l{noyD)@k>{p8L`u#W;H?v!o79uQW4#JqLr3g zZK-5jiw~DBmj{aouO@N{k1J*rl@3;u?`Ps?<MpH;%r?8T)LbtOEMEVoSQE^w`8lVR zk&Q%T^)-aEj)RJ`j-lTX93yRJ44qzYN>ssaLU|Hz%!eKvqgDC-%qVQYj~@TZ1D^~r z*ea~Frc1DMRGlC%W**l89%f*XA+8`;i>6!iPKrs+&P>tKccl9y6}Q&WqEeWRzkSgZ zSVE-MpB}fcG3zr=hZEdRinD1Aq7rMv6<_KTg6mj!TihQTuJPC6A3gm7aJcJMU@J`C z3K!sls1-GfT=_M*5r|98&T_rpB5G}TuG1tQjs@#ISTRDju!TAVvR!F?>&-!&*pCHn zIDBCCRPn*x6c~((=XVGkQM|B7b~=rK(WQA$Wny%D9P3!i4Oo@rv!F`pXOF--7UZ5V zmW_R_?6p$P$_7DGfrk6TY25e&>Y^iBAKj>-q>pphfrM!d*o5x1DAoDD^00!O2`d{M z$`|%^i`m$@ORYpS&d2Q36_cr4_vMD4U<8y}nnvRGN!;LJlj|vHZ-z`qW4saz)YRpV z*TnazRz|ALj3VdOgN%y+YkVlbb4UWa-}6Ge*8$Q9;*FpufR#3&na~v=N4ub=MklB( z)Ts<L%;(AlTYP+AS}We;V1TM1vfT*<*%6*YHzAnIe&uT0crcJOi{xw#e%+FlS7J=t z^IhfJnnzl164z4PV$9=wZ9fEZGi0ZRsS;GkN0FF3on<kN_%ZZN|B$aXOHJhfd=Of~ z@XmtmQ4JC&`EQhHcF4i&zP?!;gM<M~XKbE914a-LN96S(9E0Kxg~HGR{nU%O5OwGx zh?Bu8GBf0Jw?9=je-?3i2O!}5)vs9|glj~im${{t2wl}nCosN>YT1IJdtRM;GSvv8 z4-$-}chE>~XX-(~M{V=K9|8Ham_m=*z%3~fIwq&pMB|}wBoT}Yzla#O6A+jdz&L_G zmEZ2oe%Y=ed73${7wKSiD-7*<F^21v5h~3-9QaRm-VEl3E%rWacphz09{`~rN@9z9 z@>ql`A@I%T3q^dr=^QnWi_wADgnQw7&)}BR=t?dj*Ub;ASFcNjrmO<epCGxKoJSL! zFwMXBYcb_INW6+cdqk_=r1ruO(I%%%3|c%6!+{s7+>*DD8m+Ib&is#fZu-@5(A20b zjDKxJ=)Dok4>>AXm|Fk1m;5etADvhM<?G0b?IGLrl@wm!Qp_a}SBV(Q4{jt>m!bZm zX*t;Y^_S!>^JqYN-<d@wfUevDp2WodN61JJ7DI6^Cs6)LAE=0$Om59z;Bjvi!)Jx+ zO2{*u<BIre<!D_&MH#p9+s014>PH|X7Zrj)r%BoWe(Yt8cne13=Z*ez+3GXc{bwio zv*G(v442EP@G&r*&0n03mm}`1A7x-?d#l7x-2U$5vFRJ=I^Mb$oWV%cdR;PrWPObQ z4_je|GH@;92eO5ZQ_4CP`ST~H_~iH5TC<uJ`um;H#Ye4J{?M`kYGRMa$stEz?nf~f z_N9b@z36=Dk+`v6HlcY&=MwIM|8f84(HHpJe(Qa8^elDj^Z1Y2%0d~78+`2hz`vju zN0hMzyt>~#zw6YQMPxP46Y5(&y0qCIt9z?+>Z~o>s^e?4aW}~NL+-Q~|J{g-J+aLQ ztJEADXjuS-=g0bc5qFu<X1x(thA6ud3TXk;f6dk1Wy+ORnc2nd04L`zML4>(qB^sv ziy3Q@W$_DFPFpP4vb!xRjHx#8LL&?&xDb*FOL)*ApzMUF?%D!$Dewi?g6{D<uv#mu z7Mte1pi51Fna%idg$?deaZPq<B|6fw+X~nEqJQ%&;luATlyhxnh79lMq)gO{n{WoN zBFoJBSa!wF90t8LbIIUy58&l4)QsDC*pf(%&F1xebuuZ^G_$f>w7tq&(W*0aGhd-$ zEUbyW){Urf_+2?)n!}%$F`QI{t)(NgjuzoiV15A_7q>posG4RcwMJ`NPJP>t;+kPz zSNZ#`WMiU!Z(C8Hmh1GgwdmXiR1#lw8yv~<;?RjGDrkv0LYxw*7Gwxt7tKx;I5zC^ zSP(VT*?8U~3~qz%gOWvwjWw@q(-Qpg4FyYC#sE&O8H|J-b@=4>&BLHonjliR=Jsh3 zkpQ2ZG5ZqQD4ALrwd~#m^=Rrb0AeYo3s2T%*yE5ap~#O#u6frIMeY~Y1idBbjnR)C zUG+vJ@WAXE5+sw1_`tmkheyuR4Yi68A>$wI#k@YYcd+dCPyr~s>wxy}*Hb+EpbTFr z+V91T<YUUPji+1lE{?QAS`ryv;Mo*&I{y4`lhDw0T5>KB!?KUAi^cIw0S$1KJyGxW z0L=AvOfWscW%Rv|o%LxC?+K{HQlWGd4|OtI=Ak$ob3e$+gmX<Dr#$6*jJfR1jMFNO z+!VMK!@P~C7Rx|I(G%+W1Y+fDCWS0Y&qfwPkslm$J-7Gj3W#OdIU8@dO6CBz@Iteo z{P`y0%T)-a(S;JLaju+2rq7<Tru8DF-_A@J@q!HF3DE*|ul*Q|j*HY69@p9zrA$$M zWkXaC%3iwwa^}7>FrW6rwB)k2`)GCloV>4P``SK~xF)sT7uc1H>R&y$dS8w{^R{VM z;QDP%(K-Wfd}Kzosk&!EClBz;Fie~kG1^Ev2x6G^D8eb^5~bsrOI&3-G2G+>!bm&~ z_cTl^MPBM+p;Is*E<zVJ_@H6A#)4g8k&@Y7Z9z;q^WFo|F6<!)k^D`>FIU0pg5q0> z-ft<Ckx1UMEL*Ro2>VYY$s%G6=ScA6xazx_lPU4#^+Jkci<iPwJmU*<qcrPS?~~m; zqjU9S_SsC7l6x}s^M<px6bz|+^yuvIoIQV)h;W&A%NV=p1yK^jQ+z;O(FIMKWlRr` zH^Z|ADi%T8(^m9Ndj?-KZcISaUusd@I!KOn#=>Re94trO1$O(cl$EtRs~zUo#Z!kV zt&4^?O~tAy4@D?~#LHK-QzOMpsBMeXz4~%N=rA~1TZHQnL7+fX<r_w{9VFyOZSwde zQdu1I`k<py%YvatT}-UzaX8AmnCLgMR6Nnob)owZAvemg<33KY(W9QVCAs_GK31Pz zuN`Ch`e^+6K|USmuvdOxGmp^5+0FFg<cZ}*qL-+oYstPWjCzM6MS$$5uH6-zym&Ib zEQoc(a_Us_t;o+Aj$vvB)tgf;G)~IpY*Ck&^MOAzJ=@zwZTdXOWIE;sJARn$imwF& znV9hb70KJP-49nsyJM=Cd_vThm*<5LMfl$)L0R_nl$D3iOnGU+lXUpW&zt>izrM3; z8{`~K!u`ID4GDMT>W)_KP`7ot6hl6Enq1>*Qys*dU9^gxCJxcKIEWH8%j_v)?`wxA zO@dl}6=)CV!lo@Glxxy{ZylNz5-7;Cca#V#4qZGYyAwAh#A&DhC=p017@Juy!WMUU zA%&_->OC&kJSPJv81YprEChFd7WlCHCzVuxeoA`3Rqk6Zn{$xY2o`QJiC^mEW(%dJ zS<O_duy$+$*`^q_6EHovqv^mxyX`0uWO?Sx6ZPsBZ07o7QYyeMAfD4G07`t<=si{& zG3z?QHE@9|eQ^znJ##Rt_s?G+9^e>=Ki6T+1*T?I5O`;Ty7!9pF9*%zAIjdWe#KEc z&EcQrO|GFb$jDDASy2^B4Lt~Ca^Brd%qO-vN^I0gO07m6LA|cvznZL<gVN8KZ`_Gp z!H@bcZDx3Cnii8I_hBSUOYUy%w)o#3Lc1TPrVh`$Rn;bEAgX^%vNl*T0y7#(RJ|0q zpmEnxoT6lpwjlhSAl3?JPH^19>6x<2)4gQk&>9!NEMWU%fsb1oyl7eMYSR)IyV|(G z^FKHKHOti&Q?b~<+{9c~xoTLQUpAD~X|Z{%$qIC@8ruD*uaITKe|kffE{R|M&oIXS z*C2P~R`|953w=O>zg)IMFB}2y@|E{NHbO#0G*-^zFf8;B&JFIois@AS1E;GQwppaB zSq4vYDdTNjPOQ}?U5$>GXG~W!)}F351TCYdR5eB>*}pQ9NQM=fezVo)`Eb+QV6it; z6V)&-@~g5p>1wsk%cZMPIk+Hgi|D_Nd^PK{%va+jVp-z6jI}0Wi4yzQn22SGa@4vc zVo4<Fb-zKgnTX{|V_8t<VcA41O$f!8mWV~z%@hPV`b*b&jb_gKkSy6@E<GoN!S0gH zj9oY(j9PwU(S)$d5>|lt9FoE0AWy2gM~A#-0y$1>c0b9?=3aB<EXiCslHX%>&F>LU zSCSvKpzFJOSq__YCYjZHCYc;F>`Il(AVQ|(7ukEynNx>l#%?scs`*Og)LGqf0IjY$ zfc=#(0<|fG3lB0cd1|EAHE$|x$&RMHyV(UsY}k<Yui~psREoUTb~o#sAlHq#hmMwK zH20WmH}~{vi(!-|TG$lBe}U1geS`}Wb$i3#_^&Y6S6*rHH&hH(m>c<ZZnQC6)jKa` zxH1<vT-DSN#&y1*xY>$oudC=Fwy03f^0k#j1#6zIwi2xb6)6n?Ww@#s>QsHoDG0-r z*07~?G(n@)V`!TA_gB?QT@@4=vMM~bWU4t4>AEx#39F(2iUgAPy6wUUFXl_K3sXeT zTDvvcg#k6a*@Xr5VJotI_X1sdj%uAI-P5rw(5IHQ3!9q)T@C9)t$N_IR_Fq<Ub#V5 zr#T*$tI##aT?LZQ!7AIU4McEvb;AULS=@?DHZu3l5ZP{l`SyQJj#Nc-B55r!-~KO+ zlB$eO#GVD_OO3u;x~Q3m{YklXmNLN-0HtlwysOLCP>7vKXWf=>MHX0*aN9($^nBN2 zfj#oEtt)>y`9cnn=6&Omf-hAZ8$fiOqeD%B0VMi3wp2|4y}gyoMi_>(0IaEe<0Z+H zKyyCxrd#_nP6iMLzYGoKjTpd%vWIar&LM0Lx*+Py%&O*{<xAk+#=6D;q22~Vw`oXW zUgg9!J_kap8>(_|_2uu2A-<ya<zFz~t){{!8J<F=c?~2h(}0!IFy?KFXw}BN&7pZo z7elEEwhz~)mHXY4O!wMr3TBHX3LXVF<u4eew$URkYmS4ZRRiv!aB;+sYP&L6b=#-f z{IG222@W{KT1(tZbDzQ<!sjUQGk<T60nre|B_iLRdiT6!r+LQS#oKllsf<1B`H8ak ziGN?-1wR&=hffco17;a$SMPSqXgemx_eM%viWz`JP8-?>XF<fcHNDo#dz5Ge*nu^> z$Ph*44zO2B{vprp$owSoLM53|FO+ZW&~m_$7nW%*i;h<ewzYo~JdU%kVOQBA^yF_w zQp|sLsMi8kT@aGF5a*ES0}Nl7uyYh&c-bsraI>CMm`@;ca0l}PeCN%ZI4mwHuzD=o zs_R(3(JU}M!BwY@Nx5pSEkzFcV^D|{!QMQCd?;_?^Q9vJH>+UnFMu&Qo>u9l$n^Ro zIol;749nl4oUv=5+@kWA)nnx^Lb|S|7NqN%6y1?Ry4@;&ZAkaCCEf46p!6G%&$$fP z^itB5L|~doxP!k3CjM;8@J_?!$hmkL``X^+h_eU0#JgMebnjDAsOUQAd<5%!bc#Am z{N!Dp<4RlN#Uidw&wi4+9L^F}`=GmMXiM!t#J&OcW_N(r*_JyZ9nKNCOoUQDu}0R~ zV~zgv$HAZD`>VL)-C?qEMld`Yy~m-A>d^mscjr&M9!EE;qjyTRlMX7v32c56-=Xs* zStO}XI^S-oTkfhMOt8J5H)09#bp+Oq3p?Hf3!rLJRQ4(ZU2n`1<;F=G<E)2M99-SU zSK~M<n4_$_P1A6236wd)VI~7gm81GpCA~1Kk01e%3vipExLj~?$QlM$H)O#T`Qcwk z+|j`m=3)g}nkI8TTI>=nw0k}1Xc71hUr4ag!Bvq^YBjBYT$C7Uff7TLMu}i!JX>&4 zOVX0Rh}RNC^(_(-qg(i<Ixs|oY;716nTv{Gfy0WT;R&|oq7m?Q$QF-+uZ<%Y31927 zfUH^T-zg%#){`r#;+C?~s@*|atxaJgv2G;R6-%sRAL+$Q%dMDdsj@46LYH4_q~1B| zzSf&3#nu`wBFWYU5J%wGnp4V0&?9ELOThzr7=8oXj-mK<Soz`jwYD7&b=;4Bu*>41 zf&*&EITs1Sz<eqa7@_BlH?alfXTw%aXa=I8$va$x3FGwX2xDyyNfG+l5H_h&7cKOf zhb(c#J{?&STZ|`MuMJt8D1N|~LDR}wQ1B!9ndp^_=BFZ<dRcFyEjOyaGp1ys`!ULB z`h9I)T_XG?H(jpMFi%#7-Y6OAPhSBE5|@wouTK$t3LtbLuqNBdRowPJP_a<S6p(?W zbGAUOw{*rp<DH$d21s8<=0FR6QT9Ns16dQC7?%s3>=`i1%PclK_VLh~9i*czKDkcY zTPn=~?{At_rU7i{REJvsa)&Vs@^k@=R*mJnR=5nHqS;`%KuM%MP=R8kKGfQ-^1y4L zqe5X-F`<hjE?c37iVj9$l*YT(FNV?sxalC!jfl0jIFK7ltDHFQS`Qq{P0mwREH{CH zHPcQYu#`9&2;5W+9t_N+u6|&kr!~-F(0J)FJQ&z4sSg+!`3rOybY4yX4+fUVy&Mc( z&eKI?DT%ZcI-U^F?9>!Go|x$=eW6L}U|&S$UlvOex@(Cgotb5_Jeq_u02KzO`;Kte z0E2{%+gt}J{W&1gzAm}ebD*6?fTpDhk>6!A=JV*fqB2wI6u`eWt|hg(N#cv;&pQL` zHb?rNYhjZHHI{&~f~FuXP?*(HYyCrUbqH)zMcs8wQQqv4AH{`q4)sBI)Lq>Y0iGwu zU|p-=2;0hzs2ev$2Dj{Wy^FLZdj<6p@OtZxldrd-$!7AKf)vRm*W1uV4r<zh+m5g- zY;Q~VJ-$Ap49CpBk%f{?bGKD+6@%^2)^UA&>1q}9yxt|IUNV(t#4~s98u+^L+%;M( zDShtr9A9a-f9deYAIYSf!IO<ilbxY=+Zi~=z=ae82$?lhS@=Zx+}tFyT2oNgE^a;W zW8*cF*l`HX|M%^;5)I*Ai=#`4N%WGLQ`><ZVs3HI#Ym$hXhH1Q;<N!#wwN|_U3TA! za_3h~8{dBW|2DKSyDLvrL7?3tw1K%H<{P%ziEmh<O!p1rSPO9&1#t+%4HqX4U>uk@ z<Qa#kI`W2dtcp0!y=WZY<(`SEg}ey+xr*W-E%UKu12Sz3XW#&v0A8U<#|sJw;mr5Y z@E_6S(yxtejh3NWX-y*DAgu0J#qf6=<+Wn$<{zA09X|Y95n$ejj3}f!Y1_iuTfGV2 zKhC@;3qG<|<oEewvMRD=90xdl9Fk@R#G@~}DgtdNpDzwN0s>9$y$~(su4$^OzeA}8 z(E%6#L}24tkd#{*K5$C++<)N+3<o7TtP&j-VOP>Yt)iMyy-@;fdrpd2x!TrrWJ{Rh zt!Ws=)-<Fw8$tB=;#*UPt>~gXsqJcHb0X4#Uql=3MeNP_a{N9+`g&zwI<kr~-j_P~ z&ITlWUHaS<7#`>w6Qg-46`Q&#=ZI)-NLi)ZD)E3fWCuKms-pF_{4{5B!H5cQ1?u`d z`a~s)mVwin;G=xrg2+C#`ddxP<u1UM&SD~9yKVutp^CO|w_30-=SmX+Rf5Uic4Z2C zm8O2++oD~8&HVPNDy+%C#B*UZrfIHbnu07QGEJVhh=$Gn%OlEM7~)8ks#}0U%+<go zQ&7_}<WbKIe^_psGKDl9`Ko)ivl?v5)X%h~YG;-dB26I7ppE4~k}0uiOA$zSkeH6o z<v<b~$HciSUoq4gtf+ddOnFR8o_mvduApkH%*koVvu`rb6;z9rISnnT6TULf{;I^v zUNevfA4pelMeO_eF3_^%D;qnjs=_RD#@X`w-G0t$(MS%Eo@b}BvK{6rb;@;E_Z3N% zQq`dy`AXK#iiC7gg=d1#4#Lff&LgRE&9;20W~Wn`=Ke08dwcCmrRLkMD*_}vE;Kz_ z*Bw&w3R3w^9HoF%YpIe~ocg?*i|FWRdB%(Aob?xnI_{VWFMt0WzFBR_p&9Aw|2gP9 z>q_SM+p9kgj=SCV)?U)h1#Pv|aO!m>f_&BEc{(&=m#<#wvgXtU?`9Lpa_hQ(tah;$ zfn3(xy5RL}GPfr^OPM52PA*0aHN&)ZlCJA&ErIO1zN@teZn$RnE}6Fyw)R|L>3+9X zfon}ZCRCuxEPJ<>zPVegY)o(nbt&j?Tf==?gqCGXqAh-*7EPgB)FXD#Jh@~G-7S2L z)*9;i^=M7ckMmB3U5%65(sXBF?zb96Rmwg=&g>4ZuX4iuSx`k=x1%k-^Hop<P_mZ9 ze4{*{RX!IeI<DG^+z3+k`6`O#XWR+J3tL9c=5pIvc`=T|Dd0_H2t)o77elp*i*XDH z7m>Xfr%el8O&&$8=*sWKsUxw7^mm(KZOfRBG)RoHK*iKa0Gv%x8roQNcsJX0!y=~~ zcRyHc8R=lW%fv&i4n4@nQpn@EkuD#qz_;)^C%WWIrCJ@#a|6J)X4=?lM?2%&;>lon zvVH#I=I%2TH$VO}S(OEAng%PfUy)fWBTSyXzN0q#g<epxl(9C_rc!v`S!m%Z@0fR` z@0TCoJAnW?oMd6ihRiW)9j?*5_2fMi(8>maVrY#LT0<IIf&ci~EL!K3IBp<=S_ro* zYw5(%u^M=PEC)xB%7$<o0{L?B7;a~GVB4m@qp2j0d!W1d7i(9w4I6)1Rk8)GI@;m^ z-FRJ^ITo&LbSn<3$F?n!Mk#IJG6b}{_9P38hejy3D{a!y3KJhL7~TO5A{Tpa3(w0F zcjYZluob~-W4a{yO_o#9b^ayhUZj1xvTg%BcVke@-INZuw`kU$B@>xlsjBrI^AT0N z7mFl*-IC^$qIjuIKH^%FRR>bFV7d_p*{?txmfDRtp1TCXhB)v?vmg$s!Z8bQ4x{88 zhBR@Q&rKYgG<W>bE{H>*U@go!jFNN66UU|o!gCP^P5(lAX-)kaNT(^9ByToXzl?!2 za}apR<_eXzt2(aX?}$7Yt4nJI>@=02fvkc`GK)(kNWSuu^^y`=0R;{HXCSKvV*SS` z^`8zH5QV_6DwP$hd&DwW04uBPxg?$gqSkO3b$N5mGh8;-02>y$4z;Z6hoLq~sO61R z)(g3wuE#7^x0_dAI!Do6Rp7Y<OauA&cy~p4P%>#du6$aAyQ1g_nXDaG-o-vppD!`h zl}ak>oOd`_QG$<5*v&vbe`2trycwDBnSp%T%wR=nNHW<ygKmkb(wvUK)IZV7#J~*X zgGmORGHf~=GBS}bZns(q(x}&;F^koe&x9YWDqBqEG<4;+r@NwXE~zY5w*xJ&YMwIZ z;Xpp?a?mN-tiP<bbMHZ^UjYf)ejz3|y$mg*3O)XwCP@#l`$2ag^c7MVOj@Diws1s= zek~iF#ECz_mXX6agyfYwZ{kOp$L_J#a2iU^m~1r7pucFEN=yfRt)Drh1A;l=Kkz2M zysO{o*-(ODhy<ydxM<WBpfW5rlWYY)oaqC|!1pnm(sh$uQT_ULTw#6U`{QeG^ji)z zLSX-CJh)`HW)+3UHCMXuq}!k6e%U*o#WyuKTEbhBINaI~<H<1c!lyJyFXPE1^#A^M zhF~ShZgjQZyPkzCN4Y`Y6r6(eg0Ar0L1z>Er{S_?w#&FTLXsKP8m{XG--Q^Hrgpgq z3>SRWa6LN%r=v5<+101dHObVPuJKy55*;NXXpSTnA`FtyW8~o#-4L<!axXd)PYlbp zh-y0B!-J6fEcek!O1w%*0|E~bIk41j2Nt-H98yXhmrRyUI~8g6pXhnT(1>KuD{al^ z)k`|0q{QV~@0Wi{ogid?h?Cz^^hUpwB+-vJWutszm3x%tqildO_vC_vm=`K%3Db2b z%0i?P7xiIczYcw}3+D&y*rVv7t=>XMUvp}REDw`7O*!}Q_Io0BxiS^Y<xt!L^E;!< zd8j#`!GXxL_SD+v2jW5(5H5Wn3YT0u{1+c)z=ljL2}*0K4B@A{U8mNo2laLsMLD}G zaKZHxlRf`cn7#f#NAC_Ve|dkbytzDktGxf|;O*(5^40INID5UbxA(y~+}k_4JR(oc zU3G8o_y_VdZ*-ew(^q?Y4-XH!55{hsO!h9%_s)+GcW$%0&{X%*ED1*0?l>Eh_Fql1 z*MET*!*lq8Kl|Re_>9gjPl;fbq{Hv1|1BK)`D;fY0z_H<RLg(eE4ruIQ|K!h&<lA4 zUH3+5T6z6+TL}Z@59Q%D$ow75pkFD|#NT;Hyy<J@PdvXpJW?_2UUiDs@%Tx>kMnmZ zH)v8jH{M+kKD{ER=@2p3Tt&<ur@=@6m8MP~^Y0ISFuBcMnW|befDvCsadPK{uN&B! z*57yMC6gf9$>QlNJYfF)I?l5AuJ%*t-(<BP68u*D%g*oF&NYzJP7sX|PG6y!0J_Sr z&<M#V{?09#D>@nfR+$;b_tc9-xOn4-_kI?PJO)1IBWm9$!|_-l_(vlbZ}F7d#J|bk zaOY*Aca4b78;|ePbaWdBBY!-eT#c^3o{Z9M@|IG1&ZV3Fr%iA*_D6Aocit-n?R!4~ zgaMhN{r~E(D*AJCQ-KgoD<#uv!no(H2B%7#^ny@q^f>o#{KQ9c_sha6G03b9qj=M# zikB+)UKotg-&k)@2<Fn=_DrT<+D_KLQGSVM%E*I*37B>S`cZ+nOv!G8R0;iiKipM@ znUaDggx7n!XdK)J*^`1=c{79x58fJvPi<2E@^Cu__3jS6alEZud#OKG(6OK0`iciw z^GkB{qOmf?;siQQ5oFouHi#xH>cpSmXq%sT`4P>RUU1Q-pD!*D<37ane~FMIZD4S; zZ3W~oa{$E>gjdFrVBIskNb^f$CCY!C1dsms4PGD#LjZ35AsA=35{=))N$?S^l@|`f zU=l&)rLBFSC<$Pu3BH<RAA}r95tQy}oeO}g^tXOr+^SLawQ6eL&Q{ARovpSi=WK0z zkUoEBtFEui*;-%dP40ZNbJbpCQm?y_@o2y$H4TS`tgF>5T&>P$;A+)Y;cCTB4$H{n z+%;GF@}iBamC9_4m71>W4CiIKS#86>vIg3BHn>@tX2MU%fGxw6v@h7p3fL&|uyL}= z+myAAPFC#&IawRbs9gV5I9Q=LgX7@q1c6GZ6}2}GR_Rm9T;nPAf{vz7#<{Am(7CF0 zajs&QABcyf8cwHEYBBdJK3G3p?`rKN?BZO-<+7}zT9(trk^MP1SGA7LRqe$%S8FT2 z@vWA=Rc+&2eOBM9(1rB*`&VD0^Yr;Vqc79#`8+<&FWzCf@kaKDxX;bixMSqLMne?I zyzw=z&(}z;Z$osTQvT%l7%Mh^Fro~w+-ZY;H?S$oOz|Faiso}GddhiH{m>s(?vt5+ zC!n>i5L?21>Vi9H;MnLdjojKIS2>?^<svS+1vANMl!L2N#DgA5Vf+;8ZJ}?<J%&~J zdK`FRJZabLt#*d92u!D(DU<uEE)c7t+*u{H9G7v+rf?Z6<!^eqEKMoDy)2T~85kzM z6arrY1i61Et=tl2Q8<{cTNm)<Y*(jeKV2nAltzq~-SNzO1k+Vfg&>G{w@P~V{t1Z7 z8QjX1%tqNP@s$rjcB{aC;CIxIE)au)`d7xzk>VwZ_oRG{4%3l`R1EZ=g2*A7z{#78 zl`$GFN)fs^^nv)~G#jQT0sk6JuIZ!?0x?Sh5r;iU-oN02g~Y|TM5&NN>kgy{gi^4t zYY0P~j;8sXi2G+lL`yJzeA_HYL`OchD(7@m{E97@`J<eggxAo>p8}c%M<6)|ExW@x z*tToVjZ-jLf)Tr2&Q1y^4HHxKV#%wUAVk86KQ7Q=aPE_7a8?V7oaqKGI8Uo`*0$f; zoa<dA4MvLt3?(Gf5=_oDE|vRP;MB0eSdGX8f}(7Sxw;Le#krn^RmE)`co@wRq)ca5 z1-mJc!MT3A!7K-+ft?-j(UL-jD?|oQuvtAaknS0ekd9eg(I<rr-NfNPsttY&OU0jQ zt_+HB(XP$aKnG7GTpS&giZEi!dflRKu?*^UL;Ap_+0onfbD1e|_DOY0yj!D4;#7}w z;^{0fCpj!xCat>EVl(31+YU2g)o7y4sC~dJGNX1)z50w;<@9JXYC^Zzj5ynltQzZb z!upg<yT4_l6au5pNrWboTCi%tIf?LO$q|!IEg87roHzxY$eg66<WkE6F36WS0vnkU ztA1OB+2{4>@KvU-!M?S_l@=>_?T7w!5&f}hb2iAYPkt|A_$I5?AB}VLG$#?mcUciv zl(jagR?P1XkbW|{t^Y`y3iUdl`cbDdYU3iIfbtUQH`A)5w&4RJMp833NSrK?AwSCn zmrcaU08=uwq-lK$4<g0^qKYgvIrLJNvTJHkt<0^r;B*kepmeGQzQGO{HEoxpKZAO= z5RLv^i8&(mZ`I^Sxelhm$%Hac3Du6~43=AI>V4+a-Ak{GMiV$FQs+`jY*Gv7wUJ@K zEx*!)NI6h?TVqosc;_br=TIxbvIlc9z%+SgNFvNofm={m7aqE-lIN5I&gvk{5IX8f z;}Gq)fu!Wnqm*cIlH-V!D5MX9Cu)fHf^*_s9bB1{%wikmT07#krXKhU>T*Kqo4~*k z+}bcW!aZm9C{)@)-A_)>a;R4fEI212ACOmSG`hQ<Hu;_qDm2Ro?J|o@z8~ggiw+V; zPE<9iA*>6|NyI2jp?X*%)Lc$bb-0p2<vi?L>ZDw3&ybsR`YoA_<zZCp?oT42gl*Rs zO}K+|C9+3W$8)FWikO_q)TQ2qu;8Rb7D~5+%(I+uu2IAU>Pf}AxPb8@8q|U$<hmX& zytFo_6;2&`1`6aSEJ(JhPFP&jnFx5Ct16bAt}D2%B3C{+x4uxh)lxi6qu44L7_?}5 zM|1kN$+#DzKQ5+GuAXRECJi}h-Zpv^F*I)62bq@KIc@hT(Q6dNxiKwCVbV5woR%(9 z$iS{9Es?p)u~=35AZKvBCZeb&!KJq<{qBI)Gza?9CxPDOB%o<`ZKP;A11WuQR%)q_ zHfQa~+htf*Gq|?lT$jjf9*(k^SBtl(<}+7NUWOYr>M>QC%)>D>@EciB5J58_7{P5u zoQh<g`EF!}td&hVW-6Ecm>J5_dBv7wUh$j~sQJVY`EeC`*M6916$cPqTjUIDMcVND zPN~IzX^k4=DB0Gq|M}zK&v$qJq+8~)Xn4Ko@~_KVzhhRkXl$c8_4}*1*TK#C;KzR^ zJr8bGXFf(#-y3JWzQC@&VA5^qN?Lo#6*`Te)OS%Ujh&LdUha&Jm7U6dtc3L%=jxKE zKIcr81oc*&n5bsT`;wh<;`mE`xr6JY7y|>JXNU$>nQ$#iB1YM!&)Br~nc-jKP}P3^ zDlyeeA8#E#^efM)2aqwq*AqZIpp9=dmWly&myex3PLen|8ATA+>}5XO1ip&{d_(kY zH!D7Ipn%k>>`mY&UNX9cjIwh-jl&s%?D%mS2BRQ*7llvkF)kC|%ZBMNi|>NbPf@_A zD7WANT1U%CNhw?VXT!_4!vp1H7L8!K>|WgBAkxRL-Cw0U$s_nb2mk8hsH_dX%9FC3 z_?Qgd`M9Z`30Hp{AN={uRsVF|C@!$pZMemnS{g@qI@EXEimz8Ix60|!n_zPL!Gr8c zFZqoX<RCa&4z6M#!8zM}^@>)Ci^djplKlk-43rfb$QEG`-1xYP@_==it62e6z;#;j zEhglKokMO>^53YCi>~in*R|&@^c?wjv&RBE3jU^45!1?)Xid9&@kAXoIb0aW0Ceg! zrz91Nlvuu6JCeRfN!{y&l8c?<+$r&LQT$TFO)IIUHW{2wT%O&^d{pJfnKvHAQ?z@p za2mcMC<$2+TSVnfnzg?)wLrB-OADl9SzzBS;2=UwdUKWD%;;r-Y7iX8v)q#)grY?E zkv|RNC&)tvL`h^YA4iaHb}&mXW>dWHSrv;a?;1s?DPE^{50Rf>Lg2j#joSXX0qYNV zU$QF>mW>GxE2%s5m+sNtDoxOrILY3tBnd0?pX$3^_5d((I-v<C0Faq($sPfe*w+q_ zNTfU=C}`!Qm_U$Y%<XoL(c(n=Wz>CMvrUfnPS=NHyPKS6jBvtdyq!Bgz@@L0uFSZ< zd(R~|a#y+FElA`=c?c2LoFikvh`3@PV^w#n%iIN?OBvl(j}_Uv^o#`?yM<!;8FSpB zJ>Fwp6X)<3t>lc&8f!Euj#nI^CR>0=VS(m^K0<1&BU1@NQ+e((IlD+H<8cBma^6d7 zMQrU~du`53J;$kMIM=C0Cj6)r$)*%Vwf!RbcT@RO{oPNidN++THQxQP%exn(-?Czc zA+DIwk$w$0`U(9SCgtp>&@V4s?9-*+^Ejl`V^}riz7H}=si2h;?JwTL>ZsKysa59I zl1|iWswKBIX?6#SZ1{O{+XE=#2&I2WO8fc=7f;}6RTGdPVLXA4T_&&~IhWOF44L{N zoyb|UOXjPqQp}ekoP9RroFEST+!Q?pe*D~2{p3BYfv(G<-X^CI%wlwHn<ZV_t{h!| zo<c>=raf|Nxc5BLan7n&I0<=n-Ek6&xzvv@4wd4UoWwarfV!4`0;h-Wf*l%HUDqi0 z0JP|vlGM8Kg}+>1xU+U&_=>{Oe!jl?!@s%d=4h_^spng1<A$bEY0C|5QkkJ_gp;X# zmJVp1hZR6J1+M4ydRPVa=rwv+F>bi@(80qhutZm|ycQ3u=rW20Jgi=V{zU*IFy7yJ zkK6C>f@u5aYcbrVUsl`rWgCJUIzoKb`_|!-#alpdEm#jOS!%tV1zoZPWmN#aAaAVb z(lqQn!pEGv^N6s)e%)PS>TX-U`R%&<DRa1_{gjxLR^;`Qa-x&7y5qtz3P3GAV=2FQ z1;z3+<|G&O=%;Myt=}ge+=0=K=5C2ctwWoBB_fT*7}zRfo4{h=vM`r&C475RZ}its zNq==$sK2rjpN>ziI;P0nOp_qWZt`&p;xC?V^voJHwZomMwFJ6pUizz7t%!&gc<a=> z1VNzvXkOprEAC31kgs*5G#!^rNbz0Og$iy+OPkc|?EBRm0SvC#*+Fv@M$D~ObEH)W z>`!x?Y~O7Z#w8TS<ExYQ?I^h2TGU0Ld+zO#y{L;+=DVP}2nefA{|itSMU>J}sa!zw z!tAkw=B2Mr^Af0)l?k)TXfP&hJg=^ZrHhU;=2RG3gRVFy3i%mROR}?Oys)ka*UL?k zD)X!UlJkzHm23$orvn0wVd8tc;S;xJVp%1X<HSEj%2wcoNR1j7@4%UN>Q%h0;7?ll zNiRPcS8*#@eOYvs!N6vZx58;U)I&8*d^0n?fs9)yv#im{z3Q!nu}8SW<SKrxJQW{4 zk`KKjsf;)^g^A={k%aFkCrC0ZDI{^P&TAnF!iXUI0MLWOd5SMj-UIpAJGRP*M^h%g zTozk4*k>%L7OXiM7;R`px!Xr2rxY!fq%b*QQtBTuW$c_O6S&+7F$UbaMG#{QWXQ<j zM1nHNs3f7BeA*bQi~$y+AezN9B7YCFED5e>8NP3kST&}%0r^lENaiW(`7hHnZ?Vuy zv<!-GuYI|45vDLww`;iwb1*2%ML4RAiIH2UabsenqU9M)jDu$=7qNVGqV?B`_|I|Y zSy#eu-fqf7P&zMXH>KGa#bqMy<2kQ<^{REDa09qyV{}A0c+XQL0z=-(G`c{M2w@%A z7g!_$5c35Z(&Y@%ZjXj&!Md-zNW=;Z(VHR>^u~q7Fo~bhw(Nd_w&kRLa0$57^2TLK z!d<Q1OREb(j`LL&h9KPUS&f?b(C%Q=EN9$zVF>o-Z9&$1MTi_Kd3!(JE6-UHg2)sd z*KJkibE%RL6&%aYcs=Ix?v{~0ig233gi*SnLgU9a$S3x|%nkCcCKa}|eDd?grm{Ah zilMIGrqVrX>m}G!4wj!aqrmom4i>NT{PyaPgX4{{rqOvhV+}P>N?^LE#ZwHvSYyp# zW2~VYYX;%~zx5hx1UGc7(^xYQX}BGXHNuNWN*RdCqvVV=^h<yjFo`W0HP|I)P!|IH zrP*~3y2T83odsQ;q|D+u0~cZIaf|8pVq97(^0;AKI%poWpM!Bp40H`<L$+u(ff=8% zZl^<5l#aZvLsr&SAee4$D;TWQ>NZ%REkw?GGw5h_D`(ud)s4+syUMW(SltLz@>aJ& z|5i5vYi}Vz;L}+O34*OrA%#vEh#iPmz&|T9?n=C?s(vhxB3n3?pE2hWyH%PV&tf?C z>-C8&VF@nz_$w1@A1*G#g$vY5h3@h$u-{k;sc3mdOQE)QOW|Ubgk+6{aqm~=l@tG$ z7fx?Gj$JY8Rd?$qH<i8-+BJ|Cxr(P=HN#Rr%R)$XkRPhh@`GfSH`a-+G<lK6IzUXT zK4oj#>onF0gyc0E>oC#ub^VS2taV3L36!iQjdiCt+y9;Tzi<Czy!{XK_x<*HH}l;l zEUT_vJzS0B?D<S*m`SYu)*hN>xTqBgW2`!Vy;F&+g=}YnJ@wK8v#<oPDhm<eozEGU zMUH%Vm32PjzAZ$Y-P_f;*WEgjgC%VuB75aIO?yNn>9%lv7cc7;m{q~C{EXLgS5M12 za$eQ9I>uXB!Ya>}biCC7Qh9Y3q)N@ib)Kc_m{Y1+ZtN&8*N&pE-Hx(|Ibxkwl-kfn zpAlEJk<C?J0&Vq~GRTZU8<UB5z6Dx76m5)Vzsx1m=PldSCM>NN`<6{Rc7?{Cn#ivq zF-A6(WYM@Zf$L<Q_ATuT4n}LHlFoxB04=S`2wb!{1r^Y)RiUCq&g>_U>(_yn+C}V` zV7eGYbu}j#U6&>pfvcBbX7yTghumX~mM-C}x>=ybmPU(&DR6858Dd_!c4CAWTY#7^ zHK-HghHGBxU?-N?Gr6L*cu=QKb6L}|yxO2nY$X2g$H(peetO#e?~fm`!T5IjAK5lS zMdn>yZr^PuSMg{&xqU?cJ)!?Tb}%Gcn>f%`m<~P#I+~NaPDVN$^ge!O!#3>PPURq9 zKul=4g0(}dTbSe`=Iv(?VOp>gf~f-Dt(fNm;h~~po-Zsslv=jBZL!4aQ3s19KH^qm zW2NRG(P!KtW^O*?{>=GhFqc$CQKEb-GGpouSIf;<&Lf1Cf<<Obzujf28Ou3&G}$oc z=8UNphNS{v1t)6@!2Vr51UPwD4?Z_m6AjEe*;|+psDMjhLMkNKTHU=brkn=}t5+TA zcvUkNs30vA%es#{c#jD>*5V*T+LvDl82Oi6x)5FpBYPu^g*Dp&QrSTCFf?92&MM4T z0H%2{^+&-?KrFx)SrSB`V-_Bk6q=;Fm%*KnTVse1Zzj3r`f!#cNY^=xqnltdBiF?i z#%ljDyPG7twPzQ8_BHMIVz@XdY~AFa?|r1;c%kysY5sGT%=~Y*y9{v=&ytbfVFc14 ztqt-aNc?eu6xo4(4$_$y)&~MaDo6317etj|imCcZ;Dy0Qf1JyBMc+SC)M}I!p{_yn z%iG}Y-1oxT*gNX3>)M7<`|-?sq&9YT2aY|cxBUfk$X3((c;w}0-lX=kx~sw;+N+yQ zX>We(PyA?%5EfhqVR^eu{t#)lweSD)eG-h@*!zY4^ZPK)&=lU^dTBuzH)vIg$HPZI zJ&eOR$)EkID(HXzt~|XA5XIM8?AoraJEo-$T-6xpx+3vQF(Mub@6BR3P0>(u)vo<< z0HgEnnuUggL3P8@2d1Vuw&|$0qP>Q`#dphf(Q^a+qS>nBnucaLx@8W~Sj8Cmlu#45 zc&cgxTZLbm??c_3>cIK{HPUO1251JTWAQwn2m**qj0QpN2jk!6zR1G*zWv)*VfOkW zm_%NP$?~g7R;NT@-rzX)lPo}M=#6fR0si>o&p-1<Kc#+h<lmsC<HK7oiu@2*U)pZ? z!|V<QES{K^m(+WZ5A*wWUum^jRUYW92L|hbNq#9O1(68YPakD8!uCe~-TaaEP0=mq z9yxNJ5d7XO%nA@TyyWxcC4DjtCSQ_c3JY?aWq8Rq+~fE%jvI$DEGH6$?t@8HaH*{K zyJ+MOvx_XAQdawY;@=1HEFI3WI30Nn_Vqu%<WBl-Q#$j#be7<4own!mv!A5%iIRVG zRkN=}W7PJ1mLSHF`k@bAby@>pdin4AH~F9`=EP~{m1F*j@cj*cVy;)mcP`7$Pd*c^ z?m$<S0jwTdP({r76aq(bfw?KnFDRgw7fe{<3pqO6#-Zzjy!e-H%Sh-}+X}Ri(0h~6 zizCs?ytnaWf^df;(yl{%tk>rO=!1ru#MWKAaBr%%v1_@5fg^P$8>XWpzHHldDP)Ob zSy4J1%#7J`&*pb^{_&X|%^NX4{`AEBYF24O(62qx*^dnNqZcIZZ@9~+&0RKv|M~@g z2u(ekN9X1by*izJ5n6&)=mFVimZWh)9q@k+<2V^Z<V4A45!qUnYq$f$wGc}&U7-2u zFP2#z9lubz|KR<Amhp#jTi}=H2SC{f(NWRhgLm)W#L3-ZZI)Fb4RPQ%aT0t)T)1Rn z)wPEPKf_TpDj!$6zXj17k9{%qMo8AAjSzX$%NWE=+Cx9fP`4COksm^Eb>2p$ELyXT z_RXiRkEx|XCcN>F5|Bj=SQ{7+;iekf2rdUcnvP6*kjg8wveC&lIvJ6gG`7gnYD{ap z9wRC3&0nynv{A(3m#2tn0!8dR4)Z;-sJ0}j2tDJL?xF#qHQiMQj$7ABH@kYXt3Rb( z{T}XYU1nSBn{B<>)|+kp!nXA<-orAR+E~Q0DYHSp;C=Lk+Xw6P^wxWdXW0?b3?s0T zl$Ihx(f<8~h7dTOXpHq62lZXYQZ#F00DSQVz-Dm#q6WZuL`E|mYdHg;W|sy)U6nEb zQc6s141mvS05l|+;l=>CF#v9KiqBG~IEcqjN)m^ma_=K%T2k!B90>nx>;{`X{+aCY zDcA&i+2kAJ;AWF=Hu;O(<WJs1FI#+LD%_X~H>SepF%^E=wkEwaH8txxE}Hz~4vOTT zfi9o?(=JS~u`@lZok^G2No%(=xz4U?8oDhdqT2Rg*K{1m>PtxNAfwXX{UxX5ZiLhq zD5Q$=eom46IZ2?#UnA?M@<3-jFjx;>P`=NGp?tCo<qMb3zfh@rh1oj>FULQB)YW%y zfu+i@HCG*|rllKw`0)*;JWn=${5p}ptVAB8)UBFV2`uNvH&wTA<0G1qa^r8RpKa8u z7wrJpxbZiN)n}wwNm>6NH$HqyTU~?3np)S%HXD4i!9TeT{<L2IeZI-cKXO$I8@-JF zN||gn{btjDd7J*@#-qR4Q=iA4`m}=p8jY!Cir~jh%s@xGmRZ`h2EE#~Y_m*Hv0b_J zludn_7iQNoB{tK>uC=jiZBFaYR|0-iywS)H{VK=&jBQ(8^ju9f2fMm$xSL(R+2x=1 zE`RE6mrEPCOt}rNZ}#?PZ*TVYQZ}r<_V&u`SR3;G<jDKeHYaWDL$dZEtFRB*YEL;O znt|&V+a|tq8a@te3Hy+-iF<l!_MsP9z65bMdoYj-0=ITu)i&yF*JB@|z4=QH0N<Ry zFHpQR1mfj94Mbz6lxWPH60Jxoc?r2A8?Nywa*a*e$d@QsujA5}9@9oh$;WbEY)U>h z*6g!O6|qZ|N$b_6Zs}#Jh~>znia3Lf#`Ll@rj18^<5AxzOrNd7B(ldpD%09g^%*<T zH#Oikd;5#p+fTjhZE5$p)n#wfHshL3ZCcyS*4}LGPibp^>}6|z#@_QU+zwY?){QIt zGj)YKrCmqw$rWy^>b7DV1NaL*IWpxH2OF!-3$yCH(0hC>#PsSV#+U-4vFqrAy8g8$ z`H=GFFWIBDkq=*>d?@mRf1jWuI(t%-h8KMPyUzIi1$n?X{NhvO7hkyK-M2jbazy6m zs*U)G`(E8rMmPE@fewYwZ76~6TJTA#1iGfG8zKE=3F$AhNT0cD4RphiJ9TM|*L3XC zUi~GXyBj$@{`BN@h5n}@wX<63QmtN+M89D!pC)tJ2=)C4^&2_8f~A)wrw>Xw-Rvu^ zOxLaat|CphEZNJ7G*#b7>Mu)Df01crpJ|ZfXMU1y#Ps;n6VuOQbT%p%Pif}g6)bu0 z;3~fJC*IXK&KmN%u({r?`Ad@EH%#XfWI7x1{Y#8-*<__{veN2={hS)tyID3x-3y&7 zKi^8F%VH~CbA`$^L5ngV>CA<sGhOO_BAavj>**+t@^f)(AHY+h+1<6D^Z=nh3;pEE zizcC;mSEb_U>c55fN4mTs~vE_1jx4bIeO&^@o;c;AD8fRt^sbqZ_eR2rQo+X)p`m1 z&8WNez<+#|%;D!;)zyIC8kA&iYcgc+3gI`OZT&%vEpfmp>)gPBqm?*t45_QgRL&X` zBv{Xcgh>Iv!zo+Tgx{INKahi;v&IB|PR*hv;0M`2G&hb_D;c5ZruNr(hIA<&1VKbB za0oBzYen5wc5Ib`mxIKMMz{4JDN|}QMB2;XEvD6eOQr2miZH8L`d@>HHvc`^d}Jrt zrs(#IRrwcxx7S=NnZ@If6<It>e(@l>c!@=8Z(!D<4P+M0HdnD|?OoP-v1zS((H!B9 zv!oXd?AJ>yTKjBbEE*E&UZd@%+2sb;Ov>rs-U1q6lR~CTEn_>dolR@671J`QNMgQ^ z%E2k!+eFKt9TvQuW<VR31vZWQQs!$6y3KdFRnxe9J)hCacb~=)MacFugxfFY6b@~! z3(iW&$xT;sR(6lG;z(urtZZpkWz%<|H1%+Kca8cjnFGe4;%R9bZ!`BcmvC23<GdSE z$hr-r*G*q?-Q=0IOJ~vz>=~<AH=V}c+p~1_^87P&DcKXBe-xI}+gj^l0iLWi$IL+H z>QKeiZnJ{FxAx~L?qc0Y=gbRxC35PZkzj*w+j4N)cuktk7J>7z3!I#DXCXL+Cjo)8 zkM;c61y0UMwh){gyj9_B=Wcd~^L>zwZY4nE9E%-6bmU0ZGW#Og^EeD8Amo@M7J^Vn ztQJ+@TLi*iyax#YIZD_<01By;0N4kW;$r<%Al35HNeO^CB0)!hC65!!>WgMEzzHJU zF7R@apBI8xOu<yuWnp-qyoV0p8k{teg}@clv(+m-KXn0?vlbnJbtP%p?Uj}vy8zpt zd?cwsT2%dHVPHRY0k%IO$(1Byw`Vf0-k~A^aBtF*sY;Uapl4F<2ykz*Qx340oT)~x zCCIrWz`co5Ily9)9xPAN<?O}AYE$0Bu$(2qkhWG!S`s?AXFAMM+TJl((k5*RY|`bs zb__@5I_4<IA%+X8Q)g*Ywkd1Mc5H^>p7S=^`)Gz|3d|<MFvo+s<4kB?LptoRRt{P- zQ`MMA;J%#p`u1tVpMb@DaSM3{2YEd7b%udPlhhg6RQtSmMoa>i_K7U$%;nu%RQ2X^ z&iJ|2)>(?znp`_}%`<3QuN7ORzpfKkps{xrVM=l_lfmM9;bJsK-zLJfy4WnP89T>G z2haLqglvgT(n71yoRAr^kt{~!f=O)pTe{GLMd$5JdSJMn`k+XQ&fXcUo$9`5vvnpD zT?ze4N0C@61SA+PJ^rB+)@Y7J7S?o~8uidk3b1I*wbrsKkI;pee&i8Ka3&XelP!oe z$cAeC<4?VZ4Ip62bBWk-ol+tmu$Hv38dSxZJ@Nkdsm-eqL#!P_B`k-b2bYjc{C3Xe zb!jf|(j|TAxGwpSK}Sk8TuI2FEfF(lGUSCGsYx7aV#vpzxy!AaG{4t16#~#8`n(80 zQ>7g6Dt*^3xsnorgcjA!y!4x;1@j$ElOc7BalrRTaKdO5OK8d~0W;^83|jE7G#a^9 zntUs+B+|r@i!|XxH%lLfPN$GTIeE}xAf=Dv+hNEHw0*UlMA{_e@AgQZZ}CebmY!0m zVs=e>6qy8v@!j1l%8NfJ#WS2*V42l2&=u?_1@as9Cn`<m6`<h)WDBGg2iKW13`U<4 znGXH=x&QmjPqX7ke}t2jAG6cw)=z>A;mF_Gk8f`1{ct&kD5JD^cm2QqC{rMTnKV7~ z(%;CBTMGFX&|nx_%3<iGX}<G|!WhuHmU=N??>y;&bo=|(=+;AkLH@>72$u6aYZ0-I z>8!}BR<v!UOyZkj0xzEA`H%kNT|D;dKNiV%-@LAawnwI4`K3-LwduZ%$?D^K*fbr? z(2yi%Lb8Zzy3OrX_Jia>gx01np++c}^wOVFAJN&=8)ZMlS^lo(a#Tqnj_*!9$Qy;| zuI5qOChC(UzWWd-zoqC6Wfd0q@vFZ+4qsQE5VE#pGG-izP&YJmY?JgkLndd8VnZ+6 zz((^C-Hs_JYm#eTJ!EVD@hZ)!;R+U?69IGK-AzLuDuit9U;fT+2iMak(>U}p%BHCU z<tOoB5~nGD!tXE@4{y-0Cqd+eKYQT}4gDq#$3ZkvZs0fN9)4^|?-F@Wl1r<VYs<Nj zu)emYQLL?L$*e8KYq8wge%!3B)Y|Ih+H!6sXzW|3+_y9(S;n!m+}b{U>1%s7dn{HI zf6P}<ShLn_2^Fk`9)Lt`xaim%;7zOzWEPs2L~$EGkk#X&SCSrb8Q|TNO!wMbDD4x; zCga(tO#3XqVstvDu(X&ijZV!Vso~JWR53z%ceip(f)$cQ1cvC_Ke`m)6wxA7Gys?{ zGBj!~*}YQo56XSuDFN&NAj)JGHfgddCr0BlKfB%9KMCWwiS*jW%b-k#|1QEew)@Gu zdq24e;|Ho}B2@$~^QUDEIP`gbC~?+l&bYuNYysw74L%t(EwM$<9G99Tp<)iOwa+uv zRajKBnH*wfrMiJX608h_m&|maUd_eS3p$C8saNI2rEt83UD*L7IbYm*Q`9brXVF-& z9S~Um@7r%*+MZd#UZ^d3xf2G$1E9m2>&AS|E%`O)S#>sR-rJfNVw<gUiga{e^MP8d zxuL1DYff=6Zq~e)HNW(eJ1DAzRQ3EF)nAC1V#vtt0|@mpV08!Zmr1h$%eY;ojz1~T zzW0Kt01AolnRoSAlC+GLscB&FG6#q=X&T(DV9_$~+AwiW;`d(S-StKdFPpO3=zl8F zFIDn{px-FbZ_+Hq?c;%C!ui6{?>&?YAXQ!qFMtL6nk;}V$E!Ii8lKetG}z;nrTL;4 z>0`M>GEA2&5!U?jJwo$MwwH+K@cM$#Usd>0^!Y0B(JP`-J?99!^CeKhdSSy~nu@D) zIZ{i&iMb@28ZWcz0LmEp@b+!|Kh6tt_3&498~=|N?7y^{*hFV(HyTKtw-}S;yv3N5 zJ8yZ>s{|NcRe}<eV*C`C)Sdy8PbDU$j!uF}qr{}-(aDj<a!hi}6$@Ze-PYER$;v4x zRecfTlAMBMf6JYM983{#c=_rJ;S&DG;{^TV@?&WrlaeP?Qpa*ml~RWlC3m2KNe%;8 z5Rp6DYN@hO4Y2Svq^09tswSd|T_ppki)p$TpEACZXDj$8%ILDXMB|j<Sk!udr4b(j zH!OPS$YL=?qL3oXl8-&q1_cmYWw{E(a_N)oGG<L6<g541S7L`2q)UaOpA<n#X|yI7 z@+pD?hacZZg`>%tR#X@au~(@mTck6ru`n1CMI>j{LwO(R!eG`wxc|rs4tit?loDah zSqV2(j;kKyq=m(}U}ZXmKMJ?SK<|%9QR;U!r!UW?26EHyk;hUBdo`yoOQ}8XYF^Q+ zd{%Nro@}*;sv|Nbs`C9Kj113b)njQyUbUqhSMv2zHIq>=l{WvLC{W0iEIF(?MxPWY z5(6D^Vn5jz^o)fCXC>y9a`mJfdY0pYvl6jDr$fesZkOWbj!sL$qXHs9io+<%gF*|t z8Pj11e{b!dV=J5Dg`rYvK1voVAN?eLjehc#+xS6Aalq?e5<i{B(HJ+ln}u0`G%saz z>qQfPJnt^&eAJ*$xNQ!w^HFH3JI&3KXI?T1qM}*``9G)IN$}{8-}u4gmJ+kvZuub? zL$C|C;rvRHVHivzaEop2hyG2*?owP*Qt6PzQ?Yiq)27_{`p$pv9JhWLM`;FO-1+<F z-wDlVDm_%avUs5Fx;8d-gSP87%Xzoe9FzVWPwOm55{OT3_!j2~B;j<`Q+$!&{3uJ} zupXALIT|l4AMP;`hvmEAJhxm3w^MB#b7YI+@)_7*`_IcJ&lkFHt|)Xri294%{|kR~ zz3B0;%UeJ5uKu_QLd017@t=LZ#VC4=i`Pt^lK9WPan|Qs%%aDC{y6?Kxr&z@n~^~A zzSm(({QF6A^+!7Gi1slesPbac>Tdo-vOCyW8vUeqw8{Xt+2U!$Gj?i@jHeSDI1K>W zf|J{@Wv)M2(*;L$_^S6jT@`!1gjL3+Xp%_M0#-|xft45bu+H0_XvhGs?R>dqf@ui~ zT%$mNR2Bf`rh*0z)^y`j9S0+F!}3*8%D6;?jMIb|_KgA&ChhVIu@Kin#G0;tsw1K( z$5?ueWV{?00d`3VwiG28yujeK-uqOEsT__AHemB0?;29+8W=5VE*v|$jC;~>d8*~= zA}V(TjXr~jN`a<hTQYav;apqCKvaP9p`7+PPhHgI!{Kwar=sf872c&#p_RChx&O}5 z@zrNmfeTm0Yi#hYzgqwoy~1CFRy(Q;2PE;d#BGj4BBc;uat+X(5U`Mo`^dkWr;y<< zM#1-aaTkR9AyvSX<9?0`0dOi(OdOIn!sD9r<6(K+^phXf#*$g?jUKUNL%_XbnsAch zEo4h=A)W#Gd9h@bv?NSUKv?1>!Zm5hbOt#sS(Y3v@mwl$SR$#MDOWyS6(;QxlN?^W z7$)bt(vhM!UKZ~sfJvvsq)@u+h)K&TFlp;@m|Q+hc72$v20@e0gaJz30X+aaD3*S4 zKCz_qJ6N9olTh~X_vGpy>_%tAVG$G-oHH*=g2%7_@n18}?b=^b1a>9O{OynD3i>*i z4SUQr$GgZbIlE&>advn4tTW*bfwl;o`cDm5f56%&?Z(_nLo%7S-re=sYrkW!`H}@! zr%VduMSPOgvE?;b74KXJX|OnbT9rv$H(Z{3UQ&b2^-_+U^E?Z9l~P=Fi>+bHCv_HQ zaiTzWofnPEh*OOdp<kX^(xnJYoUY|SV5)&*`lVKs7x8lvC;kMR84lwR49|Do#E&ux zsduD-j=rs0-?@K_lAkZ@;<6-NT(vjT-CPx4MSYbQ_f-%&Yx*njuWg@2ZHg7Y1$Zpr zKW(5hycV^dEYC%Q-nw}&YMpBy43%0KPhiXZcr_xpCG}y-ZPfH-H0C_#dBl&6^R^%y zfnwsX&$tX!5mYOeG+vT*ZSfB}=q(;{;``%kZ}eLUcJr)mEft%CurP$3{F-He+sDG! z-b<s1UglVmGt`<cz#VG+nI3Rf%iPC^B+Ga*L=xFk8l;!;WD@#+|2yN_4OvEGcVINN zsdZyE%1sjADQB=NmSa134pi2IpU~M)ZQ`9-P^~wQ4b>Vh!is7Gh}jWtz936#`r9b; zujJ@pGb5ywki=`ormIh%>27T`?ZBOIKRSn^W22E&Q=+3pL{nttA;PfL91*ytK{rI~ ztQQmQNJ8e!SeKGixg!n@)mTB8t@b1sQ)AvhPi9Y_V>66Q0Bu+4wp{t9DYXUwyB;c~ zX-ObD7#?uREge&esEX}8{#8&b{!=}j7&U)oPbX(Rr_<(0TJ4b}Srf9f-)l|#Jq46< z&+Xtd3EK%ED5A^JL`fEFHLjO{yaTc+&X9J1ajUnW5M+C5+%lBCb#UBF^es4MhM1Yz zj+xmpGcz-D95YkQ%p5Z_bDWr&nVFgG*~#~NZ};tATU*t2bz0Irs%hPk)O}jIah`hy zQ@tgDdEqwMwfVsW0iJqkbBd<Pb2S`(Cqu;atGx??LZ6Un@zuxA=!~9o=*n4M9HSDd zuD<i^3yiNcqVp#Xt>q7=A`$i$lv-YmF5fO<%%=P?Eoy;NGo1rthMUCnj*L^AbXWeo z9^PJMJ`ZmUlLlAk7rxBMPmi&Tal@*vnj33;pMm@n_!|~0_Y0ew0|Nt>!S(pmN!??2 z-FJHfIcw*P><iuOvO&r%e3OGkADT($4~E-+uL*j#r+T;;1-D)@O2wFEXLsD^fmq0I z@6F`guZ0Z$6$ibSm>YBFwD&29$D#Z|HQt5n)m?ra)gghm;kQosW}nE1)3wRgyI1@a zoA=GP)VW(kMCCX?YI*<Kw&i08O>Pye=SyF#d$@}{-$xRZivH1ajbZlBh9>^d%;fbQ z?-klEiqI^nz(O+mqp6&|?zwXY-BR-Kw6Q}Glf#hP^BdxDt9Fke>dHn)WK--S9I_V^ z*l_3F;)=B2gf3<pGN)-p6;N|a&;HFNqSsaSFfw+qSKT7)M&N<$3*+YVPB+R6E~3x4 z<b02E*k1j&>o^I<&0X5o2>+zsoyoCpS9o7?xQMn&PmVc}B|bg)+wt`M1#pYkJimLB z(jV>01LvsP@ZJj3^;F(uMBX+P0mi~5R>0oZ%E-_4bu|*PIkIxWuQ*R#3)^ZUyGF#Y ze>r1afrE-Z6pp<NRcLQxtIUyH@)aJmYT3wx$BtD@G?1<*4&GFAO!m}gTQt3Y*v$9) z`yu7{z`M(Y^-9cIMJhr*yNNI92IQngAby{9>$4+Yg64#YRCnQi3k|>P{9VdP>+jh{ z_=a1fa}w8@V$1X}1kd}}sB3rwu=SIUHOkF4aRw(Wg>A6=jxUCe<+iKn)HE^G_5Slv zmMLu$)NMJ6Lip2$!t!BAwl9T`MSyg|MG}tG7fyvb&~ZSsNXe$0YtqR<ty#aQC1_ZW zgqX<dL`a0{LLsj7n!?}IBz_x`XgAkQ;fGtg4NpG3zlXu@7BHt*$6S+mo2H_vTScm3 z3`USL1AZR8eaY>@5~+rN$r4_MoP!O))2rb3;_>9iJl~+zBP5{W(y4PyZSL}uyJjXH zCGl@)OMm(WFOIni4@MWb`G?1Zb+y?=sDr<Q>&UrM;@$Jm-j9U-MO*OFO^=B=8v|2z zgF9!AT3U2*AcuT#rI5xgawYPpX`boYLw(*W!CHCTNBva&2G6ErupkUkGK6Kk!TQm( zkyj?VY%O`3w>#qVF%PcJ+)<%v(Y=5lWhp+X#mfxt$zo&Wm;ub<5d?}i;c_~P&-z*4 zq0jc614L`%zzpuD_0P}3YO{tvw!TaFjt7ir4jjFbwHWbMn~0g$5Im+%zPu)}&*&FA zMXzR_UVkIWt521LnhR1nj!nzt+mPTz?N<?xOmx%oH=@Vcjup|aq>I*P@1~ZbC*r=^ zb?BuDqi4k$7|kgc*GqTSwuj=aKCGWnvR@U%WLt<aqwpv}VU(VaL7!Mx0FFaXs;Zl- za5Lhn<@_}{>C}SNmI#pycf+g|k~Uj8$$9Hy3HlEWU}SAcB~kfSg=4K#hgsaL_hFfe zp!Z=PPkFi35O|ul1-!-ujQ$L=JaK+njpVwv1hAp+!<yJ=#u3C<%QQ`Yd$F>@Ma>LM zPXH^x)p3C%{2C-|8<cAKbFik+9M7z94UH*CxE0!fU6<+lSN*TJRgW)!YQJ>B;#D6= z(bs>AVlgp+g7GyeVh$FhEzJn1M=N3uieK!CaN@~D<7zNzvZyE;<Qh2*oPz#Z9Ue(6 z83|N5eX7D0@L*fGA*XjbdY)nE{u5_0d`T<uM-5$Qit$@;w$@*TGfp(BA5Iv}2&-k% zyXNK)(FB3n>4k^5V#leJ{x}vQocM2;u027jh_c_|#7-OT<6wC($4@zD<gW>zgxwy6 z_g}Ko()6XT7aJj&=g4V_yWxUU#EF4N&*V6FzGa-N6Yt#-f`gA_z7Zif(GNPj(Tg3; z>8x*FsYJ0sl-gc74aPL$&^j@i87Kp@U-6#v%MJN`jx7RFa*8k5u0@V!V%+QH#cf5i zX*QJcrHa%dJa`cP@(wbzwYmk_N5-Yan969kYM8S4*KiodOD+wfQe{r-xGRSKDU@pP zQN0+xwN=Gv_y{sfJ$iobmaB=&YvA#>pG9y6uEPF8&tLSIQO)Q4sYe8V*)VP0HwtGb z+@KU>Mu=*hXjbhh`5E@s;F(R}hXVsSQ9>e-aDheR!b1=rN%qJy<3S0m(&7`;UBOA; zmf>$;&C&8WPYjazOHPgS@Zvnz^c`7iMcU^ckn!dII~7|;VZiO^5hdFXFLX@0AEPSO zJPNMg&K2Vi)y{%db5IHIRB~X&x_I27q|okogsaw~JOIwFtzv+Bm$u<X^P<T(nH>LV z24xN>x`^>8*qn4n(*o7Pjs2xlA#7esjGQSEP$FN5QTUuynb1if!QRiF9y_Gx1N;$m zL#Rdh+vM>eMw4N;6bs4X0FJbJcv=kB0uCL1Cc=_iJZ|Y49mR;;ywybh_DnQ^M1B!x zG+~0E6zw`S^*)Nka(sQMKv|!&E9rnAUIypS@&vKLR=?K!9OEb0ZL!6wq8HVX6N?Z# zix4wM+Mr~USl9W*dn%=hS{?3;zFW;gS@7Wh8kRg$cb-;H{oBBKmq{<f>E0X581eq0 z6P}jObxb$rH}W?Yy0y~i-l}O$z3q91c1fMp;C00YnfLBe-G-RK>g@h3;tW+F?J%G1 z>h}SdShuJaR{kbC4A|ST3J`&>zJ3Uzv#!&V-)z*t&4qT+tETz8R@B({a>B5LpBof7 z5&9bxcAa7<T0Y1yvW*zwn;n2(4?oB>?M9tJrK?KpPM#<Bf6A0Gwd1I>&*1^L&25N} zbZl7Dd^v-pe!!_-X5pfK1;1oxc)l2DQerDBq5XD9F|Un2q_rD-sTquChgmiMAP1Y* z8Fcw-m93vWq2xm%i8F#AS1pMpcy&flfQL&?^kIefoG|L!%FqLI^B3<nvJy^%Qd^T$ zoq={RectGe-*`15He;qJ4c`w8M&%8&IP|=b9$b)$MK9E|yG`1Pu310rq+tXqv((Rx zF?BajTZx38^_L*q!4aT(MR~Fa2_NeN(YM*HV;Q<Accb9^xE?T}d-sBPvbLWdwxDmM z;N0hRTltkO3{m`A$LMW5Zq$=E#1%`bISdT1-^c}8luHek1_r_%u%4$c6rP{$g0|dF z^@YB2V<Gy52kVD72)qJJy{97%kEPR_2lGS;R8ab_2C1Gu&=Ev*7@u?e@ap)3k)(P8 zw%rfG>b3j=RH1uOdZxFZhC0wQy&zCf;__Uty(@*IC%d3R<A_QT{jTIJvbNpzJ^rd! zqeMJUpJNmJ{^b^TD4G03_DxGig&NI!bb{2`apHI2)p9xlCQW@`c?RO0NHy@Cj>+pG zO=l0AR^$<N#Gytov0G>W%+GVnWFK%zMLE9IZ$k0((~H!kXhu0YIa-tPiH=^n7;M1@ zqQbMSp;@@CVX%yT?o<gy({DY5en~=C8PWSByI`|xKB!n4!^S|R&ihC3U>WY*=`=-@ z{0~vnCchLww=E+C=ea0z1@i8tCFbzvBG`S6@h1)+cRXQXDd=;+hjvYX?<Q{8nQj+Q zwqUQ|f#<I(2``oKW{wSUj43wb4X}Z<4BxI_pc_=%<XY_lejfxTEH50~yudV^{cZw~ z>DYm<a0Q+-(TlmF5BI>CZ9z8pBlCIw-&iE@{9<~HJM-F<$xTH6`L8LH{1TlBll%*g zo<znd6Z7M&j{W(;7!&_^*G^IJ*naU}1HqYJ_TN+E@^HORl0(Bc6ma)zLUdhx>(dmY zr}6ZESL?=gH;w%sP`C<B7m8Vy)$f2_2d__SvjJn|KQG%rK$$B%u?2mLB`y76Eo*s< ziS9Ac3-29x;rr&k#@TXt^+E3;U~56?YLay&IqOv&ozr3<KfAtcpLvpzB`(`Et}Cr3 zJsS6T{|QQeL%a(?!bPK!YW96n8Y2S0#mO0fWaPiK*oM3H$oZJqENrztZ|TxwV`E=Q zr7rG`=KZ47!!_f<g!RPp*pTY4u;2mrXLfl^Phj1G%0YkTe#l?C+@8%heK8P4ehvAx zE_3OHB;^RjsU-^eCJizs=lT8_{S3B1%@5Q6MXW*p9<|0AiMVEEOB=$o{hA*?i8z7G zHvG_f{W+B*BHa9OMXX$yhy6+<<WSufpT<gc>}xRJ#gNXQ0oJ$oe6@TVY_h~wE!`=6 z7z4FgB6JkhN2D$|*+pui)Rj+#gJSP4*X^n6Kt#_hcVt2(-PIpO4AvQffbfM%c{jhk zg1aq`bNMa{-_#lHqYydDL|e4(F%IbgPE*BQjt7m;q(8N&H<@GxuAO8FVqGOamoRQJ z-<T7{{}&`PNW!Yk$QwIt;#=c@;FM2-wA*cji9#(qtzwURh;k0D>7>S~vqr(G^Xx<b z%UY979hsb6CJG8l)zwLloebvLsLYqIif^Fvh%Y2FV4J}uv7h(4$qb=qi&)y<8wDL~ z8h7i<O(x$D+a8B5DqEKA9<+_U^oiHkK40B*Rd$+c3?#LSbNMz42gi0s&nv7aKC`<P zBl9ju(+G=k&?|jwqhd`|na|I)G!M-+G%!7`3)RR-E-ky0&0lrq0D3qzxYe|lGnv_T z8Du)>$1cAF2{?5cmx7^hU3T0#iG<_HY$a{+)_<l;MlOmWwEP^AwZ-REn%fS2;#bJG zxZHyukg`4VUo*P?mhs4I)L3WB+{UK=Q%l~fv+WTnZ1l<k-!||U^d=V$A?P)o9?UoB zzH>0{Dg*n<YJLM%ztNk_ztUlD{KNBxXce?kO7b#gB{MQ<i5^&FYN{bN4w|TmunQOk znPh6N#1akv3xYPxe&e`ndVs#DX-QL($2{tn{>FicpSh&RcASxxXHZsBfQVl~dz&ew zVBjk8J+>c$YokzU;?0XDb_4<svmi5KQm3HctcYW(oP$uLnnw@h5UDirwTJbJw=rv- zE8832T{`Q$o#{g?^0uP;pku$Adi|(v>}~fTY(y4=iZxkP_ph73&5t%Aj-?I<g6Gfq zd0zJ6<;b_WmNr>*r?({mS)L5@=y`uNt+ojj&oA!n6;P)_HUmTY4xTD^)$U}(<d?Ji zVJ-YJ>j&LGI~nFVzpodMOaPx?oztGkE*mt~0Bg_&O0z^m`l&yVu-sD-zPL*}VsG{I zUv68}LOJ4jZB2vKnvdw#J6h!lF!YTyZjacdn`sRN%YDE_j=z`ctQRkgdi-m~OO-$R z4w_;KKRYp;)5tDeK+X8S;4STtzTb61H_KdxZj<dQhbSYaHYH0Me7jA(^mH*4Qiq!T zYtFMmxZ-JWsNyGArlZNzSRR>Q1KWc6(enrtk#-XeeiY27_0hb(489w-dEGR5vMh=t zqaUmCPrf|4?#OQ**V+48{lkSc@;w16eMlD$V#+!J6i+#YG|dc=DoK1|%6N)<SY6>X zGNNM2m&;JkULk4cl!0%Nu8t5)E0vH>8+ow3RXX}5vRO|ZPI&`N2v})n;b}lwNMjYy z3COT<Ym;kU>hLCbW?gXMWtUos9GlMsN<&NYpw2<-!Tdn}GY`63|A9J?*PJAh_dW=E zMEz-vd>ZuV`zgH1NT7V4g_u;!PrTNpg^k7?V|p2l%;Fvil}$dz;tn-bB09ctMRthn zfbAJlGl8&98kV3PHrvl0ko#qV{ih<e9C@{UfITFWhIQNki*+aLB|8=c4ck)OtcVC- zgC(I0v9Wuf;EJtr9`vT<vR62ChHiZvV4O4{_}nMpSSHo<+tQkg+_|F?m3@UVAqi`< z)TPo-EYB+?00SH!QKoe(Yc_>J80-W_LB<;9cZzRp;#MWF6YJp#4F3y)HV{uv!S7^b z^j=LfI$0M8!AlxZ@qFi2GlwDmRuq_lC|j|Wa`rVa<3n7xAveUpQ|lv4cNcCKLFcpE z+UsOz4|erjM|8x2GqEy$A3ElYY`^jlyDSAe-hL;O33k}iv>I-2A9KjGY2Cw0@^s3y z2D^T6;f(n^G5p74Khn&W)v*MO3NL45PBPGkB<ICS<!AhhpKJbm60SxDo<u+7@(yPu zE^c?*?A+$ErJ}&XgmL>Z3c~bPWt?#==h9yz2~O=ri>MJxJ`oyAIDF3*G%+t59ME(! zb6TQu#HGK}$MXkh?bh{;^MA32a;yvA(M1!wu*LsgE>*UFbt#R)SF)~%A>^1@y|sy% zSmusjWGtMtk-c1|@EKWD_e9ckm9G%3!8b6qGROk3@5c=kYPxbIhbxPaa`oY<#L3hl zLNDzI1fXs!=Oeb$c?^H~NvB4jAgxxw8LFzHcd@Y(G|9zgWtwGMk@B4H3;eB8r7%mG zRhBQZJ4g^CTaQXUFv*2>*^3-F^-Ft-uM^V2(_e4U(&60XLI00b(f7D}6&WF^)*kwo zlSzH}G^8D*(CIJ_+>ZLEJ%X!9YJ=y!YHS0=;LgGJ;L^N1(TS?o1d*8QL)~AO`r4!v z&7YcWZ$c3RZfe;VNQU<1NcDQjpD@vBt)J@0VJJd{8*rY*E|74Xh^afn<am7CJfei2 zXS=~ArWLvQ3khx?As?VO%*nEB?UbscF05VX?@8|+e6KDi2*PKh`xC5%q6-v?*7n_f zeb=d66)j$NvMtg8dYfK9%5}>1>8O^viokA3<}Xx&<ByXW*koE)hO~G-eQ+5H_ikU% z^XzvUM!5mw-qN)D9I<J`t)yv{E4g`%*S&h@<T1`rj;$tk7>G!;kSgGO!<PNy56WB? zRNgoc-G?e9_`{mimEbxgLDxChTaabuThKc>__4)YV<n7Cgck}kiSykasFU$7>(k;k zHe`$AvLuq+o|dwxgvHnzrLqwl1leY1v{t4N0`WZIxuV$|gnSrJCe_D{>fyhvhjM;V z#f`kr73VDQDq&ZjL(;Gm$5zb=A8f5t-}>E?q3|@`86o3=9VL09dO3b%Y`L&0XWImd zWQ3kzsptJM4>G)+Gua6(=L(xokU5?b3EhHrPyQV~J^Q)tDhfooa=RzY&<r5!l{o98 z_7^l@+)UuXT!j(R<AAxSKJ1t#{5YJVmVQujCx>4AbQT;;Ld#4n5iyN__L_7l4{Noe z?Z#<W^>7u8r#&IOOf?jl4sHtYp3=;(%@KF5x{36gq<?);`jrPlgY>T}O22xKFh2xp zkFUbfKEmk@RvOWqcIMDTrHEZ+{}mL<511x{n{n1>=UASSp~fhaW{+;XGMg@QoRU*l zLG`@5@>d^{f^gM`7pDrrJ=F)?yoxDkG%s%TJfzaoC!Y$xDbNA}P9VEt3#IgwxaRqL z4*yi61TuyDIPJf}KMk4U=)hxnslpRW+ok0Y@JNAg-_uex+P9XFhMSLsJ%(!tF$?Z= zk_0~R)33$}ArE5*Ee`{?42;enLhTc}Y=A>}&oN+d3t(Rd?bN}k4aax`<Km<=Q7c(^ zfVzfb@*t{FgRI@oX>?#2ypWT}=b~d)P7tn-H8!&rT)V&$5CS=HTisT<Rvon*)4k+O z@Txhs9EGfqsI;)J*drsYewC{HJ`)vmQtghb_l#b&#}2^t!fLCy-a7!LErfbKSKvp3 zc5}M*!iBkZYadFb!hD<`Eoyks@i;V0I@?$tTICh`yX3mR?v|~DGjNGB+U(>&X=~2& zn6l6i{M?k{O~NFx$jrknefgEs4M|ayX^;GoNgLJE4{T}x!WPFRGjE8b9q2VRHD_w1 z1~J`3hr2(T8xPKHPiw1LA^{7QJ@~!Zjuk+(1EwP%s>vPdSY&xD>A~qLq3!`e_YPyX z!EFTDm@!gI0p1CdZoO({|12SDl9njZ>a3)MS8Wj^xbMI*miTJT5mLZy?S`KsrT#3j zh?IIQDl#PaOFC8h;%eH13qEH#Vs%Ri4HCEDd|>Xjz~p!N$BD8+CF6>Kjeio?lykq3 zRl%ZeU_E5F|C5!+4>2Sf$m}*23_;8A@Yv9hziYUK-MiQI^>)O6g_LEq39EhR)Pwx# zsh^K-&mP0K4U@D1tg$?q#U_|{#+7uW&(zWwko`asNFbG?MOxy|plxEO(B4o;V6?bM zlBe|Fr|kXS76mI-{E6ivQoh1x&4W_8o8E>_y}T}l9&g3FIJacm@U&6Rnb@3!_dDGz zk{8J&60S5#*1ZeLBQaNvaA=O)zs($0Mv4CXVnw&?;Ls9oq_5QZMm%of8ADLTxAedK z0n9eUdNU6ZpA*Ke@<`5jA{3|!)-a{XN%Q(i?GY78>p4smE)TzMk~$g{zsf+-6kU3F zflp2a&2|?Wm$e($4QI&Om*Yv;U=y}|u23TsgCjPgmXpXdBQ=$7E2y^~Wdn=9Lb=EC z{(i3Aj|S59dM$rnPf5GHDfxZ69lW;IRnE-EKD-hs4`qj?3@Ba0T=eJLt32u?U13@T z?wS=|$1_o812raJraY?~p0a_Nv!h$d9{53bhEAW3*jdfn@7USEpgVuiQ`moyKl~`@ zu6MDmd;6U_FiUOMU%o*9WcFK-$4{VqO8f_3`tug+h$XthyP{ANJ_(kq{4VIcE;)}q zz{EfI_GJnYy!h`>?&~?FLjroG8c8H_XK2zVK;K%++6Pj-$$4{dTnWDP`cQC@;CWaN za^*1_51jzH@|bp5j)4gYBOjC*b)30u#>6TBEqujn5*5HX=dlQf7r4N_0&T#Ix8ocj zId&f`L4^zsFoOX&qfZ2!+oJ*G!HPcoiYNd85~qtA`uk<Ud7Em~a){I7CsMb762P?| znHwO^K5`x`SBelo%cueacyuCj3y>ltQGtnH6+Z<e@Cp|pgFNtLf6jxYWQv~#$Sjb# z3AgJc@CLlLNfE|Z!~d(=B=F{I)c)rN+V6iefZ)R@h-A~{zcs?;qD9EtJussxFsRkC zQx+l^vYQXhLbnMdQ(SIe4Fkot{7G+)4QD;>-#K%`9Udc&zD#2<XZe0(%hy^<k`z|$ ztGX}0jwwRPnjjAdT@fP!lRpuYnOd^4A_B7$#2+D#Z}H;0g*7sMK5t4GGj;WZ6oj6m zr4J4$nFXIh*jS<s4v1c%MRrS?-Zhfw6V*2rMn9Vi6E$qr%&GUrg=BE6Lj(tQx7~<e z25|g7<~u^}D~uRKt!{CNSM$7e<J%kI^89@ax(>>Ko}6QIj|XxTOE3kkQvMo_&xV&+ zctSK${bGp}e57&=fbTQ;K8YW1X2yI&EVkz32?3z^_9nd8;kOBh;<A^M7E9m)IQavY zF{=BZ0z;`Q*bm`~5RGcSystNhSn_Hn{H^>YFoIjx(5{!#Wmo%_&1huq*zV<#p@{yF z-tN`*Rem2qm<^PQu4L6iET!pqrc7V~c|P}4N3VF`0HM#cD4R|gilF<40%m-XWRmKY zDik5Kb20p~jJu2PrN8YmyV^%CdAvJ9TEmwT#mK6O*V_6MPMlnH?Z0x->s-T1`;;D< zDJ58#@blNrNz-=$`zPiu&kL-`*+o!HK9ZfYuARG+u3;CWlM^yKob(yKUaEA{joK04 zA^xs<ZN*x3t!%TOlW;F@P*uI&3Krv)IZCo$?mPVPZ*ciw-}tWjP)H|S>z2nwp%V^i zk=gMVA5H#pI=`8<0V%~cfHm|Q75&8JN8vBqbuK#ZB#Qvnnd^AGFQCpo&M&b^TO8Pn zKe0!+(>f7xXegrlxTv1cEm0!6{{gYwKwq2@vZ;V!wm#Qe##_XByw*KWXelFVfq?*t zPN)(nlp8Y~r7DUl)giSX$S+mRDTXYpvyFd|Q7hXm!oZ@qMqI`y5ts)6Jps7Pt$^~} zbJ*|^I_5#9z6=C1lnb#B&+!Mm#eh{01F$H<pADIj?n1Qzi{x8xhiok8KQzE>@2qi% z$SZ{hNKtElbLNH_6SKlE<4+Bcu)?2nVthLTgHL$N127)=%25gPcpUZD3!d14^OEE= z4O7+iu0VblraPA$r2_Q*bOEJZ(tuA;%s232x`jIikmL_j_nBsq<pogR!U;!4`G5xy zW)D-7+`|3z0WbQIpeVeLj`{*ACKxz~MwTaBYyomrX&$Cls?pd-&lhC8g)^%R`d8K2 zM=x8T|IZCX_P-fGF5NB(iUF<v!>M!%;%d7JY+=m<^ng+}TpBh=-M<UwhW~slx5Stx z5NvSOU-=acj+dS+gxQm@YCM1o70--6LX$tHo2)GCNWP!X-k~ZHShS#<2&$T1l)-Ne zFW2uxgA?CmPsz~d&vEm?`!3T~2P71sk-V!&1c|HeSVJA#=spZz7Gu_>^v}YZIWZ>a z<a_fA@O40=i7V*gz-Kj0itd{nF^tII%ewgfu`~1n`<2wdsS}}PGlIoxUj|KFIdKWO z)JlOpt^HFV_9dg(M4d7_5uWZC)k{;70vm^{JzyeBxrE}E6eFN*e5+?4e4H{cZO*3` z9Z^XGjx(r9T12CU#3A*sfDBVzLx)@rG}F;_Pbp3x-Dt{yY<3pS5NK&{OV$s_1baDQ ziW$6%D-w?zJSuM`?47}z_kdhl%r{0y-2S4Xz-kmQqfD5Hh{}`<_#goPdML{ZkRoqM zaX5IDhCVlT)p+o)5Z+{3A49&Rbo>PtoK~)rfKKGtITwjiQeLClvDXgGy#)X5Db~Vx z-=d$)lCini1S>KpJycNZ60SoXwgISOKVXO4*0^Cz<ehjs_gio7ZScu(72m0}eW1hn zT#bt`(S}C&;Qa2e&uWaxkS^(Ub`Z-E8L?V481HVVmBUJ^!G9D3oI9V<bs>olxtjys ztW-EAhxDCkf}Q_e)_O8TF0>1q{7v!6vB`y-(l0Fk4f{KAP2BA3@h8+qZ~ogBsC)Yl z3Qgg*<-gT(I1nFyO3zc~+-()<kIkBRd2oYni+{B7((krdrQeI;kKRj%?hsL>+Nq9u zC$jX~4<;doU-FU;QHI{~dV{i|kq172+L=%+E|C)bc3~yM8)l!aD@Uo7+MZ7tzytDj zu!z1fmYx?oxXy_WM@K>J-=<DLa`L3NF=k^&e&gQ;*FZ;p+n{aWmVH-{&3&-u@P{%W z@2TeyK$H77D?o}m0W81@K42OX7x2gh5db%Q|CJR$p-;^UC{lEAh6bPqETH28JnU4> z0M}yB04e7LFhE^6Xcedea-C;n1^h$=kU<0t1E#gUnE}e?8CU^o6<D}{(S=Av!2FOn zbby^YDyXU+g$QW&694BWYz6?W`Hukv%QQhG*Qx)*DMLsG0eBLa*02D0Jb&Ar=`FfB zezE6A(L7f@0&?{;+{5(-lskR__QF{tDTX?lc`q{qh0rX>-+>m?te!m*!7soG&RArb zLcSXyb@e9Nr+;J2a3P%!dBl*@JMaX_g0r{Ar`*S;cn1$&e-Ue6EGrNbf6f@K!5=1g z+D?Lc>4>{A^fa&PP^--Sa(CNI+Hhga{ru#hEi!O+A}&ey;hZt&!3U*cDq=+rkKaUp zgO6e%=-V<nVT=!F!K<eF>-8$rM`in`wQ!W*eJ#FAjeo2fHl1(v3e$&e#^+bm^X8<_ zuWrTubAe}hJ?9ripOXD1#Xj$GKAZJc*RdU&p0}Ox@ft{?F-YG+?O2`8+)~(f?=;W8 zVtttG#P~FEkv<0h5FeSO3{H@EPB?}g;z=xxz*4BCrhR<)j=MX7x%#U2mNXB|rc~)p zJVmvme8Sbl;U)1VSjh;>CTDlM<i5F%Fr#r^dUt=ut>-mmc&(NocHlf8kMUC`#phPk zF`KqnN%@s+v$h+F3caY4Y{*0#xk~UoKjD{8mf7=4T<T>L1H>f+ZG>jEtkaG$6$uc< zG20=pp}}9`xLi4VG3v)g-VF2ev3Zq<^^K@{W31dl-T3U1RiV7^I*$v(#Ek5guU{0) zOta+J17)rMk%Ek&EDm18XJL2eD}(-Y>*k-VxP--bdjHcQlw#uGv$NS={};ylAva9F z68{flynI^g+nvFf2IOuD{iKig*Uc!{2GWlUP3>>MH^rSLS>l-VS#-$~`wA?bAp+e+ z0`(NYmKjH4<}hHYLX`rFewyLKviqB1b!4ITA5Q1u3X8JX8k*E{-3D6PTBnustuXt- zEspyblhM>_+enM@u*>|8240nfY4RVBl~vp&(Y@t8D430rn3c$0QeOr3N#K<F&!5y# z=kvvwbr56>t$-silKfxeT6;}h687h#wWxORX;%<ev5jcDu?GcDMcuzAsb3%E`G2Gc z-mC71T5fV!i12hfAGtb4!u(M4zy5FuqaXKEhG(KplcMHik4)J&HGopsO&si-8=ofh zY+O(ry{ppV-JUDqC$Zi*V4pOg2?OS$00oD5T<HR1_F|L%@D2by_gKAfAydRL+(F|8 z4j<Apn${0+r<mP$>sGjlUvL+ysX}2=<TW+ME5Bd(Z@y>eG_cJ~MQS>;jA>tTNZy-{ zyZNl9sLBqU)*Q{FffG*r!AEr|^C_!OG+9t&CGesH-&qu_(5+1EVZ@+ZV|>5bk8il) zz`m>wSC(<mtB9%lQg<pON+>}8L-{ss_Llz(UPV{T+umqGWQhVy6G7pK*5cRd+Jkgc zjuPpY<Rz1xNSMx}NYl1mY@h7ZcUSy%XO>rY=X(T2AAf-xx#Rh8efek5NeI3_F~a1p z=*->f)?)vi?zZlxPEOQe*AuUnr1w>q_a3q1!pwmCEN-W&bnNesmo6(bHA0A{V_K`8 z`Tg73#&Yr6&%@HLW4JV~Wr4J(ov~j{@%F(}^b$biSihay$GzJUly`1o&)U5xZY?FR ztZOo;F<2M}Np3)=omL*0?5hUvR7Drm<Q<(;*kDWRqIPTa2t5i1ex4gW{7aSSR7V0@ z=v$ZXrR&S--AJyR<4UYQwZno&=XX4$U7gPF*;seePS=bZWW@5vjQR<>E-F8*CBz~r z{f&h-rUL`X(g{?X#~SBK2p(Ru@)`;mTTc2f?dO2YllC1rpL|^Je+Bi==T@dJCIx+) z<xBfhm)1%uaTd+_xbfizm&&)J9V%?#uRPznETNdEiAZar+QXDnr(PSgbOg`h1P=~W zJ*N6EJ*QAE^>2;w*DY8s-JRDFTD99I&X0Z!*)O`b;z~&O6XK;xh6V2Z#<6|~nd(9k zbnQN#>sUUWSkc57Xc3MQg!5PS8c@6a+caO~GaA+7^ccM1`gqlPU8aW!)F=4-eRQ>O zgzfO*<j|eb`M})5Mijsar>4rhFUlfi1c!4Q7_HFusC%~Rm=<1DF4+-%NHmRCZX-!| zNa!6Ro=A73YCsv9L~x#))OEc#Gm$Ei^B1wMkS*XkDercLyEAsSE>3cc8UEX;V{bOJ z2>0WW74N7YP+gz_ao@>8<0<2I*!xL9W&drRc?4nBn$;in!R)b*`f0Hf`S*&obmA|R zV5;7$;AtR)e83BV%DkZ8wk5xD+-)AhUuUA#qRXgIzHc=+)nV<OZHVxeDaFJ|-@#^J zu$#AsLeoz4N{-uJqi^3|KJ6^CefS{AQ4W7^Z;!!=bHG8v`2Xlz!_~L5{PP1EkHB`= zD+4y_VDwlLdbLFe+8*IzLUASGi*AO|Qw!_X!Ja!lCyUAY)pi>;etKzJU_C49aZSer z=#R(FWXU65i8T6@?{eVnR5w?(mkePQ=1H1yt%h>1Cqy5IJ2C%^&KIXoOS=3wCh7+~ zwQ*f`92gIUk|^+~7a0s?cRtKA4M6H8gRd#ydHlgmZ4KLfJ*3Ojl?(08pxvPpo}C3l z^A#%3lcpoL$h5x=Zi6C^!-<!yl#(#2E&*v}*ajY~p5Jx#r)Us33q+Vq%LXsEapG<h zMf3~Sg)()~z{skf6Dyp6BV&~feifZ1Po0Qf$T~X8WFS?NHOz-~AU0L^*JHKxA&GJF z@S7Eq7D9zq%7U^#b1_K-Z-Gf_Cnn0P@NdI=3-+keGHE9emSAI4@uGjBb*09BQ81XX zVVUe>frEp)-{`<Lk>2P`=Lx?t>*V+Swq7yF8XY*XLzM}eDv|nqE=q{bmeG)Xo)y4Z z+-zbV5@`2FxN2Qk_$F1Kicof<RVEdY19brFu^#Es_~;R=qwkV6u&g3mo@6)>Op#<) z*nu9ABF@PvjJrlYcKbRHxqx87?O9t^*2Tt{L=<<}{F)ZlKML!T1|_T=vFNvZdH;Qm z<}xWp0^JBrHuHSNHiX|_8<w=d?sb#z!~N1|3wWM4;G(L%<3aUY_Kd*EZbK1m6oq%s zu{Vu?#o#0a7t$_7fs-WSEh+BoqV77cRK23Y^5<(g7Zy|vudu-p*bEG0hop6D<~*sJ z7~<GsmI{~H+9Dl?l%9tx?3=S=U1IAh`PNH2mWR4380v6aeWB)bTfg-4`&?G$c6+6- zc6DLmSi*!3bst{?F!l!6f|-TOzzjYGi@**w4HUMtoiH*edZ^ir;oGsGuC~>>Db3AS z%81rGnOZNupTOz<8da(*o{4X1%A9zm3RSdbyIv?yEfIoROPtB8)nMr)5dC@{OE*w* z&e$v9`g#OAG-$C~tVT|~RRZ4H`N=3b`r|3QuJfX<^Id21Buk%-r;GWz$}-WF5yH=7 zrsYQs%hraM>Q1YD_{D*ypTZV~`bmFA(i)LZVdaBIgHB7gx3Rabsdwc;iz6PCdg`5g zW#<0p&Pr3uI;F-}8;o&_OCN^l2)cnV&iqP_CP&n)MjcVi4A(E}YiM0|_kUu|*0Ef- zILCcg8Y;)~@!@J9_y&eAI39r8j}`as2l}l7&IYX<bHxd3hFjPKC#$wrmCb2GpE|df z>h5SJ7aQQFtgfb~Z;zxLRJxolrVR{E@3E^5&l+)}AuRU&qgDrl^KatcumU2nC6d}) zx4lCOCbx;!`ReH$VlGzNFCP4E;xDD{#1jS{S3Q^)>jYR1><3;?_AQp)x*^)HTyD=8 znc?LY!ubNxTaocI&KOfQu~C%I4+5Qfr9jdbh1@~_muXoVTO~e8vZ3tnY_+4%WR*-_ zs^{GTbClPaH{TQSn=EffF%Rm?J@$_AoVdP6?l}D1_nT9oSE1JLb&L#LiC#)WBB_xr zE!S9(hNZAUBh$%PNcdY(RZRz#l(JVU%HNf_!&!L@TWZ0uBt41j@8%o#Gh=9v>?i_l z=!L8S&fz`cNtzUr2X{*ExYON~q3?oTYe$8*vc$T3wV>AE_Z3G0vtNGiB<74LOHpMX zp%}7>1Q@*M!T7&=O_`#Ri@tMXcvAykgn7pXueo4Gg{<!!XUO1v71y{ly>NTmX8&$3 z$Kl%3U{bo8|5MMTM2dn|$S&3HEeT##XlaRAOwy%C_QZ&da%Nh>2TsSYYS@&NJ0{IC zzC15V+cx=5*Xb0(paeI8WVHnyfA~V4t6;kEiz+7fjyABA68ud0r&(U>7>*~TlIF3p z##J<?h>KaUWJ$N0RrRL_7Hu0E1&GG!r3n1RW7IArG<eZ{Uc%MqKW9)D?fw3v9rEtk z@Wm`_lxsQV+^&Dbqx~YgRExCSF?vyU?-v5#KM5fl9hFIa)Xj&hSajVbrjC|HhxupT znEnKh5Gv^$i-=z?&>|yeYO>=y7Tr*bnwN*~>Z%0S(NCF>h#%(V7==pT9h{FMXxkUR z?J;wZlu~JeU!Zj<!&Ouj%P3(+iNZ0!bl$R39Ki|fJDZ-;<$D;!4Yik8admO*WIZu3 z{5_?Z+)!hgg8JOI(u)jD*Np5k1~{HhwFElKP<nxHC!g*^@5ImYf4t9hK7MoT;UyG- z=73M|XPkMggufVVqHy+8`Mm+8;6<P4N)JHDTPPnNNm~Wpo9@mIIDS-4BN3~-HU^^~ z{8X@4x&;4yD#QN6$t8^U7E6Amb(2M1ar$)F#_zY^s}E7aR}RjyMM_Td0E!UT&5bM` z!E0PDeEWiX6w|V^V@^+9L*mwv^(1XS?$Q-XTiN9-{R$16w8#+-CTk=IvNc8y80MT5 zkP`Q_{QoF%8UHUOjvl1M6_Ucltc3lK5{LW$R^mGU!Y#07GN>d8L<jb`oB+`F3zF2q zzM_gePewU{&o?**Ur!<p&1RXarllcEm0C%k8t}tfO7S=xlX1)_Ceu^Kzh!kLd6MbU z)}4kf%&3@fJ*)9*D~hb)9$Sy|+{5lxSzqa`2NtkQ+%J#S<`(|{Q{yP^K(k*y*ARl| zn17O$2_&5QQ-l|7r@c36c^IF@kh&G2HC&2SFd<&jgrXD_f3zQkeG+e;9rLl)0>u4d z76TPOeY*6z$X)50Q2g3{-8C-~bs=udIDYyhs-d`XnHXIVADQyg7SLMbLFSj2B{k|* zfKj)!_33qQqY)1$-y^$^)!Mb@8}xM_(N8Z;{^DNr5ElZ;Z$30LQy{d5`C&&hvvn8w znX7sKBpUHKfLVL44cB&U9YI<Y*IxXugeQJN=+t^x;J$MY5zOtah}Y|M86c@~Y_cM% zKJb9Fw-+^E!T9L`kSYg~;BLxaqZJn{|C8UQ!c-r;1=V|xR3F{~Lx>a>u0Wz4il$G8 zLhg|^IZPtoVe-F1WEC{Z)tb%bUQRHCVZgv8?420HX{f7VzI`z~hBzG-br4+(W)0SM zFCAzsCZyRGsu<}Mp%{rc4@l|#C&|t4;N{<N{gdQ4wII0lv#KD|o*{U+%MO<cXIy^T zBi6r?(rboS>EYMiHuj%RP7(5aZBUCHV2nCAzUW^%O~jX`Ku&f1tH0r(|Ht9HJ9cln zS7*@RyOYW|$&e;(`RN90q>z^~bN2&dFa@dr5?@#@R1Mv`$4kV#XP{swdK{z>VfMD1 z(f@}QC-<8%z#Z{Ghr2bgxq;wq)MiD*XLVFSDUk)2oSqqNcZK1n$w+6<qog2ONNgYp z=A-x5I7fMSWi@l6*>~1lOk255eJ&{#d|7YOFMVAmcOj~T4xCc(TYmtQ!FpTag~90h zEkG=Wy|jR%DKd8E@8X|XLY9J`4=l10|D)8ka))Y$VH2UkB*VsqfWha9<oo@NXM9Ns zDNMq#Vw5Q~w*={QyXlD%WA8B<jS|Ezt(oT1A59&k)4e98$fY?I`W@$Ird~}qymj?? zY{STeLM4dtw&P?)rxm+h@dP~5n2>{UxL*TSF8bp#;zEeWShPgJM;g))At>Iio(H2g z^kEX}!M70fyJ1KgL|@8`7x(^_*X{0y&#e>&48N-4(ChhehYCRZA>wANZ?n13$rs$Z zAXPL=LL_iNLfux{@6~AqlIcpfMbWUPB$&q>W@+rGrjIp;P^fB6D`v*EYf7;eMe4!H z!GsitltxmhT8(3K>_8>jIVP9^wok}OM*!ip1nc$1F5rO@wB5w8?0_&Wl4;No7RfY! zpl~n-HY|JJr98<rBsj=OU4REtp<4ZCVkjZOt5q6>^VKV`V4GZ;LH@paB-0J*A|%tJ z>IjfJ)dqpW=&<bnr>WFrM78QV_>YUm4Hgm)G<L;EIt^f701r$R2|`qGif$H%Wfwof z*xaOo#KU=OB?6acX@v`f9z?8(5SG>Hri5juK+Mbe0gm(-C;T=J$Su!bU(rWPJ88+K zWSom>nY9;DsO(&~2g{{xc%>O`oPq$K6hz5xKfmiSV^l4RaHHSof+=e>P)(zqkFFb_ zvqy3Hhe`%2>|2vS$SynB#*Vlljdq+sCAeH3Fr|Se_;q_l6!&`x_-)TQ`SE!{dXL<} z&YI_JK3mFxpYyq%RwQPAqgT!vG_NWc&VnR(4wwQO<Z+c+F(BuJ4&cBbY{}n3D{Pqy z$PtM|n8r0aq7t?Q{|+)mKfrj=^V$BH#z8dj?;7RW0h4s<2-Di_I$*qof{enJD-|Td zmIoD3$5k4&fE>8#jQ`Ut&|~MbZMyu&mCOry9Q{UQMK5CctWgujqY4(X2=1Et+gL3H z1-bB4H-tyEKVm>-C+6$#>~f=~Ew6Mo^)<5b40s8+nh2hM4V%vPU&98$A;<Bk-qNOG zSs5I6a0pw<AoI@IF(1oq5l&}(6}HR~vFwcGSo66pm+a5v;10|d#xmcFDE-0ToAJwz z|7d=Xg8PgqJooo_EPwjwBe<Ew#CP7ZRmfpG${og_adwMiTBc#d_*HYDhy{N#uOgmV zNqrY=Y!19^J-C@ht?Qbw1s))YPS`?v2`*mybssBuoE^}m6)+Bp$bfNvFji1RlCbqn z$_I=?4$B3MgCf$5O4#B*1B%GuDwRe+1}Gv)8bJ|h28zglaZp4CjDsRFUc1@=j1`@P z?f*2Oh!nN}MdUv&P(;S#{u@mV8Yk*m_i{_lfHtbbqG?0~>|KKyv72WpS#0kcm0zD? z6^yep_c#h9XHYqQ8I^<B178x$pahMdCgY-oO)2n!L4-?Yl)qrel1DIo*LP3OFyY1> zl~b0d86D4$>sT<qT+AQG_)u1|=tca=`etsFyu#EO%c{zmXKu5kY=J+;+I&aT7(<=D z>YI#<(8vmEM+oy4=kY4xjB1K?@#KtET=O4>5*gM3dW>&BSv#42jk6P><&?&-npQ^; z@L{H!K#f)z94!`%1M<}ZS!FvE^2cYXTXD^y`>+v`apUaalQXE5EaG>;&7qgu;gU0i zGvJbO%k}feAxGu@nX38_;S6;f&`+0H05{jD(a0Y!i$h4(ZlQxs)^4{6WUXAFSF!*% zr}{t5!zk2fbZhp1T*b(Ntb08$t1`(e0+{9{5HwX#qYMyz>Dd4r?<ge;JZ?fQx~@if z8a7ZX$|q+u|3i#U`u~HXrW76&`ua$fEQCs*bK%z+@@%Z_ZbBK)gE$-I66eNe4W(k` z1W&iKEugyxG}AhCgE>_XBuA}NNn4=h9TwrRpu=)Lo^}V*8r1zI6D&^;T@?l3Z_mpl zwc<y2Z;2Hw`C<iBxpLi4mFp~T6aHOP>0_V^h}5j(!USz$;rBJy2J4%^eOnTpuxBj0 z54h*F5g;ad*U9g-X@@c<MQiSgW-NJagN~Nl>oDl2EgyJWk$g)a`YOPEQ@`g3=M^hD zu)NB_Y{x>qMh|g9y^f<Fvq?Dz3PPN(L%z!8PeHy$&ofS2g8NeaGmBc^@~7xH5bm{$ zZ2|@9H9>^)Lr|{_x|oo!ReH_Bc?+kQ$83RuAd>&vG<qF?`wr?V{KusdE}ZAQ1z}J5 zinukp&~FK_umuy8b!O=pjEG`sf%Pc~ZVV~@ouvyYIM-j-`_O0E(IdXiMu>>5hwhWw z<R#l@DTO1*cM*b30Ps27#N2f+GP57I(8lxkDR{a)mY1+&vS-yW+vrnPup-jHxG(*C zeDxZ=)3nds*#>ucO%3R)5(>Z*zyZW6vc3H+jhShkVtv-w_kT%(bOJUDdYzqwPPi+s z-fnMF2HqLgWtP5Jf!8h7`e5-3BNmbF)@$+i-&K4J?`*r-x804*)7uVg|3c{-E6BAG z<!Eo}Pv@koU5%u99i4x#K8mSbpK)v-)iRQZrOhbb!6?r+YK8EhB_JZyr83H}%gL3E zbI<-I>(;dU(^|1KYNvmMJ-tg}tvq}<jxiXHb=$GW8ekS+=@aET$TYIdduGWw2V>A` zy-3~LVELIionrx1L9(Y8KG~_M6fRHPm6=A<Sh43|UZ&Aa-3u{R!;vkrdR9eGEn81s z{Hl54JV_gyY_904gfyc8%URJPE!vV}Bb9=GC|nV?OfP<rGEw<=a6y}gW#lX45(U1E z?2;L{WM4}Oj|;Z0EjPys^aZNzSo46yJf}6x8tx2oZ%%#dY>K8}4QM$sufZX{zSuG* zu~x58F4thriKobuh{Z87zDAONI0xNK*ziv(oL*ccS=1K3UE__V#v@bl1P2q%+jq#N z&gh6ZDnDjjGJtV`?|{j*6lLqrEfpv`TDkIs@NB&n#NT-<lCo#_$A@lI6nWMS*~})# zzexi=uYH_pzA(uMf|6l2o<L|!_&~5asXK6~xfwwXm$hYjjZ9CZ*>4x=g|yexQplKJ zZ`icKmN=|OPSCU<z#`G%Ve~_F_ej*fElNTN>~wR#2&Tt=yohxSZb`R3j|qN|<Qr>& zX5`ETbK!*LEQd~>p_kL)|IwjS;zD3Of^7s%EBC$YQ*fWuns##u2#NbT0~6!!r&L9_ z%9mcHIxcZQ(~x5$soXvkvDiewpRyr}-)mkjcWTGgkVy5_s|!?jqbwG&Aon%b4fa|S zXqq6V+Mf4nZl=-&_*@lyxe7Ylg+QxNE(A?}KzAhKa#FC{J??eO+%YyF<E3b&6btWK zq73l<yp-{Yj!Ip+^E~ypT(v89lJSZ1m)p|>o}CZPjZG16N^KeTc+>knpBOq$DHi*` z_aN?Sh7S$pHO=kqHI6mzYko)x3i{m%zHs;+Q^jI4#l>A+UdCQF6_R8V82a&lJ|Es+ zQ{~FLy>Lg0`eP8s>^a}Q3sK!v)?P>5Ts;%-Hy*_{PO&llDCS9JrM>2(^AF}KKe3gB z!xew6O!V{4#*EtyFQ@*ye43c&G_$9Sfoag|K`QTiqIhyS7}qVji_w#eRp9P{-4UfZ zYbe%Zs-miK;jH|p(&(KeA#cuIYDubWz}Edxk=TH0t!HUCB8!T6E{_~E-?5mC>2l70 z%ky)e%CCIP<q=SGa{%fSUf!#V>qgzaSvYXt9ECgAc}UaA0evz5I5X4xay-=R&0>>! z(!U&DKRsW=XDt*65tHZih$R}i9RUBJ6nt%R_edJ97{1*?Nc`f<wC<V3*z;7<YH%K> z7bd8|K{r*rv{#>eOuUfY{Wrzo+ZC_xz<5mQB_=DcJAY5iuNnF6xUL(ITl4RrJe83K z6pkY(zO(ioKojZ?JnuphxCLL@0=NN$`rmaKzasVyw#@Fg9^48-rK)JYRIU!1y5r=? zh%85aV-f9VFU448tVUbmELCQ;A|vpP`9c4Q^C3OiS|sK=qpY9!R~3Kc)b+%*E?I)n zAp5#VV93%VW7mYX=Z4(+bi-?o{KSpn%OU0L7E?p`hprq`Os-3s6egqJ+4ol^u7lFj zH5QAji~_D$Ln%#%{TRxo`ysB}eUoa>cAk#A`X-VZC>;gmvE3P@Rm;YzB%j~1Yc><I zX~#bt4`*`-vfq821F5c5S)mydg4z^Dz8-{z@bl`sPZLx174Rt*_HQL1%f=nf0U<De zi@i^STS>?eL?%gSdG9PGs$iJUg0LS#O2i#=ORD~?d7jT*1iE;2&QbAB!Ffh7KTVVR zklXcmA|JNG;kt_EKC+t5babLoU^aSx84b!2vdxu0&(6*km;n(R#=%Tzm#E&{i9*kb z4Sf)$?i4GiJNu2TK8K#6hW0#`%0D?CmDg>EHhnAnAIeA<W7FjH)_lA|2uoj=IP(a0 zl*>N7=a&bQ$ocW6dN=w8Myp$5N+nVGfqckX%!|+r`$RMW9o|eCpSCbp0e#f{kBaP2 z!u#+ozz_2`F6|kz=1*)pV9<q-uS?X*r#wJMvF_t;xy0!0335%SsLkjN=6nlst=H%c zv{%uO{zs<ePpE%YM+Va6PkIi77NE>R&_%Cawb5ItAmj39qq<1lM_MJ89kAK!za9T$ zH>~?WXz}lVG_2JF(Wj#SJ7S(nxY66uzvq<}Aj}goaoZ9s@GE1-GPT09W03WcDixS_ z6f964lwS%Yjn@u@!2uJP@k!sg`09u5IPm129b4+1mGCwqu7#{0Qc*v%?2`#Gcd8{i zVkba~`X4sIsE4gzf#2Zumm?mw`t*Qs<vfSo^*dF-?`(Q*gUAh^wu44hK-^4OW}rJt zktNI`V0S3u>D!KXiwBL~c{G%ya+|i38a}hLBYRP9Sy5HA26Sp9tD3%SN&z1KWVVfN zyt+00uT$M+;8!e?pQbhz<ys4@kN)z9mcUlh%NZi4y2rlH+M7df+7X&%AlTBg?$GCy z-WLzgp(kDlfO&$Eac$;<srfr_cr=#*2pm0hvA>;tzw|@~R2ArPb;-3xI8-q}0D6lf z5CK-Nd!=1XcyR)WSOR$Ar3*h!C2W=UMs#(9p(g+VFj71S0Z?ILH<n;ZNtp5q0!rfH z+3?Q)7iaGnolCcEjV3F0R_tWOwr$(Cp4hfmY}+<gY}>Y-6+1WYKHs@_@6*no@BWze z%&PX(Y-7$*)vBtGKKd}>UYAU%htTx3UI|kCz$cG=f?2L-7$l&mXKm`9oRp0U$u208 zfOy%I%94>$qLeSN8+L@VE2sIf<^w?+`6jai-w4gs0?m4guuhrC{6ffA;|ucMrtD{d zlGXYV4B%%2XLTiP>pXg*yMnR0f^|}7k(Irwxj{gCv^P1-dTVE>MfKrZQ*CiG(jUjg zDzqLP0%G<Df-hE6rj<-yQD1Il!oEiC^#x?_=4laP5kLJB4(xdPr86S$60x;yb7&>0 z4J&X>ck<B^@kev!4aUP);JO=uNaJ7K?0s8-Ydy;iyqUKIdMVD~ZkhJzB9Yr0yZ4Oe z!l@oFCp6QE#$B8*8iC~X{=YSUNf~TfPk|iXkBMLU|GppB5R~}!+kF@nWPX!Ye*Z&S zAsx{<d^I~J){z-&pMIdjFOwB|C!{O-)Aa%i#WnR<W6R6e7v1o2jy)Yy`+Y^f4kZwC zGp_T!`N-COFj1XEUFJB1A>>|fDGhziNpKT<*XH{$lHma2uikn4escLj#4c&we30po zJ%7%VwWMBe1Ml2{Zu5PA6m<E@-Fygz!*u!fz{}ozeE;@7$yuO#eFa?W{j>WugcNYy zt=O>hR-;Vw{5ih(ea6{-z%}3ZyXv-Yt3~gVUWMBKIgjr76KuPC=k5FK@9%<bK3k67 zr|)AF&X8TcSDv}nhi_kkgmc}6KTlu0xe-Jzl*ry&dK>Sc+WiWwe(rX|6~}zjRSrB> z=y(62s|0<?l0CY8(^a6pvRFg@p{xA-{D-d6=UWmr^bcJnc=!nN>ub_4mxFmLT5#Ig zKNrC6a5tmq94W*!BQ_79>I`2mc)B~|bhYF+Z~G)CX!J!0<9%ys6!)~pI9Tm|`r%sK zK#`%w0M{PF#g!OiJe-_CxX=nrYsGk+$NYq`!c@tzs`?6gS?8V+s<>gqKU2F$J!yW^ z{s(oK)EQ6Q{>@)_oxSlfF3!9_whdXl5$AWYvuw(p7-rzn%}nm)Pw>kax{>M8q?s|@ zZ~UaJSe=S!7%!wq-Jic=xz+g_bTL*Tn2E1OhHShawHD3wpQnNZ)zk|9;jc<bgJ?cE z2=)W6*73i=6vcM_Tqw}=e>R#%P~Sr=P$QZrm4p4L(yrpqRlrAwZ2Tq>ePc4;sETTZ z+W*0B{sp@HYjc(a1BzwK@h@OT68DGykT*hO5@aJ^=`)iM_>C6Ky9Rg^14kaiBiimX zPN0&TS;mc-{=s(oGn3^%y@8#!|LUQoWaVRCDBPGOowAHVKbs^D@>P<mWBGGiJE)ih z5I3Np4!4~_l}G-JfymNsm#)-dx#73uj<U|&azkCOtWFrhK47B4s9SQYAgR()vb!c_ zagv)yg!`JDL1cw$JVJttn?@t*sH*<;dQxE?#*1yc5VFCQ9<7O(35Gi=PFE}%FgQyV zv758-U?g}yZ)nPM63U>~i<5lIUCtbEcuob8?S(<X(*3Cx)-i{Db`R|=c1EY%<W)A8 z+R8od*tymy|0|1e;2<vNFmB;cEC73gq?x+Kl!ZOuV`S2Sk}_Zgy!*$g6#0UxmTC5a zY6kuBA}PIdYj!S;5<jImGJ@cysFO>!X7-fHE_FpZLnt0@B@iH-XwATh3XU1_W90fK z(k6?B?JcQs6)T7@V1kmywzv};rCZIbeKl6CmG_(NmXhvKrDU|?xw)1s%GxHi^o*^y z48r>7cSrhG2bhuO7ePYv+}>I2sJyi?be<cA1s`ol-<qW2a@#L-o!~B0deNmksP7Et zQeW^hyH_M7osaaXZgSkM>9dj^HQd1?J?F}hxaEYj8yYTtDuwS<#uofu71F&{#yQSX zJ04G!Us?o}ziPDr3^82GiH(OFzepfJB+@f}Z_b-WS++Qu1Jfv_JoM5a|Ji2Xii~4< z!>-?*MTx5D#;wTtw9%<itb*&(QPFB)&Z3sHY_rEK?LMtgGC6EakG?Hi{{w7F`1<{j z+82ngmbHJ?*l$`&GHn{VyQXIGzG2Zd(&evowOi;#K0xVs7@%#EG?};TSaQJ2nkdBD z9$Q@|6%NGv!y+I1xZq#4o_DJZjl<+I-?_$*3(pl`**1)Kp{*52r;ZEX{9RY*WX}r7 z3w^K&3J`{L@-2O_snmAw%Fd%bt&2GzxF`d8f=8Nll@@)M9v@&6NewSyebm=jTo`*9 z-`A=$_iC@`)b-uP6VeV1<0Q~GX4&NM8!cg7K6h!E7rQD3%I8;nv&a)Z;z2mP08|Hd zhG=BValv_|H$K%*BcCI~ILZm&UDX5vqi~)&Z3<#{u7cR&HnUj}f|g*}eIXYDYdE1y z6})_F*BHgh#8M*o;278i(O^_Sa+Ok9!(DAMV475@mRY}l;yWb~J7&hHPtYu;#|z3{ zIVl})*iwGL((KG;ZPHgg8e4dYxz0$@>0A-Kq~pSKwl%zPc97}K`)y<Xgpo2W42cbn zuSYez!5j_BIe9n{Oq;1Sm;}Hgo=g)l0t3Gmsr<ZXvQ!-=y<g~^At^DiWtjNG`b#Q$ z=%-`yRSb9-2Z#>ZYVLS`eg%VHVQd3O6cc|ge$9MP@Nm(ti4biR=`tqvGqLKqT~?c^ ztx&TNmX!&$sK&i*3YsxjVeeFA1j7)BI5bD#ygqizUfy4zc)_V1=IqH@Ughh+>M(t^ zbdh0mAPE7>_)$y+vZsbt{T?B8+D^DGL9F-N2;hxU%-q%8bi+ybP~imtn%5s}E9+_s z3S;ab7RVH*+;L!-M(VViU7K3AtaAyAz+@6+yd2Y7qw=Lh6cmXP(rBIWzSu~QBzLFo zZ^xQYB%mBnSAb;AuEm;2__scI8%bO&^?>ox+Yfpwh7RZ2(Wt_quWGNmWi-t!M3sX{ zZ!Y%+OuB0=xYhRj9xxvnP~kHNtaLU43ImNR9UJE6<vSN*w6ScfG}~NvKrkV&s;X>W z`9tD<6)-wd;Xp9n@-xK4n@35IfK`PsItpqlDUM(TB2@QqvOwI@<BTkkC7={4C16gq z78erKS{P}bgcn|n+R8`><T;cT5@c}-oubqu^bHH$fTa6(utL-$j1dQ)D4T>9R(&r4 zeo#z6uZsnO)5)M@ksvy%aVhJ3x2Br%4CSJ@oRS70$=@X<99FYfQQ?=Sj0mn^#kUlC z(muTc_Jpc{nG@xPs**zJ4CTq5c<6Nb^NBq{Re(*j({p2bIA_rJA6znV5H<M-)LS2H z%KiZ3qdZVM?rQWdYo86(c|ZrI=hbtTWtQA}@bOF?*yQGnH9XZV!oA#}^%+}~+KAxi zjSIYyCeih5#H%SR%i`-G@D(zxq?|Oh3S8IT9Vg*PPR;m_0yeWlgXw!d+Ld!aD$@u! z!QVaHK*#x0#GnJS{AnpidY9Ac0O#S*YpkPQ4AkXo(^lJ4O*3&)#&*e&!2(0__;=Xd zK`QzeFj#tFX4?%s5O5&VR<=%%9s5Z*;Q`L9yzBjL82ZG&MZDqZgBi^+DV0il?Gw3H zdO-qPzQ;Fj#=qDB7M}2n;c4~qoID{r5H+Y}s6Fz;#u4RXH}ad4U5eFBw#E^trZ>kZ zcZJKHFYcOEkmOnvbpH)udjdYJPX$XG(ncOLbC`QhBHM?%cv?2jF^buvySWqR3>_Gi z*VX)lk|k|qTyjIa%uz^p_3q}Bpdjwc&d25R*3Bom+7cwV7JmsH>?H8T;oT@0HtdXC z(kyR`gvDRypI+=V)<x)h!hCN;cfT2!P(=CBZCm)dkj5u@TejoHWtMUeOGlM(G@1=J zZ=ks^@B*h!M*-EMd00nhPA|PATG$NkjEY)i$fwFSi*KGbgpV7(yNs%Xe@d0K0qXj! z6mb+5UDtEH0d^K2vPGbAFn@oIZ+i8?7ubr<Gp|Sf07~nQ8PCm2w?Ca`vUGt=bcr(0 z{C18q+_!NG&*~#sU^BZ@)x<kXUWc1;iZbyS4MA~O1Kt{;bAN828TRSggr;5+6);#n z9Pe8QB5r+2wR19SCx@AODlls=hbgKwiaM(lX!yGj9me)R?~TaN2;DxFnBmrJyo~Sb zlDscQSS;mpf=DhwG)Gr1n`E>~Hs#k;gA>+7&4+|V$tWEi@ilL@OkcsAExPV|<fFH$ z4x$I(??KIVM=N@p(&@kPa_xUo_s0z@2q_X!s@#qublMju3W}UgvpdhP>oW?py{(Ge zeJ(EaW6_TLFNWePC-}0B-8A6SYyvdEHz4LT=p8@Ybpl{IHl#oJI_%RU38>!8g0is& z0iD<HFJ{c}ydGDL$}L`n>dA_)XIY+d-pU;DDq@S0-}KybUHAF5g2UH%wQfhU9yYa{ z!p>(JO^9QoLYl9!oY%iXr((<>iJu?iu6cab6<16j=LqvaGBODWY&MC`2P|jt7sty_ zx=vWqf%N~u%uW0+W^S_0NHmRQbh)ITZ9SHRjIq4gB1L=vUdrU0FPdU$2W2%zDW`T> zIc9kQRk+DnvX$f*l{V{Ji^2MdE1Y*hYQ4!hR=Sn4kgL3o25y=7$xp5~6;&Lip>5^u z&~S~xa1{ui!el&$SkO}aM^8#f3wc6}DzGBD#;=1w!tCVX)$K2aC_R$jcVQ}@Mo1}e zKe_Vo1(`AWSH!$eqHXG-Ki}_ay5~Z_c_23v?V>T!a<&^U8yS1RxQqB+-I=@44SM%| zQez~F>qDn2h4aL?TKDya&xiPn#rRFd_zwr`+TtC=`%b~;<;9q7T(_nbIf=&_bxxEL zNe_PayR;?tOT-Ly7pDVr$FO~wh5Agw!>49hzYpE_`@FshyC#_5gx!*V2)l0-_fIi* zaZj9GVSyrbEgajoQ;r2D;voQK-@$2JjH<1y_oA`z!{X|pyQ5>PmW}*{b8Q-C&bgd| zvG~A;{ztM|?NrYP1s;Q+BT1j|t!%AiGN$&YS-$v$daRotEAYljHS86g#n9W9ihaqq zp<%{kKjTivC%Q`x+{SXeLyshU8Du)o0ux+m9V)MLK5nK>0$+Lm<h8p5>~=Kc&1J*8 z-`8dyc1H3Qd#~H+CtM^eKidZeB>11AaV-BLLx4Zg4n;B^?rg%%%bNP;D*FG6tEk1= zTdMQ*p!YRD{BySX=|#n1CFSA$PzGaQ#CIGA{dc4CXk{<sTBSfpj^hpyyv#5J5#y9$ z1!f|bb~wX=T+dx-mk8G+)Tv&55MJhl_5stt)!NbB|HqQbY<^?E<VCL{rZE|Pbc{|A znLbA#`CUkIF<msDi2adlnvxvfUAKoS#2YK#cVdMlivV)7-&E*T5xC0?qpNtI5jYza zk;o{zZCasO)IR?pBKawLnF(f8^KQ}%$x~A@`}xWq_ve;|sQ37cm^>riR|O~2>25}J zNdKIb6*eo~(}AT8Z7VY=xZOB?;E1R(m>*8(Pr<V{VhNo!#rrius&@o5C~*<cWgi@U zxm~pF>D<Sp5Z!pF;=@QSDU&C=3Z9Nkt()Q?Ade-pSvf8bfUW`_ZHN0tm!ua3ypvEO zaXT8A0HAk|G9CI?1Yp$o%=->*KOBTR5hXfLIX=phU1HgQJ|VobdkctYP96gDC75?c zQidFsm3!jmi--;Bt1LB=xu$1V)uVPimP$n)%LVoV+WO>IdvDqL>ZxBh=nGIIJ7aYP zdnl5Nz6$J@DnCb-mUxcT^yh_aia9~vB{nf%1DBRGkJq!CodbvAsc99?!{Nn!vC6}b z45y;F2rf)Hp#wA_cg@w)I0Ji<Db|em_<Ebe)8$6EDzHjL8Ka`MekzuNeM6B)U~pFC ziN(^Do5gaHXF!E26?i>xhh`bJZq-&E7@)0l9HpO#I%%uIWGuPGHZ4D_J*pyE2QJB6 zaZ^dJ2@Ak3HBDBbsw9{NtX8$eTeEeQB20JRQXQ)+>KHCN6khxz1z%L}4qq@)@*%eI z^T8{7N+*rBkyM9x81LEQ$~Wu7&Ew^zAN%xe+|{-Sf$!t|@}=xPW;;dT{p{xXIl;xl z%ge<*`Mn%}ba>cyi>$jCVRPW`-r?VGCH~FXEEklZg#GcDVf^h(ysd$TGFp5w`;(Zx z0()-R?BOS0y<PPE?NJkg&x_Xmi@S*k9YA!EH1vD)*!GSyxA!G^E4!4h%AD<Y9Swzd zKh-9Tb*WoqS`Y5<{JwK^y23KL4~osr=Q>x6ytHjk3L3%d8(Jsyn!@fdui?Vt%C-Ic zFty%i0Ybi#>)7fz`OxL7i5%VzY1<GxApTp1502Zf8(qrVJ>HKe+%$2$v-(UPKT9tT zguXN`Z<X1l{P(UjY}xl00~~7Ic<6awy*w74)TFL-k7fJQh}e!KFUMz3FSp>y)0v!@ zI9WYHiQ2YX-@VY-;ayzP1m1YvPfr2H{Oe#Y+xfw#t^1{jkGS!f;d0T#)_V``WTcOR z^oEu{b22A7CAO)pe-}ChMUSJ0TNIevpx)!y@Z`E8tFvW96<kKsTmO_*%yqB)t{&PV z7q^Mfl{DY*{H2P)s>J-M_X#&lucL>q88#4(R99}z?Gid$h7#0Cp2!}G-)TvAA4}D# zqbY;490f>(O&50{I$g?oHM%ETg%<yPlwZ(B98tm=zj!=%tWOc8-9f)A;The+{XfBP z5jR_**Ef;JTHo_w1SF3!9l~#MxT^V6q0PjcY@1=-i(n=k*gL^C2O?YQJQKdIzr^U4 zljD;=ug}p2viQd-EHt>={vIPIJIBkp0ko>zPmwk+I<?yp0uyrRXlDkzB`>~^C?LF$ z^eO0w_d+?I1O5!camiheZN<q-#^BC<SyH@K`CdnLli`A{tS6N4z3e}O-`qS2oP7De zj%9Uazb0_NL$kB@qJf#i-f|jVs2h?&oCM7MG@*j1^`M()$p2z|MhWWvc}(6-09*LZ zMFUf|ST0t!DP&PcS6zVyUp81G*j5cp3#I}+6!{chgFzDR<$}|h1ZK+uiu&j2*@dk? z`uR?@wx{Ze#^oZ`L_3zh%H%{M=lxl<FJtd0;7kL_-QF%AH(SC6qYYt>iCH3A`v9`w zE9D=m@(v~oj+Bw|CXQGVvoI^cx$ZzsfvxvzC$aPVr)LV)QO=Rg^UYKaUBN`q2%F-o z3KkziVDJu2#%^o{jTIT`rB@&l=C+-YH0Vbv{!1wemS^lQe`N)phgQ0*+=G;hW_U&L zspm=#QdMyO@e$6G*A8IP*zBtfHrxv*ixZH7Jh)lV#gO=Z!#VjVQBPTbxsY5jocBq0 z-W6^^85~fYq>?j>ZMm$}un@rFLpXnFAzWVvON+zfC3f=D1B4K;$ht{b$A`sxH>?kp z<+6pqVYSP{cskcSBJ?Hf*me+X5IfkaVbRan0&UrwkXTgU!s!-W4=c{(4DBogfD=)g zCkW5&`LZAjlTjk%<zz-di)@(*;)cUslraJ#Jg=9>&6(>h>@`%+Ga~4<EhgNzyzC#o zMq8sJFK?9u7v<5Y6t803*<&s{53R`cu~G+5@G*}6T3j!i+qAA_1*jX8vm%@h?4n-Q zl|n9GIIih<9Zo`rHaTCkgaEBD>oG_8mR2i7!RLiq3>1<QmzM?&LUrnzr7m!rDQC>0 zp2^la_#4=Tt=1i%JuNI|8yyOjw~XiBp$9CA$;>KUa)=W5dGMIYE8)s}$`&P{sCq`r zC&?E#e0o#^_|ooiB8GFfXd|YSf2iqw7ot$iflZ}WdQhO>IDcSd0a0J<VLv*J=2`9m zj(x<502Eg%u4_9^2$)KN14h~!NLKU|^czS5@k+b1ErUdmzk)^~)sj`}N>!H>%1PC| z70SWCI>=QX>Y^1{I;x0O0;kmy%U{*S$~1W<l*_?C!}66EhdCt|2UO$42MzD@B~_fE zxg-~Z02Gp7jTPkyD+=Y!&Ir>xIEpIA-O-9olc#CQ{FXJB=Iy^l^0v#v2MwDFA{M73 zMe?@tBfu{D*QQ!B)HzAID%%(vewa~N#%=AtSD#xe0Z3Id+7#<v=Tz6V(|<3T-j%6; zOx$=7J;*6kHdFATR^)tFIv1Wy8SJYGTuBz${^5)~ZqCEmpCKPRiY@BfY$7i^dt%s> z?nS7|_q`Ln@^3p+<tK(L+%24J<Fa4?S+*wB59$libBcHXkeOa!`ej#zy0sWFX@X4> z<&wt~=I7ncK^0d!7Ms4P<8H<ycn}E@$*0BHSz}yP2^4^+EMxF0>K%!O;L-{sb<l-X z=eFcBD94py&Pow=Zn{G}53GnwR-Ub)L`P*EakN7(H$%hu@Arza<`}=B=hl};U67(O z*0LfqYst{pQ73qCZ>Us$m-Dc4232)6k7Rlef9K(3BqfP*Q2AT}v^iDGe<z6E54>Uu zsaB-euJOxFT+P}xX?A+e+wfFThcBiyYwF-(vxlFYinN6<a{gJrRth(KU}C>ebzS>` zN1w*ZqQoy|jd|G&#+BXk)W>5{;Y?YVw|3TxsR^iXmK%^3pI>yX^UTb<T+;cj1Rg1Q zyy+7;!@R~OS7q2l>(#^cGb7zKq>Wb~0G?VkyYa!s#>&E@@N7?ZGjLXKb2fJkp>*A| z+RYiX_72N$QeRXMjg0{V-_K|<g|2WNeQpy5@K^Blo1@+pd!;9iKv&2&!^ZXrgM*9T ze&Tqr@AvrSxN2-4yyA2jY`jOME#^2wruiA#fum>Tp<Bs9+xc!RB<=A@z>UX4cgtkD zjgtgD0Ict+4l`Q-k*^jwLp5vu5Zl3I+uSkz<95!skoZ<a+bD0|q4-jgn7T<1YMd25 zw2uBIQHLj{jHMxd(VGP=RiU@SAa>yB<B#~3_aPe5o#w-hO;NBb7%sUC=Zs~BeL6e} zHl1=vlo6x#1ctGi!1M#4cMF<^ycKH!Zz0z}Q7|J`K9=36y^X7^qBrkL7S!iBA$Qh7 z`{T$-#pv-*>Z|yLBqjKyxgsvVHL>REFKMOlxS7QkI6@sQGnCeOeTVPl;es_A(@(%j zYn`jhqs}c=<-xff60SIY=eaF>^-#lG9d<h%ltd0!9D?kLvz<eDrKt*9%812m7_Ylp z;nNu@h$+;pAN8*nt-2!RQh_aRPRD|biXOOO;motf?27pa(Y%~g)7B6ey5xWt1`A4X z5n3J!_(C_1r$Vr!*#YtrNFoJWrBWHE0gvxD1}BBGH*jy~b5GZ4A6$q6ddR)R&;z$4 z+G=m*Rr|yyEboN($DGJYP>r#aFm>N>4U^_5$@D!vDFvKp(+D$Ux=%r@y9<lRU^iAw z9TVkhVZg`|>4{n8*1gJUjnWsTQ-5O9^NU)13;;O$<CPkCYp*Taj3zu#-vf2y7>-kP z5C5$|9}ky|hy!y(EW&*({XOSc&z(hfJjp*Ve%tUvO;bdmu7k8EKdIGw<n5AQ@;Esk zaL9)*ZiaaTsj<&z`6qfIIs#40`7+&l9{Y`%TxS)Z8ogCYY|%aIqJcdxxYz2ZTDU2Q zq6KY+KGm2A>h#|U%T=DnPO3xs7P!k9`|6GUxbsLH*9)E2$zP4OH$A^bMKxc`E9(w% z5Xid((^@oXR6+w$*CStA1Z)j!1r(+8ENBDMepFYrGc+a@rwIuUSu#FcIJEfQZ~Tq9 z12`L6(cXuMvmGJZLV{E%S+ioUoD5-qgdFL~67|zgyu4TWKGe|vi8z^{i3%CA)S?+f zM`OtqS!^YOXdpkZZC3)%*2P$;-PA7Wyl^*p{oH&JVJBQ5c~-lkl~tmMgLZ3w^QGJT zORi3!;tQbZ?)@$*vPp=r+<DkAB}SiC6Z5-Wn|rUES9q6mLQnUgGdbasX-#&YPg-)S zp%Nuxy|&T+c$ZoGau!BAL=uc=(%Ws>3p5UY+x#fq46!^dN1zbVz6Uc%&{tn;iXah} zC(v#HGl)HKrHBc#LAI(5-3&3iYQ3J}5uQb?1>SjD9-*dM`r}($G^%<rE{{^RpyV$o z4^M+ED%BK0bLG0L$FO<%9;~3cat)e_*%PW6qLcN-{TTDJ$Zz(*QcH<Ufs0;DVXUjz zD>12FgnC&%H*#UNodmE9VleqcVJhpNf{~73^711TYeV}%yAWhjDzCoV;*spXhXw*G z5@5~qdsJ~%-DYVObsK%(FFzkD*hFlYqkhIHi+_goi(C*dqrjurRdlF7B&0*%2Ok%b z=8a3^jje2SA+oZC7_M_Hv{6zSwKh7ni-@sKaU19t<3mu5)35i{-9wv}G5@H@v=?e- z$q}zF=CnT2M`V=4%m@_dn^{nGoM|i`V)Vhut*bdsC`)-N|J9#vVeYO3{87%vlJwUI zU#5ytvzqX-GTHPDaE2L?>|V^PQQvkhwzsfT*oAC6Mf3u8OXQHgcaJZDQMZLb1@${& z;CTEMMnWZ$Q^>gr(7d|A>=kgrQ2dMVX|NCbWf@Ss7r}mijC^2X5~};thnTZ3v*Q4e zA25F|k-m89gc*V-A<;BukY!?%f7l}0u+R|Fv0NgMO5!8=`8t*1na7pn!%0WnX(OGb zQ$gsAvCBdXHg?*=_mampm8dw~9W_0-4W0lsrxUl@N)4fk?;}4NErD&!@3S^nRR}cf zO^^k~v|K`r+1)e#vhdZ9U1G%e4PXhc<ji|)zuZmReqgSJ%St)pQ=Y{ER-$!fIj^>q zazqg<!^>0fKc#zGo6N>hN&hRqd|ZsZJ3!jg^+BOL(>89I0UvpL>0c<;unOM9L5*G) z%!j>>f6l4i{>7De$iF}=GKuZ%&wrB3#rLwP)!L}@zCKEB&WmD(q)vYqsPKAby6FCQ zUipX~i5Z#u<u`b>MCDQLsluczriL=UK(m^dsP@O|(YC*N_8RL|l)+?tiAAL0{|{^> zM3kK@w!Y0EN@PDCrW20>LXz?K7?1aHm>qN>^y-APVrQD~>y^qI(we-F=^BfSm;F1R z{LXk9>;FZpP?~O%9pWnSM;9{_tr(*hQzRw+tW8_oO>5pwd)!Tn-c6g{O{?BbyWCC7 z-c5&Z+<HcAB`Vvyiy4@GGE1BYV_#g2WK{VmW}6MpNwBb_LKq`oIbfM}QWmdtW*fd` zN~O)SSXE!J|Eyse<h6BDrVY&9E8e*h{yePWqwol<(pBrscg@D85n{wEXj^>02%ar} zJ)l!jtz=G{ygTkWKFMZCpB~*6J8Pzb(+Xs)tv$+Nav7xXMveN`-KJ1C5QbYqBg<== zu_zs8+^dt39Qq`WQ<Qo(#K4Xc_M>!1+&;(DnwUF}YF@_9(wpXdrs(Rbim_@3Z!h$- zJFlr`pq=&5t8(#G0Zy)5vR`oaq7~1_s!-5bl-&1xPOPc@Q5e2vhR1DEIqY2QE3TD< zr39h!5&A$(fck*_UH8E6tR~KTVR2iEZFz;OG-TP1UXS@ZGbSIv$moRi;ico!ux_W^ zi1nL%ksy+_=>(-M*ao-AoCUt9UPQeUL1IW+4=ZkBem0U<psr0OjHapzdD^M*3yX$o z^V0yiW~<~8TPLLWls>7HRm`rddlu6i%X{$2^+{wx)HZkYIsAH=vwPdd0mAMw_GNgq z3_b1UN?Fre2B3lQBD^-VT2C(U^jV*AF&NJRtwZ7rety-xDub3FF=NbB2I}Dog|P*Y z2q;#_kgN^CWtLe>1C?=!m7MY3(sxiLMw%%dJlj8#cRuUjQVG;?Z0K*}lmk^UFFP$0 zGKEuVlCzfqA<f!r%dkvnGKJy3lcm?%IjrVoGe6|{R+({zCQ%bJ%N2#xaOF%-aa-|} zE_PHJi<>>uA(a(tz#cevVzUXT674n;VXrh9&tB{}16cD4CS{GzsjM|o{`1<)7#k4G zmSQtnmG&i;zT}Q1{#OQrnv6|P$L)?BlIS$ncz$WB@LJH-J`gIbFoOH1)9d*({;ccW zwz>?>Mq`F~5}O^KLGa8g#)N2pS^6zu6tm1>2?mPHix9m>@w+_`i_)YQ{J4%riE+LY zIZOPn(-|dKS{fob&7iFjF<&u;DbDkK<W|TJ)WK}7<N!+m-t%nWy^630o4}6n+$J1j z@JfWCFK^t@R#swhex#=7Lfr#1hNyxaD_*GkTh|wE`K>EC%gy(&#CWo8w|iXEQs1#S z*IqT=siz2%+aV1)na<kI0+dDN`s}$I)i0<g<+~B8AqF3B>3rR91wg*c=^BX;^V^#* z2ze<GP!u2_AV{Dgtte?oY?RL~3?QH<cOW42@1u?YYiBEfjU}Ctt&J(bOv%KFp4QFU zs!8YEcAq`|tIIdofEm6$(1-YR*k#|N!|uXu&C|tjMfS-6J=8DGJOf$cUOqA5LeE!) zm_(}i+0OK6T$;0NuRy)>Ri#ec`(s!s-N{AyAkvJ_b$UD7nTt8XZKD2RdQ-4^%j@d1 z;3=gBB)e+GL%`&kE^BHz<4q4h%(eYwb?hrPB_MeFo?du=d=*e6(pMkaf@+4Y;qSgQ ziz1Yq@D?=0)Z60T@^t<6_G;rIE_f$iTNNbR*7=e1CK!7Re+#GwmTTcINSkQSI=n;k zxr;Kk7i`b^B?T}YdY(sT3itrM{~GGgX-D6zU8Q#W(T4?FUK~J*LSF_xDv0zeh5pgz zyR1%HRERChZ*oQ`zQ%-y>pK#;HXcRsEm;ObIc8n)HkGWbtQMsxCQ?iZ=B&;-3imeJ zIg0UE#Gsp@Ih>izu+(syYa_1S?)*d18L$3?l|_7WHQ55edfbm?f??TXW(8zkzPHo& zy*oL2=yS;Qi4h0WpO1?PD8}Q+0Trg;pLtm*#lCWbEZ&LS*iw`zFswGXA!@~%>3DU^ zq)H6xua&~W+Z`<vY(g^GXupl6;`#g-P9C2v4hcg(3j`rog4N_Ka7wpSvw2vWbGXPK zqR$_@kb7(KGc~p;A!VZYa)$oOA^r6ft*1!B#_K;Rw7X6p46!<eWljvotvZQ<IwAWl zQc<=8(tFpj_h<4nNUXN5G?BnGqF&YO!*~)bA)|4<{Rs2-C>r`k{X+svC;Im%`BY00 zMoRw3VP>^~yY?-H8CBQ8Ig4b>$Pe@pLB1)4=8sEO17<w4h`$r<sgAMf3-MQvqQohe z15DXWnVZt|nRgAVu1iDqI7Ta=f>XZ>r3C874|-WJ;%$(_Sy7(gt?ZKh6WYM8%|1np zGH8^usOd_$!Fk^5@-Tw|&ds&_u*uuYxSWvYJ1;$AUfv}iahp<|2=|IYgrm<#(~pWm zSapf!&=Ezz?GhrQ@%GI${LNp<HC(|({XfTNI(x=WH{S|<cI`#^;S!H>E*p`P8Grvs zvk!sntwzunK6i4lrQapyO-*Z3D71!O&Wqt{O9==?WRMdqGSCOe?`!vX_$LKu^uaeG z*0VIS`*$K7k!Qj{+CrC^7&K7x@8g<wx_T=04=zZ7v^&AP6<f?U-EV8?#s+<a1`v17 z#|FeZjr!XCjkT3H$c)aX!HrYB(Ef-<hnKL>HpA}891}EFdGhFxMGqGocA1>2e~kLL zIxS3+b!{#2YMw6c%1&qZFRGopMps21Zq-rrKw%paojir6ZvMob>fe*F1a;Y8rZwOp zJh!_Csw|$7wj33swl9lZHPy5`+!FFa;0;|hHNhG#u2AR#lO=m#2SIKof`Z<I8&|F2 zy2+WxnG59)4T?yt{~|Y=b&?9L)1K!^v$Nq(I3P%U)3yXn7l7Wpo8B}R0wUFR$d->k z{CJNaMJ<qktrucM*oO7Vo+o6h*h057-z&;gfkj>b%I}z~kp_$nI_j0n*RFuyRfu^1 z>ee6$uO$U`7VT#7%Lz=a5va>)b{KI<nPx{+=ZDhFw=)Ie+Svh1wFIX^6?*^C^&ES7 z&Q(N3*H4)O6@z!gOiPHIs%}*=i?tC{>fs{j7s=4yEFRB&9u`VTz2i3~)JBM?I2q>W z+sCLg2e%5`45qAGicy{gCk&!!Qu?BgP~FQ)?1%po2qoTak9r4}BvTynP*ODIau%dx z63G1c(Bi`6=UpGmNZ^CxJ=0VVrQaWy6AUJ!b8WoJ1?i^9{fyv)fJ)p7M~zBV46`27 zMr0im?06C8F5=mK$j4HyG2B>l5R`7>_w1dcT*MC11r~D|EM}Aes8vmyGb{@@$Gt2p z*6+IUgw`jXFh^qNG8{ZDTgz2NMvx@m34HePGp`Cjc3oPWOwi0x&C`ztC*8}8d^yw_ z$*NSFm;N{cKEb)T3f1!TzE#V2Fgg68PE>4^jr?cRtb8#3or<eGq74R|*~Cr2>hXrq zBmOtQ_<xciTq|?R@eS;%(ii&M$HEsbs5`TlK`A&-6ql4&n2^zOOmeFF6~2oOBoqiA zeNf|Vk-fwlQANM3;>J^@G-=j_%}P^NxB~~`#BQK&tH3J#fIPzDnD|3IpIVEmE*bAW z=S~oPVgO89vyN?s?dMb9fW&?2m$=kSU}bAzSEF-F81dWgg4NILL<ERAoRi=2Oj;P3 z-|LCHBn3=J1+HPWYePmNvOI!Q{6QOs>!{ujHz)8INS?g+judFYwxtf9?ws2P<&A;4 zO7I#cIP(hw((@{?c1OvUQ5c<icw^^>kHkJJ|6_aZtQQA}(P)pJ(yu=z8Ac(nqQKw} z?zMSwQ;=rd4MlkN?2^EDhz@W-L#t=$#=G~9@l^oGm(2L*_-g(NpB~=)c`w{_SC#t@ zRQ2){N5g9}de-{p@awoR*c0pcWLO$R30dQTlMjf53`H%n++BBeEigla`H<W4CQWK- zPH8UOL6h};83K#v$Rw<}vGjiMP15jz5Xv4?3lHZ)1{9!@h9*X74nx<Lv;EQvCb%H( zdx^ee1^5bHC@KdlOZ{quOTp);=J`xA6&SKi+)_X?$NlvLj^T^icqU;U!Y#6qU=jY8 z<^j@VU4F~;a6ti^$hCR^#VEe{dyV<X2<N^&EYY;x5I?Ex-V7NsQ(XDtt#pr@F&5pO zeKVqhAN_bi<F4UZmbF9#1L@i1-YQ*Qd<pmKjRUoQB@~Zo-Lz)b!tRz{Y$InPR4s;8 zRNSsgG6?N9egJ5C1Vvl`&#rz%kTPytvZ((ew)%uhAO1%tQ2$#5iJBV%XxE*ia<T0Q zegouAp4<Yekdg8)*fAhgoJS2cSp5{jB#P7<?jAxlFG}EEq*z;wf`Fy76>6t2&*%^o zL5yfJlVinx4V)v|4r$C_bzX?ZNSs^Dc`8xV3+?UR9J@SJlu?$T`?F(sZFTPOdSD48 z{c*1`eR1HuXyCxX1$M-*Pt`P62e|}_aV5fnC^hJxVglk$O+{)B76MTPM<aq7KrEo@ zz*LYf(|ASTb#Tv|-{C$J<gsG=g&&~LVwKTdHcXG-!t~nQJOUf}L@`5iZb9_N+5&L2 z2brI$^pP>rOuSyH`x+0wWAk!)9<{kkp12Km1eMgb_Ut8n4)dX{&<4@OPB~3kR!y?9 zF}I(41Ov5SI94E#l=PR~IO7TYr{2gz<IvZF+c!-L6p-Il)<J22P0@uQz#JjXIw$cM zZ?MB~SP3eDPG(ME7AG>dm9w&Xs?kxuZjo$Mz?~=UVT|TjU2S`Bsqu~0CJ{~sapz8n ztdh_)1*r9CP5a&4{X%T^NPjb&Ns^D2*<Kq;GfXM}DW6{Z(FW{^FR|hqeh<B#J%cMl zeeA;@#&=(*T(U02aNpo2+Y+P^0(uLEmw>DX4b2q(_Cm6>!#>cmUCH_ODJ0j+gzi+z zR)OVM9gj;X=mvl>&+yGlEAy(*v<FB=wcoEys-Dqr&Bk)zl`3%wv$jo!Ya4;8$5-H@ z#S&K7e)z}mS|`Eu7l5oFQG(=YWbux&`yT43wETR{uxAA-Ayq&PZ0kN6`<*;2cQhmV z%S{z}oGF%v!3`A@by*lKfY=X00NP&=XfcvCm8;Zn9kbU<5YZ8qS6V{e4v8p?SK#w) z_DKbt|JbD*xiy!SSr^z9(sLXmn_^hijzW-FT<OM<{3D2)t_O|;D4&gZ9fDn;Uwy{d z`Hur$vgDe#d+blB-RyEB>T+~VDqo<S-{okMQhjp}&_Xj9J#j(LDsw0o=yi)Cgs2yR z<~b&?7eJPuwcs>uDrSo$kgf+&afoK#ayR@}h1`Ejdbt0x5gKA}el)<`<OV-~)A>+A zlIWUogf2(Xu)!v$_+B7~)uCRt9H5)YGVB^J44l%JJhIhh%lWwrXY)9t-~oy%_q%@s zb5I&|#&cOo^tTqrgt&U=)3qN3Bs7d!6<R_oP)Cdk^FGbYFbgKPCK<jZHrwC_WWB&l z<BfM*+d82VkS1DQgR^!a(Cc`AJIFZK8BlSUox`b<tPW$Dyx}R&Gjrxynpe&Ki1&G8 zDC9y*Q<6Y2x;^S%y6w*4_4T+r6*{irQ%AcSexDERUPV%KGexUaIt$9~R3vl0O6JV- z?8Z@SbCu3oYcM-2?9x#xsd|(V?>9XTioJS@&UjteobNLscDxj~Ae^Qcv-E&c(v$J3 z<zo<Qs!vI=%wA*doGfQTL?8CaX&dB3cA|0v75IS$MV+eWnSs*+j5A5o4vE<X70J`Q zbH*lfX?MfXDR~XRIcJW;P!OhB0E2SSe6>Lj#V2^@K_p-<IOD@6JyH5=nxh#ubL9pm z{%p!J@JA!@kcrq|Cb^16OEl${Ur9}FT_I6s-}tAsd8CrodFiGCYl*`vjZoR#Pxyr@ zuAxkp+{?n%@N!YRr1r*!vYQW5CjZq)qv(mVCQYr>$CQLmk|pQ@B7Iq-`GXGHImUz} z?8c4DGSC#2j}~J%n1`&edPdOnIp<$bXY>vI^|Ikv?63H9G+-c!BCssn#<}I{;f`hJ z*mOA+eC*Jz>5PUNd>Z?$_cDbw-mO%}<!MXtE3I=%i`51BB4+pq4!YEfoUG&ycF=)n z5trL*IYM+{(Y57A(_Q$`I;E}DZodf2%?^Hjh(e_{6U<Ro3cH@?=_tn4M~Yt&W}RC) z)JX;zR8R7H=7Kv?-w#y20!j%CrNc1@t#=DDYdr;mg!bV!<vC2zRmz0hY%CIEn{u$u ziM$$1+0<r-6gWaACE{Q+QJ_h8Im!~sxxs6%!$^5jyE0kBF0HAgDh(96+Ke=a$(KN5 z53caO3=iLeO^qhXcIr5D!PTLTO=vdu3J8^;a<x;|e9T%o>g^Y;D}wt$Co=<R6o<px zqVEbWZ)+Z1+w=<z9aeY`e}+tB0t0atQLH_l2;X`@T@1%u^MS2UPKcmsDe<eW7QEa- zs28OFdP6cFVK%bvprdtsJE(AET7SlFB&fZ%XDum(6hMcNj>n+FAPiqtl{@wT*rwaY zb)-5zC{9%{SI%S3>=7pA39N`D*Z1S!`wXA#OK_Xx6{Ez6-=c@1w)(?aa?F}`<OWlW zJHoyD>T#*nau>Nn8RC>Cqz}3=V#_UX2xFkbI_2=9dkrEb-M|`Gu`hf`1!MLl|LKh+ zS4J5VZ;@Hn)hS1A$I?Evw6^@UJw|NN;$)(GAK#BKmFvYwpHSB-rB0gpLlvCe_MUf# zCoR!<MhE)q5AyBoTJ92luI4GW#}Yk(ho5+nv3%Row4q9v1fkhzr@^4_3TenOw1g23 z!Cbp~&fksEg(b%6A`Zq1(sx5Q4Otmm?CGLCDAz^W0Ca}Ky{Wg#AQS%6R!k@qXf3b( z_g?>;CQYT8UuwFhjPi>cHu1pQ3XZcQ0!32P8z6j8c7Ru`B`3vD(I0sR{For*ITxgJ zS#1F3TOSu>xXDcoGocR+-y1%4XlJ?Fj(#2wTTo=IE@}?B9#h5@nneTTt(SAZs8F7{ zUznhqh=XK6!JPHPHnvh_H9m-=nFXg$bOd3`FEGdQ<IPm_=Ig+$+=m{;ettFUZllpR zK~i)GxcTFIEpGzHAdF(LjU8s&m$QN0E9>TWxtm-0K-iSovz?%|c+YYvy*P5^Qp8)8 ze}f2Sds>H5L_VYZqmX8g+_l%_NiNTpmFk^!6uE<@^BQ$^0KsEqb2YLB5b8KR`uf&D zhd)!{4mbj`fxX~&&RkH*ba&_Cc0M(5kGvp((`^s9&a%{d(`0XlepipvKMmMadiE(h zl`EG{O!BP1T2C}Y1ooGs^8&ff!V1SYcpaPh*VP4hty>fE+Tg02M|%Bz$t`+h*Vwe6 zuU6ArQ1-QjInR`#2GF*grDfQOJ{-l>Q-=}A9c27HaQBx35U>}O+_z&G)PYydN_3uO zj**Ya?olp3k?>f6f>gk_anZ#mvmsYz8HT@sMV7mKfq5McuG_=H_?I~BfvR@2AgpDc zjWy|u7BrMk+5YP1;@)8b@ZRo$+ktc?x(2ar=}q7?8UO54cP_p=eD7I9r=bX@zZyR< z@VYa!FInHNQ&&RzoouCxaaUzbL%~Q!cl4F=?r*BTyPh0WXE%LntKPr*DlfUBUo%&- zU69t}6YfJ!WCL4QwO)`J^IF6gIzzzZ{YP9>Tlh?v4Gd#AevSucKLval&r;<e%@qUY zB{HvfRw@=wvpvH3$^Jx*2N~#IH}G=5Iq)3(Bau65|F;KW;ku`<4H>mw;Q|GzS%$Ns zV}Tk?asr@kH%1LgiGisL3+7AaLz_)Yo0j%fW60z;uJ@0=V8+u*pd|CZo4nBq?A9Q1 z&!M_#b)hsgTm96_OLdK`dMlTm>D_HUEO18)EF3+IzAQX$)q{h@?>T!g*U-eO@Yjpv zsTKEb=?{rhJ+sc9f?ZfS%#w%uvDcqh%mS28F8Sh#YFzG<Gg)QP;JwsCWlo;V-ikx- z@MyoZ)7Q$#uMoRHj!&InOoYoGo6f$Uvtbol@#3l;a`O;CYs(H%8}m263ZI&^OP-j$ z5kuT%6fAF0%_Yy-d-p#Zy{R2%1UggI3b5ODvZf3U^5tM<cm4ceU_4I^9u9%En5Gnx z=63qxH>MiI{IfMq7JNF1huCa=U!;#qDfvI9G%)oo^05YikB|K^WA%>4!@m&5{4;%F z$NWz^j+tf07I=8T-VFUQcz27=KJVw3dOOtaid5B-j7Tu`XY7uU>d)Q;W)_sQkb+z; zy?>0XGZ@aFIhZ{ENunEa<sa*}^Ae57z`k`WQRfkkta;AjCR90b7~7kK7DzBtg7k?; zl-9}hVSYI=k-*pb(&g#Q4-b*OMuL@7y&?34Vta-&intN<d@i2^jJYmcaBH_Bb1cGK zvUc$ivoec-D6kqlZQ|+rwI@^@$Y#-Qj^6)0d00cU(bqwtdT>gLaUxv^OzZI<uI=je z4>?m~`n{2QjNT)vw@uBpe?E1&H^xQZbFZ&`^TNVE5lE-U>5EHe^LgYaJlW{$Y<e~X z2ML|#HRQaem-Ha=r@ZGmE~0(}-bqHq-f8WMxY04WcWiJqbXxXTxiv3kyl@Vur=U5t zDO%ezoh^6Ijt~-!oX~UVBK?5>OGq)?1DMMs;n$pWTQCp-vNpC|TEQLxDRKL%q%#ap z>fwncu7Bnw{K}-#*z^Vw@YlG=CGe(pr&J#NLW1npBjez%({)8j*TW$=bF?nzuY{1b zR{<yI)n1s87~nuT+~e_|$gK<b$t&Xv2~7NXgtZuo(lw=)YFAMk;9@^Wzbo-=C}!NS z2>*FzGH>Xe7TjvB$1F#jcx3lYX#Pxwm>P=7iYr|6YfG1O260hLHKXIID7Tm<0@uf? zi^S!@Se3P|4K#bhBTTFX0|W%+?&1)DuucEOxdF$4Lquf#edfq@#sr;=o|Q4Dh&c@B zlt8r}e4dKu{ZLQ_B%J1<qkC1fWB@?zj{K7fkM1$A3~|^b=UGLpN@jr`{Zlq@&gdkN zpkA)sjEO}x>j9Qw$o!WBp&(Z({1;myO0k}GBmcGfp1be6RuZE@uf&crRre+}`i+LS zA8t3KuKoeQ&c@272QPTWxwX7j&o}>sc?#+n(UQ)d=%iM&J&ji%<qrJn<ve2fTF=+* z<MC3fB(`{91KZ9Bf7J)1DGGWMJ>qqDl5h)9rF`31ZCkPn;RN5EH@_AE^jveU{XU@d zTA09lFR>-UEhEH!<8F&i%AA;cV`xIHFrL5*hgKPRIz40%GKE+HYxtemLGIspX0!E= zVD7ycIxpAk%|w`2BV9XZTgGa#8)q28hwJ&2x1Js-OdB@rL<#Y%?z_VBx#a#f1(i2f z)Y*iriu%G<GOr1j#egE}peyI`X{E&m4dFvn2o*nQz}d`%q^16Tye-cY;W2Z-ADY}u zO!1qaIX2f>-hPW_zJy&MH!_up<UHKa4NJfOW>r^H=@pzm?uoVE>u*bm@z8C1Ysr#j zdxG!>^F@wp0lEn1H`&ri+n}eV%BSix@UdDos<hQ+T}+U)yIY$aeQbrHeB?CWfRZ?a z9L`XD+@-poJbo;9(IJDBqHce=oM^v=PiXa<gO~1eRMEjxU@(FQP9tMX<EnMLJxN*v z6MLE*4h}tSi<jGPh}g&s8QJ>v>!aOOlvwwPNHG@3)*O2!OorVx;Qs-ZP9_*&R&JED zSl6m?%QZ}sW7L)*QyGV!{IP(>uj-?a`(Av(;q7Spq9_v8_P%zqs<qx?;*TNl4ZXie zP{uSb@Wz}IP<F>ymZXW=7w*n0`yMumt~zPK<+$j7Vbc~^<iXQ|a<ED@?aL>HVv?Sx z)la^XoS|_pPD&Swk3Iw%>>P1kPt)qU((?McZ*uT`{ou>a(eXM>oU-MMsJXV-w)^z` z&ya_nZ~xABv;!#byJ7vWArA=~Q`>){9u0LhBa;f`QZ$rP6VnYUj0;TiisF+}Q*xsd zQY|W!G!pYo^7SqI_4ZTKQsdGHvNV4uq{dtJ73KNE$U%wGlAcM9iq|Ml(anyMkBpB@ z&dK_X;qLv=$SK%KQ;d^=RT5E>iYZqG?vv3-l7Xz7W<#;T8pZJ^NrC>;;LaDDWgTE3 zpeaxwApCzf*v!Ge&KzK5U?pMWWa40IU}W--)su<aa)I=S!`n}4v0dlQ0}%Ka<B>`d zPDJZotVwv4;NMz%Dc|}V2Kpo5L#Y_v`HeYSG1r@mIahZR>%drLi$PJ-ViO>!mcLXu z4U*#<q*&p=KWT0asf@CN!-0_Tgy?U$`EJp;L!q=*yoy+Y%V)$xz=(V?oPnjJSnOvJ zA5<r+dOsvYwr~`PsD39WQCTKW(;*_moSln>P9+zmX&|p5%}F?nRhg8#sa9*~Te!-} zw{e-&6j3mKy7<Y(;3pNnblKTUHi0EB5VKS^yb=oCQH_2O=X>HhIvjqn0Z%HY_v)R^ z&-@g7a)#sUUpUGw-C)i6T;Kf21v91+2ikn*pN6#Rkyl2;AIO98`~&$Q3ysL8I%s0@ zN(!x8HDIe>J$cL}pOxS~EOR0p$DMF3udq1-PM;F4M2Cz;R;g6`yI8T1tlLPZ{fAb* zoniQxbOg3qCf|ie9Pj_|%*<wbeAu@~M!y@yzk9~c%GnHH<47kAFfg;Rb#ww4DLLEO zIhZ&)+B*E>BkSm1=stQx;p>lZlk2rY2nrGjy6mD{KE!iP^tnP}z|ZcjGm#+12>@Qd z(xszQt-Lf&hiEH0<iVSr5ubVHowu5iCA70K*K;i6)3JLxVG&9`1&}fX8CU!e4Uo)D z`Nij-ZI3!NG4pb0B$4K5J=Pi|86%^wonU@RL_7623AjDaqA}|vw*S1)n7)2``+QGh z<-3vpZ_|;sH3Jw4*ce#3dzd)L|7(u_H}}ckQMqYpmkFtfvPwxB=n)E;>4}E#yQLON z{zhs-rb$IG&XrD*dSpaeb^=P4h5{H%xzgCI0N+oGXMmfe{hhmGEP!d=pZY65ae**5 zPoBy8zK#>_f4C&Zt|4FU+jjl$_8&LPf4f9UT1e>s-gKx(dl&fs#bQXR)x+b}69}NB zGolKx|6$8*oMnX9cW^b-3>XOQ-`CU8$-v3P)XLWNpVhnMv2@(ytl$2iQnt#XAwaC1 zB;p`m9W#z+a-TE?adc@><VXa8b{k&7Tqpk3a^<VnWc*^SPYMf6Xc2-@rnMR0X5w10 zxb-%CH^LvY;^H*EF+IAzh|^~}eRh7N&&TF+J<iqYizDu7t>*Z*(|`w89P%=%aZ8?! zVeaj%Rg(q6r0^cvdr8!dZ@Ga1`05xQrO4}9KP9PrL-_XUx@mKJaY*-&61<uV{WYs< zHDN=5MdN(qYczEn_d<D>XdHNER-WyZm3384amV5js6COcwKYMgczI}L!v6nh@2sQZ zT(W+RyK90=W5M0sT@xe(Z!EYw1ZdnXxI>WO?jAf4ENBQW!QHu?GvA!#FlXk@_xHW; zT5ost>Q&FGcURS}U0uJbPF7j)-aE6p?<y$s?Y*3zwNrgf8i~4e7c{>SUo{sXH<dGL za~mj2h$}VpxI}2lMX4J<X%0!#6ws5&Ka)K;L|T7Q)PgOG#7O|<J2BdR?gZrJTRSK$ zq%A5xusNJD0UYk-rhfcZm?yM*wIfElQ!YMUB2&&?pXLmM|DtI?gaY~<>o|ECWt}S3 zcO)<CVg6~4BMXI`>y3ksrhwG+FYS)=kNN09j}&o+`j!_Bi=ynr)zO|a+g*oOU;4hf zY+W^bp6whp$49LwkqnHJ=<6v!=bk#|5?-CUIR)=8io)f2FMT;c@#6DfIm<jCv51n_ zAcu^SmO7$m9fjs<QcaM9p&@Un9f#x;-@n+Ars!<4dl?dxvt*dJKcB#?(ClsI^~0y9 zJ~YycT#VfxFJdRMHGrUQpD%8Og6jijy63Rd!VU6H+(#2}-ZgluNn8ro@rN67US!s7 zehmENfaKczk=?<sW7115Ta}LKs43*E&$X&j!fW&SCBjx6iOsT@o;L+}w(}6VD#MwR zx;ti)CXQ#5$?EMW)`12(RPF5+;tDy#Z=2uF;m`LHwD3Bam`90wm_~*&Y@#u7vMr2V z>&P<6a634+=!iLAS-zU%ypv7olhc)>*J!7Z^d6lScvpIQj^#FnCG^3ptJUjzzUgLu z$46j~h<Zn87JMT4cCqQgJV1}YCS^#Q*ZGLPc)*j4QeB70(A7NlR^>L|^X7W;_}pUa z%DCY)t2AFjVw}WEOYmG;fmPV&`etR72RU*PUd;{R6){CJoDa2w=mOu3gS)f+-JxHa z1(v<-WL;o(hAycdiL0=$Yye4GGk*cImEgoEdA&1t;-d+)XJP^(N^K;9Lh$Y;-P?25 zDQa99$Gg{N5uf#7?W*(3y9#VL#MjHw44;YAOcs335{g7wES~Ehqe=3X^KdnKo#(54 z!M!E=V})biM;VGxdw>3>GZ4P6mMM@_ilN2#-RL`hKz3xqw12V8+X@uLa+I2xW$hs{ zfQ}4@2YaZC^{7d-ai%W4qu}s^{+(g{`QzNMKp)C;nW4}1A7i9-oIQh+`5j))m4CIA zDYri4vJ}1#{4v|M7c3c{%!YR0epYH=6#E#~{Kj@BRir7$Zz=J{B+1;Z;t)VRPXil} z%&+nRtg0jYo=;@@p|G;!`5mALp5WtU1;Yd%O4ZjSF}S*!*%Y=CGR$_=5)Aq{g;2HS zZ=e*zHL>erWeX!E_8i-{%GRz>%7gpE8ZAAnXFm1R*r(-}k><z2%o)nPCOm?C%4uaL z*j)j)><5vCQysJS`EO)3vGfTkHXb+NVAL@=<t4>j(u7l5_H0kj*ZN03<}qgplae|s zJqjFTVuqJG-fV#TOZsx9Y?@uCMo~t_ChlBDKfQx}FxAZ*OU1y!q8=viFmn~4AtX-J z2h#@A;j}Y#sjcQFo~g+$cqtR;(JsA0FB^=O;O3fyRROB#t;d*`o&=CT=G>YmVvrEd z9$0R6b}EU+%_^rwq=_HtS6cJB*8%W#u&mj20D>saYB)9&=o<$Z@zVQRAh8!D=`gKG z`?}xx?N-lZhH)BH0_CCJ(2`4Yp9U)BAmCTcv$cIsL=jTM30Mx}fTLopZEG9t=adjO zXO0xASUL%Xy(|2(bp-5SMI+5Y&vNjC6PBmF2(88FJXVGxk<?NkTdW5N)vzE+!l-@G zu}4p}ZHKI3XK0)p>wbqPi9NGmsbx$4E(yr=Wu;D4raorR`TgFKK}}C)oksX*6wJJi z+!^(LHUfT{T@~X*A6H*94pY6P)>g;2zE`%UEwkp@glSPg{`Hbv9|_-C0@e<X)UH>= zn|>_<d%8qEA_6BCHH&uV5ixl<+`9MHZFZJ$*OG24l|r3`7a#eT?4x6FqZ*vd_3Mn) z;@Mi>es@dr^Q7lHzP1;Q1Kg8XxGMRizefgj5ZWNWY#<+q<3a(!L?_k)tS-cl<Oo{h zP%8?%N)fMEuNG9E%QSqC7JE=>T$r)l-js9o?7_N;zR(c+nq;_0A<GvB^oLdg3~9u^ z!E|6$E08GZl-|%R&Mz5}!_mnV;r}Rd@s5%)X)clIt(+<whIe)u1nWp<t`vs1lx!k_ z(~E$VG9Jm9!V(j*8<7njNp#gnvY_O5O()(T2sAVre)I`Ezha!YWc1fgf>i2eanIKT zc1t413MCA(#3O6d#eZolTThHRjpatkbq{zQlH|W&+n3?RX~P=@B3+LZTc4RUkw>me zNB9~LQlnt4>W0{@(k)+!q~~uD-3?A4sIPwYL?ozlhq8}akS-Fm*A<v&z!%Bm@&$bU zyl?}-#`7iw-A|#S@^&)E8yFcXHxyC+Zs~FB4gT^nWk?gbV`j&ToYGjE?uH9piaJ=? zW+?g7uuuKEbZ1x;M&%kFh^j1_oF3ZH$cNl#n9Dt1#_TWUq%V^qD`yBPevpiCo4oGj zag-a#Mt9kS*kN*DbPE3Bmx)-1m|&V)B2ihI|3x6@O(7Ak3h0hP;dq(RFP1KX4Oc3M zWmn@_V)s<Fp;kXa0OdBJ6DWdUv4@nkc~V!6RWv$j#S%K=!1`^khoY2*5%ePH+qe?$ zV0OJ*@rc}pd2zQ~qIvO<+{+4_!s$||+vIpU@^7`i1y`E8yIHKKkz4eJ0?2FEiJ#c9 zZyTz!H`Gqxjz3H62qurOnA1Lfq*&zYwU@+ni0ky$7u9fJS3%g<Cep@HYr|A)!xk`L zu!vQz(g*P&IE&a8q8Y7;SP?PUtr?^;D}oc<_}4$U(NZ0)iFEyu?I;`2QiUs>$7SH( z%*=?sI$NcvN0VadGCCzAp4Xh+q_!dvaK23nzrf5m5jd?+#0dNrDYtzWd-tgHa4El? zfRi<M<w;&EDk8X!Gdbu|7`(K#7k3~YxVWWPtQOKZ)}~g6VV~t$@E|2Qn^ln#P?a;c zjY)_Xdyi<Pt%A3c3G2AKY`oY3mj33`42@%NY=l-HOYpko_GZy8(a4?9$wsPAcnDe< zq%no7T8_7K*E&$4Lu<B@;Er|R7acAW#yHfLyFDOGE5{P}s|mExz+RvFfRrGhujO;R z#<I!HCSuGcW1gb|;ZUjKgV@r7y3LE&&5Kevrsg;_vdQgbJC02Y16x-DkU{z?QZ}zE zSIhdThjq~$swP+Msa<r;WlMT)Wf5YJOg^^o+<vocUJUo{xg?(?Y<|8&YS5wgYIUkv zYyPViDwn6l`%+!v&!q43(dh8nRp4{b%&Dfj#ugkOyk&P|78fvf$)?^puZ>QN9#7{m zyPSde0CvkMd_}s%N@l$9lH;!kQe$?e<1LnVP}{vR)97(1-rb_%hy_}QR+hmASu2Jc zVHm!y0G}cWvfket!LD~EMp}r=SM-AKQTk+mkZ{Dvx#o;IjI=xyM)F$XDv7bXVN+!> zxiWubhak{)$!lAOQea%`3MoJT!!i9W0|MRSI;c)$dJv+Wjw6799O2kO+wHxeS5O6_ zS6ihF^U1ve(inCA(H;nA{!OWLb}-dce^4n{K8Uv$LUJo*wjH}j2L4~BfM<kZvQwEp zpk;Ol$=bdIhga7p6V0HSFIX`@9@5$kY66Fj=qvD^;d21f^;b0~y&Uw~;AzG0t?7G< zmWX%LH9coRw3TUWJ3h$G=vO`XP|B8M)O*xrVu&h3RWGLdL#H5|N4G`cln!A838D_~ zL^yY1k0ERP>s7|;iD<^QklYw*AtW-Ppx(eg10qGNb`_}`X!s#g+)bI`W?WS5i184I zTg54nk9~)!X)wF$;TxBt93|A0&h2O>7IYJ|)TUnR3`^;KHJz;%6jHiet_?86wJ;?u zHs2G`$~wr#z{_g16X$?52nkz`Q6N;?G~dPsCI}h%YgGr2;@!WLY*<N0sCp(&%r6=Q zBYbq&4|Xx^c}VePp7vH64ZMjmDbkE;o2roslEvaM1^l)BQOF#gTD#*>>tk=2sbjru z?KfyTif1Q`5Ng*Pm0*g*Z%0*uhx|dixY8<!g;?Dht%uJFHHrE)#FI-diF?k%@{+%> zjw_xSn6JaT-w?ZrABUnzUVCk$gP6IkaCBfK(B2IoVmuc~zzB(hP=$~{eOH8t!TGri ze;!E}YD?uz?cfI&`zx_fhUBZ51wX~xi5&H7M4k^oHpY01l)Xf{T7?{7m}cPwTVfKc z>HHcdfpBk%eW7DdEjm_kXUifYk;Oor?x@I7d-lkK3d#1aWJ?uD;9DEG?*M{ixrcLP zLBMwct5Kef%0=_b{m(FKGVa^c0{g=`F2`)Ll!O#^+=X+IC2`)2>yWe(1-v(A>-x%w zR?+)CG1;$oW%^kwL41;5*7jW`W+pFQ*GCqVi2((o@KM~6ObPe=8i{_JaP%R(!!p;{ zWGb$GIG<h<%v$NzeUi4Gvy>|syJI>^YgR~w#57+QWdnjaRP-*zy57E`aiepGd_5-n zoz-)>d_6k*oV9bye7*DCmqlg}-;&dhSb0~B9lHD10j$)$4lM8*_*eUe5`|x#`tx>j z!)XVR^_^BiqwWU#ZLW(QbjcQv2o+nSE-%C~mmJhqwTB(#hS?(W`fJ%*cJdu63lpC! zme!;x?P9*w86}G5V7#4kH@5PKbLgVl@RuKgeV>3lEl-Bi_D+3X0fNYK$I&uX9Fj<E zd3Zfx+@fU5u#5?4ZW3A!F(;TG&I`dePS}oRhq*-@BJWXo^4Odf?0RT$84Bq;g-S}X zqa1=+c1a{8XN6NB?<PVNJ10!VCHI^u*<CEvPy4%VA++N<3dys3(~B<~`oJbP=-y#- zjfgNpfgpUfA>*-)K#iQvJt~}PR71OAR!AXw4^7yPuzBl1AMzVo!iXltjPX#K*P#pX z`Pi+(?$@rI$Ft8YL2c*E^C7l5K?}wA-)KMjP;5&b)pK{?+u~}Z@8;t1OLv%WnTv~u z1&|H7L#_A4M)S<;44uFo_!q*7g<&g*rGM2+pSC<2v1h};Vgz_BQF+i@VBAZwdFLgq z=S!0H@`W+?@-2ST<+W@|VL<8O<_moMY{heo<WUtD6g#7r9Z<tR%(s<}bxT<*Y7VV~ zXnhpTn?B}|ua&?D*itVFP=TL`<kp0D-ht=utMbi3qc25kpR+*MPmA)^^NuMMBM%h& zSR%#&1xh|ISpv}o^5DL}F#_V|KBw&+uEr5t@5Vr?sz$1+>1>4*D*<WbCB|3^^RLgH zPM|>Mpo@{d(jdhVw%N3*X5beQI7jf-()K>;p%~Lk0>XvB#Dc$nNvh!sJ~*j|L6+PF zzZ8QaaP&v{cxc~tpzZT4bjcw195lp5*Fv;**?p==tvDqPkP<?M7F7lYFSTUUAnayx zdXlB$da~Ej6(fCrK11m#AVr|pRqYIWg;J~YD@PyTc@PTJAW^*SUC?(^aGaT+d=@9^ zM1CrckKNs4GsZ?bh$MA`V=a@Psj%&+8=^+-iRz%dTJ>(fT(KElTd7b^B1SKm9Mb@r zA6C}mnb>BV9r>vF78<KNZS+eK9sbad%rT*oOyuj^rkUUI!^%xJ>7;T3J(94QQ9h&u z>c*b+thBCT9onQc$dzM<w3b87+K1(c$<&Cc<ZmND{*cV{$Bw&HAl%0t@K$>rX`J@f zbTq_u#DmI$hDsdi_*F0!hzB@VMd+bZjfpGd!jAbi<!Iz%fdTSZ#L)=DI6M0^7G`-0 zDA_^&Xq5Iupgkp=pMgq<a5GbN9R*7EQXz@PO#2}v;(a1RuW-+Voren#=OD<_)aNoH z4r{B~<sgOdVJNzbQS8<{RboAw&io3pDNssyCDYvw>xknugSPuNGG2F9=Nq+rCY*lP zPi|RiFBs0d00z)*yPbxWN9?OT$AVIj5y~xlo>4p?wHE^5$;XO2GWnI?GQvGV=(GDW z1lAcn0)Yxf>5#tfdF8YiFl=`}ryc5w!*C4vC)sS4WsQ_W!edShSgVM`)^8XarXmXH zzsGA;>=}wxYHC-y`jR;p%LL;~zm|XZO{Ky<CN4sNF0>7ad`O#E3tIIRe&QSDfs^@x z6F4EWkTUeD^QwWeXbU}|s`KL^NZt9FU_RiFfTX&roz4XV%#w6HA7C0u;^^X?im$=x zT4aE_G2I4U%dO~?9Q%Mtct(`dwg_lCa&{-1S)u)tPS%Kw1xpp<;SJtCB@?oHW<gfR z-JSR)vM>Hkb|BoI_X_MzL&y0?Arb@iIF3WXxwC2Ku9oT!7~6xlIm;9k<H#M2Dc^%< z{WY=Q7NPVaB|<_;pwAO@-NMK2cWu!1z{(<>2b_ows!0^(DDT+=#IV!u6Mc*I_Tlx@ z$-Hhz%qXf8lJfb9`bseZfh`YE`@wR-wj|w;v_=K$ukV0W6W`W?v{d`Tnh)5P(tRnV z2ONnM2Tq3uYqF|oOvu9E16|2y32&yrr^1b4nN*3U1l1>1x6Xw-Z5QAS%X86Ivm=AF z=s+0!7e@U)vHTa4E~ULu_w?{~7W@}=^LP9g53zly3&j=F)nr5&2fck4Ep4(^!NCFr zR`Wr=QdXT4Tz56w;cHR0#4s4xpArW30?5EW%BHWSQ|{e$u))9FB$rM~eX*fyd?VX! zL4)qQmv68dW4QP6dvun`T~&NA=FL$kaW_NGEX_u?Nh2R*mP<9O#xNRh-1V}w3DyGz zx`5s1<1adS0g*<RI$G{;EjP+`yQIkH#HyD8<1$tafbki%TyBdN$;Q<{dYjntMhmVy zyFSL=Z9RYb^74_xuy7NXWfoW6H-r9HFAo|UgnZ(^7{(Gk>@V4$)0LG+@-rpuG<kYl zJDd8uA(-xZ^lRsmG#|9tVAOTpYiMTZr|r}rlNlkd>&FZG%<ZhTv6|4W_ZZhHxv%$l zA!qsVoYXX$oMe+wEXD9p#?Gv&oebV`Kd&lpgC84*E3fPp1rSMuJ7Fl+7zGBHlbe3W zB9e&Qy+g~T9Nor5j-K7sY+fM53aE%KXY83}(O0FUbd=Q@dHE_X9_a2~&9=zgJ<Q(8 zl(8jVla&r!`6~OuNx@ES(-rlOkKwD_C8TM4uUfK`HQRlRB^5QMdqvXoJFtT~n7}%M z1-&iWGL2J(7fO2{!AIbXy9y7{X}$KPm}l9V`;hbQy?;HpVKQNi__;;}50ThWMbjS0 zBV6)!N+KXsC?+KiWFy{6T)n}IP4Tx#M+n4FdOwBdn=(nIRR`K@L)ILoMyx%mLLeQc z@Mf4~Kw2@@4w0=#AszmVex+pqoR*$-;`H=a+Ai!Vyw+s<7XE%yf6xQ;t@@6>rDMEf z0$JI4UICd@K1}RzL~Wb%s7ithkNgPwb6r7*xKIzidYHtr$dn|a;OtcuA^+7y<V<XR z=|W2jqlAy6aJa6ibH2(h4^FO5nfSpRAHhygPCS1J@Pb%2cfYza9R_iCHm5*<i3U;3 z*ujmG<I91M|E(6kwn{Bs<1%`7r840epUjPl1m=s^4`Z*M1!Kw>z&bUE!7`G>tfQJ> z7N{<ZdFh7d@FE!{PQ-{?0lw^bVb3G7&Pj8RlS)+CzAin;F8N@S-(d)lc97Ho_9%gc zCeAOWd=~Sl?(#^?x`pNB)%0sP8lvT7)QPMa-)N*UevPbklXv65>}Cw~TmrqmP-g)s zV3U6nYyGO$+Q$?y3)I?X>cPoM1t&t(Pu}mbNt9l`pe*B_Qsj&AY~E>1o$GOe&;7(r z232L8-4vixDT?*_0?qRvxqZ9jB)Cj4u8s!>1NS^R{?*mTy_Y;I0Q~b$rHwMCND6jU z{P6gw=QNGk#-#HFs=^d(wCLh(AD&ySm<s5TxG<p!XJgw^v-6g5Z+)-5W>1G(b6yk@ z+Yen^Ri!43oF}r{<IwN>RIs6Q!621-%0e+bRLawYW*^71NwQ^bW=0Z~uv^L#mfo24 zIeIVnMhPh6O)TCXHQFD~7Ck>)Cuy#GktT?(TkL56@;!d%^d2Xj3^Z#-+7hf?d}b$k zSFG=W!3*igEY({cX?A54K=LW~-Uqg?x(JSw_4Dx&1&j!uxXq#Nwpz;Y6OX^GSM-55 zgNa^wg_VLA8n59XAh5yf6|co@!3&EvPWl?|c0k8BKNl<d5)I!juwVo|hJE>pMZXlx zDwWPQfr<n~&cB7!ytWFLp&_SJY}M~jk848KmQHdyi!W=r{I;bOcf4+DtauzqZYiDE z$kY!$7qon4>ecFP&-*X%s=Y880rr83+pJ-$rhM+(f}i}u>0af^5Bessm7p>9PPhX; zb1-Siw4#)qWhag2dU2C<ydP2(lgmpG>~(SoNByYq!nDP$z8uEQw${Jbdyu9?zJ7Ox ziNV;1{V17KGdh**EcdE)rF#j12=Byd3^fqqp48j57{9G<^wixFz2xL($_A~$x^}sm zEql(==!18wQ5U3N&2fZ#UOj!Dh4%bBk^3g+YoE2Zm`;&q&SkotvFPcjvTN;!yn$!9 z3@tL@h?X*BHFiSVL%v4BW2gKsK2X!;k2J2c!;^&1<Ua44@TfjC6D%>Y5O?{?u9H3Q zAlZ*1aD`$WW(ul@^y(*Y?03$A1Tn`)*Ws_VY1gGb`$T&o&~6It^&#TqmAE_;br~N0 zA@ry1Zo*poL!B}q%;X37plhxxxHk+3W;Mtwh*(^o%6JR;6n%Lg%yu%V8hp!ll>fT6 zS3a=i%LT4m0C*7@8C<ve4nQkMW~QI71(VBiJuEnIN1BLD`jdE=vCb{3hOW8ike}yk zIBKuO<C^yO6>%G!M@^=Nk75t+2FOo0^jy}l%dmBDIpo#kR9-gYh2fv&d8G)dtO^tn z@Re0&!#gD~;Dei9XE1*`=BHSdTwPJZ!%<4(a!VC|`C3ujxX5}eFCLxGC>o4*Chn=< z*ge0A24|SO#ILogcPJBaN=Pu^z44bjQwf0I^sVWoB{>P`dW4*9Osz(+T-qt|#_D7o zh#y95+7GmxbJcz9m3`&|!V?))T9~0qOxknfSFSnp=S;?jeyL*(<15{vMo5f_dLo<O zf;?eov}p20i+G0bn{HNH5K0;T_5*~XuKuzxdq1RV)|+YVKx$X+wV(=T2jKN~)n~#A zixWbQG0*6d$0BvDHDak!Pf|j!gFgJfns?1w(J}yRULts~iGN?}`-h#4tZa?nnt&IB z9Sp61cB4P+-ZyP6FUE=ke^lWxcMJZrbBb2EXR+C27H4cxE&WR?nX{&rS?w0+nx{G# zrWH)CX8c?5w>_!*ptwPHKIVweGJ<8XFr4g7;{ufEc?<FKaaRz0@D?1VCZU;t{a2?X zRDo`v@VjpSTwjDJB@r&d)W(oBzN;In_7C;)z>+`kDKS>k+2wzzn}>By6C7|E%TF^~ zhl7gnlb%E%>W_)FFUND&Eg&t>VC>}8`ot(7&L7Crm`uohPRAbRkz=a1ZLz#go0sF$ zZk=uUa+|sQEAftxs&_|`k5w#0c_g|&s@V+R*|$bDvyBMkeT(UGj&GxfF_Fvz4Rp|U z*(|*bFU35AkX_0|ne@j|XJ}k9aMPkjh%Wdtyql|COr`>)8-~8Buhmkx6HW^wEK6UK z8kjA2e||upxx$;_;o8IOcfGf<kW<&872V>A%9?KM>D~2KNc7{c1R0RE@WI(Yp~#Qg z?Ays!B){$puTbm^<v3M4Z*t-pF&h@D6x-$m*$7&eY5uhmGn)>>Yr&OA46aD3f33tn zx5WNaAM!^n0;9Vudst9{^!v8kX^Hb9Fh4YOmA}1(_@qi4uf>)0waivOL#`+42Gp+n zXm=%F+N744Jl9?RqYL9!KoSk_^M|qbt}GKo$~L14cs2k7w6!C}(zhOzjtoXP-A0Bs zWnN@qS#-QR4&*bVRA1Lqqc{!heeB;I)g4}HWj(J1rdAC4k9mcz$S8L3H4zjEnq^dT zcHrKay;{CY`$3U0hDcSI#d(rDv$QZ1hEDXI=X>F_+mk)O#e%qE`{2jLfPV7WMkdy7 zCWcOi%r6~*4ieymJ_j3<wVR=XgQ2^z!PyxQ0!j#@YoxOiE}zFQITR8~E5}O;fP!ge zh!Jo?>BmD^HOtOSSw~v~;Oy(j2CxgG=f7ZN{{W~P;1#ZD%rD|-0(68xmKGVSdawq3 zsF634rGO@YXd3o|Twzk8zB@32s(zMpLlkpXWpIp+9w!7zD-65N)0V)Iw|Zxke2*V9 zV%Tehh8@Qv;|&$(!NssU7c=E3cJC_S;?jGDsJ=&jhUNK;G<P?k?MyyE9Nza~_VIH) zhp)~LY|j`$JeWO0iJD+&k`mI+8`x*E;kL;wAivp3-U<$UnZo={NZH0Nl!T_Y-_N0c z8zz75nf~9{i~axG>wjf0j{isP1qlTK@sC~kv)~q{E$;OF3OrDsf^Rf%&;09UZf(Kr z3N!-0F<BcrsmTAz`?GZ(wM~f|gB@54m`M0P8NnaH7XTIl!W!sg_(zvEwsioiIM~_& z9h@wHjz7nwr=Y`4LA5?`HfeBf;y(Zo5dQ#mg5$$KLDsJScU0s`qD?XwF#*1*|B3>S zm;V+e=?0EI9W88a{;qh;Y!SYw;3)M0Y_^}`nqOBs!f#9`b7yNK8$$~#COaFmr;q3& zLdnGg&gcieDSiRKsU@)K{yYoePe1t62Wl9avHY`<{`b6>ME`-u`tNv#wsIYL!w?XG zGDr~5|EGNasDjbI@Sa2$PmA^RkcXe7e_%dr|5mI&$G1O@e0U0ZDx3TTNri;`Wvf3S z{~RQra-OOge{tlYe&hVTw(%+KsQ~X6Yy<i?*gv&j|4xqg6#G;N_X}GK^EcRkBa3@V zeJV}+MRkMy8|q($YENNLwPn9xFmS)Y{-QMdo$+_`y<d!463D-s{rwL3>1&=&Dt-ZC z$RK~8Vm!_GG+h3b@sRwt(*K9x`6=;f?DmUTOZhLve`%zDL~>7&PsjP6$bVd=fZvdR wdWXM>lKy+-0@Z&;{uxO8_ef-#|BU=|tW}YR1$*?LZWIr~7o6g!{plV45895t82|tP literal 0 HcmV?d00001 diff --git a/controls/model/Quadcopter_Model_R2015_A.mdl b/controls/model/Quadcopter_Model_R2015_A.mdl deleted file mode 100644 index dc185578f..000000000 --- a/controls/model/Quadcopter_Model_R2015_A.mdl +++ /dev/null @@ -1,17773 +0,0 @@ -Model { - Name "Quadcopter_Model_R2015_A" - Version 8.5 - SavedCharacterEncoding "windows-1252" - GraphicalInterface { - NumRootInports 0 - NumRootOutports 0 - ParameterArgumentNames "" - ComputedModelVersion "1.2982" - NumModelReferences 0 - NumTestPointedSignals 0 - } - ScopeRefreshTime 0.035000 - OverrideScopeRefreshTime on - DisableAllScopes off - DataTypeOverride "UseLocalSettings" - DataTypeOverrideAppliesTo "AllNumericTypes" - MinMaxOverflowLogging "UseLocalSettings" - MinMaxOverflowArchiveMode "Overwrite" - FPTRunName "Run 1" - MaxMDLFileLineLength 120 - InitFcn "clear mex\ndelete test_model_sfun.mexw64" - Object { - $PropName "BdWindowsInfo" - $ObjectID 1 - $ClassName "Simulink.BDWindowsInfo" - Object { - $PropName "WindowsInfo" - $ObjectID 2 - $ClassName "Simulink.WindowInfo" - IsActive [1] - Location [-8.0, -8.0, 1936.0, 1056.0] - Object { - $PropName "ModelBrowserInfo" - $ObjectID 3 - $ClassName "Simulink.ModelBrowserInfo" - Visible [0] - DockPosition "Left" - Width [50] - Height [50] - Filter [9] - } - Object { - $PropName "ExplorerBarInfo" - $ObjectID 4 - $ClassName "Simulink.ExplorerBarInfo" - Visible [0] - } - Array { - Type "Simulink.EditorInfo" - Dimension 4 - Object { - $ObjectID 5 - IsActive [0] - ViewObjType "SimulinkTopLevel" - LoadSaveID "0" - Extents [1755.0, 904.0] - ZoomFactor [1.0] - Offset [336.19666666666762, 144.20000000000005] - } - Object { - $ObjectID 6 - IsActive [1] - ViewObjType "SimulinkSubsys" - LoadSaveID "573" - Extents [1755.0, 904.0] - ZoomFactor [0.8] - Offset [-151.38571428571572, -12.602379760288613] - } - Object { - $ObjectID 7 - IsActive [0] - ViewObjType "SimulinkSubsys" - LoadSaveID "650" - Extents [1755.0, 904.0] - ZoomFactor [0.5] - Offset [383.52935415893444, -40.361112608789426] - } - Object { - $ObjectID 8 - IsActive [0] - ViewObjType "SimulinkSubsys" - LoadSaveID "436" - Extents [1755.0, 904.0] - ZoomFactor [1.25] - Offset [716.49880952381045, 116.5285714285709] - } - PropName "EditorsInfo" - } - } - } - Created "Thu Nov 03 18:34:52 2016" - Creator "Andy" - UpdateHistory "UpdateHistoryNever" - ModifiedByFormat "%<Auto>" - LastModifiedBy "Andy" - ModifiedDateFormat "%<Auto>" - LastModifiedDate "Tue Apr 04 18:41:22 2017" - RTWModifiedTimeStamp 413232081 - ModelVersionFormat "1.%<AutoIncrement:2982>" - ConfigurationManager "none" - SampleTimeColors on - SampleTimeAnnotations off - LibraryLinkDisplay "disabled" - WideLines off - ShowLineDimensions on - ShowPortDataTypes off - ShowDesignRanges off - ShowLoopsOnError on - IgnoreBidirectionalLines off - ShowStorageClass off - ShowTestPointIcons on - ShowSignalResolutionIcons on - ShowViewerIcons on - SortedOrder off - ExecutionContextIcon off - ShowLinearizationAnnotations on - ShowMarkup on - BlockNameDataTip off - BlockParametersDataTip off - BlockDescriptionStringDataTip off - ToolBar on - StatusBar on - BrowserShowLibraryLinks off - BrowserLookUnderMasks off - SimulationMode "normal" - PauseTimes "5" - NumberOfSteps 1 - SnapshotBufferSize 10 - SnapshotInterval 10 - NumberOfLastSnapshots 0 - LinearizationMsg "none" - Profile off - ParamWorkspaceSource "MATLABWorkspace" - AccelSystemTargetFile "accel.tlc" - AccelTemplateMakefile "accel_default_tmf" - AccelMakeCommand "make_rtw" - TryForcingSFcnDF off - Object { - $PropName "DataLoggingOverride" - $ObjectID 10 - $ClassName "Simulink.SimulationData.ModelLoggingInfo" - model_ "Quadcopter_Model_R2015_A" - overrideMode_ [0.0] - Array { - Type "Cell" - Dimension 1 - Cell "Quadcopter_Model_R2015_A" - PropName "logAsSpecifiedByModels_" - } - Array { - Type "Cell" - Dimension 1 - Cell [] - PropName "logAsSpecifiedByModelsSSIDs_" - } - } - RecordCoverage off - CovPath "/" - CovSaveName "covdata" - CovMetricSettings "dwe" - CovNameIncrementing off - CovHtmlReporting off - CovForceBlockReductionOff on - CovEnableCumulative on - covSaveCumulativeToWorkspaceVar off - CovSaveSingleToWorkspaceVar off - CovCumulativeVarName "covCumulativeData" - CovCumulativeReport off - CovReportOnPause on - CovModelRefEnable "Off" - CovExternalEMLEnable on - CovSFcnEnable on - CovBoundaryAbsTol 0.000010 - CovBoundaryRelTol 0.010000 - CovUseTimeInterval off - CovStartTime 0 - CovStopTime 0 - ExtModeBatchMode off - ExtModeEnableFloating on - ExtModeTrigType "manual" - ExtModeTrigMode "normal" - ExtModeTrigPort "1" - ExtModeTrigElement "any" - ExtModeTrigDuration 1000 - ExtModeTrigDurationFloating "auto" - ExtModeTrigHoldOff 0 - ExtModeTrigDelay 0 - ExtModeTrigDirection "rising" - ExtModeTrigLevel 0 - ExtModeArchiveMode "off" - ExtModeAutoIncOneShot off - ExtModeIncDirWhenArm off - ExtModeAddSuffixToVar off - ExtModeWriteAllDataToWs off - ExtModeArmWhenConnect on - ExtModeSkipDownloadWhenConnect off - ExtModeLogAll on - ExtModeAutoUpdateStatusClock on - ShowModelReferenceBlockVersion off - ShowModelReferenceBlockIO off - Array { - Type "Handle" - Dimension 1 - Simulink.ConfigSet { - $ObjectID 11 - Version "1.15.0" - Array { - Type "Handle" - Dimension 8 - Simulink.SolverCC { - $ObjectID 12 - Version "1.15.0" - StartTime "0.0" - StopTime "runtime" - AbsTol "auto" - FixedStep "auto" - InitialStep "auto" - MaxNumMinSteps "-1" - MaxOrder 5 - ZcThreshold "auto" - ConsecutiveZCsStepRelTol "10*128*eps" - MaxConsecutiveZCs "1000" - ExtrapolationOrder 4 - NumberNewtonIterations 1 - MaxStep "auto" - MinStep "auto" - MaxConsecutiveMinStep "1" - RelTol "1e-3" - SolverMode "SingleTasking" - EnableConcurrentExecution off - ConcurrentTasks off - Solver ode45 - SolverName ode45 - SolverJacobianMethodControl "auto" - ShapePreserveControl "DisableAll" - ZeroCrossControl "UseLocalSettings" - ZeroCrossAlgorithm "Nonadaptive" - AlgebraicLoopSolver "TrustRegion" - SolverResetMethod "Fast" - PositivePriorityOrder off - AutoInsertRateTranBlk off - SampleTimeConstraint "Unconstrained" - InsertRTBMode "Whenever possible" - } - Simulink.DataIOCC { - $ObjectID 13 - Version "1.15.0" - Decimation "1" - ExternalInput "[t, u]" - FinalStateName "xFinal" - InitialState "xInitial" - LimitDataPoints off - MaxDataPoints "1000" - LoadExternalInput off - LoadInitialState off - SaveFinalState off - SaveCompleteFinalSimState off - SaveFormat "Dataset" - SignalLoggingSaveFormat "Dataset" - SaveOutput on - SaveState off - SignalLogging on - DSMLogging on - InspectSignalLogs off - VisualizeSimOutput on - SaveTime on - ReturnWorkspaceOutputs off - StateSaveName "xout" - TimeSaveName "tout" - OutputSaveName "yout" - SignalLoggingName "logsout" - DSMLoggingName "dsmout" - OutputOption "RefineOutputTimes" - OutputTimes "[]" - ReturnWorkspaceOutputsName "out" - Refine "1" - } - Simulink.OptimizationCC { - $ObjectID 14 - Version "1.15.0" - Array { - Type "Cell" - Dimension 8 - Cell "BooleansAsBitfields" - Cell "PassReuseOutputArgsAs" - Cell "PassReuseOutputArgsThreshold" - Cell "ZeroExternalMemoryAtStartup" - Cell "ZeroInternalMemoryAtStartup" - Cell "OptimizeModelRefInitCode" - Cell "NoFixptDivByZeroProtection" - Cell "UseSpecifiedMinMax" - PropName "DisabledProps" - } - BlockReduction on - BooleanDataType on - ConditionallyExecuteInputs on - InlineParams off - UseDivisionForNetSlopeComputation "off" - UseFloatMulNetSlope off - DefaultUnderspecifiedDataType "double" - UseSpecifiedMinMax off - InlineInvariantSignals off - OptimizeBlockIOStorage on - BufferReuse on - EnhancedBackFolding off - CachingGlobalReferences off - GlobalBufferReuse on - StrengthReduction off - ExpressionFolding on - BooleansAsBitfields off - BitfieldContainerType "uint_T" - EnableMemcpy on - MemcpyThreshold 64 - PassReuseOutputArgsAs "Structure reference" - PassReuseOutputArgsThreshold 12 - ExpressionDepthLimit 128 - LocalBlockOutputs on - RollThreshold 5 - StateBitsets off - DataBitsets off - ActiveStateOutputEnumStorageType "Native Integer" - ZeroExternalMemoryAtStartup on - ZeroInternalMemoryAtStartup on - InitFltsAndDblsToZero off - NoFixptDivByZeroProtection off - EfficientFloat2IntCast off - EfficientMapNaN2IntZero on - OptimizeModelRefInitCode off - LifeSpan "inf" - MaxStackSize "Inherit from target" - BufferReusableBoundary on - SimCompilerOptimization "off" - AccelVerboseBuild off - } - Simulink.DebuggingCC { - $ObjectID 15 - Version "1.15.0" - RTPrefix "error" - ConsistencyChecking "none" - ArrayBoundsChecking "none" - SignalInfNanChecking "none" - SignalRangeChecking "none" - ReadBeforeWriteMsg "UseLocalSettings" - WriteAfterWriteMsg "UseLocalSettings" - WriteAfterReadMsg "UseLocalSettings" - AlgebraicLoopMsg "error" - ArtificialAlgebraicLoopMsg "warning" - SaveWithDisabledLinksMsg "warning" - SaveWithParameterizedLinksMsg "warning" - CheckSSInitialOutputMsg on - UnderspecifiedInitializationDetection "Simplified" - MergeDetectMultiDrivingBlocksExec "error" - CheckExecutionContextPreStartOutputMsg off - CheckExecutionContextRuntimeOutputMsg off - SignalResolutionControl "UseLocalSettings" - BlockPriorityViolationMsg "warning" - MinStepSizeMsg "warning" - TimeAdjustmentMsg "none" - MaxConsecutiveZCsMsg "error" - MaskedZcDiagnostic "warning" - IgnoredZcDiagnostic "warning" - SolverPrmCheckMsg "none" - InheritedTsInSrcMsg "warning" - MultiTaskDSMMsg "error" - MultiTaskCondExecSysMsg "error" - MultiTaskRateTransMsg "error" - SingleTaskRateTransMsg "none" - TasksWithSamePriorityMsg "warning" - SigSpecEnsureSampleTimeMsg "warning" - CheckMatrixSingularityMsg "none" - IntegerOverflowMsg "warning" - Int32ToFloatConvMsg "warning" - ParameterDowncastMsg "error" - ParameterOverflowMsg "error" - ParameterUnderflowMsg "none" - ParameterPrecisionLossMsg "warning" - ParameterTunabilityLossMsg "warning" - FixptConstUnderflowMsg "none" - FixptConstOverflowMsg "none" - FixptConstPrecisionLossMsg "none" - UnderSpecifiedDataTypeMsg "none" - UnnecessaryDatatypeConvMsg "none" - VectorMatrixConversionMsg "none" - InvalidFcnCallConnMsg "error" - FcnCallInpInsideContextMsg "EnableAllAsError" - SignalLabelMismatchMsg "none" - UnconnectedInputMsg "warning" - UnconnectedOutputMsg "warning" - UnconnectedLineMsg "warning" - SFcnCompatibilityMsg "none" - FrameProcessingCompatibilityMsg "error" - UniqueDataStoreMsg "none" - BusObjectLabelMismatch "warning" - RootOutportRequireBusObject "warning" - AssertControl "UseLocalSettings" - ModelReferenceIOMsg "none" - ModelReferenceMultiInstanceNormalModeStructChecksumCheck "error" - ModelReferenceVersionMismatchMessage "none" - ModelReferenceIOMismatchMessage "none" - UnknownTsInhSupMsg "warning" - ModelReferenceDataLoggingMessage "warning" - ModelReferenceSymbolNameMessage "warning" - ModelReferenceExtraNoncontSigs "error" - StateNameClashWarn "none" - SimStateInterfaceChecksumMismatchMsg "warning" - SimStateOlderReleaseMsg "error" - InitInArrayFormatMsg "warning" - StrictBusMsg "ErrorLevel1" - BusNameAdapt "WarnAndRepair" - NonBusSignalsTreatedAsBus "none" - BlockIODiagnostic "none" - SFUnusedDataAndEventsDiag "warning" - SFUnexpectedBacktrackingDiag "error" - SFInvalidInputDataAccessInChartInitDiag "warning" - SFNoUnconditionalDefaultTransitionDiag "error" - SFTransitionOutsideNaturalParentDiag "warning" - SFUnconditionalTransitionShadowingDiag "warning" - SFUndirectedBroadcastEventsDiag "warning" - SFTransitionActionBeforeConditionDiag "warning" - SFOutputUsedAsStateInMooreChartDiag "error" - IntegerSaturationMsg "warning" - } - Simulink.HardwareCC { - $ObjectID 16 - Version "1.15.0" - ProdBitPerChar 8 - ProdBitPerShort 16 - ProdBitPerInt 32 - ProdBitPerLong 32 - ProdBitPerLongLong 64 - ProdBitPerFloat 32 - ProdBitPerDouble 64 - ProdBitPerPointer 64 - ProdLargestAtomicInteger "Char" - ProdLargestAtomicFloat "Float" - ProdIntDivRoundTo "Zero" - ProdEndianess "LittleEndian" - ProdWordSize 32 - ProdShiftRightIntArith on - ProdLongLongMode off - ProdHWDeviceType "Specified" - TargetBitPerChar 8 - TargetBitPerShort 16 - TargetBitPerInt 32 - TargetBitPerLong 32 - TargetBitPerLongLong 64 - TargetBitPerFloat 32 - TargetBitPerDouble 64 - TargetBitPerPointer 32 - TargetLargestAtomicInteger "Char" - TargetLargestAtomicFloat "None" - TargetShiftRightIntArith on - TargetLongLongMode off - TargetIntDivRoundTo "Undefined" - TargetEndianess "Unspecified" - TargetWordSize 32 - TargetPreprocMaxBitsSint 32 - TargetPreprocMaxBitsUint 32 - TargetHWDeviceType "Specified" - TargetUnknown off - ProdEqTarget on - } - Simulink.ModelReferenceCC { - $ObjectID 17 - Version "1.15.0" - UpdateModelReferenceTargets "Force" - CheckModelReferenceTargetMessage "error" - EnableParallelModelReferenceBuilds off - ParallelModelReferenceErrorOnInvalidPool on - ParallelModelReferenceMATLABWorkerInit "None" - ModelReferenceNumInstancesAllowed "Multi" - PropagateVarSize "Infer from blocks in model" - ModelReferencePassRootInputsByReference on - ModelReferenceMinAlgLoopOccurrences off - PropagateSignalLabelsOutOfModel on - SupportModelReferenceSimTargetCustomCode off - } - Simulink.SFSimCC { - $ObjectID 18 - Version "1.15.0" - SimCustomHeaderCode "#include \"complementary_filter.h\"\n#include \"aeb_mat.h\"\n#include \"angle_accel.h\"" - SimUserSources "complementary_filter.c\naeb_mat.c\nangle_accel.c" - SimUserIncludeDirs "../../quad/src/computation_graph\n../../quad/src/quad_app\n../../quad/src/graph_blocks\n../.." - "/quad/src/commands" - SFSimEcho on - SimCtrlC on - SimIntegrity on - SimUseLocalCustomCode off - SimParseCustomCode on - SimBuildMode "sf_incremental_build" - SimGenImportedTypeDefs off - } - Simulink.RTWCC { - $BackupClass "Simulink.RTWCC" - $ObjectID 19 - Version "1.15.0" - Array { - Type "Cell" - Dimension 13 - Cell "IncludeHyperlinkInReport" - Cell "GenerateTraceInfo" - Cell "GenerateTraceReport" - Cell "GenerateTraceReportSl" - Cell "GenerateTraceReportSf" - Cell "GenerateTraceReportEml" - Cell "PortableWordSizes" - Cell "GenerateWebview" - Cell "GenerateCodeMetricsReport" - Cell "GenerateCodeReplacementReport" - Cell "GenerateMissedCodeReplacementReport" - Cell "GenerateErtSFunction" - Cell "CreateSILPILBlock" - PropName "DisabledProps" - } - SystemTargetFile "grt.tlc" - TLCOptions "" - GenCodeOnly off - MakeCommand "make_rtw" - GenerateMakefile on - PackageGeneratedCodeAndArtifacts off - TemplateMakefile "grt_default_tmf" - PostCodeGenCommand "" - GenerateReport off - SaveLog off - RTWVerbose on - RetainRTWFile off - ProfileTLC off - TLCDebug off - TLCCoverage off - TLCAssert off - RTWUseLocalCustomCode off - RTWUseSimCustomCode off - Toolchain "MinGW64 v4.x | gmake (64-bit Windows)" - BuildConfiguration "Faster Builds" - IncludeHyperlinkInReport off - LaunchReport off - PortableWordSizes off - CreateSILPILBlock "None" - CodeExecutionProfiling off - CodeExecutionProfileVariable "executionProfile" - CodeProfilingSaveOptions "SummaryOnly" - CodeProfilingInstrumentation off - SILDebugging off - TargetLang "C" - IncludeBusHierarchyInRTWFileBlockHierarchyMap off - GenerateTraceInfo off - GenerateTraceReport off - GenerateTraceReportSl off - GenerateTraceReportSf off - GenerateTraceReportEml off - GenerateWebview off - GenerateCodeMetricsReport off - GenerateCodeReplacementReport off - GenerateMissedCodeReplacementReport off - RTWCompilerOptimization "off" - RTWCustomCompilerOptimizations "" - CheckMdlBeforeBuild "Off" - SharedConstantsCachingThreshold 1024 - Array { - Type "Handle" - Dimension 2 - Simulink.CodeAppCC { - $ObjectID 20 - Version "1.15.0" - Array { - Type "Cell" - Dimension 25 - Cell "IgnoreCustomStorageClasses" - Cell "IgnoreTestpoints" - Cell "InsertBlockDesc" - Cell "InsertPolySpaceComments" - Cell "SFDataObjDesc" - Cell "MATLABFcnDesc" - Cell "SimulinkDataObjDesc" - Cell "DefineNamingRule" - Cell "SignalNamingRule" - Cell "ParamNamingRule" - Cell "InternalIdentifier" - Cell "InlinedPrmAccess" - Cell "CustomSymbolStr" - Cell "CustomSymbolStrGlobalVar" - Cell "CustomSymbolStrType" - Cell "CustomSymbolStrField" - Cell "CustomSymbolStrFcn" - Cell "CustomSymbolStrModelFcn" - Cell "CustomSymbolStrFcnArg" - Cell "CustomSymbolStrBlkIO" - Cell "CustomSymbolStrTmpVar" - Cell "CustomSymbolStrMacro" - Cell "CustomSymbolStrUtil" - Cell "CustomUserTokenString" - Cell "ReqsInCode" - PropName "DisabledProps" - } - ForceParamTrailComments off - GenerateComments on - CommentStyle "Auto" - IgnoreCustomStorageClasses on - IgnoreTestpoints off - IncHierarchyInIds off - MaxIdLength 31 - PreserveName off - PreserveNameWithParent off - ShowEliminatedStatement off - OperatorAnnotations off - IncAutoGenComments off - SimulinkDataObjDesc off - SFDataObjDesc off - MATLABFcnDesc off - IncDataTypeInIds off - MangleLength 1 - CustomSymbolStrGlobalVar "$R$N$M" - CustomSymbolStrType "$N$R$M_T" - CustomSymbolStrField "$N$M" - CustomSymbolStrFcn "$R$N$M$F" - CustomSymbolStrFcnArg "rt$I$N$M" - CustomSymbolStrBlkIO "rtb_$N$M" - CustomSymbolStrTmpVar "$N$M" - CustomSymbolStrMacro "$R$N$M" - CustomSymbolStrUtil "$N$C" - DefineNamingRule "None" - ParamNamingRule "None" - SignalNamingRule "None" - InsertBlockDesc off - InsertPolySpaceComments off - SimulinkBlockComments on - MATLABSourceComments off - EnableCustomComments off - InternalIdentifier "Shortened" - InlinedPrmAccess "Literals" - ReqsInCode off - UseSimReservedNames off - } - Simulink.GRTTargetCC { - $BackupClass "Simulink.TargetCC" - $ObjectID 21 - Version "1.15.0" - Array { - Type "Cell" - Dimension 15 - Cell "IncludeMdlTerminateFcn" - Cell "SuppressErrorStatus" - Cell "ERTCustomFileBanners" - Cell "GenerateSampleERTMain" - Cell "ExistingSharedCode" - Cell "GenerateTestInterfaces" - Cell "ModelStepFunctionPrototypeControlCompliant" - Cell "GenerateAllocFcn" - Cell "PurelyIntegerCode" - Cell "SupportComplex" - Cell "SupportAbsoluteTime" - Cell "SupportContinuousTime" - Cell "SupportNonInlinedSFcns" - Cell "RemoveDisableFunc" - Cell "RemoveResetFunc" - PropName "DisabledProps" - } - TargetFcnLib "ansi_tfl_table_tmw.mat" - TargetLibSuffix "" - TargetPreCompLibLocation "" - GenFloatMathFcnCalls "NOT IN USE" - TargetLangStandard "C99 (ISO)" - CodeReplacementLibrary "None" - UtilityFuncGeneration "Auto" - ERTMultiwordTypeDef "System defined" - ERTMultiwordLength 256 - MultiwordLength 2048 - GenerateFullHeader on - InferredTypesCompatibility off - GenerateSampleERTMain off - GenerateTestInterfaces off - ModelReferenceCompliant on - ParMdlRefBuildCompliant on - CompOptLevelCompliant on - ConcurrentExecutionCompliant on - IncludeMdlTerminateFcn on - GeneratePreprocessorConditionals "Use local settings" - CombineOutputUpdateFcns on - CombineSignalStateStructs off - SuppressErrorStatus off - ERTFirstTimeCompliant off - IncludeFileDelimiter "Auto" - ERTCustomFileBanners off - SupportAbsoluteTime on - LogVarNameModifier "rt_" - MatFileLogging on - MultiInstanceERTCode off - CodeInterfacePackaging "Nonreusable function" - SupportNonFinite on - SupportComplex on - PurelyIntegerCode off - SupportContinuousTime on - SupportNonInlinedSFcns on - SupportVariableSizeSignals off - ParenthesesLevel "Nominal" - CastingMode "Nominal" - MATLABClassNameForMDSCustomization "Simulink.SoftwareTarget.GRTCustomization" - ModelStepFunctionPrototypeControlCompliant off - CPPClassGenCompliant on - AutosarCompliant off - GRTInterface off - GenerateAllocFcn off - GenerateSharedConstants on - UseMalloc off - ExtMode off - ExtModeStaticAlloc off - ExtModeTesting off - ExtModeStaticAllocSize 1000000 - ExtModeTransport 0 - ExtModeMexFile "ext_comm" - ExtModeIntrfLevel "Level1" - RTWCAPISignals off - RTWCAPIParams off - RTWCAPIStates off - RTWCAPIRootIO off - GenerateASAP2 off - MultiInstanceErrorCode "Error" - } - PropName "Components" - } - } - PropName "Components" - } - Name "Configuration" - CurrentDlgPage "Solver" - ConfigPrmDlgPosition [ 510, 71, 1400, 811 ] - } - PropName "ConfigurationSets" - } - Simulink.ConfigSet { - $PropName "ActiveConfigurationSet" - $ObjectID 11 - } - Object { - $PropName "DataTransfer" - $ObjectID 23 - $ClassName "Simulink.GlobalDataTransfer" - DefaultTransitionBetweenSyncTasks "Ensure deterministic transfer (maximum delay)" - DefaultTransitionBetweenAsyncTasks "Ensure data integrity only" - DefaultTransitionBetweenContTasks "Ensure deterministic transfer (minimum delay)" - DefaultExtrapolationMethodBetweenContTasks "None" - AutoInsertRateTranBlk [0] - } - ExplicitPartitioning off - BlockDefaults { - ForegroundColor "black" - BackgroundColor "white" - DropShadow off - NamePlacement "normal" - FontName "Helvetica" - FontSize 10 - FontWeight "normal" - FontAngle "normal" - ShowName on - BlockRotation 0 - BlockMirror off - } - AnnotationDefaults { - HorizontalAlignment "center" - VerticalAlignment "middle" - ForegroundColor "black" - BackgroundColor "white" - DropShadow off - FontName "Helvetica" - FontSize 10 - FontWeight "normal" - FontAngle "normal" - UseDisplayTextAsClickCallback off - } - LineDefaults { - FontName "Helvetica" - FontSize 9 - FontWeight "normal" - FontAngle "normal" - } - MaskDefaults { - SelfModifiable "off" - IconFrame "on" - IconOpaque "on" - RunInitForIconRedraw "off" - IconRotate "none" - PortRotate "default" - IconUnits "autoscale" - } - MaskParameterDefaults { - Evaluate "on" - Tunable "on" - NeverSave "off" - Internal "off" - ReadOnly "off" - Enabled "on" - Visible "on" - ToolTip "on" - } - BlockParameterDefaults { - Block { - BlockType BusCreator - DisplayOption "none" - OutDataTypeStr "Inherit: auto" - NonVirtualBus off - } - Block { - BlockType BusSelector - OutputSignals "signal1,signal2,signal3" - OutputAsBus off - } - Block { - BlockType Constant - Value "1" - VectorParams1D on - SamplingMode "Sample based" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: Inherit from 'Constant value'" - LockScale off - SampleTime "inf" - FramePeriod "inf" - PreserveConstantTs off - } - Block { - BlockType Delay - DelayLengthSource "Dialog" - DelayLength "2" - DelayLengthUpperLimit "100" - InitialConditionSource "Dialog" - InitialCondition "0.0" - ExternalReset "None" - ShowEnablePort off - PreventDirectFeedthrough off - DiagnosticForOutOfRangeDelayLength "None" - RemoveProtectionDelayLength off - InputProcessing "Elements as channels (sample based)" - UseCircularBuffer off - SampleTime "-1" - StateMustResolveToSignalObject off - CodeGenStateStorageClass "Auto" - } - Block { - BlockType Demux - Outputs "4" - DisplayOption "none" - BusSelectionMode off - } - Block { - BlockType DiscreteFilter - NumeratorSource "Dialog" - Numerator "[1]" - DenominatorSource "Dialog" - Denominator "[1 0.5]" - InitialStatesSource "Dialog" - InitialStates "0" - InputProcessing "Elements as channels (sample based)" - ExternalReset "None" - InitialDenominatorStates "0" - FilterStructure "Direct form II" - SampleTime "-1" - a0EqualsOne off - NumCoefMin "[]" - NumCoefMax "[]" - DenCoefMin "[]" - DenCoefMax "[]" - OutMin "[]" - OutMax "[]" - StateDataTypeStr "Inherit: Same as input" - MultiplicandDataTypeStr "Inherit: Same as input" - NumCoefDataTypeStr "Inherit: Inherit via internal rule" - DenCoefDataTypeStr "Inherit: Inherit via internal rule" - NumProductDataTypeStr "Inherit: Inherit via internal rule" - DenProductDataTypeStr "Inherit: Inherit via internal rule" - NumAccumDataTypeStr "Inherit: Inherit via internal rule" - DenAccumDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - LockScale off - RndMeth "Floor" - SaturateOnIntegerOverflow off - StateMustResolveToSignalObject off - RTWStateStorageClass "Auto" - } - Block { - BlockType DiscreteIntegrator - IntegratorMethod "Integration: Forward Euler" - gainval "1.0" - ExternalReset "none" - InitialConditionSource "internal" - InitialCondition "0" - InitialConditionSetting "Output" - SampleTime "1" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: Inherit via internal rule" - LockScale off - RndMeth "Floor" - SaturateOnIntegerOverflow off - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - ShowSaturationPort off - ShowStatePort off - IgnoreLimit off - StateMustResolveToSignalObject off - RTWStateStorageClass "Auto" - } - Block { - BlockType FromWorkspace - VariableName "simulink_input" - OutDataTypeStr "Inherit: auto" - SampleTime "-1" - Interpolate on - ZeroCross off - OutputAfterFinalValue "Extrapolation" - } - Block { - BlockType Gain - Gain "1" - Multiplication "Element-wise(K.*u)" - ParamMin "[]" - ParamMax "[]" - ParamDataTypeStr "Inherit: Same as input" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: Same as input" - LockScale off - RndMeth "Floor" - SaturateOnIntegerOverflow on - SampleTime "-1" - } - Block { - BlockType Ground - } - Block { - BlockType Inport - Port "1" - OutputFunctionCall off - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: auto" - LockScale off - BusOutputAsStruct off - PortDimensions "-1" - VarSizeSig "Inherit" - SampleTime "-1" - SignalType "auto" - SamplingMode "auto" - LatchByDelayingOutsideSignal off - LatchInputForFeedbackSignals off - Interpolate on - } - Block { - BlockType Integrator - ExternalReset "none" - InitialConditionSource "internal" - InitialCondition "0" - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - WrapState off - WrappedStateUpperValue "pi" - WrappedStateLowerValue "-pi" - ShowSaturationPort off - ShowStatePort off - AbsoluteTolerance "auto" - IgnoreLimit off - ZeroCross on - ContinuousStateAttributes "''" - } - Block { - BlockType Mux - Inputs "4" - DisplayOption "none" - UseBusObject off - BusObject "BusObject" - NonVirtualBus off - } - Block { - BlockType Outport - Port "1" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: auto" - LockScale off - BusOutputAsStruct off - PortDimensions "-1" - VarSizeSig "Inherit" - SampleTime "-1" - SignalType "auto" - SamplingMode "auto" - SourceOfInitialOutputValue "Dialog" - OutputWhenDisabled "held" - InitialOutput "[]" - } - Block { - BlockType Quantizer - QuantizationInterval "0.5" - LinearizeAsGain on - SampleTime "-1" - } - Block { - BlockType RandomNumber - Mean "0" - Variance "1" - Seed "0" - SampleTime "-1" - VectorParams1D on - } - Block { - BlockType RateTransition - Integrity on - Deterministic on - X0 "0" - OutPortSampleTimeOpt "Specify" - OutPortSampleTimeMultiple "1" - OutPortSampleTime "-1" - } - Block { - BlockType S-Function - FunctionName "system" - SFunctionModules "''" - PortCounts "[]" - } - Block { - BlockType Saturate - UpperLimitSource "Dialog" - UpperLimit "0.5" - LowerLimitSource "Dialog" - LowerLimit "-0.5" - LinearizeAsGain on - ZeroCross on - SampleTime "-1" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: Same as input" - LockScale off - RndMeth "Floor" - } - Block { - BlockType Scope - Floating off - } - Block { - BlockType Step - Time "1" - Before "0" - After "1" - SampleTime "-1" - VectorParams1D on - ZeroCross on - } - Block { - BlockType SubSystem - ShowPortLabels "FromPortIcon" - Permissions "ReadWrite" - PermitHierarchicalResolution "All" - TreatAsAtomicUnit off - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - SystemSampleTime "-1" - RTWSystemCode "Auto" - RTWFcnNameOpts "Auto" - RTWFileNameOpts "Auto" - FunctionInterfaceSpec "void_void" - FunctionWithSeparateData off - RTWMemSecFuncInitTerm "Inherit from model" - RTWMemSecFuncExecute "Inherit from model" - RTWMemSecDataConstants "Inherit from model" - RTWMemSecDataInternal "Inherit from model" - RTWMemSecDataParameters "Inherit from model" - SimViewingDevice off - DataTypeOverride "UseLocalSettings" - DataTypeOverrideAppliesTo "AllNumericTypes" - MinMaxOverflowLogging "UseLocalSettings" - Opaque off - MaskHideContents off - SFBlockType "NONE" - GeneratePreprocessorConditionals off - PropagateVariantConditions off - TreatAsGroupedWhenPropagatingVariantConditions on - ContentPreviewEnabled off - IsWebBlock off - } - Block { - BlockType Sum - IconShape "rectangular" - Inputs "++" - CollapseMode "All dimensions" - CollapseDim "1" - InputSameDT on - AccumDataTypeStr "Inherit: Inherit via internal rule" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: Same as first input" - LockScale off - RndMeth "Floor" - SaturateOnIntegerOverflow on - SampleTime "-1" - } - Block { - BlockType Terminator - } - Block { - BlockType ToWorkspace - VariableName "simulink_output" - MaxDataPoints "1000" - Decimation "1" - SaveFormat "Array" - Save2DSignal "Inherit from input (this choice will be removed - see release notes)" - FixptAsFi off - NumInputs "1" - SampleTime "0" - } - Block { - BlockType TransportDelay - DelayTime "1" - InitialOutput "0" - BufferSize "1024" - FixedBuffer off - TransDelayFeedthrough off - PadeOrder "0" - } - Block { - BlockType ZeroOrderHold - SampleTime "1" - } - } - System { - Name "Quadcopter_Model_R2015_A" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - ReportName "simulink-default.rpt" - SIDHighWatermark "1424" - Block { - BlockType SubSystem - Name " Sensors " - SID "650" - Ports [6, 3] - Position [1300, 422, 1520, 658] - ZOrder 73 - ShowName off - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 24 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{B}Omega', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on');" - "\nport_label('input', 3, '^{B}v_o', 'texmode', 'on');\nport_label('input', 4, '^{E}r_o', 'texmode', 'on');\nport_labe" - "l('input', 5, '^{B}dv_o/dt', 'texmode', 'on');\nport_label('input', 6, '^{B}g', 'texmode', 'on');\nport_label('output" - "', 1, '\\Theta_{filtered}', 'texmode', 'on');\nport_label('output', 2, 'd\\Theta_{gyro}/dt', 'texmode', 'on');\nport_" - "label('output', 3, '^{E}r_o', 'texmode', 'on');\ndisp('Sensors', 'texmode', 'on'); " - } - System { - Name " Sensors " - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "50" - Block { - BlockType Inport - Name "B_Omega" - SID "651" - Position [635, 568, 665, 582] - ZOrder 265 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles" - SID "652" - Position [830, 1338, 860, 1352] - ZOrder 266 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_vo" - SID "653" - Position [635, 503, 665, 517] - ZOrder 267 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "E_ro" - SID "654" - Position [985, 1313, 1015, 1327] - ZOrder 268 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_vo_dot" - SID "655" - Position [635, 438, 665, 452] - ZOrder 269 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_g" - SID "656" - Position [635, 633, 665, 647] - ZOrder 273 - Port "6" - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "3D Graphical Simulation" - SID "698" - Ports [2] - Position [1265, 1425, 1415, 1485] - ZOrder 287 - Commented "on" - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 25 - $ClassName "Simulink.Mask" - Display "port_label('input',1,'r_{o}','texmode','on')\nport_label('input',2,'\\Theta','texmode','on')" - } - System { - Name "3D Graphical Simulation" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "Displacement" - SID "699" - Position [110, 218, 140, 232] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Euler Angles" - SID "700" - Position [125, 108, 155, 122] - ZOrder -2 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType BusCreator - Name "Bus\nCreator" - SID "701" - Ports [3, 1] - Position [600, 76, 610, 154] - ZOrder -3 - ShowName off - Inputs "3" - DisplayOption "bar" - InheritFromInputs on - } - Block { - BlockType BusCreator - Name "Bus\nCreator1" - SID "702" - Ports [3, 1] - Position [630, 191, 640, 269] - ZOrder -4 - ShowName off - Inputs "3" - DisplayOption "bar" - InheritFromInputs on - } - Block { - BlockType BusCreator - Name "Bus\nCreator2" - SID "703" - Ports [3, 1] - Position [385, 75, 390, 155] - ZOrder -5 - ShowName off - Inputs "3" - DisplayOption "bar" - InheritFromInputs on - } - Block { - BlockType BusSelector - Name "Bus\nSelector" - SID "704" - Ports [1, 3] - Position [500, 77, 505, 153] - ZOrder -6 - ShowName off - OutputSignals "phi,theta,psi" - Port { - PortNumber 1 - Name "<phi>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "<theta>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "<psi>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux" - SID "705" - Ports [1, 3] - Position [440, 183, 450, 267] - ZOrder -7 - BackgroundColor "black" - ShowName off - Outputs "3" - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux1" - SID "706" - Ports [1, 3] - Position [290, 75, 295, 155] - ZOrder -8 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "phi" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "theta" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "psi" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Gain - Name "Gain" - SID "707" - Position [550, 240, 580, 270] - ZOrder -10 - Gain "-1" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Gain - Name "Gain1" - SID "708" - Position [670, 208, 710, 252] - ZOrder -11 - Gain "eye(3)*1" - Multiplication "Matrix(K*u)" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Gain - Name "Gain2" - SID "709" - Position [550, 190, 580, 220] - ZOrder -12 - Gain "-1" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType SubSystem - Name "MATLAB Function" - SID "710" - Ports [1, 1] - Position [655, 92, 725, 138] - ZOrder 5 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - System { - Name "MATLAB Function" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "21" - Block { - BlockType Inport - Name "u" - SID "710::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "710::20" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "710::19" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 11" - Ports [1, 2] - Position [180, 100, 230, 160] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[1 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "y" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "710::21" - Position [460, 241, 480, 259] - ZOrder 12 - } - Block { - BlockType Outport - Name "y" - SID "710::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "u" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - Name "y" - ZOrder 2 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "y" - DstPort 1 - } - Line { - ZOrder 3 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType RateTransition - Name "Rate Transition" - SID "711" - Position [755, 94, 795, 136] - ZOrder -13 - NamePlacement "alternate" - OutPortSampleTime "0.06" - } - Block { - BlockType RateTransition - Name "Rate Transition1" - SID "712" - Position [735, 210, 770, 250] - ZOrder -14 - OutPortSampleTime "0.06" - } - Block { - BlockType Reference - Name "VR Sink" - SID "713" - Ports [2] - Position [865, 76, 1055, 234] - ZOrder -15 - LibraryVersion "1.36" - SourceBlock "vrlib/VR Sink" - SourceType "Virtual Reality Sink" - InstantiateOnLoad on - SampleTime "-1" - ViewEnable on - RemoteChange off - RemoteView off - FieldsWritten "Helicopter.rotation.4.1.1.double#Helicopter.translation.3.1.1.double" - WorldFileName "quadrotor_world_ucart.wrl" - AutoView on - VideoDimensions "[]" - AllowVariableSize off - } - Line { - ZOrder 1 - SrcBlock "Displacement" - SrcPort 1 - DstBlock "Demux" - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "Bus\nCreator2" - SrcPort 1 - DstBlock "Bus\nSelector" - DstPort 1 - } - Line { - ZOrder 3 - SrcBlock "Demux" - SrcPort 1 - Points [40, 0; 0, 40; 120, 0] - DstBlock "Bus\nCreator1" - DstPort 3 - } - Line { - ZOrder 4 - SrcBlock "Gain" - SrcPort 1 - Points [5, 0; 0, -25] - DstBlock "Bus\nCreator1" - DstPort 2 - } - Line { - ZOrder 5 - SrcBlock "Gain2" - SrcPort 1 - DstBlock "Bus\nCreator1" - DstPort 1 - } - Line { - ZOrder 6 - SrcBlock "Rate Transition1" - SrcPort 1 - Points [35, 0; 0, -35] - DstBlock "VR Sink" - DstPort 2 - } - Line { - ZOrder 7 - SrcBlock "Rate Transition" - SrcPort 1 - DstBlock "VR Sink" - DstPort 1 - } - Line { - ZOrder 8 - SrcBlock "Demux" - SrcPort 3 - DstBlock "Gain" - DstPort 1 - } - Line { - ZOrder 9 - SrcBlock "Demux" - SrcPort 2 - Points [80, 0] - DstBlock "Gain2" - DstPort 1 - } - Line { - ZOrder 10 - SrcBlock "Bus\nCreator1" - SrcPort 1 - DstBlock "Gain1" - DstPort 1 - } - Line { - Name "<phi>" - ZOrder 11 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 1 - Points [0, -10; 45, 0; 0, 60] - DstBlock "Bus\nCreator" - DstPort 3 - } - Line { - Name "<psi>" - ZOrder 12 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 3 - Points [0, -10; 75, 0] - DstBlock "Bus\nCreator" - DstPort 2 - } - Line { - Name "<theta>" - ZOrder 13 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 2 - Points [30, 0; 0, -25] - DstBlock "Bus\nCreator" - DstPort 1 - } - Line { - ZOrder 14 - SrcBlock "Gain1" - SrcPort 1 - DstBlock "Rate Transition1" - DstPort 1 - } - Line { - Name "psi" - ZOrder 15 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 3 - DstBlock "Bus\nCreator2" - DstPort 3 - } - Line { - Name "theta" - ZOrder 16 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 2 - DstBlock "Bus\nCreator2" - DstPort 2 - } - Line { - Name "phi" - ZOrder 17 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 1 - DstBlock "Bus\nCreator2" - DstPort 1 - } - Line { - ZOrder 18 - SrcBlock "Euler Angles" - SrcPort 1 - DstBlock "Demux1" - DstPort 1 - } - Line { - ZOrder 19 - SrcBlock "Bus\nCreator" - SrcPort 1 - DstBlock "MATLAB Function" - DstPort 1 - } - Line { - ZOrder 20 - SrcBlock "MATLAB Function" - SrcPort 1 - DstBlock "Rate Transition" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "3D Graphical Simulation1" - SID "714" - Ports [2] - Position [1900, 1435, 2050, 1495] - ZOrder 290 - Commented "on" - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 26 - $ClassName "Simulink.Mask" - Display "port_label('input',1, '\\Theta','texmode','on')\nport_label('input',2,'r_{o}','texmode','on')" - } - System { - Name "3D Graphical Simulation1" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "Euler Angles\n" - SID "715" - Position [180, 108, 210, 122] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Displacement" - SID "716" - Position [180, 218, 210, 232] - ZOrder -2 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType BusCreator - Name "Bus\nCreator" - SID "717" - Ports [3, 1] - Position [600, 76, 610, 154] - ZOrder -3 - ShowName off - Inputs "3" - DisplayOption "bar" - InheritFromInputs on - } - Block { - BlockType BusCreator - Name "Bus\nCreator1" - SID "718" - Ports [3, 1] - Position [630, 191, 640, 269] - ZOrder -4 - ShowName off - Inputs "3" - DisplayOption "bar" - InheritFromInputs on - } - Block { - BlockType BusCreator - Name "Bus\nCreator2" - SID "719" - Ports [3, 1] - Position [385, 75, 390, 155] - ZOrder -5 - ShowName off - Inputs "3" - DisplayOption "bar" - InheritFromInputs on - } - Block { - BlockType BusSelector - Name "Bus\nSelector" - SID "720" - Ports [1, 3] - Position [500, 77, 505, 153] - ZOrder -6 - ShowName off - OutputSignals "phi,theta,psi" - Port { - PortNumber 1 - Name "<phi>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "<theta>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "<psi>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux" - SID "721" - Ports [1, 3] - Position [440, 183, 450, 267] - ZOrder -7 - BackgroundColor "black" - ShowName off - Outputs "3" - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux1" - SID "722" - Ports [1, 3] - Position [290, 75, 295, 155] - ZOrder -8 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "phi" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "theta" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "psi" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Gain - Name "Gain" - SID "723" - Position [550, 240, 580, 270] - ZOrder -10 - Gain "-1" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Gain - Name "Gain1" - SID "724" - Position [670, 208, 710, 252] - ZOrder -11 - Gain "eye(3)*1" - Multiplication "Matrix(K*u)" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Gain - Name "Gain2" - SID "725" - Position [550, 190, 580, 220] - ZOrder -12 - Gain "-1" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType SubSystem - Name "MATLAB Function" - SID "726" - Ports [1, 1] - Position [655, 92, 725, 138] - ZOrder 5 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - System { - Name "MATLAB Function" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "21" - Block { - BlockType Inport - Name "u" - SID "726::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "726::20" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "726::19" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 3" - Ports [1, 2] - Position [180, 100, 230, 160] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[1 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "y" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "726::21" - Position [460, 241, 480, 259] - ZOrder 12 - } - Block { - BlockType Outport - Name "y" - SID "726::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "u" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - Name "y" - ZOrder 2 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "y" - DstPort 1 - } - Line { - ZOrder 3 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType RateTransition - Name "Rate Transition" - SID "727" - Position [755, 94, 795, 136] - ZOrder -13 - NamePlacement "alternate" - OutPortSampleTime "0.06" - } - Block { - BlockType RateTransition - Name "Rate Transition1" - SID "728" - Position [745, 210, 780, 250] - ZOrder -14 - OutPortSampleTime "0.06" - } - Block { - BlockType Reference - Name "VR Sink" - SID "729" - Ports [2] - Position [865, 76, 1055, 234] - ZOrder -15 - LibraryVersion "1.36" - SourceBlock "vrlib/VR Sink" - SourceType "Virtual Reality Sink" - InstantiateOnLoad on - SampleTime "-1" - ViewEnable on - RemoteChange off - RemoteView off - FieldsWritten "Helicopter.rotation.4.1.1.double#Helicopter.translation.3.1.1.double" - WorldFileName "quadrotor_world_ucart.wrl" - AutoView on - VideoDimensions "[]" - AllowVariableSize off - } - Line { - ZOrder 1 - SrcBlock "Bus\nCreator2" - SrcPort 1 - DstBlock "Bus\nSelector" - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "Demux" - SrcPort 1 - Points [40, 0; 0, 40; 120, 0] - DstBlock "Bus\nCreator1" - DstPort 3 - } - Line { - ZOrder 3 - SrcBlock "Gain" - SrcPort 1 - Points [5, 0; 0, -25] - DstBlock "Bus\nCreator1" - DstPort 2 - } - Line { - ZOrder 4 - SrcBlock "Gain2" - SrcPort 1 - DstBlock "Bus\nCreator1" - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock "Rate Transition1" - SrcPort 1 - Points [25, 0; 0, -35] - DstBlock "VR Sink" - DstPort 2 - } - Line { - ZOrder 6 - SrcBlock "Rate Transition" - SrcPort 1 - DstBlock "VR Sink" - DstPort 1 - } - Line { - ZOrder 7 - SrcBlock "Demux" - SrcPort 3 - DstBlock "Gain" - DstPort 1 - } - Line { - ZOrder 8 - SrcBlock "Demux" - SrcPort 2 - Points [80, 0] - DstBlock "Gain2" - DstPort 1 - } - Line { - ZOrder 9 - SrcBlock "Bus\nCreator1" - SrcPort 1 - DstBlock "Gain1" - DstPort 1 - } - Line { - Name "<phi>" - ZOrder 10 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 1 - Points [0, -10; 45, 0; 0, 60] - DstBlock "Bus\nCreator" - DstPort 3 - } - Line { - Name "<psi>" - ZOrder 11 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 3 - Points [0, -10; 75, 0] - DstBlock "Bus\nCreator" - DstPort 2 - } - Line { - Name "<theta>" - ZOrder 12 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 2 - Points [30, 0; 0, -25] - DstBlock "Bus\nCreator" - DstPort 1 - } - Line { - ZOrder 13 - SrcBlock "Gain1" - SrcPort 1 - DstBlock "Rate Transition1" - DstPort 1 - } - Line { - Name "psi" - ZOrder 14 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 3 - DstBlock "Bus\nCreator2" - DstPort 3 - } - Line { - Name "theta" - ZOrder 15 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 2 - DstBlock "Bus\nCreator2" - DstPort 2 - } - Line { - Name "phi" - ZOrder 16 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 1 - DstBlock "Bus\nCreator2" - DstPort 1 - } - Line { - ZOrder 17 - SrcBlock "Bus\nCreator" - SrcPort 1 - DstBlock "MATLAB Function" - DstPort 1 - } - Line { - ZOrder 18 - SrcBlock "MATLAB Function" - SrcPort 1 - DstBlock "Rate Transition" - DstPort 1 - } - Line { - ZOrder 19 - SrcBlock "Displacement" - SrcPort 1 - DstBlock "Demux" - DstPort 1 - } - Line { - ZOrder 20 - SrcBlock "Euler Angles\n" - SrcPort 1 - DstBlock "Demux1" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Aeb\n\n\n\n\n\n\n\n\n\n" - SID "679" - Ports [2, 1] - Position [1475, 579, 1655, 701] - ZOrder 275 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 27 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Gyroscope Reading', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{IMU" - "}', 'texmode', 'on');\nport_label('output', 1, 'd\\Theta_{Gyro}/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode'," - " 'on');" - } - System { - Name "Aeb\n\n\n\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "25" - Block { - BlockType Inport - Name "gyro_reading" - SID "679::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles_filtered" - SID "679::22" - Position [20, 136, 40, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "679::24" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 15 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "679::23" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 12" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 14 - FunctionName "sf_sfun" - PortCounts "[2 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "euler_rates_IMU" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "679::25" - Position [460, 241, 480, 259] - ZOrder 16 - } - Block { - BlockType Outport - Name "euler_rates_IMU" - SID "679::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "gyro_reading" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "euler_angles_filtered" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "euler_rates_IMU" - ZOrder 3 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "euler_rates_IMU" - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Aeb_c\n\n\n\n\n\n\n\n\n\n1" - SID "1335" - Ports [2, 1] - Position [1460, 969, 1640, 1091] - ZOrder 322 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 28 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Gyroscope Reading', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{IMU" - "}', 'texmode', 'on');\nport_label('output', 1, 'd\\Theta_{Gyro}/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode'," - " 'on');" - } - System { - Name "Aeb_c\n\n\n\n\n\n\n\n\n\n1" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "25" - Block { - BlockType Inport - Name "gyro_reading" - SID "1335::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles_filtered" - SID "1335::22" - Position [20, 136, 40, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "1335::24" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 15 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "1335::23" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 16" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 14 - FunctionName "sf_sfun" - PortCounts "[2 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "euler_rates_IMU" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "1335::25" - Position [460, 241, 480, 259] - ZOrder 16 - } - Block { - BlockType Outport - Name "euler_rates_IMU" - SID "1335::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "gyro_reading" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "euler_angles_filtered" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "euler_rates_IMU" - ZOrder 3 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "euler_rates_IMU" - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Calculate Pitch and Roll" - SID "680" - Ports [2, 2] - Position [1485, 379, 1655, 521] - ZOrder 284 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 29 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Accelerometer Reading', 'texmode', 'on');\nport_label('input', 2, '\\phi_{a" - "ccel}', 'texmode', 'on');\nport_label('output', 1, '\\theta_{accel}', 'texmode', 'on');\nport_label('output', 2, " - "'\\phi_{accel}', 'texmode', 'on');\ndisp('Calculate Pitch and Roll', 'texmode', 'on');" - } - System { - Name "Calculate Pitch and Roll" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "26" - Block { - BlockType Inport - Name "accel_reading" - SID "680::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "accel_roll_prev" - SID "680::23" - Position [20, 136, 40, 154] - ZOrder 14 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "680::20" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "680::19" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 13" - Ports [2, 3] - Position [180, 105, 230, 185] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[2 3]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "accel_pitch" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "accel_roll" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "680::21" - Position [460, 241, 480, 259] - ZOrder 12 - } - Block { - BlockType Outport - Name "accel_pitch" - SID "680::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "accel_roll" - SID "680::22" - Position [460, 136, 480, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "accel_reading" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "accel_roll_prev" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "accel_pitch" - ZOrder 3 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "accel_pitch" - DstPort 1 - } - Line { - Name "accel_roll" - ZOrder 4 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 3 - DstBlock "accel_roll" - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 6 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Complimentary Filter" - SID "1339" - Ports [4, 1] - Position [1880, 372, 2065, 713] - ZOrder 326 - ForegroundColor "red" - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 30 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '\\theta_{accel}', 'texmode', 'on');\nport_label('input', 2, '\\phi_{accel}'" - ", 'texmode', 'on');\nport_label('input', 3, '\\Theta_{Gyro}', 'texmode', 'on');\n%port_label('input', 4, '\\Theta" - "_{IMU}', 'texmode', 'on');\nport_label('output', 1, '\\Theta_{IMU}', 'texmode', 'on');\ndisp('Complementary Filte" - "r', 'texmode', 'on');" - } - System { - Name "Complimentary Filter" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "35" - Block { - BlockType Inport - Name "accel_pitch" - SID "1339::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "accel_roll" - SID "1339::29" - Position [20, 136, 40, 154] - ZOrder 20 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_rates_gyro" - SID "1339::22" - Position [20, 171, 40, 189] - ZOrder 13 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "prev_euler_angles" - SID "1339::35" - Position [20, 206, 40, 224] - ZOrder 21 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "1339::20" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "1339::19" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 19" - Ports [4, 2] - Position [180, 147, 230, 248] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[4 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "euler_angles_IMU" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "1339::21" - Position [460, 241, 480, 259] - ZOrder 12 - } - Block { - BlockType Outport - Name "euler_angles_IMU" - SID "1339::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 7 - SrcBlock "accel_pitch" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 8 - SrcBlock "accel_roll" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - ZOrder 9 - SrcBlock "euler_rates_gyro" - SrcPort 1 - DstBlock " SFunction " - DstPort 3 - } - Line { - ZOrder 10 - SrcBlock "prev_euler_angles" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " - DstPort 4 - } - Line { - Name "euler_angles_IMU" - ZOrder 11 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "euler_angles_IMU" - DstPort 1 - } - Line { - ZOrder 12 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 13 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType Delay - Name "Delay" - SID "1341" - Ports [1, 1] - Position [1955, 728, 1990, 762] - ZOrder 328 - BlockMirror on - InputPortMap "u0" - DelayLength "1" - InitialCondition "0" - } - Block { - BlockType Delay - Name "Delay1" - SID "731" - Ports [1, 1] - Position [1555, 528, 1590, 562] - ZOrder 285 - BlockMirror on - ForegroundColor "red" - InputPortMap "u0" - DelayLength "1" - InitialCondition "0" - SampleTime "Tq" - } - Block { - BlockType Delay - Name "Delay2" - SID "772" - Ports [1, 1] - Position [695, 428, 730, 462] - ZOrder 304 - InputPortMap "u0" - DelayLength "1" - InitialCondition "0" - SampleTime "Tq" - } - Block { - BlockType Demux - Name "Demux" - SID "1344" - Ports [1, 3] - Position [920, 1313, 925, 1377] - ZOrder 329 - ShowName off - Outputs "3" - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux1" - SID "1404" - Ports [1, 2] - Position [2285, 726, 2290, 764] - ZOrder 347 - ShowName off - Outputs "2" - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux2" - SID "1405" - Ports [1, 2] - Position [2285, 916, 2290, 954] - ZOrder 348 - ShowName off - Outputs "2" - DisplayOption "bar" - } - Block { - BlockType Reference - Name "First-Order\nHold" - SID "734" - Ports [1, 1] - Position [1790, 1435, 1825, 1465] - ZOrder 292 - ForegroundColor "yellow" - LibraryVersion "1.388" - DisableCoverage on - SourceBlock "simulink/Discrete/First-Order\nHold" - SourceType "First-Order Hold" - ContentPreviewEnabled off - Ts "5e-3" - } - Block { - BlockType Reference - Name "First-Order\nHold1" - SID "735" - Ports [1, 1] - Position [1790, 1530, 1825, 1560] - ZOrder 296 - ForegroundColor "yellow" - LibraryVersion "1.388" - DisableCoverage on - SourceBlock "simulink/Discrete/First-Order\nHold" - SourceType "First-Order Hold" - ContentPreviewEnabled off - Ts "5e-3" - } - Block { - BlockType SubSystem - Name "IMU\n\n\n\n\n\n" - SID "658" - Ports [4, 2] - Position [765, 410, 960, 675] - ZOrder 272 - ShowName off - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 31 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{B}dv_o/dt', 'texmode', 'on')\nport_label('input', 2, '^{B}v_o', 'texmode'" - ", 'on')\nport_label('input', 3, '^{B}\\Omega', 'texmode', 'on')\nport_label('input', 4, '^{B}g', 'texmode', 'on')" - "\nport_label('output', 1, 'Accelerometer Reading', 'texmode', 'on')\nport_label('output', 2, 'Gyroscope Reading'," - " 'texmode', 'on')\ndisp('IMU', 'texmode', 'on');" - } - System { - Name "IMU\n\n\n\n\n\n" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "B_vo_dot" - SID "659" - Position [110, 173, 140, 187] - ZOrder 17 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_vo" - SID "660" - Position [110, 208, 140, 222] - ZOrder 25 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_Omega" - SID "661" - Position [110, 243, 140, 257] - ZOrder 26 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_g" - SID "662" - Position [110, 278, 140, 292] - ZOrder 27 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "\n\n\n\n\n\n\n" - SID "663" - Ports [5, 2] - Position [250, 165, 445, 335] - ZOrder 1 - LibraryVersion "1.32" - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 32 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{B}dv_o/dt', 'texmode', 'on')\nport_label('input', 2, '^{B}v_o', 'texmode', 'on'" - ")\nport_label('input', 3, '^{B}\\Omega', 'texmode', 'on')\nport_label('input', 4, '^{B}g', 'texmode', 'on')\nport_la" - "bel('input', 5, 'r_{oc}', 'texmode', 'on')\nport_label('output', 1, 'Accelerometer Reading', 'texmode', 'on')\nport_" - "label('output', 2, 'Gyroscope Reading', 'texmode', 'on')\ndisp('Ideal IMU', 'texmode', 'on');" - } - System { - Name "\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "31" - Block { - BlockType Inport - Name "B_vo_dot" - SID "663::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_vo" - SID "663::22" - Position [20, 136, 40, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_Omega" - SID "663::19" - Position [20, 171, 40, 189] - ZOrder 10 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_g" - SID "663::20" - Position [20, 206, 40, 224] - ZOrder 11 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "r_oc" - SID "663::23" - Position [20, 246, 40, 264] - ZOrder 14 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "663::25" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 16 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "663::24" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 10" - Ports [5, 3] - Position [180, 110, 230, 230] - ZOrder 15 - FunctionName "sf_sfun" - Parameters "g" - PortCounts "[5 3]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "accelReading" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "gyroReading" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "663::26" - Position [460, 241, 480, 259] - ZOrder 17 - } - Block { - BlockType Outport - Name "accelReading" - SID "663::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "gyroReading" - SID "663::21" - Position [460, 136, 480, 154] - ZOrder 12 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "B_vo_dot" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "B_vo" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - ZOrder 3 - SrcBlock "B_Omega" - SrcPort 1 - DstBlock " SFunction " - DstPort 3 - } - Line { - ZOrder 4 - SrcBlock "B_g" - SrcPort 1 - DstBlock " SFunction " - DstPort 4 - } - Line { - ZOrder 5 - SrcBlock "r_oc" - SrcPort 1 - DstBlock " SFunction " - DstPort 5 - } - Line { - Name "accelReading" - ZOrder 6 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "accelReading" - DstPort 1 - } - Line { - Name "gyroReading" - ZOrder 7 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 3 - DstBlock "gyroReading" - DstPort 1 - } - Line { - ZOrder 8 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 9 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType Delay - Name "Delay" - SID "1371" - Ports [1, 1] - Position [915, 193, 950, 227] - ZOrder 50 - Commented "through" - InputPortMap "u0" - DelayLength "4" - InitialCondition "0" - SampleTime "Tq" - } - Block { - BlockType Delay - Name "Delay1" - SID "1372" - Ports [1, 1] - Position [915, 278, 950, 312] - ZOrder 51 - Commented "through" - InputPortMap "u0" - DelayLength "4" - InitialCondition "0" - SampleTime "Tq" - } - Block { - BlockType DiscreteFilter - Name "Discrete Filter1" - SID "921" - Ports [1, 1] - Position [790, 192, 850, 228] - ZOrder 48 - InputPortMap "u0" - Numerator "[0 0.1454]" - Denominator "[1 -0.8546]" - InitialStates "[0, 0, -1]" - SampleTime "Tq" - } - Block { - BlockType DiscreteFilter - Name "Discrete Filter2" - SID "922" - Ports [1, 1] - Position [790, 277, 850, 313] - ZOrder 49 - InputPortMap "u0" - Numerator "[0 0.1454]" - Denominator "[1 -0.8546]" - SampleTime "Tq" - } - Block { - BlockType DiscreteIntegrator - Name "Discrete-Time\nIntegrator" - SID "835" - Ports [1, 1] - Position [765, 407, 800, 443] - ZOrder 30 - InitialConditionSetting "State (most efficient)" - SampleTime "-1" - ICPrevOutput "DiscIntNeverNeededParam" - ICPrevScaledInput "DiscIntNeverNeededParam" - } - Block { - BlockType DiscreteIntegrator - Name "Discrete-Time\nIntegrator2" - SID "839" - Ports [1, 1] - Position [595, 407, 630, 443] - ZOrder 34 - InitialConditionSetting "State (most efficient)" - SampleTime "-1" - ICPrevOutput "DiscIntNeverNeededParam" - ICPrevScaledInput "DiscIntNeverNeededParam" - } - Block { - BlockType Ground - Name "Ground" - SID "664" - Position [605, 340, 625, 360] - ZOrder 23 - } - Block { - BlockType Ground - Name "Ground1" - SID "665" - Position [605, 145, 625, 165] - ZOrder 24 - } - Block { - BlockType Integrator - Name "Integrator" - SID "844" - Ports [1, 1] - Position [240, 360, 270, 390] - ZOrder 39 - } - Block { - BlockType Scope - Name "Scope" - SID "836" - Ports [1] - Position [845, 409, 875, 441] - ZOrder 31 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin -0.0001 - YMax 0.00021 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [680 330 1240 750] - } - Block { - BlockType Scope - Name "Scope2" - SID "840" - Ports [1] - Position [670, 409, 700, 441] - ZOrder 35 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData3 - YMin -1.00000 - YMax 1.00000 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [680 330 1240 750] - } - Block { - BlockType Scope - Name "Scope5" - SID "845" - Ports [1] - Position [295, 359, 325, 391] - ZOrder 40 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData6 - YMin -1.00000 - YMax 1.00000 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [306 114 866 534] - } - Block { - BlockType Sum - Name "Sum" - SID "666" - Ports [2, 1] - Position [715, 285, 735, 305] - ZOrder 7 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum1" - SID "667" - Ports [2, 1] - Position [715, 200, 735, 220] - ZOrder 8 - ShowName off - IconShape "round" - Inputs "++|" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum2" - SID "668" - Ports [2, 1] - Position [625, 285, 645, 305] - ZOrder 11 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum3" - SID "669" - Ports [2, 1] - Position [625, 200, 645, 220] - ZOrder 12 - ShowName off - IconShape "round" - Inputs "++|" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType RandomNumber - Name "accelerometer_noise" - SID "670" - Position [655, 105, 685, 135] - ZOrder 2 - Mean "zeros(3,1)" - Variance "[ 3e-7 ; 3.3e-7 ; 7.2e-7 ] " - Seed "[0,1,2]" - SampleTime "Tq" - } - Block { - BlockType Quantizer - Name "accelerometer_quantizer" - SID "671" - Position [1030, 195, 1060, 225] - ZOrder 9 - ForegroundColor "red" - QuantizationInterval "2.4400e-04" - } - Block { - BlockType ZeroOrderHold - Name "accelerometer_sampling" - SID "672" - Position [510, 195, 545, 225] - ZOrder 15 - SampleTime "Tq" - } - Block { - BlockType RandomNumber - Name "gyroscope_noise" - SID "673" - Position [655, 335, 685, 365] - ZOrder 6 - Mean "zeros(3,1)" - Variance "[ 2.2e-8 ; 1.1e-7 ; 2.4e-8 ]" - Seed "[0,1,2]" - SampleTime "Tq" - } - Block { - BlockType Quantizer - Name "gyroscope_qunatizer" - SID "674" - Position [1030, 280, 1060, 310] - ZOrder 10 - ForegroundColor "red" - QuantizationInterval "1.1e-3" - } - Block { - BlockType ZeroOrderHold - Name "gyroscope_sampling" - SID "675" - Position [510, 280, 545, 310] - ZOrder 16 - SampleTime "Tq" - } - Block { - BlockType Constant - Name "r_oc" - SID "676" - Position [30, 307, 95, 333] - ZOrder 28 - Value "zeros(3,1)" - } - Block { - BlockType Outport - Name "accelerometer" - SID "677" - Position [1135, 203, 1165, 217] - ZOrder 29 - ForegroundColor "red" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "gyroscope" - SID "678" - Position [1135, 288, 1165, 302] - ZOrder 21 - ForegroundColor "red" - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 3 - SrcBlock "accelerometer_noise" - SrcPort 1 - Points [35, 0] - DstBlock "Sum1" - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock "Sum2" - SrcPort 1 - DstBlock "Sum" - DstPort 1 - } - Line { - ZOrder 6 - SrcBlock "Sum3" - SrcPort 1 - DstBlock "Sum1" - DstPort 2 - } - Line { - ZOrder 8 - SrcBlock "gyroscope_noise" - SrcPort 1 - Points [35, 0] - Branch { - ZOrder 87 - DstBlock "Sum" - DstPort 2 - } - Branch { - ZOrder 35 - Points [0, 75] - DstBlock "Discrete-Time\nIntegrator" - DstPort 1 - } - } - Line { - ZOrder 11 - SrcBlock "gyroscope_sampling" - SrcPort 1 - Points [30, 0] - Branch { - ZOrder 85 - DstBlock "Sum2" - DstPort 1 - } - Branch { - ZOrder 45 - DstBlock "Discrete-Time\nIntegrator2" - DstPort 1 - } - } - Line { - ZOrder 12 - SrcBlock "accelerometer_sampling" - SrcPort 1 - DstBlock "Sum3" - DstPort 2 - } - Line { - ZOrder 13 - SrcBlock "Ground" - SrcPort 1 - Points [5, 0] - DstBlock "Sum2" - DstPort 2 - } - Line { - ZOrder 14 - SrcBlock "Ground1" - SrcPort 1 - Points [5, 0] - DstBlock "Sum3" - DstPort 1 - } - Line { - ZOrder 15 - SrcBlock "B_vo_dot" - SrcPort 1 - DstBlock "\n\n\n\n\n\n\n" - DstPort 1 - } - Line { - ZOrder 16 - SrcBlock "B_vo" - SrcPort 1 - DstBlock "\n\n\n\n\n\n\n" - DstPort 2 - } - Line { - ZOrder 17 - SrcBlock "B_Omega" - SrcPort 1 - Points [48, 0] - Branch { - ZOrder 50 - Points [0, 125] - DstBlock "Integrator" - DstPort 1 - } - Branch { - ZOrder 49 - DstBlock "\n\n\n\n\n\n\n" - DstPort 3 - } - } - Line { - ZOrder 18 - SrcBlock "B_g" - SrcPort 1 - DstBlock "\n\n\n\n\n\n\n" - DstPort 4 - } - Line { - ZOrder 19 - SrcBlock "r_oc" - SrcPort 1 - DstBlock "\n\n\n\n\n\n\n" - DstPort 5 - } - Line { - ZOrder 30 - SrcBlock "\n\n\n\n\n\n\n" - SrcPort 2 - DstBlock "gyroscope_sampling" - DstPort 1 - } - Line { - ZOrder 31 - SrcBlock "\n\n\n\n\n\n\n" - SrcPort 1 - DstBlock "accelerometer_sampling" - DstPort 1 - } - Line { - ZOrder 36 - SrcBlock "Discrete-Time\nIntegrator" - SrcPort 1 - DstBlock "Scope" - DstPort 1 - } - Line { - ZOrder 40 - SrcBlock "Discrete-Time\nIntegrator2" - SrcPort 1 - DstBlock "Scope2" - DstPort 1 - } - Line { - ZOrder 48 - SrcBlock "Integrator" - SrcPort 1 - DstBlock "Scope5" - DstPort 1 - } - Line { - ZOrder 124 - SrcBlock "Sum1" - SrcPort 1 - DstBlock "Discrete Filter1" - DstPort 1 - } - Line { - ZOrder 126 - SrcBlock "Sum" - SrcPort 1 - DstBlock "Discrete Filter2" - DstPort 1 - } - Line { - ZOrder 128 - SrcBlock "accelerometer_quantizer" - SrcPort 1 - DstBlock "accelerometer" - DstPort 1 - } - Line { - ZOrder 130 - SrcBlock "gyroscope_qunatizer" - SrcPort 1 - DstBlock "gyroscope" - DstPort 1 - } - Line { - ZOrder 127 - SrcBlock "Discrete Filter1" - SrcPort 1 - DstBlock "Delay" - DstPort 1 - } - Line { - ZOrder 129 - SrcBlock "Discrete Filter2" - SrcPort 1 - DstBlock "Delay1" - DstPort 1 - } - Line { - ZOrder 133 - SrcBlock "Delay" - SrcPort 1 - DstBlock "accelerometer_quantizer" - DstPort 1 - } - Line { - ZOrder 134 - SrcBlock "Delay1" - SrcPort 1 - DstBlock "gyroscope_qunatizer" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "MATLAB Function" - SID "1389" - Ports [3, 1] - Position [1885, 897, 2075, 1113] - ZOrder 343 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - System { - Name "MATLAB Function" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "23" - Block { - BlockType Inport - Name "accel_pitch" - SID "1389::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "accel_roll" - SID "1389::22" - Position [20, 136, 40, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_rates_gyro" - SID "1389::23" - Position [20, 171, 40, 189] - ZOrder 14 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "1389::20" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "1389::19" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 17" - Ports [3, 2] - Position [180, 100, 230, 180] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[3 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "euler_angles_IMU" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "1389::21" - Position [460, 241, 480, 259] - ZOrder 12 - } - Block { - BlockType Outport - Name "euler_angles_IMU" - SID "1389::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 14 - SrcBlock "accel_pitch" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 15 - SrcBlock "accel_roll" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - ZOrder 16 - SrcBlock "euler_rates_gyro" - SrcPort 1 - DstBlock " SFunction " - DstPort 3 - } - Line { - Name "euler_angles_IMU" - ZOrder 17 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "euler_angles_IMU" - DstPort 1 - } - Line { - ZOrder 18 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 19 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "MATLAB Function1" - SID "1407" - Ports [1, 2] - Position [1520, 196, 1625, 329] - ZOrder 350 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - System { - Name "MATLAB Function1" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "22" - Block { - BlockType Inport - Name "accel_reading" - SID "1407::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "1407::20" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "1407::19" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 18" - Ports [1, 3] - Position [180, 100, 230, 180] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[1 3]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "accel_pitch" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "accel_roll" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "1407::21" - Position [460, 241, 480, 259] - ZOrder 12 - } - Block { - BlockType Outport - Name "accel_pitch" - SID "1407::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "accel_roll" - SID "1407::22" - Position [460, 136, 480, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 9 - SrcBlock "accel_reading" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - Name "accel_pitch" - ZOrder 10 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "accel_pitch" - DstPort 1 - } - Line { - Name "accel_roll" - ZOrder 11 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 3 - DstBlock "accel_roll" - DstPort 1 - } - Line { - ZOrder 12 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 13 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType Mux - Name "Mux" - SID "1345" - Ports [2, 1] - Position [2180, 536, 2185, 574] - ZOrder 330 - ShowName off - Inputs "2" - DisplayOption "bar" - } - Block { - BlockType SubSystem - Name "OptiTrack Camera System\n\n " - SID "681" - Ports [2, 2] - Position [1255, 1296, 1495, 1389] - ZOrder 299 - ForegroundColor "yellow" - ShowName off - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 33 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{E}r_o', 'texmode', 'on');\nport_label('input', 2, '\\psi', 'texmode', 'on" - "');\nport_label('output', 1, '^{E}r_o camera', 'texmode', 'on');\nport_label('output', 2, '\\psi camera', 'texmod" - "e', 'on');\ndisp('OptiTrack Camera System', 'texmode', 'on');" - } - System { - Name "OptiTrack Camera System\n\n " - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "E_ro" - SID "682" - Position [295, 238, 325, 252] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "yaw" - SID "683" - Position [295, 338, 325, 352] - ZOrder 4 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType RandomNumber - Name "E_ro_noise" - SID "684" - Position [545, 175, 575, 205] - ZOrder 30 - Mean "zeros(3,1)" - Variance "[ 7.9664e-10 ; 1.1928e-10 ; 5.0636e-10 ] " - Seed "[0,1,2]" - SampleTime "Tc" - } - Block { - BlockType Quantizer - Name "E_ro_quantizer" - SID "685" - Position [685, 230, 715, 260] - ZOrder 34 - QuantizationInterval "2.4400e-04" - } - Block { - BlockType ZeroOrderHold - Name "E_ro_sampling" - SID "686" - Position [410, 230, 445, 260] - ZOrder 38 - SampleTime "Tc" - } - Block { - BlockType Ground - Name "Ground1" - SID "687" - Position [465, 180, 485, 200] - ZOrder 42 - } - Block { - BlockType Ground - Name "Ground2" - SID "688" - Position [465, 390, 485, 410] - ZOrder 56 - } - Block { - BlockType Sum - Name "Sum1" - SID "689" - Ports [2, 1] - Position [605, 235, 625, 255] - ZOrder 33 - ShowName off - IconShape "round" - Inputs "++|" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum3" - SID "690" - Ports [2, 1] - Position [485, 235, 505, 255] - ZOrder 37 - ShowName off - IconShape "round" - Inputs "++|" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum4" - SID "691" - Ports [2, 1] - Position [605, 335, 625, 355] - ZOrder 47 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum6" - SID "692" - Ports [2, 1] - Position [485, 335, 505, 355] - ZOrder 51 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType RandomNumber - Name "yaw_noise" - SID "693" - Position [545, 365, 575, 395] - ZOrder 46 - Variance "1.0783e-9" - SampleTime "Tc" - } - Block { - BlockType Quantizer - Name "yaw_quantizer" - SID "694" - Position [685, 330, 715, 360] - ZOrder 50 - QuantizationInterval "1.1e-3" - } - Block { - BlockType ZeroOrderHold - Name "yaw_sampling" - SID "695" - Position [410, 330, 445, 360] - ZOrder 54 - SampleTime "Tc" - } - Block { - BlockType Outport - Name "E_ro_camera" - SID "696" - Position [800, 238, 830, 252] - ZOrder 43 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "yaw_camera" - SID "697" - Position [800, 338, 830, 352] - ZOrder 55 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 2 - SrcBlock "E_ro_noise" - SrcPort 1 - Points [35, 0] - DstBlock "Sum1" - DstPort 1 - } - Line { - ZOrder 3 - SrcBlock "Sum3" - SrcPort 1 - DstBlock "Sum1" - DstPort 2 - } - Line { - ZOrder 4 - SrcBlock "Sum1" - SrcPort 1 - DstBlock "E_ro_quantizer" - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock "E_ro_sampling" - SrcPort 1 - DstBlock "Sum3" - DstPort 2 - } - Line { - ZOrder 6 - SrcBlock "Ground1" - SrcPort 1 - Points [5, 0] - DstBlock "Sum3" - DstPort 1 - } - Line { - ZOrder 8 - SrcBlock "Sum4" - SrcPort 1 - DstBlock "yaw_quantizer" - DstPort 1 - } - Line { - ZOrder 9 - SrcBlock "Sum6" - SrcPort 1 - DstBlock "Sum4" - DstPort 1 - } - Line { - ZOrder 10 - SrcBlock "yaw_noise" - SrcPort 1 - Points [35, 0] - DstBlock "Sum4" - DstPort 2 - } - Line { - ZOrder 11 - SrcBlock "yaw_sampling" - SrcPort 1 - DstBlock "Sum6" - DstPort 1 - } - Line { - ZOrder 12 - SrcBlock "Ground2" - SrcPort 1 - Points [5, 0] - DstBlock "Sum6" - DstPort 2 - } - Line { - ZOrder 17 - SrcBlock "yaw" - SrcPort 1 - DstBlock "yaw_sampling" - DstPort 1 - } - Line { - ZOrder 18 - SrcBlock "E_ro" - SrcPort 1 - DstBlock "E_ro_sampling" - DstPort 1 - } - Line { - ZOrder 19 - SrcBlock "E_ro_quantizer" - SrcPort 1 - DstBlock "E_ro_camera" - DstPort 1 - } - Line { - ZOrder 20 - SrcBlock "yaw_quantizer" - SrcPort 1 - DstBlock "yaw_camera" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Raw Accelerometer Data" - SID "1258" - Ports [1, 1] - Position [1030, 457, 1185, 503] - ZOrder 317 - ForegroundColor "magenta" - ShowName off - RequestExecContextInheritance off - Variant on - Object { - $PropName "MaskObject" - $ObjectID 34 - $ClassName "Simulink.Mask" - Display "disp('Raw Accelerometer Data', 'texmode', 'on');" - } - System { - Name "Raw Accelerometer Data" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "175" - Block { - BlockType Inport - Name "raw_accel_model" - SID "1259" - Position [20, 128, 50, 142] - ZOrder 288 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Feedback" - SID "1260" - Ports [1, 1] - Position [145, 155, 340, 185] - ZOrder 287 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==0" - Object { - $PropName "MaskObject" - $ObjectID 35 - $ClassName "Simulink.Mask" - Display "disp('Raw Accelerometer Data from Model', 'texmode', 'on');" - } - System { - Name "Feedback" - Location [-7, -7, 1288, 688] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "raw_accel_model" - SID "1261" - Position [105, 103, 135, 117] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "raw_accel" - SID "1262" - Position [360, 103, 390, 117] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "raw_accel_model" - SrcPort 1 - DstBlock "raw_accel" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Raw Accelerometer Data " - SID "1263" - Ports [0, 1] - Position [175, 75, 305, 105] - ZOrder 279 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==1" - Object { - $PropName "MaskObject" - $ObjectID 36 - $ClassName "Simulink.Mask" - Display "disp('Raw Accelerometer Data', 'texmode', 'on');" - } - System { - Name "Raw Accelerometer Data " - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType FromWorkspace - Name "From\nWorkspace5" - SID "1264" - Position [5, 18, 105, 42] - ZOrder 210 - VariableName "raw_accel_data" - SampleTime "Tq" - ZeroCross on - } - Block { - BlockType Outport - Name "raw_accel" - SID "1265" - Position [145, 23, 175, 37] - ZOrder 172 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "From\nWorkspace5" - SrcPort 1 - DstBlock "raw_accel" - DstPort 1 - } - } - } - Block { - BlockType Outport - Name "raw_accel" - SID "1266" - Position [405, 128, 435, 142] - ZOrder -2 - ForegroundColor "magenta" - IconDisplay "Port number" - } - Annotation { - SID "1267" - Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">" - "\n<html><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap" - "; }\n</style></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n" - "<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inde" - "nt:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"m" - "atlab://addvsschoiceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-deco" - "ration: underline; color:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;" - "\"> or </span><a href=\"matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helveti" - "ca'; font-size:10px; text-decoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'H" - "elvetica'; font-size:10px;\"> blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-b" - "ottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span st" - "yle=\" font-family:'Helvetica'; font-size:10px;\">2) You cannot connect blocks at this level. At simulation, co" - "nnectivity is automatically </span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin" - "-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; fo" - "nt-size:10px;\">determined, based on the active variant and port name matching.</span></p></body></html>" - Tag "VSSAddChoiceText" - Position [71, 28, 448, 69] - InternalMargins [0, 0, 0, 0] - FixedHeight off - FixedWidth off - HorizontalAlignment "left" - Interpreter "rich" - ZOrder -1 - } - } - } - Block { - BlockType SubSystem - Name "Raw Gyroscope Data" - SID "1268" - Ports [1, 1] - Position [1030, 587, 1185, 633] - ZOrder 318 - ForegroundColor "magenta" - ShowName off - RequestExecContextInheritance off - Variant on - Object { - $PropName "MaskObject" - $ObjectID 37 - $ClassName "Simulink.Mask" - Display "disp('Raw Gyroscope Data', 'texmode', 'on');" - } - System { - Name "Raw Gyroscope Data" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "175" - Block { - BlockType Inport - Name "raw_gyro_model" - SID "1269" - Position [40, 128, 70, 142] - ZOrder 288 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Feedback" - SID "1270" - Ports [1, 1] - Position [160, 153, 330, 187] - ZOrder 287 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==0" - Object { - $PropName "MaskObject" - $ObjectID 38 - $ClassName "Simulink.Mask" - Display "disp('Raw Gyroscope Data from Model', 'texmode', 'on');" - } - System { - Name "Feedback" - Location [633, 0, 1286, 687] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "raw_gyro_model" - SID "1271" - Position [105, 103, 135, 117] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "raw_gyro" - SID "1272" - Position [360, 103, 390, 117] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "raw_gyro_model" - SrcPort 1 - DstBlock "raw_gyro" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Raw Gyroscope Data " - SID "1273" - Ports [0, 1] - Position [180, 77, 310, 113] - ZOrder 279 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==1" - Object { - $PropName "MaskObject" - $ObjectID 39 - $ClassName "Simulink.Mask" - Display "disp('Raw Gyroscope Data', 'texmode', 'on');" - } - System { - Name "Raw Gyroscope Data " - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType FromWorkspace - Name "From\nWorkspace5" - SID "1274" - Position [145, 53, 230, 77] - ZOrder 210 - VariableName "raw_accel_data" - SampleTime "Tq" - ZeroCross on - } - Block { - BlockType Outport - Name "raw_gyro" - SID "1275" - Position [295, 58, 325, 72] - ZOrder 172 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "From\nWorkspace5" - SrcPort 1 - DstBlock "raw_gyro" - DstPort 1 - } - } - } - Block { - BlockType Outport - Name "raw_gyro" - SID "1276" - Position [405, 128, 435, 142] - ZOrder -2 - ForegroundColor "magenta" - IconDisplay "Port number" - } - Annotation { - SID "1277" - Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">" - "\n<html><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap" - "; }\n</style></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n" - "<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inde" - "nt:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"m" - "atlab://addvsschoiceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-deco" - "ration: underline; color:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;" - "\"> or </span><a href=\"matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helveti" - "ca'; font-size:10px; text-decoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'H" - "elvetica'; font-size:10px;\"> blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-b" - "ottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span st" - "yle=\" font-family:'Helvetica'; font-size:10px;\">2) You cannot connect blocks at this level. At simulation, co" - "nnectivity is automatically </span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin" - "-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; fo" - "nt-size:10px;\">determined, based on the active variant and port name matching.</span></p></body></html>" - Tag "VSSAddChoiceText" - Position [71, 28, 448, 69] - InternalMargins [0, 0, 0, 0] - FixedHeight off - FixedWidth off - HorizontalAlignment "left" - Interpreter "rich" - ZOrder -1 - } - } - } - Block { - BlockType ZeroOrderHold - Name "Sample" - SID "936" - Position [1640, 1305, 1675, 1335] - ZOrder 313 - ForegroundColor "green" - SampleTime "Tc" - } - Block { - BlockType ZeroOrderHold - Name "Sample1" - SID "937" - Position [1640, 1350, 1675, 1380] - ZOrder 314 - ForegroundColor "green" - SampleTime "Tc" - } - Block { - BlockType Scope - Name "Scope" - SID "737" - Ports [1] - Position [1315, 559, 1345, 591] - ZOrder 270 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin -0.00277 - YMax 0.00209 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [680 330 1240 750] - } - Block { - BlockType Scope - Name "Scope1" - SID "738" - Ports [1] - Position [1315, 499, 1345, 531] - ZOrder 271 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData2 - YMin -2.04337 - YMax 0.22704 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1909 1039] - } - Block { - BlockType Scope - Name "Scope2" - SID "1386" - Ports [2] - Position [1810, 221, 1840, 254] - ZOrder 340 - NumInputPorts "2" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends on - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin -1.867~-5 - YMax 1.68089~5 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope3" - SID "1387" - Ports [2] - Position [1810, 286, 1840, 319] - ZOrder 341 - NumInputPorts "2" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends on - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData2 - YMin -3.89902~-5 - YMax 3.92383~5 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1909 1039] - } - Block { - BlockType Scope - Name "Scope4" - SID "1388" - Ports [2] - Position [1720, 911, 1750, 944] - ZOrder 342 - NumInputPorts "2" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends on - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData3 - YMin -3.39538~-5 - YMax 1.81736~5 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope5" - SID "1403" - Ports [2] - Position [2525, 733, 2565, 782] - ZOrder 346 - NumInputPorts "2" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData4 - YMin -0.99149~-5 - YMax 0.86243~5 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope6" - SID "1406" - Ports [2] - Position [2525, 823, 2565, 872] - ZOrder 349 - NumInputPorts "2" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData5 - YMin -1.37391~-5 - YMax 0.98927~5 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType S-Function - Name "Soft Real Time" - SID "742" - Ports [] - Position [2008, 1540, 2095, 1571] - ZOrder 288 - ShowName off - Commented "on" - FunctionName "sfun_time" - Parameters "x" - SFunctionDeploymentMode off - EnableBusSupport off - Object { - $PropName "MaskObject" - $ObjectID 40 - $ClassName "Simulink.Mask" - Display "color('red')\ndisp('Soft Real Time')\n" - Object { - $PropName "Parameters" - $ObjectID 41 - $ClassName "Simulink.MaskParameter" - Type "edit" - Name "x" - Prompt "Time Scaling Factor" - Value "1" - } - } - } - Block { - BlockType ToWorkspace - Name "To Workspace4" - SID "1420" - Ports [1] - Position [1925, 1230, 2050, 1260] - ZOrder 351 - ShowName off - VariableName "position_model" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tc" - } - Block { - BlockType ToWorkspace - Name "To Workspace5" - SID "1256" - Ports [1] - Position [2360, 405, 2470, 435] - ZOrder 315 - ForegroundColor "red" - VariableName "angle_IMU_reading" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tq" - } - Block { - BlockType TransportDelay - Name "Transport\nDelay" - SID "933" - Ports [1, 1] - Position [1565, 1305, 1595, 1335] - ZOrder 310 - DelayTime "6e-3" - } - Block { - BlockType TransportDelay - Name "Transport\nDelay1" - SID "935" - Ports [1, 1] - Position [1565, 1350, 1595, 1380] - ZOrder 312 - DelayTime "6e-3" - } - Block { - BlockType Outport - Name "euler_angles_filtered" - SID "743" - Position [2245, 548, 2275, 562] - ZOrder 262 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "euler_rates" - SID "744" - Position [1255, 653, 1290, 667] - ZOrder 259 - ForegroundColor "red" - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "current_position" - SID "745" - Position [1925, 1313, 1955, 1327] - ZOrder 289 - Port "3" - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "IMU\n\n\n\n\n\n" - SrcPort 1 - DstBlock "Raw Accelerometer Data" - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock "IMU\n\n\n\n\n\n" - SrcPort 2 - DstBlock "Raw Gyroscope Data" - DstPort 1 - } - Line { - ZOrder 8 - SrcBlock "B_vo" - SrcPort 1 - DstBlock "IMU\n\n\n\n\n\n" - DstPort 2 - } - Line { - ZOrder 9 - SrcBlock "B_Omega" - SrcPort 1 - DstBlock "IMU\n\n\n\n\n\n" - DstPort 3 - } - Line { - ZOrder 10 - SrcBlock "B_g" - SrcPort 1 - DstBlock "IMU\n\n\n\n\n\n" - DstPort 4 - } - Line { - ZOrder 11 - SrcBlock "Calculate Pitch and Roll" - SrcPort 2 - Points [102, 0] - Branch { - ZOrder 553 - Points [0, -175] - DstBlock "Scope3" - DstPort 2 - } - Branch { - ZOrder 548 - Points [0, 60] - DstBlock "Delay1" - DstPort 1 - } - Branch { - ZOrder 245 - Points [76, 0] - Branch { - ZOrder 597 - Points [0, 520] - DstBlock "MATLAB Function" - DstPort 2 - } - Branch { - ZOrder 596 - Points [27, 0] - DstBlock "Complimentary Filter" - DstPort 2 - } - } - } - Line { - ZOrder 16 - SrcBlock "Calculate Pitch and Roll" - SrcPort 1 - Points [25, 0] - Branch { - ZOrder 552 - Points [0, -170] - DstBlock "Scope2" - DstPort 2 - } - Branch { - ZOrder 551 - Points [173, 0] - Branch { - ZOrder 595 - Points [0, 520] - DstBlock "MATLAB Function" - DstPort 1 - } - Branch { - ZOrder 594 - DstBlock "Complimentary Filter" - DstPort 1 - } - } - } - Line { - ZOrder 25 - SrcBlock "Delay1" - SrcPort 1 - Points [-89, 0; 0, -60] - DstBlock "Calculate Pitch and Roll" - DstPort 2 - } - Line { - ZOrder 33 - SrcBlock "First-Order\nHold" - SrcPort 1 - DstBlock "3D Graphical Simulation1" - DstPort 1 - } - Line { - ZOrder 34 - SrcBlock "E_ro" - SrcPort 1 - Points [191, 0] - Branch { - ZOrder 35 - Points [0, 120] - DstBlock "3D Graphical Simulation" - DstPort 1 - } - Branch { - ZOrder 36 - DstBlock "OptiTrack Camera System\n\n " - DstPort 1 - } - } - Line { - ZOrder 38 - SrcBlock "First-Order\nHold1" - SrcPort 1 - Points [20, 0; 0, -65] - DstBlock "3D Graphical Simulation1" - DstPort 2 - } - Line { - ZOrder 62 - SrcBlock "B_vo_dot" - SrcPort 1 - DstBlock "Delay2" - DstPort 1 - } - Line { - ZOrder 63 - SrcBlock "Delay2" - SrcPort 1 - DstBlock "IMU\n\n\n\n\n\n" - DstPort 1 - } - Line { - ZOrder 45 - SrcBlock "OptiTrack Camera System\n\n " - SrcPort 1 - Points [24, 0] - Branch { - ZOrder 235 - DstBlock "Transport\nDelay" - DstPort 1 - } - Branch { - ZOrder 208 - Points [0, 225] - DstBlock "First-Order\nHold1" - DstPort 1 - } - } - Line { - ZOrder 209 - SrcBlock "OptiTrack Camera System\n\n " - SrcPort 2 - Points [46, 0] - Branch { - ZOrder 234 - Points [0, 85] - DstBlock "First-Order\nHold" - DstPort 1 - } - Branch { - ZOrder 229 - DstBlock "Transport\nDelay1" - DstPort 1 - } - } - Line { - ZOrder 226 - SrcBlock "Transport\nDelay" - SrcPort 1 - DstBlock "Sample" - DstPort 1 - } - Line { - ZOrder 228 - SrcBlock "Transport\nDelay1" - SrcPort 1 - DstBlock "Sample1" - DstPort 1 - } - Line { - ZOrder 230 - SrcBlock "Sample" - SrcPort 1 - Points [110, 0] - Branch { - ZOrder 708 - Points [0, -75] - DstBlock "To Workspace4" - DstPort 1 - } - Branch { - ZOrder 707 - DstBlock "current_position" - DstPort 1 - } - } - Line { - ZOrder 295 - SrcBlock "Raw Accelerometer Data" - SrcPort 1 - Points [100, 0] - Branch { - ZOrder 414 - Points [83, 0; 0, -65; 48, 0] - Branch { - ZOrder 467 - Points [0, -150] - DstBlock "MATLAB Function1" - DstPort 1 - } - Branch { - ZOrder 466 - DstBlock "Calculate Pitch and Roll" - DstPort 1 - } - } - Branch { - ZOrder 297 - Points [0, 35] - DstBlock "Scope1" - DstPort 1 - } - } - Line { - ZOrder 298 - SrcBlock "Raw Gyroscope Data" - SrcPort 1 - Points [30, 0] - Branch { - ZOrder 413 - Points [66, 0] - Branch { - ZOrder 6 - Points [74, 0] - Branch { - ZOrder 561 - Points [0, 390] - DstBlock "Aeb_c\n\n\n\n\n\n\n\n\n\n1" - DstPort 1 - } - Branch { - ZOrder 316 - DstBlock "Aeb\n\n\n\n\n\n\n\n\n\n" - DstPort 1 - } - } - Branch { - ZOrder 5 - Points [0, -35] - DstBlock "Scope" - DstPort 1 - } - } - Branch { - ZOrder 160 - Points [0, 50] - DstBlock "euler_rates" - DstPort 1 - } - } - Line { - ZOrder 342 - SrcBlock "Delay" - SrcPort 1 - Points [-179, 0] - Branch { - ZOrder 562 - Points [0, -75] - DstBlock "Complimentary Filter" - DstPort 4 - } - Branch { - ZOrder 565 - Points [0, 115; -374, 0; 0, 200] - DstBlock "Aeb_c\n\n\n\n\n\n\n\n\n\n1" - DstPort 2 - } - Branch { - ZOrder 411 - Points [-339, 0; 0, -75] - DstBlock "Aeb\n\n\n\n\n\n\n\n\n\n" - DstPort 2 - } - } - Line { - ZOrder 416 - SrcBlock "euler_angles" - SrcPort 1 - DstBlock "Demux" - DstPort 1 - } - Line { - ZOrder 417 - SrcBlock "Demux" - SrcPort 3 - DstBlock "OptiTrack Camera System\n\n " - DstPort 2 - } - Line { - ZOrder 419 - SrcBlock "Sample1" - SrcPort 1 - Points [483, 0; 0, -800] - DstBlock "Mux" - DstPort 2 - } - Line { - ZOrder 420 - SrcBlock "Mux" - SrcPort 1 - DstBlock "euler_angles_filtered" - DstPort 1 - } - Line { - ZOrder 335 - SrcBlock "Complimentary Filter" - SrcPort 1 - Points [54, 0] - Branch { - ZOrder 665 - DstBlock "Mux" - DstPort 1 - } - Branch { - ZOrder 546 - Points [0, -125] - DstBlock "To Workspace5" - DstPort 1 - } - Branch { - ZOrder 533 - Points [0, 200] - Branch { - ZOrder 667 - DstBlock "Demux1" - DstPort 1 - } - Branch { - ZOrder 666 - DstBlock "Delay" - DstPort 1 - } - } - } - Line { - ZOrder 407 - SrcBlock "Aeb\n\n\n\n\n\n\n\n\n\n" - SrcPort 1 - Points [45, 0] - Branch { - ZOrder 560 - DstBlock "Scope4" - DstPort 1 - } - Branch { - ZOrder 558 - Points [108, 0] - Branch { - ZOrder 600 - Points [0, 435] - DstBlock "MATLAB Function" - DstPort 3 - } - Branch { - ZOrder 599 - Points [2, 0; 0, -55] - DstBlock "Complimentary Filter" - DstPort 3 - } - } - } - Line { - ZOrder 557 - SrcBlock "Aeb_c\n\n\n\n\n\n\n\n\n\n1" - SrcPort 1 - Points [35, 0; 0, -95] - DstBlock "Scope4" - DstPort 2 - } - Line { - ZOrder 604 - SrcBlock "MATLAB Function" - SrcPort 1 - Points [40, 0; 0, -70] - DstBlock "Demux2" - DstPort 1 - } - Line { - ZOrder 605 - SrcBlock "Demux1" - SrcPort 1 - Points [105, 0; 0, 10] - DstBlock "Scope5" - DstPort 1 - } - Line { - ZOrder 606 - SrcBlock "Demux2" - SrcPort 1 - Points [118, 0; 0, -155] - DstBlock "Scope5" - DstPort 2 - } - Line { - ZOrder 607 - SrcBlock "Demux1" - SrcPort 2 - Points [62, 0; 0, 80] - DstBlock "Scope6" - DstPort 1 - } - Line { - ZOrder 608 - SrcBlock "Demux2" - SrcPort 2 - Points [174, 0; 0, -85] - DstBlock "Scope6" - DstPort 2 - } - Line { - ZOrder 611 - SrcBlock "MATLAB Function1" - SrcPort 1 - DstBlock "Scope2" - DstPort 1 - } - Line { - ZOrder 614 - SrcBlock "MATLAB Function1" - SrcPort 2 - DstBlock "Scope3" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Actuation" - SID "436" - Ports [1, 6] - Position [955, 426, 1205, 654] - ZOrder 71 - ShowName off - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 42 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'P', 'texmode', 'on');\nport_label('output', 1, '^{B}Omega', 'texmode', 'on');\npor" - "t_label('output', 2, '\\Theta', 'texmode', 'on');\nport_label('output', 3, '^{B}v_o', 'texmode', 'on');\nport_label('" - "output', 4, '^{E}r_o', 'texmode', 'on');\nport_label('output', 5, '^{B}dv_o/dt', 'texmode', 'on');\nport_label('outpu" - "t', 6, '^{B}g', 'texmode', 'on');\ndisp('Actuation', 'texmode', 'on'); " - } - System { - Name "Actuation" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "125" - Block { - BlockType Inport - Name "P" - SID "437" - Position [-105, 393, -75, 407] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SID "446" - Ports [2, 1] - Position [1395, 303, 1630, 452] - ZOrder 81 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 43 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^B\\Omega', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode'," - " 'on');\nport_label('output', 1, 'd\\Theta/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode', 'on');" - } - System { - Name "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "25" - Block { - BlockType Inport - Name "B_omega" - SID "446::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles" - SID "446::22" - Position [20, 136, 40, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "446::24" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 15 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "446::23" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 7" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 14 - FunctionName "sf_sfun" - PortCounts "[2 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "euler_rates" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "446::25" - Position [460, 241, 480, 259] - ZOrder 16 - } - Block { - BlockType Outport - Name "euler_rates" - SID "446::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "B_omega" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "euler_angles" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "euler_rates" - ZOrder 3 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "euler_rates" - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType Demux - Name "Demux1" - SID "449" - Ports [1, 3] - Position [1830, 526, 1835, 574] - ZOrder 107 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "x position" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "y position" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "z position" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux2" - SID "450" - Ports [1, 3] - Position [1830, 301, 1835, 349] - ZOrder 109 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "Roll" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "Pitch" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "Yaw" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux3" - SID "451" - Ports [1, 3] - Position [1830, 406, 1835, 454] - ZOrder 117 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "Body x velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "Body y velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "Body z velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux4" - SID "452" - Ports [1, 3] - Position [1830, 161, 1835, 209] - ZOrder 115 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "Body roll velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "Body pitch velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "Body yaw velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux5" - SID "453" - Ports [1, 3] - Position [1830, 641, 1835, 689] - ZOrder 119 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "Body x acceleration" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "Body y acceleration" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "Body z acceleration" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType SubSystem - Name "ESC System" - SID "442" - Ports [1, 1] - Position [35, 282, 290, 518] - ZOrder 36 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 44 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'P', 'texmode', 'on');\nport_label('output', 1, 'Vb_{eff}', 'texmode', 'on')" - ";\ndisp('ESC System');" - } - System { - Name "ESC System" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "37" - Block { - BlockType Inport - Name "P" - SID "442::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "442::36" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 17 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "442::35" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 4" - Ports [1, 2] - Position [180, 105, 230, 165] - ZOrder 16 - FunctionName "sf_sfun" - Parameters "Pmax,Pmin,Vb" - PortCounts "[1 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "Vb_eff" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "442::37" - Position [460, 241, 480, 259] - ZOrder 18 - } - Block { - BlockType Outport - Name "Vb_eff" - SID "442::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 34 - SrcBlock "P" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - Name "Vb_eff" - ZOrder 35 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "Vb_eff" - DstPort 1 - } - Line { - ZOrder 36 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 37 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Gravity\n\n" - SID "443" - Ports [0, 1] - Position [335, 664, 485, 786] - ZOrder 96 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 45 - $ClassName "Simulink.Mask" - Display "port_label('output', 1, '^EF_g', 'texmode', 'on');\nfprintf('Gravity');\n" - } - System { - Name "Gravity\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "30" - Block { - BlockType Demux - Name " Demux " - SID "443::28" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 19 - Outputs "1" - } - Block { - BlockType Ground - Name " Ground " - SID "443::30" - Position [20, 121, 40, 139] - ZOrder 21 - } - Block { - BlockType S-Function - Name " SFunction " - SID "443::27" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 1" - Ports [1, 2] - Position [180, 100, 230, 160] - ZOrder 18 - FunctionName "sf_sfun" - Parameters "g,m" - PortCounts "[1 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "E_Fg" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "443::29" - Position [460, 241, 480, 259] - ZOrder 20 - } - Block { - BlockType Outport - Name "E_Fg" - SID "443::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - Name "E_Fg" - ZOrder 1 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "E_Fg" - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock " Ground " - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 3 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType Integrator - Name "Integrator" - SID "454" - Ports [1, 1] - Position [740, 340, 770, 370] - ZOrder 49 - InitialCondition "[omega0_o, omega1_o, omega2_o, omega3_o]" - } - Block { - BlockType Integrator - Name "Integrator1" - SID "455" - Ports [1, 1] - Position [1225, 445, 1255, 475] - ZOrder 53 - InitialCondition "[x_vel_o; y_vel_o; z_vel_o]" - } - Block { - BlockType Integrator - Name "Integrator2" - SID "456" - Ports [1, 1] - Position [1225, 325, 1255, 355] - ZOrder 54 - InitialCondition "[rollrate_o; pitchrate_o; yawrate_o]" - } - Block { - BlockType Integrator - Name "Integrator3" - SID "457" - Ports [1, 1] - Position [1685, 590, 1715, 620] - ZOrder 98 - InitialCondition "[x_o; y_o; z_o]" - } - Block { - BlockType Integrator - Name "Integrator4" - SID "458" - Ports [1, 1] - Position [1685, 365, 1715, 395] - ZOrder 77 - InitialCondition "[roll_o; pitch_o; yaw_o]" - ContinuousStateAttributes "['phi' 'theta' 'psi']" - } - Block { - BlockType SubSystem - Name "Lbe\n\n\n\n\n\n" - SID "444" - Ports [2, 1] - Position [1395, 499, 1630, 706] - ZOrder 75 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 46 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^Bv_o', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on" - "');\nport_label('output', 1, '^Ev_o', 'texmode', 'on');\ndisp('L_{EB}', 'texmode', 'on');" - } - System { - Name "Lbe\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "31" - Block { - BlockType Inport - Name "B_vo" - SID "444::24" - Position [20, 101, 40, 119] - ZOrder 15 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles" - SID "444::28" - Position [20, 136, 40, 154] - ZOrder 19 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "444::30" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 21 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "444::29" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 2" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 20 - FunctionName "sf_sfun" - PortCounts "[2 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "E_ro" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "444::31" - Position [460, 241, 480, 259] - ZOrder 22 - } - Block { - BlockType Outport - Name "E_ro" - SID "444::26" - Position [460, 101, 480, 119] - ZOrder 17 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "B_vo" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "euler_angles" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "E_ro" - ZOrder 3 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "E_ro" - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SID "447" - Ports [2, 2] - Position [600, 694, 770, 816] - ZOrder 97 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 47 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^EF_g', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on" - "');\nport_label('output', 1, '^BF_g', 'texmode', 'on');\nport_label('output', 2, '^Bg', 'texmode', 'on');\ndisp('" - "L_{BE}', 'texmode', 'on');" - } - System { - Name "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "33" - Block { - BlockType Inport - Name "E_Fg" - SID "447::24" - Position [20, 101, 40, 119] - ZOrder 15 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles" - SID "447::28" - Position [20, 136, 40, 154] - ZOrder 19 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "447::30" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 21 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "447::29" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 8" - Ports [2, 3] - Position [180, 100, 230, 180] - ZOrder 20 - FunctionName "sf_sfun" - Parameters "m" - PortCounts "[2 3]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "B_Fg" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "B_g" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "447::31" - Position [460, 241, 480, 259] - ZOrder 22 - } - Block { - BlockType Outport - Name "B_Fg" - SID "447::26" - Position [460, 101, 480, 119] - ZOrder 17 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "B_g" - SID "447::32" - Position [460, 136, 480, 154] - ZOrder 23 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "E_Fg" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "euler_angles" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "B_Fg" - ZOrder 3 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "B_Fg" - DstPort 1 - } - Line { - Name "B_g" - ZOrder 4 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 3 - DstBlock "B_g" - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 6 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Motor System" - SID "441" - Ports [2, 1] - Position [420, 280, 640, 520] - ZOrder 48 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 48 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Vb_{eff}', 'texmode', 'on');\nport_label('input', 2, '\\omega', 'texmode', " - "'on');\nport_label('output', 1, '\\alpha', 'texmode', 'on');\ndisp('Motor System');\n" - } - System { - Name "Motor System" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "35" - Block { - BlockType Inport - Name "Vb_eff" - SID "441::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "w" - SID "441::35" - Position [20, 136, 40, 154] - ZOrder 20 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "441::32" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 17 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "441::31" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 5" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 16 - FunctionName "sf_sfun" - Parameters "If,Jreq,Kd,Kq,Kv,Rm" - PortCounts "[2 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "w_dot" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "441::33" - Position [460, 241, 480, 259] - ZOrder 18 - } - Block { - BlockType Outport - Name "w_dot" - SID "441::23" - Position [460, 101, 480, 119] - ZOrder 14 - IconDisplay "Port number" - } - Line { - ZOrder 33 - SrcBlock "Vb_eff" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 34 - SrcBlock "w" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "w_dot" - ZOrder 35 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "w_dot" - DstPort 1 - } - Line { - ZOrder 36 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 37 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Rotor System\n\n\n\n\n\n\n\n" - SID "758" - Ports [5, 2] - Position [945, 281, 1145, 519] - ZOrder 122 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 49 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '\\alpha', 'texmode', 'on');\nport_label('input', 2, '\\omega', 'texmode', '" - "on');\nport_label('input', 3, '^BF_g', 'texmode', 'on');\nport_label('input', 4, '^B\\Omega', 'texmode', 'on');\n" - "port_label('input', 5, '^Bv_o', 'texmode', 'on');\nport_label('output', 1, '^Bd\\Omega/dt', 'texmode', 'on');\npo" - "rt_label('output', 2, '^Bdv_o/dt', 'texmode', 'on');\ndisp('Rotor System', 'texmode', 'on');" - } - System { - Name "Rotor System\n\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "51" - Block { - BlockType Inport - Name "w_dot" - SID "758::27" - Position [20, 101, 40, 119] - ZOrder 18 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "w" - SID "758::28" - Position [20, 136, 40, 154] - ZOrder 19 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_Fg" - SID "758::47" - Position [20, 171, 40, 189] - ZOrder 20 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_omega" - SID "758::25" - Position [20, 206, 40, 224] - ZOrder 16 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_vo" - SID "758::24" - Position [20, 246, 40, 264] - ZOrder 15 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "758::49" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 22 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "758::48" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 6" - Ports [5, 3] - Position [180, 100, 230, 220] - ZOrder 21 - FunctionName "sf_sfun" - Parameters "Jreq,Jxx,Jyy,Jzz,Kd,Kt,m,rhx,rhy,rhz" - PortCounts "[5 3]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "B_omega_dot" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "B_vo_dot" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "758::50" - Position [460, 241, 480, 259] - ZOrder 23 - } - Block { - BlockType Outport - Name "B_omega_dot" - SID "758::22" - Position [460, 101, 480, 119] - ZOrder 13 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "B_vo_dot" - SID "758::5" - Position [460, 136, 480, 154] - ZOrder -5 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 29 - SrcBlock "w_dot" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 30 - SrcBlock "w" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - ZOrder 31 - SrcBlock "B_Fg" - SrcPort 1 - DstBlock " SFunction " - DstPort 3 - } - Line { - ZOrder 32 - SrcBlock "B_omega" - SrcPort 1 - DstBlock " SFunction " - DstPort 4 - } - Line { - ZOrder 33 - SrcBlock "B_vo" - SrcPort 1 - DstBlock " SFunction " - DstPort 5 - } - Line { - Name "B_omega_dot" - ZOrder 34 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "B_omega_dot" - DstPort 1 - } - Line { - Name "B_vo_dot" - ZOrder 35 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 3 - DstBlock "B_vo_dot" - DstPort 1 - } - Line { - ZOrder 36 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 37 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType Scope - Name "Scope" - SID "459" - Ports [1] - Position [350, 279, 380, 311] - ZOrder 46 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData - YMin -0.88633 - YMax 7.97693 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope1" - SID "460" - Ports [1] - Position [740, 229, 770, 261] - ZOrder 50 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends on - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin -4063.58997 - YMax 3472.27662 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope10" - SID "461" - Ports [3] - Position [1935, 303, 1975, 347] - ZOrder 108 - NumInputPorts "3" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends on - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin -1.00000~-1.00000~-1.00000 - YMax 1.00000~1.00000~1.00000 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope11" - SID "462" - Ports [3] - Position [1935, 163, 1975, 207] - ZOrder 114 - NumInputPorts "3" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends on - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData3 - YMin -1.00000~-1.00000~-1.00000 - YMax 1.00000~1.00000~1.00000 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope2" - SID "463" - Ports [1] - Position [890, 229, 920, 261] - ZOrder 51 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData2 - YMin -87.04326 - YMax 669.47775 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope3" - SID "464" - Ports [3] - Position [1935, 408, 1975, 452] - ZOrder 116 - NumInputPorts "3" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends on - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData2 - YMin -1.00000~-1.00000~-0.000000000000004 - YMax 1.00000~1.00000~0.000000000000032 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope4" - SID "465" - Ports [3] - Position [1935, 643, 1975, 687] - ZOrder 118 - NumInputPorts "3" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends on - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData4 - YMin -1.00000~-1.00000~0.0000000000000004 - YMax 1.00000~1.00000~0.0000000000000024 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope5" - SID "1050" - Ports [1] - Position [1335, 364, 1365, 396] - ZOrder 316 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData3 - YMin -0.66996 - YMax 5.80636 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope6" - SID "466" - Ports [3] - Position [1935, 528, 1975, 572] - ZOrder 79 - NumInputPorts "3" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends on - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData4 - YMin -1.00000~-1.00000~-0.00000000000004 - YMax 1.00000~1.00000~0.00000000000032 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope7" - SID "467" - Ports [1] - Position [600, 639, 630, 671] - ZOrder 99 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin -1.52545 - YMax 13.7291 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope8" - SID "468" - Ports [1] - Position [820, 629, 850, 661] - ZOrder 100 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData2 - YMin -14.59237 - YMax 14.59237 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope9" - SID "469" - Ports [1] - Position [1225, 229, 1255, 261] - ZOrder 102 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData3 - YMin -1.00000 - YMax 1.00000 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Outport - Name "B_omega" - SID "471" - Position [1845, 238, 1875, 252] - ZOrder 61 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "euler_angles" - SID "472" - Position [1845, 373, 1875, 387] - ZOrder 91 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "B_vo" - SID "473" - Position [1845, 473, 1875, 487] - ZOrder 58 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "E_ro" - SID "474" - Position [1845, 598, 1875, 612] - ZOrder 88 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "B_vo_dot" - SID "475" - Position [1845, 718, 1875, 732] - ZOrder 103 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "B_g" - SID "476" - Position [1845, 778, 1875, 792] - ZOrder 104 - Port "6" - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "ESC System" - SrcPort 1 - Points [23, 0; 0, -60] - Branch { - ZOrder 2 - Points [0, -45] - DstBlock "Scope" - DstPort 1 - } - Branch { - ZOrder 3 - DstBlock "Motor System" - DstPort 1 - } - } - Line { - ZOrder 4 - SrcBlock "Motor System" - SrcPort 1 - Points [40, 0; 0, -45] - Branch { - ZOrder 5 - DstBlock "Integrator" - DstPort 1 - } - Branch { - ZOrder 6 - Points [0, -45] - Branch { - ZOrder 101 - DstBlock "Rotor System\n\n\n\n\n\n\n\n" - DstPort 1 - } - Branch { - ZOrder 7 - Points [0, -65] - DstBlock "Scope1" - DstPort 1 - } - } - } - Line { - ZOrder 103 - SrcBlock "Rotor System\n\n\n\n\n\n\n\n" - SrcPort 1 - Points [39, 0] - Branch { - ZOrder 15 - Points [0, -95] - DstBlock "Scope9" - DstPort 1 - } - Branch { - ZOrder 16 - DstBlock "Integrator2" - DstPort 1 - } - } - Line { - ZOrder 22 - SrcBlock "Integrator2" - SrcPort 1 - Points [55, 0] - Branch { - ZOrder 105 - Points [0, 252; -416, 0; 0, -147] - DstBlock "Rotor System\n\n\n\n\n\n\n\n" - DstPort 4 - } - Branch { - ZOrder 23 - Points [0, -95; 454, 0] - Branch { - ZOrder 24 - DstBlock "B_omega" - DstPort 1 - } - Branch { - ZOrder 25 - Points [0, -60] - DstBlock "Demux4" - DstPort 1 - } - } - Branch { - ZOrder 27 - DstBlock "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - DstPort 1 - } - } - Line { - ZOrder 28 - SrcBlock "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SrcPort 1 - DstBlock "Integrator4" - DstPort 1 - } - Line { - ZOrder 32 - SrcBlock "Lbe\n\n\n\n\n\n" - SrcPort 1 - DstBlock "Integrator3" - DstPort 1 - } - Line { - ZOrder 33 - SrcBlock "Integrator3" - SrcPort 1 - Points [64, 0] - Branch { - ZOrder 34 - Points [0, -55] - DstBlock "Demux1" - DstPort 1 - } - Branch { - ZOrder 35 - DstBlock "E_ro" - DstPort 1 - } - } - Line { - ZOrder 36 - SrcBlock "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SrcPort 1 - Points [24, 0] - Branch { - ZOrder 368 - Points [0, -80] - DstBlock "Scope8" - DstPort 1 - } - Branch { - ZOrder 107 - Points [82, 0; 0, -325] - DstBlock "Rotor System\n\n\n\n\n\n\n\n" - DstPort 3 - } - } - Line { - ZOrder 39 - SrcBlock "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SrcPort 2 - DstBlock "B_g" - DstPort 1 - } - Line { - Name "y position" - ZOrder 45 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 2 - DstBlock "Scope6" - DstPort 2 - } - Line { - Name "x position" - ZOrder 46 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 1 - DstBlock "Scope6" - DstPort 1 - } - Line { - Name "z position" - ZOrder 47 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 3 - DstBlock "Scope6" - DstPort 3 - } - Line { - Name "Pitch" - ZOrder 57 - Labels [0, 0] - SrcBlock "Demux2" - SrcPort 2 - DstBlock "Scope10" - DstPort 2 - } - Line { - Name "Roll" - ZOrder 58 - Labels [0, 0] - SrcBlock "Demux2" - SrcPort 1 - DstBlock "Scope10" - DstPort 1 - } - Line { - Name "Yaw" - ZOrder 59 - Labels [0, 0] - SrcBlock "Demux2" - SrcPort 3 - DstBlock "Scope10" - DstPort 3 - } - Line { - Name "Body pitch velocity" - ZOrder 60 - Labels [0, 0] - SrcBlock "Demux4" - SrcPort 2 - DstBlock "Scope11" - DstPort 2 - } - Line { - Name "Body roll velocity" - ZOrder 61 - Labels [0, 0] - SrcBlock "Demux4" - SrcPort 1 - DstBlock "Scope11" - DstPort 1 - } - Line { - Name "Body yaw velocity" - ZOrder 62 - Labels [0, 0] - SrcBlock "Demux4" - SrcPort 3 - DstBlock "Scope11" - DstPort 3 - } - Line { - Name "Body y velocity" - ZOrder 63 - Labels [0, 0] - SrcBlock "Demux3" - SrcPort 2 - DstBlock "Scope3" - DstPort 2 - } - Line { - Name "Body x velocity" - ZOrder 64 - Labels [0, 0] - SrcBlock "Demux3" - SrcPort 1 - DstBlock "Scope3" - DstPort 1 - } - Line { - Name "Body z velocity" - ZOrder 65 - Labels [0, 0] - SrcBlock "Demux3" - SrcPort 3 - DstBlock "Scope3" - DstPort 3 - } - Line { - Name "Body y acceleration" - ZOrder 66 - Labels [0, 0] - SrcBlock "Demux5" - SrcPort 2 - DstBlock "Scope4" - DstPort 2 - } - Line { - Name "Body x acceleration" - ZOrder 67 - Labels [0, 0] - SrcBlock "Demux5" - SrcPort 1 - DstBlock "Scope4" - DstPort 1 - } - Line { - Name "Body z acceleration" - ZOrder 68 - Labels [0, 0] - SrcBlock "Demux5" - SrcPort 3 - DstBlock "Scope4" - DstPort 3 - } - Line { - ZOrder 69 - SrcBlock "Integrator1" - SrcPort 1 - Points [34, 0] - Branch { - ZOrder 414 - Points [0, -80] - DstBlock "Scope5" - DstPort 1 - } - Branch { - ZOrder 413 - Points [0, 90] - Branch { - ZOrder 104 - Points [-370, 0; 0, -60] - DstBlock "Rotor System\n\n\n\n\n\n\n\n" - DstPort 5 - } - Branch { - ZOrder 71 - Points [76, 0] - Branch { - ZOrder 72 - DstBlock "Lbe\n\n\n\n\n\n" - DstPort 1 - } - Branch { - ZOrder 73 - Points [0, -70; 401, 0] - Branch { - ZOrder 367 - Points [0, -50] - DstBlock "Demux3" - DstPort 1 - } - Branch { - ZOrder 75 - DstBlock "B_vo" - DstPort 1 - } - } - } - } - } - Line { - ZOrder 102 - SrcBlock "Rotor System\n\n\n\n\n\n\n\n" - SrcPort 2 - Points [27, 0] - Branch { - ZOrder 205 - Points [0, 265; 607, 0] - Branch { - ZOrder 201 - Points [0, -60] - DstBlock "Demux5" - DstPort 1 - } - Branch { - ZOrder 200 - DstBlock "B_vo_dot" - DstPort 1 - } - } - Branch { - ZOrder 198 - DstBlock "Integrator1" - DstPort 1 - } - } - Line { - ZOrder 48 - SrcBlock "Integrator4" - SrcPort 1 - Points [20, 0] - Branch { - ZOrder 277 - Points [60, 0] - Branch { - ZOrder 361 - DstBlock "euler_angles" - DstPort 1 - } - Branch { - ZOrder 360 - Points [0, -55] - DstBlock "Demux2" - DstPort 1 - } - } - Branch { - ZOrder 52 - Points [0, 502; -385, 0] - Branch { - ZOrder 352 - Points [0, -227] - Branch { - ZOrder 54 - DstBlock "Lbe\n\n\n\n\n\n" - DstPort 2 - } - Branch { - ZOrder 55 - Points [0, -240] - DstBlock "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - DstPort 2 - } - } - Branch { - ZOrder 56 - Points [-787, 0; 0, -97] - DstBlock "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - DstPort 2 - } - } - } - Line { - ZOrder 286 - SrcBlock "P" - SrcPort 1 - DstBlock "ESC System" - DstPort 1 - } - Line { - ZOrder 416 - SrcBlock "Gravity\n\n" - SrcPort 1 - Points [86, 0] - Branch { - ZOrder 410 - Points [0, -70] - DstBlock "Scope7" - DstPort 1 - } - Branch { - ZOrder 409 - DstBlock "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - DstPort 1 - } - } - Line { - ZOrder 415 - SrcBlock "Integrator" - SrcPort 1 - Points [58, 0] - Branch { - ZOrder 290 - Points [0, 210; -473, 0; 0, -105] - DstBlock "Motor System" - DstPort 2 - } - Branch { - ZOrder 292 - DstBlock "Rotor System\n\n\n\n\n\n\n\n" - DstPort 2 - } - Branch { - ZOrder 291 - Points [0, -110] - DstBlock "Scope2" - DstPort 1 - } - } - } - } - Block { - BlockType SubSystem - Name "Communication System" - SID "582" - Ports [0, 1] - Position [515, 432, 570, 478] - ZOrder 70 - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 50 - $ClassName "Simulink.Mask" - Display "port_label('output', 1, 'Setpoints', 'texmode', 'on');" - } - System { - Name "Communication System" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "175" - Block { - BlockType Step - Name "Step" - SID "583" - Position [925, 390, 955, 420] - ZOrder 32 - Before "[0; 0; 0; 0]" - After "[0; 0; 0; 0]" - SampleTime "Tq" - } - Block { - BlockType Outport - Name "setpoints" - SID "584" - Position [1050, 398, 1080, 412] - ZOrder 6 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "Step" - SrcPort 1 - DstBlock "setpoints" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Control System" - SID "573" - Ports [4, 1] - Position [645, 423, 900, 652] - ZOrder 69 - ShowName off - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 51 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Setpoints', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{filtered}', 'texmo" - "de', 'on');\nport_label('input', 3, 'd\\Theta_{gyro}/dt', 'texmode', 'on');\nport_label('input', 4, '^{E}r_o', 'texmo" - "de', 'on');\nport_label('output', 1, 'P', 'texmode', 'on');\ndisp('Control System', 'texmode', 'on');" - } - System { - Name "Control System" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "80" - Block { - BlockType Inport - Name "setpoints" - SID "574" - Position [215, 363, 245, 377] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles_filtered" - SID "575" - Position [215, 523, 245, 537] - ZOrder 9 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_rates" - SID "576" - Position [215, 598, 245, 612] - ZOrder 11 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "current_position" - SID "577" - Position [215, 448, 245, 462] - ZOrder -1 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Constant - Name "Constant" - SID "919" - Position [275, 1020, 305, 1050] - ZOrder 66 - Value "Tc" - SampleTime "Tc" - } - Block { - BlockType SubSystem - Name "Controller" - SID "604" - Ports [13, 4] - Position [395, 315, 530, 645] - ZOrder 31 - RequestExecContextInheritance off - Variant off - Object { - $PropName "MaskObject" - $ObjectID 52 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{E}r_{x,setpoint}', 'texmode', 'on');\nport_label('input', 2, '^{E}r_{y,se" - "tpoint}', 'texmode', 'on');\nport_label('input', 3, '^{E}r_{z,setpoint}', 'texmode', 'on');\nport_label('input', " - "4, '\\psi_{setpoint}', 'texmode', 'on');\nport_label('input', 5, '^{E}r_x', 'texmode', 'on');\nport_label('input'" - ", 6, '^{E}r_y', 'texmode', 'on');\nport_label('input', 7, '^{E}r_z', 'texmode', 'on');\nport_label('input', 8, '\\" - "phi', 'texmode', 'on');\nport_label('input', 9, '\\theta', 'texmode', 'on');\nport_label('input', 10, '\\psi', 't" - "exmode', 'on');\nport_label('input', 11, 'd\\phi/dt', 'texmode', 'on');\nport_label('input', 12, 'd\\theta/dt', '" - "texmode', 'on');\nport_label('input', 13, 'd\\psi/dt', 'texmode', 'on');\nport_label('output', 1, 'u_T', 'texmode" - "', 'on');\nport_label('output', 2, 'u_A', 'texmode', 'on');\nport_label('output', 3, 'u_E', 'texmode', 'on');\npo" - "rt_label('output', 4, 'u_R', 'texmode', 'on');\ndisp('Controller', 'texmode', 'on');" - } - System { - Name "Controller" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "300" - Block { - BlockType Inport - Name "x_setpoint" - SID "605" - Position [475, -217, 505, -203] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "y_setpoint" - SID "607" - Position [475, -477, 505, -463] - ZOrder 45 - ForegroundColor "gray" - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "z_setpoint" - SID "608" - Position [475, -717, 505, -703] - ZOrder 46 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "yaw_setpoint" - SID "632" - Position [475, 53, 505, 67] - ZOrder 103 - ForegroundColor "gray" - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "x_position" - SID "622" - Position [545, -172, 575, -158] - ZOrder 60 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "y_position" - SID "623" - Position [540, -432, 570, -418] - ZOrder 61 - Port "6" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "z_position" - SID "624" - Position [555, -662, 585, -648] - ZOrder 62 - Port "7" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "roll" - SID "630" - Position [835, -432, 865, -418] - ZOrder 68 - Port "8" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "pitch" - SID "631" - Position [840, -172, 870, -158] - ZOrder 69 - Port "9" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "yaw" - SID "649" - Position [560, 98, 590, 112] - ZOrder 105 - Port "10" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "roll_rate" - SID "633" - Position [1095, -432, 1125, -418] - ZOrder 71 - Port "11" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "pitch_rate" - SID "634" - Position [1090, -172, 1120, -158] - ZOrder 72 - Port "12" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "yaw_rate" - SID "635" - Position [820, 118, 850, 132] - ZOrder 73 - Port "13" - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Altitude Controller Input" - SID "1177" - Ports [1, 1] - Position [685, -727, 750, -693] - ZOrder 292 - ForegroundColor "magenta" - ShowName off - RequestExecContextInheritance off - Variant on - Object { - $PropName "MaskObject" - $ObjectID 53 - $ClassName "Simulink.Mask" - Display "disp('^Ez_{y,error}', 'texmode', 'on');" - } - System { - Name "Altitude Controller Input" - Location [-7, -7, 1288, 688] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "200" - Block { - BlockType Inport - Name "z_error_model" - SID "1250" - Position [85, 123, 115, 137] - ZOrder 290 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Feedback" - SID "1251" - Ports [1, 1] - Position [215, 151, 285, 189] - ZOrder 289 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==0" - Object { - $PropName "MaskObject" - $ObjectID 54 - $ClassName "Simulink.Mask" - Display "disp('Feedback', 'texmode', 'on');" - } - System { - Name "Feedback" - Location [-7, -7, 1288, 688] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "z_error_model" - SID "1252" - Position [105, 103, 135, 117] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "z_error" - SID "1253" - Position [360, 103, 390, 117] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "z_error_model" - SrcPort 1 - DstBlock "z_error" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "z error" - SID "1090" - Ports [0, 1] - Position [215, 78, 285, 112] - ZOrder 280 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==1" - Object { - $PropName "MaskObject" - $ObjectID 55 - $ClassName "Simulink.Mask" - Display "disp('^Er_{z,error}', 'texmode', 'on');" - } - System { - Name "z error" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "200" - Block { - BlockType FromWorkspace - Name "From\nWorkspace6" - SID "999" - Position [15, 18, 80, 42] - ZOrder 221 - VariableName "z_error" - SampleTime "Tc" - ZeroCross on - } - Block { - BlockType Outport - Name "z_error" - SID "1093" - Position [145, 23, 175, 37] - ZOrder 172 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "From\nWorkspace6" - SrcPort 1 - DstBlock "z_error" - DstPort 1 - } - } - } - Block { - BlockType Outport - Name "z_error" - SID "1184" - Position [400, 123, 430, 137] - ZOrder -2 - ForegroundColor "magenta" - IconDisplay "Port number" - } - Annotation { - SID "1186" - Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" - "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" - "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" - " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" - "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" - "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" - "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" - "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" - "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " - "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" - "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" - "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" - "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" - "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" - "ve variant and port name matching.</span></p></body></html>" - Tag "VSSAddChoiceText" - Position [71, 28, 448, 69] - InternalMargins [0, 0, 0, 0] - FixedHeight off - FixedWidth off - HorizontalAlignment "left" - Interpreter "rich" - ZOrder -1 - } - } - } - Block { - BlockType Gain - Name "Gain" - SID "880" - Position [935, -135, 965, -105] - ZOrder 149 - Gain "180/pi" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Gain - Name "Gain1" - SID "1021" - Position [930, 135, 960, 165] - ZOrder 242 - Gain "180/pi" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Gain - Name "Gain2" - SID "980" - Position [935, -395, 965, -365] - ZOrder 202 - Gain "180/pi" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType SubSystem - Name "Latitude Controller Input" - SID "1127" - Ports [1, 1] - Position [675, -227, 740, -193] - ZOrder 287 - ForegroundColor "magenta" - ShowName off - RequestExecContextInheritance off - Variant on - Object { - $PropName "MaskObject" - $ObjectID 56 - $ClassName "Simulink.Mask" - Display "disp('^Er_{x,error}', 'texmode', 'on');" - } - System { - Name "Latitude Controller Input" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "x_error_model" - SID "1226" - Position [85, 158, 115, 172] - ZOrder 286 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Feedback" - SID "1227" - Ports [1, 1] - Position [185, 146, 255, 184] - ZOrder 285 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==0" - Object { - $PropName "MaskObject" - $ObjectID 57 - $ClassName "Simulink.Mask" - Display "disp('Feedback', 'texmode', 'on');" - } - System { - Name "Feedback" - Location [-7, -7, 1288, 688] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "x_error_model" - SID "1228" - Position [105, 103, 135, 117] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "x_error" - SID "1229" - Position [360, 103, 390, 117] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "x_error_model" - SrcPort 1 - DstBlock "x_error" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "x error" - SID "1059" - Ports [0, 1] - Position [185, 73, 255, 107] - ZOrder 278 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==1" - Object { - $PropName "MaskObject" - $ObjectID 58 - $ClassName "Simulink.Mask" - Display "disp('^Er_{x,error}', 'texmode', 'on');" - } - System { - Name "x error" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "300" - Block { - BlockType FromWorkspace - Name "From\nWorkspace" - SID "947" - Position [20, 18, 85, 42] - ZOrder 171 - VariableName "x_error" - SampleTime "Tc" - ZeroCross on - } - Block { - BlockType Outport - Name "x_error" - SID "1060" - Position [230, 23, 260, 37] - ZOrder 172 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "From\nWorkspace" - SrcPort 1 - DstBlock "x_error" - DstPort 1 - } - } - } - Block { - BlockType Outport - Name "x_error" - SID "1134" - Position [405, 128, 435, 142] - ZOrder -2 - ForegroundColor "magenta" - IconDisplay "Port number" - } - Annotation { - SID "1136" - Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" - "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" - "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" - " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" - "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" - "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" - "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" - "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" - "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " - "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" - "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" - "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" - "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" - "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" - "ve variant and port name matching.</span></p></body></html>" - Tag "VSSAddChoiceText" - Position [71, 28, 448, 69] - InternalMargins [0, 0, 0, 0] - FixedHeight off - FixedWidth off - HorizontalAlignment "left" - Interpreter "rich" - ZOrder -1 - } - } - } - Block { - BlockType SubSystem - Name "Longitude Controller Input" - SID "1147" - Ports [1, 1] - Position [670, -487, 735, -453] - ZOrder 289 - ForegroundColor "magenta" - ShowName off - RequestExecContextInheritance off - Variant on - Object { - $PropName "MaskObject" - $ObjectID 59 - $ClassName "Simulink.Mask" - Display "disp('^Er_{y,error}', 'texmode', 'on');" - } - System { - Name "Longitude Controller Input" - Location [-7, -7, 1288, 688] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "y_error_model" - SID "1238" - Position [85, 173, 115, 187] - ZOrder 288 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Feedback" - SID "1239" - Ports [1, 1] - Position [185, 161, 255, 199] - ZOrder 287 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==0" - Object { - $PropName "MaskObject" - $ObjectID 60 - $ClassName "Simulink.Mask" - Display "disp('Feedback', 'texmode', 'on');" - } - System { - Name "Feedback" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "y_error_model" - SID "1240" - Position [105, 103, 135, 117] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "y_error" - SID "1241" - Position [360, 103, 390, 117] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "y_error_model" - SrcPort 1 - DstBlock "y_error" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "y error" - SID "1078" - Ports [0, 1] - Position [185, 73, 255, 107] - ZOrder 279 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==1" - Object { - $PropName "MaskObject" - $ObjectID 61 - $ClassName "Simulink.Mask" - Display "disp('^Er_{y,error}', 'texmode', 'on');" - } - System { - Name "y error" - Location [-7, -7, 1288, 688] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "200" - Block { - BlockType FromWorkspace - Name "From\nWorkspace3" - SID "977" - Position [15, 18, 80, 42] - ZOrder 207 - VariableName "y_error" - SampleTime "Tc" - ZeroCross on - } - Block { - BlockType Outport - Name "y_error" - SID "1081" - Position [145, 23, 175, 37] - ZOrder 172 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "From\nWorkspace3" - SrcPort 1 - DstBlock "y_error" - DstPort 1 - } - } - } - Block { - BlockType Outport - Name "y_error" - SID "1154" - Position [385, 123, 415, 137] - ZOrder -2 - ForegroundColor "magenta" - IconDisplay "Port number" - } - Annotation { - SID "1156" - Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" - "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" - "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" - " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" - "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" - "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" - "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" - "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" - "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " - "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" - "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" - "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" - "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" - "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" - "ve variant and port name matching.</span></p></body></html>" - Tag "VSSAddChoiceText" - Position [71, 28, 448, 69] - InternalMargins [0, 0, 0, 0] - FixedHeight off - FixedWidth off - HorizontalAlignment "left" - Interpreter "rich" - ZOrder -1 - } - } - } - Block { - BlockType Reference - Name "PID Controller1" - SID "1355" - Ports [1, 1] - Position [1045, 41, 1085, 79] - ZOrder 313 - LibraryVersion "1.388" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "P" - TimeDomain "Discrete-time" - SampleTime "Tq" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter on - ControllerParametersSource "internal" - P "29700" - I "-77.7" - D "2.32" - N "1/0.0818" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross off - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller11" - SID "1370" - Ports [1, 1] - Position [790, -229, 830, -191] - ZOrder 321 - LibraryVersion "1.388" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "PID" - TimeDomain "Discrete-time" - SampleTime "Tc" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter on - ControllerParametersSource "internal" - P "-0.015" - I "0" - D "-0.25" - N "3" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller17" - SID "1352" - Ports [1, 1] - Position [790, -728, 830, -692] - ZOrder 310 - LibraryVersion "1.388" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "PID" - TimeDomain "Discrete-time" - SampleTime "Tc" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter off - ControllerParametersSource "internal" - P "9804" - I "817" - D "7353" - N "5.79502261645411" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller2" - SID "1424" - Ports [1, 1] - Position [1045, -488, 1085, -452] - ZOrder 326 - LibraryVersion "1.388" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "PD" - TimeDomain "Discrete-time" - SampleTime "Tq" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter off - ControllerParametersSource "internal" - P "15" - I "35.1207902652377" - D "0.2" - N "40.0107970227961" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller3" - SID "1423" - Ports [1, 1] - Position [1295, -488, 1335, -452] - ZOrder 325 - LibraryVersion "1.388" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "PD" - TimeDomain "Discrete-time" - SampleTime "Tq" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter off - ControllerParametersSource "internal" - P "4600" - I "1575.82088970639" - D "550" - N "244.660686071579" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller4" - SID "1354" - Ports [1, 1] - Position [790, 42, 830, 78] - ZOrder 312 - LibraryVersion "1.388" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "PD" - TimeDomain "Discrete-time" - SampleTime "Tc" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter off - ControllerParametersSource "internal" - P "2.6" - I "2.36803176515497" - D "0" - N "3.83298618768959" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller5" - SID "1368" - Ports [1, 1] - Position [1045, -228, 1085, -192] - ZOrder 319 - LibraryVersion "1.388" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "PD" - TimeDomain "Discrete-time" - SampleTime "Tq" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter off - ControllerParametersSource "internal" - P "15" - I "35.1207902652377" - D "0.2" - N "40.0107970227961" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller7" - SID "1365" - Ports [1, 1] - Position [790, -488, 830, -452] - ZOrder 316 - LibraryVersion "1.388" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "PID" - TimeDomain "Discrete-time" - SampleTime "Tc" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter on - ControllerParametersSource "internal" - P "0.015" - I "0" - D "0.25" - N "3" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller9" - SID "1367" - Ports [1, 1] - Position [1295, -228, 1335, -192] - ZOrder 318 - LibraryVersion "1.388" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "PD" - TimeDomain "Discrete-time" - SampleTime "Tq" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter off - ControllerParametersSource "internal" - P "4600" - I "1575.82088970639" - D "550" - N "244.660686071579" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType SubSystem - Name "Pitch Controller Input" - SID "1103" - Ports [1, 1] - Position [940, -227, 1005, -193] - ZOrder 283 - ForegroundColor "magenta" - ShowName off - RequestExecContextInheritance off - Variant on - Object { - $PropName "MaskObject" - $ObjectID 62 - $ClassName "Simulink.Mask" - Display "disp('\\theta_{error}', 'texmode', 'on');" - } - System { - Name "Pitch Controller Input" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "pitch_error_model" - SID "1230" - Position [85, 168, 115, 182] - ZOrder 286 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Feedback" - SID "1231" - Ports [1, 1] - Position [185, 156, 255, 194] - ZOrder 285 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==0" - Object { - $PropName "MaskObject" - $ObjectID 63 - $ClassName "Simulink.Mask" - Display "disp('Feedback', 'texmode', 'on');" - } - System { - Name "Feedback" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "pitch_error_model" - SID "1232" - Position [105, 103, 135, 117] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "pitch_error" - SID "1233" - Position [360, 103, 390, 117] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "pitch_error_model" - SrcPort 1 - DstBlock "pitch_error" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "pitch error" - SID "1066" - Ports [0, 1] - Position [185, 73, 255, 107] - ZOrder 274 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==1" - Object { - $PropName "MaskObject" - $ObjectID 64 - $ClassName "Simulink.Mask" - Display "disp('\\theta_{error}', 'texmode', 'on');" - } - System { - Name "pitch error" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType FromWorkspace - Name "From\nWorkspace" - SID "1068" - Position [20, 18, 85, 42] - ZOrder 171 - VariableName "pitch_error" - SampleTime "Tq" - ZeroCross on - } - Block { - BlockType Outport - Name "pitch_error" - SID "1069" - Position [145, 23, 175, 37] - ZOrder 172 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "From\nWorkspace" - SrcPort 1 - DstBlock "pitch_error" - DstPort 1 - } - } - } - Block { - BlockType Outport - Name "pitch_error" - SID "1105" - Position [410, 123, 440, 137] - ZOrder -2 - ForegroundColor "magenta" - IconDisplay "Port number" - } - Annotation { - SID "1106" - Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" - "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" - "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" - " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" - "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" - "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" - "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" - "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" - "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " - "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" - "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" - "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" - "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" - "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" - "ve variant and port name matching.</span></p></body></html>" - Tag "VSSAddChoiceText" - Position [71, 28, 448, 69] - InternalMargins [0, 0, 0, 0] - FixedHeight off - FixedWidth off - HorizontalAlignment "left" - Interpreter "rich" - ZOrder -1 - } - } - } - Block { - BlockType SubSystem - Name "Pitch Rate Controller Input" - SID "1137" - Ports [1, 1] - Position [1185, -227, 1250, -193] - ZOrder 288 - ForegroundColor "magenta" - ShowName off - RequestExecContextInheritance off - Variant on - Object { - $PropName "MaskObject" - $ObjectID 65 - $ClassName "Simulink.Mask" - Display "disp('d\\theta/dt_{error}', 'texmode', 'on');" - } - System { - Name "Pitch Rate Controller Input" - Location [-7, -7, 1288, 688] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "pitchrate_error_model" - SID "1234" - Position [85, 183, 115, 197] - ZOrder 286 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Feedback" - SID "1235" - Ports [1, 1] - Position [185, 171, 255, 209] - ZOrder 285 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==0" - Object { - $PropName "MaskObject" - $ObjectID 66 - $ClassName "Simulink.Mask" - Display "disp('Feedback', 'texmode', 'on');" - } - System { - Name "Feedback" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "pitchrate_error_model" - SID "1236" - Position [105, 103, 135, 117] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "pitchrate_error" - SID "1237" - Position [360, 103, 390, 117] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "pitchrate_error_model" - SrcPort 1 - DstBlock "pitchrate_error" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "pitchrate error" - SID "1074" - Ports [0, 1] - Position [185, 73, 255, 107] - ZOrder 278 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==1" - Object { - $PropName "MaskObject" - $ObjectID 67 - $ClassName "Simulink.Mask" - Display "disp('d\\theta/dt_{error}', 'texmode', 'on');" - } - System { - Name "pitchrate error" - Location [-7, -7, 1288, 688] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType FromWorkspace - Name "From\nWorkspace2" - SID "950" - Position [10, 18, 80, 42] - ZOrder 175 - VariableName "pitchrate_error" - SampleTime "Tq" - ZeroCross on - } - Block { - BlockType Outport - Name "pitchrate_error" - SID "1077" - Position [145, 23, 175, 37] - ZOrder 172 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "From\nWorkspace2" - SrcPort 1 - DstBlock "pitchrate_error" - DstPort 1 - } - } - } - Block { - BlockType Outport - Name "pitchrate_error" - SID "1144" - Position [410, 133, 440, 147] - ZOrder -2 - ForegroundColor "magenta" - IconDisplay "Port number" - } - Annotation { - SID "1146" - Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" - "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" - "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" - " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" - "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" - "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" - "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" - "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" - "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " - "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" - "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" - "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" - "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" - "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" - "ve variant and port name matching.</span></p></body></html>" - Tag "VSSAddChoiceText" - Position [71, 28, 448, 69] - InternalMargins [0, 0, 0, 0] - FixedHeight off - FixedWidth off - HorizontalAlignment "left" - Interpreter "rich" - ZOrder -1 - } - } - } - Block { - BlockType SubSystem - Name "Roll Controller Input" - SID "1157" - Ports [1, 1] - Position [950, -487, 1015, -453] - ZOrder 290 - ForegroundColor "magenta" - ShowName off - RequestExecContextInheritance off - Variant on - Object { - $PropName "MaskObject" - $ObjectID 68 - $ClassName "Simulink.Mask" - Display "disp('\\phi_{error}', 'texmode', 'on');" - } - System { - Name "Roll Controller Input" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "roll_error_model" - SID "1242" - Position [85, 158, 115, 172] - ZOrder 288 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Feedback" - SID "1243" - Ports [1, 1] - Position [185, 146, 255, 184] - ZOrder 287 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==0" - Object { - $PropName "MaskObject" - $ObjectID 69 - $ClassName "Simulink.Mask" - Display "disp('Feedback', 'texmode', 'on');" - } - System { - Name "Feedback" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "roll_error_model" - SID "1244" - Position [105, 103, 135, 117] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "roll_error" - SID "1245" - Position [360, 103, 390, 117] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "roll_error_model" - SrcPort 1 - DstBlock "roll_error" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "roll error" - SID "1082" - Ports [0, 1] - Position [185, 73, 255, 107] - ZOrder 278 - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==1" - Object { - $PropName "MaskObject" - $ObjectID 70 - $ClassName "Simulink.Mask" - Display "disp('\\phi_{error}', 'texmode', 'on');" - } - System { - Name "roll error" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType FromWorkspace - Name "From\nWorkspace4" - SID "978" - Position [190, 88, 255, 112] - ZOrder 209 - ForegroundColor "green" - VariableName "roll_error" - SampleTime "Tq" - ZeroCross on - } - Block { - BlockType Outport - Name "roll_error" - SID "1085" - Position [315, 93, 345, 107] - ZOrder 172 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "From\nWorkspace4" - SrcPort 1 - DstBlock "roll_error" - DstPort 1 - } - } - } - Block { - BlockType Outport - Name "roll_error" - SID "1164" - Position [410, 118, 440, 132] - ZOrder -2 - ForegroundColor "magenta" - IconDisplay "Port number" - } - Annotation { - SID "1166" - Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" - "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" - "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" - " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" - "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" - "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" - "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" - "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" - "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " - "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" - "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" - "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" - "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" - "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" - "ve variant and port name matching.</span></p></body></html>" - Tag "VSSAddChoiceText" - Position [71, 28, 448, 69] - InternalMargins [0, 0, 0, 0] - FixedHeight off - FixedWidth off - HorizontalAlignment "left" - Interpreter "rich" - ZOrder -1 - } - } - } - Block { - BlockType SubSystem - Name "Roll Rate Controller Input" - SID "1167" - Ports [1, 1] - Position [1200, -487, 1265, -453] - ZOrder 291 - ForegroundColor "magenta" - ShowName off - RequestExecContextInheritance off - Variant on - Object { - $PropName "MaskObject" - $ObjectID 71 - $ClassName "Simulink.Mask" - Display "disp('d\\phi/dt_{error}', 'texmode', 'on');" - } - System { - Name "Roll Rate Controller Input" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "175" - Block { - BlockType Inport - Name "rollrate_error_model" - SID "1246" - Position [85, 163, 115, 177] - ZOrder 288 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Feedback" - SID "1247" - Ports [1, 1] - Position [185, 151, 255, 189] - ZOrder 287 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==0" - Object { - $PropName "MaskObject" - $ObjectID 72 - $ClassName "Simulink.Mask" - Display "disp('Feedback', 'texmode', 'on');" - } - System { - Name "Feedback" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "rollrate_error_model" - SID "1248" - Position [105, 103, 135, 117] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "rollrate_error" - SID "1249" - Position [360, 103, 390, 117] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "rollrate_error_model" - SrcPort 1 - DstBlock "rollrate_error" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "rollrate error" - SID "1086" - Ports [0, 1] - Position [185, 73, 255, 107] - ZOrder 279 - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==1" - Object { - $PropName "MaskObject" - $ObjectID 73 - $ClassName "Simulink.Mask" - Display "disp('d\\phi/dt_{error}', 'texmode', 'on');" - } - System { - Name "rollrate error" - Location [-7, -7, 1288, 688] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType FromWorkspace - Name "From\nWorkspace5" - SID "979" - Position [10, 18, 80, 42] - ZOrder 210 - VariableName "rollrate_error" - SampleTime "Tq" - ZeroCross on - } - Block { - BlockType Outport - Name "rollrate_error" - SID "1089" - Position [145, 23, 175, 37] - ZOrder 172 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "From\nWorkspace5" - SrcPort 1 - DstBlock "rollrate_error" - DstPort 1 - } - } - } - Block { - BlockType Outport - Name "rollrate_error" - SID "1174" - Position [405, 128, 435, 142] - ZOrder -2 - ForegroundColor "magenta" - IconDisplay "Port number" - } - Annotation { - SID "1176" - Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" - "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" - "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" - " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" - "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" - "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" - "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" - "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" - "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " - "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" - "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" - "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" - "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" - "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" - "ve variant and port name matching.</span></p></body></html>" - Tag "VSSAddChoiceText" - Position [71, 28, 448, 69] - InternalMargins [0, 0, 0, 0] - FixedHeight off - FixedWidth off - HorizontalAlignment "left" - Interpreter "rich" - ZOrder -1 - } - } - } - Block { - BlockType Saturate - Name "Saturation" - SID "932" - Ports [1, 1] - Position [1380, 45, 1410, 75] - ZOrder 161 - InputPortMap "u0" - UpperLimit "20000" - LowerLimit "-20000" - } - Block { - BlockType Saturate - Name "Saturation1" - SID "1001" - Ports [1, 1] - Position [1390, -225, 1420, -195] - ZOrder 222 - InputPortMap "u0" - UpperLimit "20000" - LowerLimit "-20000" - } - Block { - BlockType Saturate - Name "Saturation2" - SID "1002" - Ports [1, 1] - Position [1390, -485, 1420, -455] - ZOrder 223 - InputPortMap "u0" - UpperLimit "20000" - LowerLimit "-20000" - } - Block { - BlockType Saturate - Name "Saturation3" - SID "1003" - Ports [1, 1] - Position [1390, -725, 1420, -695] - ZOrder 224 - InputPortMap "u0" - UpperLimit "20000" - LowerLimit "-20000" - } - Block { - BlockType Scope - Name "Scope1" - SID "1022" - Ports [1] - Position [990, 134, 1020, 166] - ZOrder 241 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData5 - YMin -237.62576 - YMax 9.97394 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [680 330 1240 750] - } - Block { - BlockType Scope - Name "Scope11" - SID "984" - Ports [1] - Position [1215, -386, 1245, -354] - ZOrder 199 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints on - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData2 - YMin -1.23139 - YMax 0.20473 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat Array - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1909 1039] - } - Block { - BlockType Scope - Name "Scope12" - SID "985" - Ports [1] - Position [645, -336, 675, -304] - ZOrder 200 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData3 - YMin -5094.66345 - YMax 568.26972 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope13" - SID "986" - Ports [1] - Position [995, -396, 1025, -364] - ZOrder 201 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints on - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData4 - YMin -10 - YMax 10 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat Array - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [680 330 1240 750] - } - Block { - BlockType Scope - Name "Scope2" - SID "795" - Ports [1] - Position [665, -591, 695, -559] - ZOrder 107 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData5 - YMin -233.85726 - YMax 2104.70554 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope3" - SID "1006" - Ports [1] - Position [655, 199, 685, 231] - ZOrder 226 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin -171.38344 - YMax 42.10594 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope4" - SID "1030" - Ports [1] - Position [650, -76, 680, -44] - ZOrder 250 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints on - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin -227.57395 - YMax 29.15339 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat Array - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope6" - SID "825" - Ports [1] - Position [1205, -126, 1235, -94] - ZOrder 117 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin -32.40215 - YMax 23.21935 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Scope - Name "Scope9" - SID "878" - Ports [1] - Position [995, -136, 1025, -104] - ZOrder 147 - NumInputPorts "1" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin -0.5042 - YMax 4.53783 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [1 76 1921 1039] - } - Block { - BlockType Sum - Name "Sum1" - SID "1007" - Ports [2, 1] - Position [610, 50, 630, 70] - ZOrder 225 - ForegroundColor "green" - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum10" - SID "988" - Ports [2, 1] - Position [1140, -480, 1160, -460] - ZOrder 193 - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum11" - SID "989" - Ports [2, 1] - Position [610, -480, 630, -460] - ZOrder 194 - ForegroundColor "green" - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum2" - SID "1023" - Ports [2, 1] - Position [870, 50, 890, 70] - ZOrder 240 - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum3" - SID "602" - Ports [2, 1] - Position [875, -220, 895, -200] - ZOrder 43 - ForegroundColor "green" - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum4" - SID "603" - Ports [2, 1] - Position [1130, -220, 1150, -200] - ZOrder 44 - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum5" - SID "618" - Ports [2, 1] - Position [610, -220, 630, -200] - ZOrder 56 - ForegroundColor "green" - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum7" - SID "620" - Ports [2, 1] - Position [610, -720, 630, -700] - ZOrder 58 - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum9" - SID "987" - Ports [2, 1] - Position [875, -480, 895, -460] - ZOrder 192 - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType ToWorkspace - Name "To Workspace" - SID "948" - Ports [1] - Position [875, -290, 985, -260] - ZOrder 172 - ShowName off - VariableName "pitch_setpoint_model" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "-1" - } - Block { - BlockType ToWorkspace - Name "To Workspace1" - SID "951" - Ports [1] - Position [1125, -290, 1250, -260] - ZOrder 175 - ShowName off - VariableName "pitchrate_setpoint_model" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tq" - } - Block { - BlockType ToWorkspace - Name "To Workspace10" - SID "1029" - Ports [1] - Position [650, 135, 770, 165] - ZOrder 249 - VariableName "yaw_value_model" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tc" - } - Block { - BlockType ToWorkspace - Name "To Workspace11" - SID "1032" - Ports [1] - Position [645, -390, 765, -360] - ZOrder 252 - ShowName off - VariableName "y_position_model" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tc" - } - Block { - BlockType ToWorkspace - Name "To Workspace12" - SID "1033" - Ports [1] - Position [660, -640, 780, -610] - ZOrder 253 - ShowName off - VariableName "z_position_model" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tc" - } - Block { - BlockType ToWorkspace - Name "To Workspace2" - SID "952" - Ports [1] - Position [1495, -290, 1605, -260] - ZOrder 176 - VariableName "x_command_model" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tq" - } - Block { - BlockType ToWorkspace - Name "To Workspace3" - SID "993" - Ports [1] - Position [895, -545, 1005, -515] - ZOrder 207 - ShowName off - VariableName "roll_setpoint_model" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tc" - } - Block { - BlockType ToWorkspace - Name "To Workspace4" - SID "994" - Ports [1] - Position [1150, -545, 1275, -515] - ZOrder 210 - ShowName off - VariableName "rollrate_setpoint_model" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tq" - } - Block { - BlockType ToWorkspace - Name "To Workspace5" - SID "995" - Ports [1] - Position [1500, -545, 1610, -515] - ZOrder 211 - ForegroundColor "red" - VariableName "y_command_model" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tq" - } - Block { - BlockType ToWorkspace - Name "To Workspace6" - SID "1000" - Ports [1] - Position [1420, -805, 1530, -775] - ZOrder 327 - VariableName "z_command_model" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tq" - } - Block { - BlockType ToWorkspace - Name "To Workspace7" - SID "1025" - Ports [1] - Position [870, -20, 990, 10] - ZOrder 243 - ShowName off - VariableName "yawrate_setpoint_model" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tc" - } - Block { - BlockType ToWorkspace - Name "To Workspace8" - SID "1026" - Ports [1] - Position [1495, -20, 1605, 10] - ZOrder 247 - ShowName off - VariableName "yaw_command_model" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tq" - } - Block { - BlockType ToWorkspace - Name "To Workspace9" - SID "1028" - Ports [1] - Position [650, -135, 770, -105] - ZOrder 248 - ShowName off - VariableName "x_position_model" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tc" - } - Block { - BlockType SubSystem - Name "Yaw Controller Input" - SID "1187" - Ports [1, 1] - Position [675, 43, 740, 77] - ZOrder 293 - ForegroundColor "magenta" - ShowName off - RequestExecContextInheritance off - Variant on - Object { - $PropName "MaskObject" - $ObjectID 74 - $ClassName "Simulink.Mask" - Display "disp('\\psi_{error}', 'texmode', 'on');" - } - System { - Name "Yaw Controller Input" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "200" - Block { - BlockType Inport - Name "yaw_error_model" - SID "1216" - Position [50, 158, 80, 172] - ZOrder 282 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Feedback" - SID "1188" - Ports [1, 1] - Position [185, 146, 255, 184] - ZOrder 276 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==0" - Object { - $PropName "MaskObject" - $ObjectID 75 - $ClassName "Simulink.Mask" - Display "disp('Feedback', 'texmode', 'on');" - } - System { - Name "Feedback" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "yaw_error_model" - SID "1215" - Position [105, 103, 135, 117] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "yaw_error" - SID "1190" - Position [360, 103, 390, 117] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 2 - SrcBlock "yaw_error_model" - SrcPort 1 - DstBlock "yaw_error" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "yaw error" - SID "1094" - Ports [0, 1] - Position [185, 73, 255, 107] - ZOrder 281 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==1" - Object { - $PropName "MaskObject" - $ObjectID 76 - $ClassName "Simulink.Mask" - Display "disp('\\psi_{error}', 'texmode', 'on');" - } - System { - Name "yaw error" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType FromWorkspace - Name "From\nWorkspace7" - SID "1005" - Position [20, 18, 85, 42] - ZOrder 228 - VariableName "yaw_error" - SampleTime "Tc" - ZeroCross on - } - Block { - BlockType Outport - Name "yaw_error" - SID "1097" - Position [145, 23, 175, 37] - ZOrder 172 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "From\nWorkspace7" - SrcPort 1 - DstBlock "yaw_error" - DstPort 1 - } - } - } - Block { - BlockType Outport - Name "yaw_error" - SID "1194" - Position [410, 123, 440, 137] - ZOrder -2 - ForegroundColor "magenta" - IconDisplay "Port number" - } - Annotation { - SID "1196" - Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" - "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" - "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" - " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" - "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" - "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" - "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" - "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" - "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " - "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" - "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" - "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" - "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" - "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" - "ve variant and port name matching.</span></p></body></html>" - Tag "VSSAddChoiceText" - Position [71, 28, 448, 69] - InternalMargins [0, 0, 0, 0] - FixedHeight off - FixedWidth off - HorizontalAlignment "left" - Interpreter "rich" - ZOrder -1 - } - } - } - Block { - BlockType SubSystem - Name "Yaw Rate Controller Input" - SID "1197" - Ports [1, 1] - Position [940, 43, 1005, 77] - ZOrder 294 - ForegroundColor "magenta" - ShowName off - RequestExecContextInheritance off - Variant on - Object { - $PropName "MaskObject" - $ObjectID 77 - $ClassName "Simulink.Mask" - Display "disp('d\\psi/dt_{error}', 'texmode', 'on');" - } - System { - Name "Yaw Rate Controller Input" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "yawrate_error_model" - SID "1225" - Position [85, 158, 115, 172] - ZOrder 284 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Feedback" - SID "1222" - Ports [1, 1] - Position [185, 146, 255, 184] - ZOrder 283 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==0" - Object { - $PropName "MaskObject" - $ObjectID 78 - $ClassName "Simulink.Mask" - Display "disp('Feedback', 'texmode', 'on');" - } - System { - Name "Feedback" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "yawrate_error_model" - SID "1223" - Position [105, 103, 135, 117] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "yawrate_error" - SID "1224" - Position [360, 103, 390, 117] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "yawrate_error_model" - SrcPort 1 - DstBlock "yawrate_error" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "yawrate error" - SID "1098" - Ports [0, 1] - Position [185, 73, 255, 107] - ZOrder 282 - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==1" - Object { - $PropName "MaskObject" - $ObjectID 79 - $ClassName "Simulink.Mask" - Display "disp('d\\psi/dt_{error}', 'texmode', 'on');" - } - System { - Name "yawrate error" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "200" - Block { - BlockType FromWorkspace - Name "From\nWorkspace8" - SID "1020" - Position [15, 18, 80, 42] - ZOrder 245 - VariableName "yawrate_error" - SampleTime "Tq" - ZeroCross on - } - Block { - BlockType Outport - Name "yawrate_error" - SID "1101" - Position [145, 23, 175, 37] - ZOrder 172 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "From\nWorkspace8" - SrcPort 1 - DstBlock "yawrate_error" - DstPort 1 - } - } - } - Block { - BlockType Outport - Name "yawrate_error" - SID "1204" - Position [410, 83, 440, 97] - ZOrder -2 - ForegroundColor "magenta" - IconDisplay "Port number" - } - Annotation { - SID "1206" - Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">\n<htm" - "l><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap; }\n</st" - "yle></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n<p style=\"" - " margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-h" - "eight:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"matlab://addvsscho" - "iceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-decoration: underline; c" - "olor:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> or </span><a href=\"" - "matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-d" - "ecoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'Helvetica'; font-size:10px;\"> " - "blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margi" - "n-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font" - "-size:10px;\">2) You cannot connect blocks at this level. At simulation, connectivity is automatically </span></p>" - "\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inden" - "t:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">determined, based on the acti" - "ve variant and port name matching.</span></p></body></html>" - Tag "VSSAddChoiceText" - Position [71, 28, 448, 69] - InternalMargins [0, 0, 0, 0] - FixedHeight off - FixedWidth off - HorizontalAlignment "left" - Interpreter "rich" - ZOrder -1 - } - } - } - Block { - BlockType Outport - Name "height_controlled" - SID "606" - Position [1500, -717, 1530, -703] - ZOrder -2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "y_controlled" - SID "636" - Position [1505, -477, 1535, -463] - ZOrder 74 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "x_controlled" - SID "637" - Position [1500, -217, 1530, -203] - ZOrder 75 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "yaw_controlled" - SID "638" - Position [1495, 53, 1525, 67] - ZOrder 76 - Port "4" - IconDisplay "Port number" - } - Line { - ZOrder 48 - SrcBlock "pitch_rate" - SrcPort 1 - Points [15, 0] - Branch { - ZOrder 491 - Points [0, 55] - DstBlock "Scope6" - DstPort 1 - } - Branch { - ZOrder 229 - DstBlock "Sum4" - DstPort 2 - } - } - Line { - ZOrder 26 - SrcBlock "z_setpoint" - SrcPort 1 - DstBlock "Sum7" - DstPort 1 - } - Line { - ZOrder 31 - SrcBlock "x_position" - SrcPort 1 - Points [40, 0] - Branch { - ZOrder 839 - Points [0, 45] - Branch { - ZOrder 843 - Points [0, 60] - DstBlock "Scope4" - DstPort 1 - } - Branch { - ZOrder 842 - DstBlock "To Workspace9" - DstPort 1 - } - } - Branch { - ZOrder 237 - DstBlock "Sum5" - DstPort 2 - } - } - Line { - ZOrder 1613 - SrcBlock "PID Controller5" - SrcPort 1 - Points [15, 0] - Branch { - ZOrder 954 - DstBlock "Sum4" - DstPort 1 - } - Branch { - ZOrder 953 - Points [0, -65] - DstBlock "To Workspace1" - DstPort 1 - } - } - Line { - ZOrder 1614 - SrcBlock "PID Controller11" - SrcPort 1 - Points [17, 0] - Branch { - ZOrder 956 - DstBlock "Sum3" - DstPort 1 - } - Branch { - ZOrder 955 - Points [0, -65] - DstBlock "To Workspace" - DstPort 1 - } - } - Line { - ZOrder 43 - SrcBlock "pitch" - SrcPort 1 - Points [10, 0] - Branch { - ZOrder 492 - Points [0, 45] - DstBlock "Gain" - DstPort 1 - } - Branch { - ZOrder 490 - DstBlock "Sum3" - DstPort 2 - } - } - Line { - ZOrder 494 - SrcBlock "Gain" - SrcPort 1 - DstBlock "Scope9" - DstPort 1 - } - Line { - ZOrder 1609 - SrcBlock "PID Controller1" - SrcPort 1 - Points [260, 0] - Branch { - ZOrder 1345 - Points [0, -65] - DstBlock "To Workspace8" - DstPort 1 - } - Branch { - ZOrder 1344 - DstBlock "Saturation" - DstPort 1 - } - } - Line { - ZOrder 1611 - SrcBlock "PID Controller9" - SrcPort 1 - Points [21, 0] - Branch { - ZOrder 1274 - Points [0, -65] - DstBlock "To Workspace2" - DstPort 1 - } - Branch { - ZOrder 1273 - DstBlock "Saturation1" - DstPort 1 - } - } - Line { - ZOrder 1615 - SrcBlock "Latitude Controller Input" - SrcPort 1 - DstBlock "PID Controller11" - DstPort 1 - } - Line { - ZOrder 699 - SrcBlock "x_setpoint" - SrcPort 1 - DstBlock "Sum5" - DstPort 1 - } - Line { - ZOrder 753 - SrcBlock "roll_rate" - SrcPort 1 - Points [20, 0] - Branch { - ZOrder 719 - Points [0, 55] - DstBlock "Scope11" - DstPort 1 - } - Branch { - ZOrder 718 - DstBlock "Sum10" - DstPort 2 - } - } - Line { - ZOrder 751 - SrcBlock "y_position" - SrcPort 1 - Points [45, 0] - Branch { - ZOrder 722 - Points [0, 50] - Branch { - ZOrder 1043 - Points [0, 55] - DstBlock "Scope12" - DstPort 1 - } - Branch { - ZOrder 845 - DstBlock "To Workspace11" - DstPort 1 - } - } - Branch { - ZOrder 721 - DstBlock "Sum11" - DstPort 2 - } - } - Line { - ZOrder 1764 - SrcBlock "PID Controller2" - SrcPort 1 - Points [25, 0] - Branch { - ZOrder 1709 - DstBlock "Sum10" - DstPort 1 - } - Branch { - ZOrder 1708 - Points [0, -60] - DstBlock "To Workspace4" - DstPort 1 - } - } - Line { - ZOrder 1616 - SrcBlock "PID Controller7" - SrcPort 1 - Points [16, 0] - Branch { - ZOrder 1713 - DstBlock "Sum9" - DstPort 1 - } - Branch { - ZOrder 1712 - Points [0, -60] - DstBlock "To Workspace3" - DstPort 1 - } - } - Line { - ZOrder 752 - SrcBlock "roll" - SrcPort 1 - Points [15, 0] - Branch { - ZOrder 731 - Points [0, 45] - DstBlock "Gain2" - DstPort 1 - } - Branch { - ZOrder 730 - DstBlock "Sum9" - DstPort 2 - } - } - Line { - ZOrder 733 - SrcBlock "Gain2" - SrcPort 1 - DstBlock "Scope13" - DstPort 1 - } - Line { - ZOrder 750 - SrcBlock "y_setpoint" - SrcPort 1 - DstBlock "Sum11" - DstPort 1 - } - Line { - ZOrder 1503 - SrcBlock "PID Controller17" - SrcPort 1 - Points [525, 0] - Branch { - ZOrder 1767 - Points [0, -80] - DstBlock "To Workspace6" - DstPort 1 - } - Branch { - ZOrder 1766 - DstBlock "Saturation3" - DstPort 1 - } - } - Line { - ZOrder 785 - SrcBlock "yaw" - SrcPort 1 - Points [25, 0] - Branch { - ZOrder 778 - Points [0, 45] - Branch { - ZOrder 1214 - Points [0, 65] - DstBlock "Scope3" - DstPort 1 - } - Branch { - ZOrder 841 - DstBlock "To Workspace10" - DstPort 1 - } - } - Branch { - ZOrder 777 - DstBlock "Sum1" - DstPort 2 - } - } - Line { - ZOrder 784 - SrcBlock "yaw_setpoint" - SrcPort 1 - DstBlock "Sum1" - DstPort 1 - } - Line { - ZOrder 810 - SrcBlock "yaw_rate" - SrcPort 1 - Points [25, 0] - Branch { - ZOrder 822 - Points [0, 25] - DstBlock "Gain1" - DstPort 1 - } - Branch { - ZOrder 821 - DstBlock "Sum2" - DstPort 2 - } - } - Line { - ZOrder 806 - SrcBlock "Gain1" - SrcPort 1 - DstBlock "Scope1" - DstPort 1 - } - Line { - ZOrder 1501 - SrcBlock "PID Controller4" - SrcPort 1 - Points [11, 0] - Branch { - ZOrder 1591 - DstBlock "Sum2" - DstPort 1 - } - Branch { - ZOrder 1590 - Points [0, -65] - DstBlock "To Workspace7" - DstPort 1 - } - } - Line { - ZOrder 34 - SrcBlock "z_position" - SrcPort 1 - Points [30, 0] - Branch { - ZOrder 108 - Points [0, 30] - Branch { - ZOrder 849 - DstBlock "To Workspace12" - DstPort 1 - } - Branch { - ZOrder 848 - Points [0, 50] - DstBlock "Scope2" - DstPort 1 - } - } - Branch { - ZOrder 107 - DstBlock "Sum7" - DstPort 2 - } - } - Line { - ZOrder 1163 - SrcBlock "Sum1" - SrcPort 1 - DstBlock "Yaw Controller Input" - DstPort 1 - } - Line { - ZOrder 1500 - SrcBlock "Yaw Controller Input" - SrcPort 1 - DstBlock "PID Controller4" - DstPort 1 - } - Line { - ZOrder 1190 - SrcBlock "Sum2" - SrcPort 1 - DstBlock "Yaw Rate Controller Input" - DstPort 1 - } - Line { - ZOrder 1608 - SrcBlock "Yaw Rate Controller Input" - SrcPort 1 - DstBlock "PID Controller1" - DstPort 1 - } - Line { - ZOrder 1194 - SrcBlock "Sum5" - SrcPort 1 - DstBlock "Latitude Controller Input" - DstPort 1 - } - Line { - ZOrder 1195 - SrcBlock "Sum3" - SrcPort 1 - DstBlock "Pitch Controller Input" - DstPort 1 - } - Line { - ZOrder 1612 - SrcBlock "Pitch Controller Input" - SrcPort 1 - DstBlock "PID Controller5" - DstPort 1 - } - Line { - ZOrder 1197 - SrcBlock "Sum4" - SrcPort 1 - DstBlock "Pitch Rate Controller Input" - DstPort 1 - } - Line { - ZOrder 1610 - SrcBlock "Pitch Rate Controller Input" - SrcPort 1 - DstBlock "PID Controller9" - DstPort 1 - } - Line { - ZOrder 1199 - SrcBlock "Sum11" - SrcPort 1 - DstBlock "Longitude Controller Input" - DstPort 1 - } - Line { - ZOrder 1617 - SrcBlock "Longitude Controller Input" - SrcPort 1 - DstBlock "PID Controller7" - DstPort 1 - } - Line { - ZOrder 1201 - SrcBlock "Sum9" - SrcPort 1 - DstBlock "Roll Controller Input" - DstPort 1 - } - Line { - ZOrder 1765 - SrcBlock "Roll Controller Input" - SrcPort 1 - DstBlock "PID Controller2" - DstPort 1 - } - Line { - ZOrder 1204 - SrcBlock "Sum10" - SrcPort 1 - DstBlock "Roll Rate Controller Input" - DstPort 1 - } - Line { - ZOrder 1502 - SrcBlock "Altitude Controller Input" - SrcPort 1 - DstBlock "PID Controller17" - DstPort 1 - } - Line { - ZOrder 1210 - SrcBlock "Sum7" - SrcPort 1 - DstBlock "Altitude Controller Input" - DstPort 1 - } - Line { - ZOrder 1763 - SrcBlock "Roll Rate Controller Input" - SrcPort 1 - DstBlock "PID Controller3" - DstPort 1 - } - Line { - ZOrder 1762 - SrcBlock "PID Controller3" - SrcPort 1 - Points [16, 0] - Branch { - ZOrder 1602 - Points [0, -60] - DstBlock "To Workspace5" - DstPort 1 - } - Branch { - ZOrder 1601 - DstBlock "Saturation2" - DstPort 1 - } - } - Line { - ZOrder 1701 - SrcBlock "Saturation2" - SrcPort 1 - DstBlock "y_controlled" - DstPort 1 - } - Line { - ZOrder 1716 - SrcBlock "Saturation1" - SrcPort 1 - DstBlock "x_controlled" - DstPort 1 - } - Line { - ZOrder 1768 - SrcBlock "Saturation" - SrcPort 1 - DstBlock "yaw_controlled" - DstPort 1 - } - } - } - Block { - BlockType Reference - Name "Counter\nFree-Running" - SID "899" - Ports [0, 1] - Position [275, 955, 305, 985] - ZOrder 59 - LibraryVersion "1.388" - SourceBlock "simulink/Sources/Counter\nFree-Running" - SourceType "Counter Free-Running" - ContentPreviewEnabled off - NumBits "32" - tsamp "Tc" - } - Block { - BlockType Demux - Name "Demux" - SID "586" - Ports [1, 4] - Position [300, 319, 305, 416] - ZOrder 13 - ShowName off - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux1" - SID "639" - Ports [1, 3] - Position [300, 494, 305, 566] - ZOrder 32 - ShowName off - Outputs "3" - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux2" - SID "588" - Ports [1, 3] - Position [285, 419, 290, 491] - ZOrder 15 - ShowName off - Outputs "3" - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux3" - SID "1422" - Ports [1, 4] - Position [1650, 511, 1655, 549] - ZOrder 321 - ShowName off - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux4" - SID "640" - Ports [1, 3] - Position [275, 569, 280, 641] - ZOrder 33 - ShowName off - Outputs "3" - DisplayOption "bar" - } - Block { - BlockType SubSystem - Name "MATLAB Function1" - SID "887" - Ports [15, 6] - Position [390, 687, 530, 1013] - ZOrder 47 - Commented "on" - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - SystemSampleTime "Tq" - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 80 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{E}r_{x,setpoint}', 'texmode', 'on');\nport_label('input', 2, '^{E}r_{y,se" - "tpoint}', 'texmode', 'on');\nport_label('input', 3, '^{E}r_{z,setpoint}', 'texmode', 'on');\nport_label('input', " - "4, '\\psi_{setpoint}', 'texmode', 'on');\nport_label('input', 5, '^{E}r_x', 'texmode', 'on');\nport_label('input'" - ", 6, '^{E}r_y', 'texmode', 'on');\nport_label('input', 7, '^{E}r_z', 'texmode', 'on');\nport_label('input', 8, '\\" - "phi', 'texmode', 'on');\nport_label('input', 9, '\\theta', 'texmode', 'on');\nport_label('input', 10, '\\psi', 't" - "exmode', 'on');\nport_label('input', 11, 'd\\phi/dt', 'texmode', 'on');\nport_label('input', 12, 'd\\theta/dt', '" - "texmode', 'on');\nport_label('input', 13, 'd\\psi/dt', 'texmode', 'on');\nport_label('input', 14, 'VRPN ID', 'tex" - "mode', 'on');\nport_label('input', 15, '\\tau_c', 'texmode', 'on');\nport_label('output', 1, 'u_T', 'texmode', 'o" - "n');\nport_label('output', 2, 'u_A', 'texmode', 'on');\nport_label('output', 3, 'u_E', 'texmode', 'on');\nport_la" - "bel('output', 4, 'u_R', 'texmode', 'on');\nport_label('output', 5, 'PID y out', 'texmode', 'on');\nport_label('ou" - "tput', 6, 'PID roll out', 'texmode', 'on');\ndisp('C Controller', 'texmode', 'on');" - } - System { - Name "MATLAB Function1" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "41" - Block { - BlockType Inport - Name "set_x" - SID "887::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "set_y" - SID "887::22" - Position [20, 136, 40, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "set_z" - SID "887::23" - Position [20, 171, 40, 189] - ZOrder 14 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "set_yaw" - SID "887::24" - Position [20, 206, 40, 224] - ZOrder 15 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "cur_x" - SID "887::25" - Position [20, 246, 40, 264] - ZOrder 16 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "cur_y" - SID "887::26" - Position [20, 281, 40, 299] - ZOrder 17 - Port "6" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "cur_z" - SID "887::27" - Position [20, 316, 40, 334] - ZOrder 18 - Port "7" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "cur_phi" - SID "887::28" - Position [20, 351, 40, 369] - ZOrder 19 - Port "8" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "cur_theta" - SID "887::29" - Position [20, 386, 40, 404] - ZOrder 20 - Port "9" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "cur_psi" - SID "887::30" - Position [20, 426, 40, 444] - ZOrder 21 - Port "10" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "cur_phi_d" - SID "887::31" - Position [20, 461, 40, 479] - ZOrder 22 - Port "11" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "cur_theta_d" - SID "887::32" - Position [20, 496, 40, 514] - ZOrder 23 - Port "12" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "cur_psi_d" - SID "887::33" - Position [20, 531, 40, 549] - ZOrder 24 - Port "13" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "vrpn_id" - SID "887::37" - Position [20, 566, 40, 584] - ZOrder 28 - Port "14" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Tc" - SID "887::41" - Position [20, 606, 40, 624] - ZOrder 31 - Port "15" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "887::20" - Ports [1, 1] - Position [270, 350, 320, 390] - ZOrder 11 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "887::19" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 15" - Ports [15, 7] - Position [180, 110, 230, 430] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[15 7]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "z_corr" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "y_cor" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 4 - Name "x_corr" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 5 - Name "yaw_corr" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 6 - Name "pid_y_out" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 7 - Name "pid_roll_out" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "887::21" - Position [460, 361, 480, 379] - ZOrder 12 - } - Block { - BlockType Outport - Name "z_corr" - SID "887::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "y_cor" - SID "887::34" - Position [460, 136, 480, 154] - ZOrder 25 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "x_corr" - SID "887::35" - Position [460, 171, 480, 189] - ZOrder 26 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "yaw_corr" - SID "887::36" - Position [460, 206, 480, 224] - ZOrder 27 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "pid_y_out" - SID "887::38" - Position [460, 246, 480, 264] - ZOrder 29 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "pid_roll_out" - SID "887::39" - Position [460, 281, 480, 299] - ZOrder 30 - Port "6" - IconDisplay "Port number" - } - Line { - ZOrder 319 - SrcBlock "set_x" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 320 - SrcBlock "set_y" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - ZOrder 321 - SrcBlock "set_z" - SrcPort 1 - DstBlock " SFunction " - DstPort 3 - } - Line { - ZOrder 322 - SrcBlock "set_yaw" - SrcPort 1 - DstBlock " SFunction " - DstPort 4 - } - Line { - ZOrder 323 - SrcBlock "cur_x" - SrcPort 1 - DstBlock " SFunction " - DstPort 5 - } - Line { - ZOrder 324 - SrcBlock "cur_y" - SrcPort 1 - DstBlock " SFunction " - DstPort 6 - } - Line { - ZOrder 325 - SrcBlock "cur_z" - SrcPort 1 - DstBlock " SFunction " - DstPort 7 - } - Line { - ZOrder 326 - SrcBlock "cur_phi" - SrcPort 1 - DstBlock " SFunction " - DstPort 8 - } - Line { - ZOrder 327 - SrcBlock "cur_theta" - SrcPort 1 - DstBlock " SFunction " - DstPort 9 - } - Line { - ZOrder 328 - SrcBlock "cur_psi" - SrcPort 1 - DstBlock " SFunction " - DstPort 10 - } - Line { - ZOrder 329 - SrcBlock "cur_phi_d" - SrcPort 1 - DstBlock " SFunction " - DstPort 11 - } - Line { - ZOrder 330 - SrcBlock "cur_theta_d" - SrcPort 1 - DstBlock " SFunction " - DstPort 12 - } - Line { - ZOrder 331 - SrcBlock "cur_psi_d" - SrcPort 1 - DstBlock " SFunction " - DstPort 13 - } - Line { - ZOrder 332 - SrcBlock "vrpn_id" - SrcPort 1 - DstBlock " SFunction " - DstPort 14 - } - Line { - ZOrder 333 - SrcBlock "Tc" - SrcPort 1 - DstBlock " SFunction " - DstPort 15 - } - Line { - Name "z_corr" - ZOrder 334 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "z_corr" - DstPort 1 - } - Line { - Name "y_cor" - ZOrder 335 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 3 - DstBlock "y_cor" - DstPort 1 - } - Line { - Name "x_corr" - ZOrder 336 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 4 - DstBlock "x_corr" - DstPort 1 - } - Line { - Name "yaw_corr" - ZOrder 337 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 5 - DstBlock "yaw_corr" - DstPort 1 - } - Line { - Name "pid_y_out" - ZOrder 338 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 6 - DstBlock "pid_y_out" - DstPort 1 - } - Line { - Name "pid_roll_out" - ZOrder 339 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 7 - DstBlock "pid_roll_out" - DstPort 1 - } - Line { - ZOrder 340 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 341 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Motor Commands" - SID "1409" - Ports [1, 1] - Position [1400, 457, 1555, 503] - ZOrder 319 - ForegroundColor "magenta" - ShowName off - RequestExecContextInheritance off - Variant on - Object { - $PropName "MaskObject" - $ObjectID 81 - $ClassName "Simulink.Mask" - Display "disp('Motor Commands', 'texmode', 'on');" - } - System { - Name "Motor Commands" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "175" - Block { - BlockType Inport - Name "z_command_model" - SID "1410" - Position [85, 118, 115, 132] - ZOrder 288 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Feedback" - SID "1411" - Ports [1, 1] - Position [185, 153, 345, 187] - ZOrder 287 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==0" - Object { - $PropName "MaskObject" - $ObjectID 82 - $ClassName "Simulink.Mask" - Display "disp('Motor Command from Model', 'texmode', 'on');" - } - System { - Name "Feedback" - Location [-7, -7, 1288, 688] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "z_command_model" - SID "1412" - Position [105, 103, 135, 117] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "z_command" - SID "1413" - Position [360, 103, 390, 117] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "z_command_model" - SrcPort 1 - DstBlock "z_command" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Motor Command" - SID "1414" - Ports [0, 1] - Position [210, 75, 320, 105] - ZOrder 279 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==1" - Object { - $PropName "MaskObject" - $ObjectID 83 - $ClassName "Simulink.Mask" - Display "disp('Motor Command', 'texmode', 'on');" - } - System { - Name "Motor Command" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "125" - Block { - BlockType FromWorkspace - Name "From\nWorkspace5" - SID "1415" - Position [-35, 17, 80, 43] - ZOrder 210 - VariableName "motor_commands" - SampleTime "Tq" - ZeroCross on - } - Block { - BlockType Outport - Name "z_command" - SID "1416" - Position [145, 23, 175, 37] - ZOrder 172 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "From\nWorkspace5" - SrcPort 1 - DstBlock "z_command" - DstPort 1 - } - } - } - Block { - BlockType Outport - Name "z_command" - SID "1417" - Position [410, 118, 440, 132] - ZOrder -2 - ForegroundColor "magenta" - IconDisplay "Port number" - } - Annotation { - SID "1418" - Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">" - "\n<html><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap" - "; }\n</style></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n" - "<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inde" - "nt:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"m" - "atlab://addvsschoiceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-deco" - "ration: underline; color:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;" - "\"> or </span><a href=\"matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helveti" - "ca'; font-size:10px; text-decoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'H" - "elvetica'; font-size:10px;\"> blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-b" - "ottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span st" - "yle=\" font-family:'Helvetica'; font-size:10px;\">2) You cannot connect blocks at this level. At simulation, co" - "nnectivity is automatically </span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin" - "-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; fo" - "nt-size:10px;\">determined, based on the active variant and port name matching.</span></p></body></html>" - Tag "VSSAddChoiceText" - Position [71, 28, 448, 69] - InternalMargins [0, 0, 0, 0] - FixedHeight off - FixedWidth off - HorizontalAlignment "left" - Interpreter "rich" - ZOrder -1 - } - } - } - Block { - BlockType Saturate - Name "Saturation" - SID "756" - Ports [1, 1] - Position [1270, 465, 1300, 495] - ZOrder 44 - InputPortMap "u0" - UpperLimit "Pmax*ones(4,1)" - LowerLimit "Pmin*ones(4,1)" - } - Block { - BlockType Scope - Name "Scope" - SID "1421" - Ports [4] - Position [1705, 514, 1735, 546] - ZOrder 320 - NumInputPorts "4" - Open off - TimeRange auto - TickLabels OneTimeTick - ShowLegends off - LimitDataPoints off - MaxDataPoints 5000 - SaveToWorkspace off - SaveName ScopeData1 - YMin 127563.375~120690.00000~120652.25~129711.75 - YMax 167209.625~181750.00000~182389.75~170414.25 - SampleInput off - SampleTime -1 - ZoomMode on - Grid on - DataFormat StructureWithTime - Decimation 1 - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - axes4 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - Location [962 84 1920 1038] - } - Block { - BlockType SubSystem - Name "Signal Mixer" - SID "647" - Ports [4, 1] - Position [960, 320, 1220, 640] - ZOrder 35 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ParametersOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Variant off - Object { - $PropName "MaskObject" - $ObjectID 84 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'u_T', 'texmode', 'on');\nport_label('input', 2, 'u_A', 'texmode', 'on');\np" - "ort_label('input', 3, 'u_E', 'texmode', 'on');\nport_label('input', 4, 'u_R', 'texmode', 'on');\nport_label('outp" - "ut', 1, 'P', 'texmode', 'on');\ndisp('Signal Mixer', 'texmode', 'on');" - } - System { - Name "Signal Mixer" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "27" - Block { - BlockType Inport - Name "height_controlled" - SID "647::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "y_controlled" - SID "647::23" - Position [20, 136, 40, 154] - ZOrder 14 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "x_controlled" - SID "647::22" - Position [20, 171, 40, 189] - ZOrder 13 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "yaw_controlled" - SID "647::24" - Position [20, 206, 40, 224] - ZOrder 15 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "647::20" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "647::19" - Tag "Stateflow S-Function Quadcopter_Model_R2015_A 14" - Ports [4, 2] - Position [180, 107, 230, 208] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[4 2]" - SFunctionDeploymentMode off - EnableBusSupport on - Port { - PortNumber 2 - Name "P" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "647::21" - Position [460, 241, 480, 259] - ZOrder 12 - } - Block { - BlockType Outport - Name "P" - SID "647::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 105 - SrcBlock "height_controlled" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 106 - SrcBlock "y_controlled" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - ZOrder 107 - SrcBlock "x_controlled" - SrcPort 1 - DstBlock " SFunction " - DstPort 3 - } - Line { - ZOrder 108 - SrcBlock "yaw_controlled" - SrcPort 1 - DstBlock " SFunction " - DstPort 4 - } - Line { - Name "P" - ZOrder 109 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "P" - DstPort 1 - } - Line { - ZOrder 110 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 111 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType Sum - Name "Sum" - SID "748" - Ports [2, 1] - Position [665, 350, 685, 370] - ZOrder 36 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum1" - SID "749" - Ports [2, 1] - Position [665, 430, 685, 450] - ZOrder 37 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum2" - SID "750" - Ports [2, 1] - Position [665, 510, 685, 530] - ZOrder 38 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum3" - SID "751" - Ports [2, 1] - Position [665, 590, 685, 610] - ZOrder 39 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType SubSystem - Name "Throttle Command Input" - SID "1278" - Ports [1, 1] - Position [740, 337, 895, 383] - ZOrder 318 - ForegroundColor "magenta" - ShowName off - RequestExecContextInheritance off - Variant on - Object { - $PropName "MaskObject" - $ObjectID 85 - $ClassName "Simulink.Mask" - Display "disp('Throttle Command', 'texmode', 'on');" - } - System { - Name "Throttle Command Input" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "175" - Block { - BlockType Inport - Name "z_command_model" - SID "1279" - Position [85, 118, 115, 132] - ZOrder 288 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Feedback" - SID "1280" - Ports [1, 1] - Position [185, 153, 345, 187] - ZOrder 287 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==0" - Object { - $PropName "MaskObject" - $ObjectID 86 - $ClassName "Simulink.Mask" - Display "disp('Throttle Command from Model', 'texmode', 'on');" - } - System { - Name "Feedback" - Location [-7, -7, 1288, 688] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "z_command_model" - SID "1281" - Position [105, 103, 135, 117] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "z_command" - SID "1282" - Position [360, 103, 390, 117] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "z_command_model" - SrcPort 1 - DstBlock "z_command" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Throttle Command" - SID "1283" - Ports [0, 1] - Position [210, 75, 320, 105] - ZOrder 279 - ShowName off - RequestExecContextInheritance off - Variant off - VariantControl "logAnalysisToggle==1" - Object { - $PropName "MaskObject" - $ObjectID 87 - $ClassName "Simulink.Mask" - Display "disp('Throttle Command', 'texmode', 'on');" - } - System { - Name "Throttle Command" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "175" - Block { - BlockType FromWorkspace - Name "From\nWorkspace5" - SID "1284" - Position [-35, 17, 80, 43] - ZOrder 210 - VariableName "throttle_command" - SampleTime "Tq" - ZeroCross on - } - Block { - BlockType Outport - Name "z_command" - SID "1285" - Position [145, 23, 175, 37] - ZOrder 172 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "From\nWorkspace5" - SrcPort 1 - DstBlock "z_command" - DstPort 1 - } - } - } - Block { - BlockType Outport - Name "z_command" - SID "1286" - Position [410, 118, 440, 132] - ZOrder -2 - ForegroundColor "magenta" - IconDisplay "Port number" - } - Annotation { - SID "1287" - Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">" - "\n<html><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap" - "; }\n</style></head><body style=\" font-family:'Arial'; font-size:10px; font-weight:400; font-style:normal;\">\n" - "<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-inde" - "nt:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; font-size:10px;\">1) Add </span><a href=\"m" - "atlab://addvsschoiceddg_cb(gcs,'SubSystem')\"><span style=\" font-family:'Helvetica'; font-size:10px; text-deco" - "ration: underline; color:#0000ff;\">Subsystem</span></a><span style=\" font-family:'Helvetica'; font-size:10px;" - "\"> or </span><a href=\"matlab://addvsschoiceddg_cb(gcs,'ModelReference')\"><span style=\" font-family:'Helveti" - "ca'; font-size:10px; text-decoration: underline; color:#0000ff;\">Model</span></a><span style=\" font-family:'H" - "elvetica'; font-size:10px;\"> blocks as valid variant choices.</span></p>\n<p style=\" margin-top:0px; margin-b" - "ottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span st" - "yle=\" font-family:'Helvetica'; font-size:10px;\">2) You cannot connect blocks at this level. At simulation, co" - "nnectivity is automatically </span></p>\n<p style=\" margin-top:0px; margin-bottom:0px; margin-left:0px; margin" - "-right:0px; -qt-block-indent:0; text-indent:0px; line-height:100%;\"><span style=\" font-family:'Helvetica'; fo" - "nt-size:10px;\">determined, based on the active variant and port name matching.</span></p></body></html>" - Tag "VSSAddChoiceText" - Position [71, 28, 448, 69] - InternalMargins [0, 0, 0, 0] - FixedHeight off - FixedWidth off - HorizontalAlignment "left" - Interpreter "rich" - ZOrder -1 - } - } - } - Block { - BlockType ToWorkspace - Name "To Workspace3" - SID "1207" - Ports [1] - Position [1445, 380, 1555, 410] - ZOrder 228 - ShowName off - VariableName "motorCommands" - MaxDataPoints "inf" - SaveFormat "Structure With Time" - Save2DSignal "3-D array (concatenate along third dimension)" - FixptAsFi on - SampleTime "Tq" - } - Block { - BlockType Constant - Name "height_controlled_o" - SID "752" - Position [615, 380, 645, 410] - ZOrder 40 - Value "height_controlled_o" - SampleTime "Tc" - } - Block { - BlockType Constant - Name "x_controlled_o" - SID "754" - Position [615, 545, 645, 575] - ZOrder 42 - Value "x_controlled_o" - } - Block { - BlockType Constant - Name "y_controlled_o" - SID "753" - Position [615, 465, 645, 495] - ZOrder 41 - Value "y_controlled_o" - } - Block { - BlockType Constant - Name "yaw_controlled_o" - SID "755" - Position [615, 630, 645, 660] - ZOrder 43 - Value "yaw_controlled_o" - } - Block { - BlockType Outport - Name "P" - SID "578" - Position [1665, 473, 1695, 487] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "setpoints" - SrcPort 1 - DstBlock "Demux" - DstPort 1 - } - Line { - ZOrder 30 - SrcBlock "euler_angles_filtered" - SrcPort 1 - DstBlock "Demux1" - DstPort 1 - } - Line { - ZOrder 3 - SrcBlock "current_position" - SrcPort 1 - DstBlock "Demux2" - DstPort 1 - } - Line { - ZOrder 34 - SrcBlock "euler_rates" - SrcPort 1 - DstBlock "Demux4" - DstPort 1 - } - Line { - ZOrder 27 - SrcBlock "Demux" - SrcPort 1 - DstBlock "Controller" - DstPort 1 - } - Line { - ZOrder 28 - SrcBlock "Demux" - SrcPort 2 - DstBlock "Controller" - DstPort 2 - } - Line { - ZOrder 29 - SrcBlock "Demux" - SrcPort 3 - DstBlock "Controller" - DstPort 3 - } - Line { - ZOrder 40 - SrcBlock "Demux2" - SrcPort 1 - DstBlock "Controller" - DstPort 5 - } - Line { - ZOrder 41 - SrcBlock "Demux2" - SrcPort 2 - DstBlock "Controller" - DstPort 6 - } - Line { - ZOrder 42 - SrcBlock "Demux2" - SrcPort 3 - DstBlock "Controller" - DstPort 7 - } - Line { - ZOrder 68 - SrcBlock "Controller" - SrcPort 2 - DstBlock "Sum1" - DstPort 1 - } - Line { - ZOrder 72 - SrcBlock "Controller" - SrcPort 4 - DstBlock "Sum3" - DstPort 1 - } - Line { - ZOrder 77 - SrcBlock "y_controlled_o" - SrcPort 1 - Points [25, 0] - DstBlock "Sum1" - DstPort 2 - } - Line { - ZOrder 78 - SrcBlock "x_controlled_o" - SrcPort 1 - Points [25, 0] - DstBlock "Sum2" - DstPort 2 - } - Line { - ZOrder 79 - SrcBlock "yaw_controlled_o" - SrcPort 1 - Points [25, 0] - DstBlock "Sum3" - DstPort 2 - } - Line { - ZOrder 80 - SrcBlock "Signal Mixer" - SrcPort 1 - DstBlock "Saturation" - DstPort 1 - } - Line { - ZOrder 84 - SrcBlock "Demux1" - SrcPort 1 - DstBlock "Controller" - DstPort 8 - } - Line { - ZOrder 86 - SrcBlock "Demux1" - SrcPort 2 - DstBlock "Controller" - DstPort 9 - } - Line { - ZOrder 90 - SrcBlock "Demux4" - SrcPort 1 - DstBlock "Controller" - DstPort 11 - } - Line { - ZOrder 91 - SrcBlock "Demux4" - SrcPort 2 - DstBlock "Controller" - DstPort 12 - } - Line { - ZOrder 93 - SrcBlock "Demux4" - SrcPort 3 - DstBlock "Controller" - DstPort 13 - } - Line { - ZOrder 94 - SrcBlock "Demux" - SrcPort 4 - DstBlock "Controller" - DstPort 4 - } - Line { - ZOrder 95 - SrcBlock "Demux1" - SrcPort 3 - DstBlock "Controller" - DstPort 10 - } - Line { - ZOrder 131 - SrcBlock "Controller" - SrcPort 3 - DstBlock "Sum2" - DstPort 1 - } - Line { - ZOrder 205 - SrcBlock "Counter\nFree-Running" - SrcPort 1 - DstBlock "MATLAB Function1" - DstPort 14 - } - Line { - ZOrder 235 - SrcBlock "Constant" - SrcPort 1 - Points [43, 0; 0, -45] - DstBlock "MATLAB Function1" - DstPort 15 - } - Line { - ZOrder 501 - SrcBlock "Sum1" - SrcPort 1 - DstBlock "Signal Mixer" - DstPort 2 - } - Line { - ZOrder 500 - SrcBlock "Sum2" - SrcPort 1 - DstBlock "Signal Mixer" - DstPort 3 - } - Line { - ZOrder 499 - SrcBlock "Sum3" - SrcPort 1 - DstBlock "Signal Mixer" - DstPort 4 - } - Line { - ZOrder 495 - SrcBlock "Throttle Command Input" - SrcPort 1 - DstBlock "Signal Mixer" - DstPort 1 - } - Line { - ZOrder 519 - SrcBlock "Controller" - SrcPort 1 - DstBlock "Sum" - DstPort 1 - } - Line { - ZOrder 520 - SrcBlock "height_controlled_o" - SrcPort 1 - Points [25, 0] - DstBlock "Sum" - DstPort 2 - } - Line { - ZOrder 521 - SrcBlock "Motor Commands" - SrcPort 1 - Points [42, 0] - Branch { - ZOrder 540 - Points [0, 50] - DstBlock "Demux3" - DstPort 1 - } - Branch { - ZOrder 539 - DstBlock "P" - DstPort 1 - } - } - Line { - ZOrder 535 - SrcBlock "Demux3" - SrcPort 1 - DstBlock "Scope" - DstPort 1 - } - Line { - ZOrder 536 - SrcBlock "Demux3" - SrcPort 2 - DstBlock "Scope" - DstPort 2 - } - Line { - ZOrder 537 - SrcBlock "Demux3" - SrcPort 3 - DstBlock "Scope" - DstPort 3 - } - Line { - ZOrder 538 - SrcBlock "Demux3" - SrcPort 4 - DstBlock "Scope" - DstPort 4 - } - Line { - ZOrder 543 - SrcBlock "Sum" - SrcPort 1 - DstBlock "Throttle Command Input" - DstPort 1 - } - Line { - ZOrder 206 - SrcBlock "Saturation" - SrcPort 1 - Points [49, 0] - Branch { - ZOrder 557 - Points [0, -85] - DstBlock "To Workspace3" - DstPort 1 - } - Branch { - ZOrder 556 - DstBlock "Motor Commands" - DstPort 1 - } - } - } - } - Line { - ZOrder 52 - SrcBlock "Control System" - SrcPort 1 - DstBlock "Actuation" - DstPort 1 - } - Line { - ZOrder 55 - SrcBlock "Communication System" - SrcPort 1 - DstBlock "Control System" - DstPort 1 - } - Line { - ZOrder 189 - SrcBlock "Actuation" - SrcPort 1 - DstBlock " Sensors " - DstPort 1 - } - Line { - ZOrder 190 - SrcBlock "Actuation" - SrcPort 2 - DstBlock " Sensors " - DstPort 2 - } - Line { - ZOrder 191 - SrcBlock "Actuation" - SrcPort 3 - DstBlock " Sensors " - DstPort 3 - } - Line { - ZOrder 192 - SrcBlock "Actuation" - SrcPort 4 - DstBlock " Sensors " - DstPort 4 - } - Line { - ZOrder 193 - SrcBlock "Actuation" - SrcPort 5 - DstBlock " Sensors " - DstPort 5 - } - Line { - ZOrder 194 - SrcBlock "Actuation" - SrcPort 6 - DstBlock " Sensors " - DstPort 6 - } - Line { - ZOrder 222 - SrcBlock " Sensors " - SrcPort 3 - Points [15, 0; 0, 56; -909, 0; 0, -56] - DstBlock "Control System" - DstPort 4 - } - Line { - ZOrder 223 - SrcBlock " Sensors " - SrcPort 2 - Points [33, 0; 0, 154; -941, 0; 0, -129] - DstBlock "Control System" - DstPort 3 - } - Line { - ZOrder 224 - SrcBlock " Sensors " - SrcPort 1 - Points [47, 0; 0, 247; -965, 0; 0, -197] - DstBlock "Control System" - DstPort 2 - } - } -} -#Finite State Machines -# -# Stateflow 80000010 -# -# -Stateflow { - machine { - id 1 - name "Quadcopter_Model_R2015_A" - created "03-Nov-2016 18:34:53" - isLibrary 0 - sfVersion 80000006 - firstTarget 197 - } - chart { - id 2 - machine 1 - name "Actuation/Gravity\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 3 0 0] - viewObj 2 - ssIdHighWaterMark 7 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 1 - disableImplicitCasting 1 - eml { - name "gravity" - } - firstData 4 - firstTransition 8 - firstJunction 7 - } - state { - id 3 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 2 - treeNode [2 0 0 0] - superState SUBCHART - subviewer 2 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function E_Fg = gravity(m, g)\n\nE_Fg = [0; 0; m*g];\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 4 - ssIdNumber 5 - name "E_Fg" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [2 0 5] - } - data { - id 5 - ssIdNumber 6 - name "m" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 1 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [2 4 6] - } - data { - id 6 - ssIdNumber 7 - name "g" - scope PARAMETER_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [2 5 0] - } - junction { - id 7 - position [23.5747 49.5747 7] - chart 2 - subviewer 2 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [2 0 0] - } - transition { - id 8 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 7 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 2 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 2 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [2 0 0] - } - instance { - id 9 - machine 1 - name "Actuation/Gravity\n\n" - chart 2 - } - chart { - id 10 - machine 1 - name "Actuation/Lbe\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 11 0 0] - viewObj 10 - ssIdHighWaterMark 11 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 2 - disableImplicitCasting 1 - eml { - name "linear_body_earth_conversion" - } - firstData 12 - firstTransition 16 - firstJunction 15 - } - state { - id 11 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 10 - treeNode [10 0 0 0] - superState SUBCHART - subviewer 10 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function E_ro = linear_body_earth_conversion(B_vo, euler_angles)\n\neuler_rates = zeros(3,1);\nE" - "_ro = zeros(3,1);\n\nphi = euler_angles(1);\ntheta = euler_angles(2);\npsi = euler_angles(3);\n\nLeb = [cos(thet" - "a)*cos(psi), sin(phi)*sin(theta)*cos(psi)-cos(phi)*sin(psi), cos(phi)*sin(theta)*cos(psi)+sin(phi)*sin(psi); ..." - "\n cos(theta)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), cos(phi)*sin(theta)*sin(psi)-sin(p" - "hi)*cos(psi); ...\n -sin(theta) , sin(phi)*cos(theta) , c" - "os(phi)*cos(theta) ];\n\nE_ro = Leb * B_vo;" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 12 - ssIdNumber 7 - name "B_vo" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [10 0 13] - } - data { - id 13 - ssIdNumber 11 - name "euler_angles" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [10 12 14] - } - data { - id 14 - ssIdNumber 9 - name "E_ro" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [10 13 0] - } - junction { - id 15 - position [23.5747 49.5747 7] - chart 10 - subviewer 10 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [10 0 0] - } - transition { - id 16 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 15 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 10 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 10 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [10 0 0] - } - instance { - id 17 - machine 1 - name "Actuation/Lbe\n\n\n\n\n\n" - chart 10 - } - chart { - id 18 - machine 1 - name " Sensors /3D Graphical Simulation1/MATLAB Function" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 19 0 0] - viewObj 18 - ssIdHighWaterMark 5 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 3 - disableImplicitCasting 1 - eml { - name "eigenaxis_ucart" - } - firstData 20 - firstTransition 23 - firstJunction 22 - } - state { - id 19 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 18 - treeNode [18 0 0 0] - superState SUBCHART - subviewer 18 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function y = eigenaxis_ucart(u)\n\n\nif abs(u(1))< 0.0001\n u(1) = 0.0001;\nend\n\nif abs(u(2)" - ")< 0.0001\n u(2) = 0.0001;\nend\n\nif abs(u(3))< 0.0001\n u(3) = 0.0001;\nend\n\nu = [ -u(1); -u(2); u(3) " - "];% [Pitch, Yaw, Roll] \n\nC11 = cos(u(2))*cos(u(3));\nC12 = cos(u(2))*sin(u(3));\nC13 = -sin(u(2));\nC21 = sin(" - "u(1))*sin(u(2))*cos(u(3))-cos(u(1))*sin(u(3));\nC22 = sin(u(1))*sin(u(2))*sin(u(3))+cos(u(1))*cos(u(3));\nC23 = " - "sin(u(1))*cos(u(2));\nC31 = cos(u(1))*sin(u(2))*cos(u(3))+sin(u(1))*sin(u(3));\nC32 = cos(u(1))*sin(u(2))*sin(u(" - "3))-sin(u(1))*cos(u(3));\nC33 = cos(u(1))*cos(u(2));\n \ntheta = acos(0.5*(C11+C22+C33-1));\n\ne = [C23-C32; " - "C31-C13; C12-C21]/(2*sin(theta));\n \ny = [e; theta];\n\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 20 - ssIdNumber 4 - name "u" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [18 0 21] - } - data { - id 21 - ssIdNumber 5 - name "y" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [18 20 0] - } - junction { - id 22 - position [23.5747 49.5747 7] - chart 18 - subviewer 18 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [18 0 0] - } - transition { - id 23 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 22 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 18 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 18 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [18 0 0] - } - instance { - id 24 - machine 1 - name " Sensors /3D Graphical Simulation1/MATLAB Function" - chart 18 - } - chart { - id 25 - machine 1 - name "Actuation/ESC System" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 26 0 0] - viewObj 25 - ssIdHighWaterMark 18 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 4 - disableImplicitCasting 1 - eml { - name "ESC" - } - firstData 27 - firstTransition 33 - firstJunction 32 - } - state { - id 26 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 25 - treeNode [25 0 0 0] - superState SUBCHART - subviewer 25 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function Vb_eff = ESC(P, Pmin, Pmax, Vb)\n\nP1 = P(1);\nP2 = P(2);\nP3 = P(3);\nP4 = P(4);\n\n%" - " Define u_Pi for each of the rotors, limiting it to be greater than 0\n% u_P0 = (rotor_0_duty_cycle/100 - Pmin) " - "/ (Pmax - Pmin);\n% u_P1 = (rotor_1_duty_cycle/100 - Pmin) / (Pmax - Pmin);\n% u_P2 = (rotor_2_duty_cycle/100 - " - "Pmin) / (Pmax - Pmin);\n% u_P3 = (rotor_3_duty_cycle/100 - Pmin) / (Pmax - Pmin);\nu_P0 = (P1 - Pmin) / (Pmax - " - "Pmin);\nu_P1 = (P2 - Pmin) / (Pmax - Pmin);\nu_P2 = (P3 - Pmin) / (Pmax - Pmin);\nu_P3 = (P4 - Pmin) / (Pmax - P" - "min);\n\n\n% Determine the effective battery voltage from each ESC\nVb_eff_0 = u_P0 * Vb;\nVb_eff_1 = u_P1 * Vb;" - "\nVb_eff_2 = u_P2 * Vb;\nVb_eff_3 = u_P3 * Vb;\n \nVb_eff = [Vb_eff_0, Vb_eff_1, Vb_eff_2, Vb_eff_3];\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 27 - ssIdNumber 4 - name "P" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [25 0 28] - } - data { - id 28 - ssIdNumber 5 - name "Vb_eff" - scope OUTPUT_DATA - machine 1 - props { - array { - size "1,4" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [25 27 29] - } - data { - id 29 - ssIdNumber 16 - name "Pmin" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 1 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [25 28 30] - } - data { - id 30 - ssIdNumber 17 - name "Pmax" - scope PARAMETER_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [25 29 31] - } - data { - id 31 - ssIdNumber 18 - name "Vb" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 2 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [25 30 0] - } - junction { - id 32 - position [23.5747 49.5747 7] - chart 25 - subviewer 25 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [25 0 0] - } - transition { - id 33 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 32 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 25 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 25 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [25 0 0] - } - instance { - id 34 - machine 1 - name "Actuation/ESC System" - chart 25 - } - chart { - id 35 - machine 1 - name "Actuation/Motor System" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 36 0 0] - viewObj 35 - ssIdHighWaterMark 16 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 5 - disableImplicitCasting 1 - eml { - name "motor" - } - firstData 37 - firstTransition 47 - firstJunction 46 - } - state { - id 36 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 35 - treeNode [35 0 0 0] - superState SUBCHART - subviewer 35 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function w_dot = motor(Vb_eff, w, Rm, Kv, Kq, Kd, If, Jreq)\n\n% Define each motors effective bat" - "tery voltage\nVb_eff_0 = Vb_eff(1);\nVb_eff_1 = Vb_eff(2);\nVb_eff_2 = Vb_eff(3);\nVb_eff_3 = Vb_eff(4);\n\n% De" - "termine the angular velocity of each rotor from feedback\nw_0 = w(1);\nw_1 = w(2);\nw_2 = w(3);\nw_3 = w(4);\n\n" - "% Determine angular acceleration of each rotor\nw_0_dot = 1/(Jreq*Rm*Kq) * Vb_eff_0 - 1/(Jreq*Rm*Kq*Kv) * w_0 - " - "1/(Jreq*Kq)*If - (Kd/Jreq) * w_0^2;\nw_1_dot = 1/(Jreq*Rm*Kq) * Vb_eff_1 - 1/(Jreq*Rm*Kq*Kv) * w_1 - 1/(Jreq*Kq)" - "*If - (Kd/Jreq) * w_1^2;\nw_2_dot = 1/(Jreq*Rm*Kq) * Vb_eff_2 - 1/(Jreq*Rm*Kq*Kv) * w_2 - 1/(Jreq*Kq)*If - (Kd/J" - "req) * w_2^2;\nw_3_dot = 1/(Jreq*Rm*Kq) * Vb_eff_3 - 1/(Jreq*Rm*Kq*Kv) * w_3 - 1/(Jreq*Kq)*If - (Kd/Jreq) * w_3^" - "2;\n\nw_dot = [w_0_dot, w_1_dot, w_2_dot, w_3_dot]; " - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 37 - ssIdNumber 4 - name "Vb_eff" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [35 0 38] - } - data { - id 38 - ssIdNumber 16 - name "w" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [35 37 39] - } - data { - id 39 - ssIdNumber 7 - name "w_dot" - scope OUTPUT_DATA - machine 1 - props { - array { - size "1,4" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [35 38 40] - } - data { - id 40 - ssIdNumber 9 - name "Rm" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 5 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [35 39 41] - } - data { - id 41 - ssIdNumber 10 - name "Kv" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 4 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [35 40 42] - } - data { - id 42 - ssIdNumber 11 - name "Kq" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 3 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [35 41 43] - } - data { - id 43 - ssIdNumber 12 - name "Kd" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 2 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [35 42 44] - } - data { - id 44 - ssIdNumber 13 - name "If" - scope PARAMETER_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [35 43 45] - } - data { - id 45 - ssIdNumber 14 - name "Jreq" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 1 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [35 44 0] - } - junction { - id 46 - position [23.5747 49.5747 7] - chart 35 - subviewer 35 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [35 0 0] - } - transition { - id 47 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 46 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 35 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 35 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [35 0 0] - } - instance { - id 48 - machine 1 - name "Actuation/Motor System" - chart 35 - } - chart { - id 49 - machine 1 - name "Actuation/Rotor System\n\n\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 50 0 0] - viewObj 49 - ssIdHighWaterMark 31 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 6 - disableImplicitCasting 1 - eml { - name "rotor" - } - firstData 51 - firstTransition 69 - firstJunction 68 - } - state { - id 50 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 49 - treeNode [49 0 0 0] - superState SUBCHART - subviewer 49 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function [B_omega_dot, B_vo_dot]= rotor(w_dot, w, B_Fg, B_omega, B_vo, m, Kt, Kd, rhx, rhy, rhz, " - "Jreq, Jxx, Jyy, Jzz)\n\n% Create J vector\nJ = [Jxx, 0 , 0 ; ...\n 0 , Jyy, 0 ; ...\n 0 , 0 , Jzz;" - "];\n\n% Create r_hi vector\nrh_0 = [-rhx; rhy; -rhz];\nrh_1 = [rhx; rhy; -rhz];\nrh_2 = [-rhx; -rhy; -rhz];\nrh_" - "3 = [rhx; -rhy; -rhz];\n\n% Define vector from body frame origin to center of mass\nbr_oc = [0; 0; 0];\n\n% Defi" - "ne 3x3 Identity Matrix\nI = eye(3);\n\n% Create gamma vectors\ngamma_Ti = [0; 0; -1];\ngamma_omega_03 = [0; 0; 1" - "]; %Rotors 0 and 3 use this gamma_omega vector\ngamma_omega_12 = [0; 0; -1]; %Rotors 1 and 2 use this gamma_ome" - "ga vector\n\n% Define angular velocities for each rotor\nw_0 = w(1);\nw_1 = w(2);\nw_2 = w(3);\nw_3 = w(4);\n\n%" - " Define angular acceleration for each rotor\nw_0_dot = w_dot(1);\nw_1_dot = w_dot(2);\nw_2_dot = w_dot(3);\nw_3_" - "dot = w_dot(4);\n\n% Define the rotor force in the z-direction from each rotor\nB_Fr_0 = Kt * w_0 * w_0 * gamma_" - "Ti;\nB_Fr_1 = Kt * w_1 * w_1 * gamma_Ti;\nB_Fr_2 = Kt * w_2 * w_2 * gamma_Ti;\nB_Fr_3 = Kt * w_3 * w_3 * gamma_T" - "i;\n\n% Sum up the rotor forces in the z-direction from each vector to get the\n% total body force in the z-dire" - "ction\nB_Fr = B_Fr_0 + B_Fr_1 + B_Fr_2 + B_Fr_3;\n\n% Define the in-plane drag and induced torque produced by ea" - "ch rotor\n B_Q_d0 = -1 * Kd * w_0 * w_0 * gamma_omega_03;\n B_Q_d1 = -1 * Kd * w_1 * w_1 * gamma_omega_12;\n B_Q" - "_d2 = -1 * Kd * w_2 * w_2 * gamma_omega_12;\n B_Q_d3 = -1 * Kd * w_3 * w_3 * gamma_omega_03;\n\n% Sum up the tot" - "al in-plane drag and induced torque to get the total\n% in-plane drag and induced torque on the body\nB_Q_d = B_" - "Q_d0 + B_Q_d1 + B_Q_d2 + B_Q_d3;\n\n% Define the force lever arm torque created from the force produced by each\n" - "% rotor in the z-direction\nB_Q_F0 = cross( rh_0, B_Fr_0 );\nB_Q_F1 = cross( rh_1, B_Fr_1 );\nB_Q_F2 = cross( rh" - "_2, B_Fr_2 );\nB_Q_F3 = cross( rh_3, B_Fr_3 );\n\nB_Q_F = B_Q_F0 + B_Q_F1 + B_Q_F2 + B_Q_F3;\n\n%Define the chan" - "ge in angular momentum torque produced by each rotor \nB_Q_L0 = -1 * Jreq * ( cross(B_omega, w_0 * gamma_omega_0" - "3) + w_0_dot * gamma_omega_03 );\nB_Q_L1 = -1 * Jreq * ( cross(B_omega, w_1 * gamma_omega_12) + w_1_dot * gamma_" - "omega_12 ); \nB_Q_L2 = -1 * Jreq * ( cross(B_omega, w_2 * gamma_omega_12) + w_2_dot * gamma_omega_12 ); \nB_Q_L3" - " = -1 * Jreq * ( cross(B_omega, w_3 * gamma_omega_03) + w_3_dot * gamma_omega_03 );\n\n% Sum up the total change" - " in angular momentum torque produced by each rotor\nB_Q_L = B_Q_L0 + B_Q_L1 + B_Q_L2 + B_Q_L3;\n\n% Define the t" - "otal rotor system torque as the sum of the in-plane drag and\n% induced torque, force lever arm torque, and chan" - "ge in angular momentum\n% torques\nB_Q = B_Q_d + B_Q_F + B_Q_L;\n\n% Define the body forces in the z-direction f" - "rom each vector to get the\n% total body force in the z-direction\nB_F = B_Fr + B_Fg; \n\n% Define the body fram" - "e linear velocities\nB_vo_dot = (m*I)^(-1) * ( B_F - cross( B_omega, m*(B_vo + cross(B_omega, br_oc)) ) );\n\n% " - "Define the body frame angular velocities\nB_omega_dot = J ^(-1) * ( B_Q - cross(B_omega, J * B_omega) - cross(br" - "_oc, B_F) );\n\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 51 - ssIdNumber 6 - name "B_omega_dot" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [49 0 52] - } - data { - id 52 - ssIdNumber 10 - name "w_dot" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 51 53] - } - data { - id 53 - ssIdNumber 11 - name "w" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 52 54] - } - data { - id 54 - ssIdNumber 30 - name "B_Fg" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 53 55] - } - data { - id 55 - ssIdNumber 8 - name "B_omega" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 54 56] - } - data { - id 56 - ssIdNumber 5 - name "B_vo_dot" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [49 55 57] - } - data { - id 57 - ssIdNumber 7 - name "B_vo" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 56 58] - } - data { - id 58 - ssIdNumber 12 - name "m" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 6 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 57 59] - } - data { - id 59 - ssIdNumber 14 - name "Kt" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 5 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 58 60] - } - data { - id 60 - ssIdNumber 13 - name "Kd" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 4 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 59 61] - } - data { - id 61 - ssIdNumber 15 - name "rhx" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 7 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 60 62] - } - data { - id 62 - ssIdNumber 16 - name "rhy" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 8 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 61 63] - } - data { - id 63 - ssIdNumber 17 - name "rhz" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 9 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 62 64] - } - data { - id 64 - ssIdNumber 18 - name "Jreq" - scope PARAMETER_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 63 65] - } - data { - id 65 - ssIdNumber 19 - name "Jxx" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 1 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 64 66] - } - data { - id 66 - ssIdNumber 20 - name "Jyy" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 2 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 65 67] - } - data { - id 67 - ssIdNumber 21 - name "Jzz" - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 3 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [49 66 0] - } - junction { - id 68 - position [23.5747 49.5747 7] - chart 49 - subviewer 49 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [49 0 0] - } - transition { - id 69 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 68 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 49 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 49 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [49 0 0] - } - instance { - id 70 - machine 1 - name "Actuation/Rotor System\n\n\n\n\n\n\n\n" - chart 49 - } - chart { - id 71 - machine 1 - name "Actuation/Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 72 0 0] - viewObj 71 - ssIdHighWaterMark 6 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 7 - disableImplicitCasting 1 - eml { - name "angular_body_earth_conversion" - } - firstData 73 - firstTransition 77 - firstJunction 76 - } - state { - id 72 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 71 - treeNode [71 0 0 0] - superState SUBCHART - subviewer 71 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function euler_rates = angular_body_earth_conversion(B_omega, euler_angles)\n\nphi = euler_angles" - "(1);\ntheta = euler_angles(2);\n\nAeb = [1, sin(phi)*tan(theta), cos(phi)*tan(theta); ...\n 0, cos(p" - "hi) , -sin(phi) ; ...\n 0, sin(phi)/cos(theta), cos(phi)/cos(theta)];\n\n \neuler_rates " - "= Aeb * B_omega;\n " - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 73 - ssIdNumber 4 - name "B_omega" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [71 0 74] - } - data { - id 74 - ssIdNumber 5 - name "euler_rates" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [71 73 75] - } - data { - id 75 - ssIdNumber 6 - name "euler_angles" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [71 74 0] - } - junction { - id 76 - position [23.5747 49.5747 7] - chart 71 - subviewer 71 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [71 0 0] - } - transition { - id 77 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 76 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 71 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 71 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [71 0 0] - } - instance { - id 78 - machine 1 - name "Actuation/Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - chart 71 - } - chart { - id 79 - machine 1 - name "Actuation/Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 80 0 0] - viewObj 79 - ssIdHighWaterMark 13 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 8 - disableImplicitCasting 1 - eml { - name "linear_earth_body_conversion" - } - firstData 81 - firstTransition 87 - firstJunction 86 - } - state { - id 80 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 79 - treeNode [79 0 0 0] - superState SUBCHART - subviewer 79 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function [B_Fg, B_g] = linear_earth_body_conversion(E_Fg, euler_angles, m)\n\nphi = euler_angles" - "(1);\ntheta = euler_angles(2);\npsi = euler_angles(3);\n\nLbe = [ cos(theta)*cos(psi) ," - " cos(theta)*sin(psi) , -sin(theta) ; ...\n sin(phi)*sin(theta)*cos(psi)-c" - "os(phi)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), sin(phi)*cos(theta); ...\n cos(phi)*sin(" - "theta)*cos(psi)+sin(phi)*sin(psi), cos(phi)*sin(theta)*sin(psi)-sin(phi)*cos(psi), cos(phi)*cos(theta)];\n\nB_Fg" - " = Lbe * E_Fg;\n\nB_g = B_Fg/m;" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 81 - ssIdNumber 7 - name "E_Fg" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [79 0 82] - } - data { - id 82 - ssIdNumber 11 - name "euler_angles" - scope INPUT_DATA - machine 1 - props { - array { - size "3" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [79 81 83] - } - data { - id 83 - ssIdNumber 9 - name "B_Fg" - scope OUTPUT_DATA - machine 1 - props { - array { - size "3" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [79 82 84] - } - data { - id 84 - ssIdNumber 12 - name "B_g" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [79 83 85] - } - data { - id 85 - ssIdNumber 13 - name "m" - scope PARAMETER_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [79 84 0] - } - junction { - id 86 - position [23.5747 49.5747 7] - chart 79 - subviewer 79 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [79 0 0] - } - transition { - id 87 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 86 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 79 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 79 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [79 0 0] - } - instance { - id 88 - machine 1 - name "Actuation/Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - chart 79 - } - chart { - id 89 - machine 1 - name " Sensors /IMU\n\n\n\n\n\n/\n\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 90 0 0] - viewObj 89 - ssIdHighWaterMark 15 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 10 - disableImplicitCasting 1 - eml { - name "idealIMU" - } - firstData 91 - firstTransition 100 - firstJunction 99 - } - state { - id 90 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 89 - treeNode [89 0 0 0] - superState SUBCHART - subviewer 89 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function [accelReading,gyroReading] = idealIMU(B_vo_dot, B_vo, B_Omega, B_g, r_oc, g)\n%#codegen\n" - "\na = B_vo_dot + cross(B_Omega,B_vo); % body frame acceleration \n\naccelReading = (a - B_g)/g ; % accelerometer" - " reading (ideal)\n\ngyroReading = B_Omega ; % gyroscope reading (ideal) \n\nend\n\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 91 - ssIdNumber 4 - name "B_vo_dot" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [89 0 92] - } - data { - id 92 - ssIdNumber 9 - name "B_vo" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [89 91 93] - } - data { - id 93 - ssIdNumber 5 - name "accelReading" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [89 92 94] - } - data { - id 94 - ssIdNumber 6 - name "B_Omega" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [89 93 95] - } - data { - id 95 - ssIdNumber 7 - name "B_g" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [89 94 96] - } - data { - id 96 - ssIdNumber 8 - name "gyroReading" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [89 95 97] - } - data { - id 97 - ssIdNumber 10 - name "r_oc" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [89 96 98] - } - data { - id 98 - ssIdNumber 12 - name "g" - scope PARAMETER_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [89 97 0] - } - junction { - id 99 - position [23.5747 49.5747 7] - chart 89 - subviewer 89 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [89 0 0] - } - transition { - id 100 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 99 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 89 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 89 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [89 0 0] - } - instance { - id 101 - machine 1 - name " Sensors /IMU\n\n\n\n\n\n/\n\n\n\n\n\n\n" - chart 89 - } - chart { - id 102 - machine 1 - name " Sensors /3D Graphical Simulation/MATLAB Function" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 103 0 0] - viewObj 102 - ssIdHighWaterMark 5 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 11 - disableImplicitCasting 1 - eml { - name "eigenaxis_ucart" - } - firstData 104 - firstTransition 107 - firstJunction 106 - } - state { - id 103 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 102 - treeNode [102 0 0 0] - superState SUBCHART - subviewer 102 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function y = eigenaxis_ucart(u)\n\n\nif abs(u(1))< 0.0001\n u(1) = 0.0001;\nend\n\nif abs(u(2)" - ")< 0.0001\n u(2) = 0.0001;\nend\n\nif abs(u(3))< 0.0001\n u(3) = 0.0001;\nend\n\nu = [ -u(1); -u(2); u(3) " - "];% [Pitch, Yaw, Roll] \n\nC11 = cos(u(2))*cos(u(3));\nC12 = cos(u(2))*sin(u(3));\nC13 = -sin(u(2));\nC21 = sin(" - "u(1))*sin(u(2))*cos(u(3))-cos(u(1))*sin(u(3));\nC22 = sin(u(1))*sin(u(2))*sin(u(3))+cos(u(1))*cos(u(3));\nC23 = " - "sin(u(1))*cos(u(2));\nC31 = cos(u(1))*sin(u(2))*cos(u(3))+sin(u(1))*sin(u(3));\nC32 = cos(u(1))*sin(u(2))*sin(u(" - "3))-sin(u(1))*cos(u(3));\nC33 = cos(u(1))*cos(u(2));\n \ntheta = acos(0.5*(C11+C22+C33-1));\n\ne = [C23-C32; " - "C31-C13; C12-C21]/(2*sin(theta));\n \ny = [e; theta];\n\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 104 - ssIdNumber 4 - name "u" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [102 0 105] - } - data { - id 105 - ssIdNumber 5 - name "y" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [102 104 0] - } - junction { - id 106 - position [23.5747 49.5747 7] - chart 102 - subviewer 102 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [102 0 0] - } - transition { - id 107 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 106 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 102 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 102 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [102 0 0] - } - instance { - id 108 - machine 1 - name " Sensors /3D Graphical Simulation/MATLAB Function" - chart 102 - } - chart { - id 109 - machine 1 - name " Sensors /Aeb\n\n\n\n\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 110 0 0] - viewObj 109 - ssIdHighWaterMark 6 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 12 - disableImplicitCasting 1 - eml { - name "angular_body_earth_conversion" - } - firstData 111 - firstTransition 115 - firstJunction 114 - } - state { - id 110 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 109 - treeNode [109 0 0 0] - superState SUBCHART - subviewer 109 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function euler_rates_IMU = angular_body_earth_conversion(gyro_reading, euler_angles_filtered)\n\n" - "phi = euler_angles_filtered(1);\ntheta = euler_angles_filtered(2);\n\nAeb = [1, sin(phi)*tan(theta), cos(phi)*ta" - "n(theta); ...\n 0, cos(phi) , -sin(phi) ; ...\n 0, sin(phi)/cos(theta), cos(phi)" - "/cos(theta)];\n\n \neuler_rates_IMU = Aeb * gyro_reading;\n " - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 111 - ssIdNumber 4 - name "gyro_reading" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [109 0 112] - } - data { - id 112 - ssIdNumber 5 - name "euler_rates_IMU" - scope OUTPUT_DATA - machine 1 - props { - array { - size "[3,1]" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [109 111 113] - } - data { - id 113 - ssIdNumber 6 - name "euler_angles_filtered" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [109 112 0] - } - junction { - id 114 - position [23.5747 49.5747 7] - chart 109 - subviewer 109 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [109 0 0] - } - transition { - id 115 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 114 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 109 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 109 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [109 0 0] - } - instance { - id 116 - machine 1 - name " Sensors /Aeb\n\n\n\n\n\n\n\n\n\n" - chart 109 - } - chart { - id 117 - machine 1 - name " Sensors /Calculate Pitch and Roll" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 118 0 0] - viewObj 117 - ssIdHighWaterMark 10 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 13 - disableImplicitCasting 1 - eml { - name "getPitchAndRoll" - } - firstData 119 - firstTransition 124 - firstJunction 123 - } - state { - id 118 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 117 - treeNode [117 0 0 0] - superState SUBCHART - subviewer 117 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function [accel_pitch, accel_roll] = getPitchAndRoll(accel_reading, accel_roll_prev)\n\nmag = nor" - "m(accel_reading);\n\n% x_accel = accel_reading(1)/mag;\n% y_accel = accel_reading(2)/mag;\n% z_accel = accel_rea" - "ding(3)/mag;\n\nx_accel = accel_reading(1);\ny_accel = accel_reading(2);\nz_accel = accel_reading(3);\n\naccel_p" - "itch = atan(x_accel/sqrt(y_accel^2 + z_accel^2));\n\n%accel_roll = atan2( -y_accel,(sign(-z_accel)*sqrt(z_accel^" - "2 + (1/100)*x_accel^2)) );\n\n%accel_roll = atan2( -y_accel,(sign(-z_accel)*sqrt(z_accel^2 + x_accel^2)) );\nacc" - "el_roll = atan( -y_accel/( sqrt(z_accel^2 + x_accel^2)) );\n\n% unwrapped_roll = unwrap([accel_roll_prev accel_" - "roll]);\n% accel_roll = unwrapped_roll(2);\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 119 - ssIdNumber 4 - name "accel_reading" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [117 0 120] - } - data { - id 120 - ssIdNumber 5 - name "accel_pitch" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [117 119 121] - } - data { - id 121 - ssIdNumber 6 - name "accel_roll" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [117 120 122] - } - data { - id 122 - ssIdNumber 7 - name "accel_roll_prev" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [117 121 0] - } - junction { - id 123 - position [23.5747 49.5747 7] - chart 117 - subviewer 117 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [117 0 0] - } - transition { - id 124 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 123 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 117 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 117 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [117 0 0] - } - instance { - id 125 - machine 1 - name " Sensors /Calculate Pitch and Roll" - chart 117 - } - chart { - id 126 - machine 1 - name "Control System/Signal Mixer" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 127 0 0] - viewObj 126 - ssIdHighWaterMark 11 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 14 - disableImplicitCasting 1 - eml { - name "signal_mixer" - } - firstData 128 - firstTransition 134 - firstJunction 133 - } - state { - id 127 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 126 - treeNode [126 0 0 0] - superState SUBCHART - subviewer 126 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function P = signal_mixer(height_controlled, y_controlled, x_controlled, yaw_controlled)\n\ncont" - "roller_outputs = [ height_controlled; x_controlled; y_controlled; yaw_controlled ];\nsignal_mixer = [ 1, -1, -1," - " -1; ... \n 1, 1, -1, 1; ...\n 1, -1, 1, 1; ...\n 1, 1, 1," - " -1 ];\n\n% signal_mixer = [ 1, 1, -1, -1; ... \n% 1, -1, -1, 1; ...\n% 1, " - "1, 1, 1; ...\n% 1, -1, 1, -1 ];\n \nP = signal_mixer * controller_outputs;\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 128 - ssIdNumber 4 - name "height_controlled" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [126 0 129] - } - data { - id 129 - ssIdNumber 7 - name "y_controlled" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [126 128 130] - } - data { - id 130 - ssIdNumber 5 - name "P" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [126 129 131] - } - data { - id 131 - ssIdNumber 6 - name "x_controlled" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [126 130 132] - } - data { - id 132 - ssIdNumber 8 - name "yaw_controlled" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [126 131 0] - } - junction { - id 133 - position [23.5747 49.5747 7] - chart 126 - subviewer 126 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [126 0 0] - } - transition { - id 134 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 133 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 126 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 126 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [126 0 0] - } - instance { - id 135 - machine 1 - name "Control System/Signal Mixer" - chart 126 - } - chart { - id 136 - machine 1 - name "Control System/MATLAB Function1" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 137 0 0] - viewObj 136 - ssIdHighWaterMark 25 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 15 - disableImplicitCasting 1 - eml { - name "c_controller" - } - firstData 138 - firstTransition 160 - firstJunction 159 - } - state { - id 137 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 136 - treeNode [136 0 0 0] - superState SUBCHART - subviewer 136 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function [z_corr, y_cor, x_corr, yaw_corr, pid_y_out, pid_roll_out] = c_controller(set_x, set_y, " - "set_z, set_yaw, ...\n cur_x, cur_y, cur_z, ...\n cur_phi, cur_theta, cur_psi, ...\n cur_phi_d, cur_thet" - "a_d, cur_psi_d, vrpn_id, Tc)\n\nout_z = -1;\nout_y = -1;\nout_x = -1;\nout_yaw = -1;\nc_pid_y = -1;\nc_pid_roll " - "= -1;\n\ncoder.ceval('c_controller', vrpn_id, Tc, set_x, set_y, set_z, set_yaw, ...\n cur_x, " - "cur_y, cur_z, ...\n cur_phi, cur_theta, cur_psi, ...\n cur_phi_d, cur_thet" - "a_d, cur_psi_d, ...\n coder.wref(out_z), coder.wref(out_y), coder.wref(out_x), coder.wref(out" - "_yaw), ...\n coder.wref(c_pid_y), coder.wref(c_pid_roll));\n\nz_corr = out_z;\ny_cor = out_y;" - "\nx_corr = out_x;\npid_y_out = c_pid_y;\npid_roll_out = c_pid_roll;\nyaw_corr = out_yaw;\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 138 - ssIdNumber 4 - name "set_x" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 0 139] - } - data { - id 139 - ssIdNumber 5 - name "z_corr" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [136 138 140] - } - data { - id 140 - ssIdNumber 6 - name "set_y" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 139 141] - } - data { - id 141 - ssIdNumber 7 - name "set_z" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 140 142] - } - data { - id 142 - ssIdNumber 8 - name "set_yaw" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 141 143] - } - data { - id 143 - ssIdNumber 9 - name "cur_x" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 142 144] - } - data { - id 144 - ssIdNumber 10 - name "cur_y" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 143 145] - } - data { - id 145 - ssIdNumber 11 - name "cur_z" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 144 146] - } - data { - id 146 - ssIdNumber 12 - name "cur_phi" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 145 147] - } - data { - id 147 - ssIdNumber 13 - name "cur_theta" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 146 148] - } - data { - id 148 - ssIdNumber 14 - name "cur_psi" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 147 149] - } - data { - id 149 - ssIdNumber 15 - name "cur_phi_d" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 148 150] - } - data { - id 150 - ssIdNumber 16 - name "cur_theta_d" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 149 151] - } - data { - id 151 - ssIdNumber 17 - name "cur_psi_d" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 150 152] - } - data { - id 152 - ssIdNumber 18 - name "y_cor" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [136 151 153] - } - data { - id 153 - ssIdNumber 19 - name "x_corr" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [136 152 154] - } - data { - id 154 - ssIdNumber 20 - name "yaw_corr" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [136 153 155] - } - data { - id 155 - ssIdNumber 21 - name "vrpn_id" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 154 156] - } - data { - id 156 - ssIdNumber 22 - name "pid_y_out" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [136 155 157] - } - data { - id 157 - ssIdNumber 23 - name "pid_roll_out" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [136 156 158] - } - data { - id 158 - ssIdNumber 25 - name "Tc" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [136 157 0] - } - junction { - id 159 - position [23.5747 49.5747 7] - chart 136 - subviewer 136 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [136 0 0] - } - transition { - id 160 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 159 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 136 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 136 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [136 0 0] - } - instance { - id 161 - machine 1 - name "Control System/MATLAB Function1" - chart 136 - } - chart { - id 162 - machine 1 - name " Sensors /Aeb_c\n\n\n\n\n\n\n\n\n\n1" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 163 0 0] - viewObj 162 - ssIdHighWaterMark 6 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 16 - disableImplicitCasting 1 - eml { - name "angular_body_earth_conversion" - } - firstData 164 - firstTransition 168 - firstJunction 167 - } - state { - id 163 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 162 - treeNode [162 0 0 0] - superState SUBCHART - subviewer 162 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function euler_rates_IMU = angular_body_earth_conversion(gyro_reading, euler_angles_filtered)\n\n" - "phi = euler_angles_filtered(1);\ntheta = euler_angles_filtered(2);\npsi = NaN;\n\nphi_dot = -1;\ntheta_dot = -1;" - "\npsi_dot = -1;\n\np = gyro_reading(1);\nq = gyro_reading(2);\nr = gyro_reading(3);\n\ncoder.ceval( 'aeb_mat', p" - ", q, r, phi, theta, psi, coder.wref(phi_dot), ...\n coder.wref(theta_dot), coder.wref(psi_dot) );\n\n \neul" - "er_rates_IMU = [phi_dot; theta_dot; psi_dot];\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 164 - ssIdNumber 4 - name "gyro_reading" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [162 0 165] - } - data { - id 165 - ssIdNumber 5 - name "euler_rates_IMU" - scope OUTPUT_DATA - machine 1 - props { - array { - size "[3,1]" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [162 164 166] - } - data { - id 166 - ssIdNumber 6 - name "euler_angles_filtered" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [162 165 0] - } - junction { - id 167 - position [23.5747 49.5747 7] - chart 162 - subviewer 162 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [162 0 0] - } - transition { - id 168 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 167 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 162 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 162 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [162 0 0] - } - instance { - id 169 - machine 1 - name " Sensors /Aeb_c\n\n\n\n\n\n\n\n\n\n1" - chart 162 - } - chart { - id 170 - machine 1 - name " Sensors /MATLAB Function" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 171 0 0] - viewObj 170 - ssIdHighWaterMark 7 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 17 - disableImplicitCasting 1 - eml { - name "complimentaryFilterC" - } - firstData 172 - firstTransition 177 - firstJunction 176 - } - state { - id 171 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 170 - treeNode [170 0 0 0] - superState SUBCHART - subviewer 170 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function euler_angles_IMU = complimentaryFilterC(accel_pitch, accel_roll, euler_rates_gyro)\n\ne" - "uler_x = euler_rates_gyro(1);\neuler_y = euler_rates_gyro(2);\n\nfiltered_pitch = -1;\nfiltered_roll = -1;\n\nco" - "der.ceval('compl_filter', accel_pitch, accel_roll, euler_x, euler_y, ...\n coder.wref(filtered_pitch)" - ", coder.wref(filtered_roll));\n\neuler_angles_IMU = [filtered_roll; filtered_pitch];\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 172 - ssIdNumber 4 - name "accel_pitch" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [170 0 173] - } - data { - id 173 - ssIdNumber 5 - name "euler_angles_IMU" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [170 172 174] - } - data { - id 174 - ssIdNumber 6 - name "accel_roll" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [170 173 175] - } - data { - id 175 - ssIdNumber 7 - name "euler_rates_gyro" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [170 174 0] - } - junction { - id 176 - position [23.5747 49.5747 7] - chart 170 - subviewer 170 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [170 0 0] - } - transition { - id 177 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 176 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 170 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 170 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [170 0 0] - } - instance { - id 178 - machine 1 - name " Sensors /MATLAB Function" - chart 170 - } - chart { - id 179 - machine 1 - name " Sensors /MATLAB Function1" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 180 0 0] - viewObj 179 - ssIdHighWaterMark 6 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 18 - disableImplicitCasting 1 - eml { - name "angle_IMU_C" - } - firstData 181 - firstTransition 185 - firstJunction 184 - } - state { - id 180 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 179 - treeNode [179 0 0 0] - superState SUBCHART - subviewer 179 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function [accel_pitch, accel_roll] = angle_IMU_C(accel_reading)\n\naccel_x = accel_reading(1);\n" - "accel_y = accel_reading(2);\naccel_z = accel_reading(3);\n\ncalculated_pitch = -1;\ncalculated_roll = -1;\n\ncod" - "er.ceval('angle_accel', accel_x, accel_y, accel_z, coder.wref(calculated_pitch), coder.wref(calculated_roll));\n" - "\naccel_pitch = calculated_pitch;\naccel_roll = calculated_roll;" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 181 - ssIdNumber 4 - name "accel_reading" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [179 0 182] - } - data { - id 182 - ssIdNumber 5 - name "accel_pitch" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [179 181 183] - } - data { - id 183 - ssIdNumber 6 - name "accel_roll" - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [179 182 0] - } - junction { - id 184 - position [23.5747 49.5747 7] - chart 179 - subviewer 179 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [179 0 0] - } - transition { - id 185 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 184 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 179 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 179 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [179 0 0] - } - instance { - id 186 - machine 1 - name " Sensors /MATLAB Function1" - chart 179 - } - chart { - id 187 - machine 1 - name " Sensors /Complimentary Filter" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 188 0 0] - viewObj 187 - ssIdHighWaterMark 17 - decomposition CLUSTER_CHART - type EML_CHART - chartFileNumber 19 - disableImplicitCasting 1 - eml { - name "complimentaryFilter" - } - firstData 189 - firstTransition 195 - firstJunction 194 - } - state { - id 188 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 187 - treeNode [187 0 0 0] - superState SUBCHART - subviewer 187 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "%function euler_angles_IMU = complimentaryFilter(accel_pitch, accel_roll, euler_angles_gyro, pre" - "v_euler_angles_IMU)\nfunction euler_angles_IMU = complimentaryFilter(accel_pitch, accel_roll, euler_rates_gyro," - " prev_euler_angles)\n\nk_gyro = 0.98; \nk_accel = 1-k_gyro; \n\nTs = 0.005; % 5 milliseconds\n\nprev_phi = prev_" - "euler_angles(1);\nprev_theta = prev_euler_angles(2);\n\nprev_phi_dot = euler_rates_gyro(1);\nprev_theta_dot = eu" - "ler_rates_gyro(2);\n\nintegrated_phi_gyro = Ts * prev_phi_dot + prev_phi;\nintegrated_theta_gyro = Ts * prev_the" - "ta_dot + prev_theta;\n\nphi = k_gyro * integrated_phi_gyro + k_accel * accel_roll;\ntheta = k_gyro * integrated_" - "theta_gyro + k_accel * accel_pitch;\n\neuler_angles_IMU = [phi; theta];\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 189 - ssIdNumber 4 - name "accel_pitch" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [187 0 190] - } - data { - id 190 - ssIdNumber 13 - name "accel_roll" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [187 189 191] - } - data { - id 191 - ssIdNumber 5 - name "euler_angles_IMU" - scope OUTPUT_DATA - machine 1 - props { - array { - size "[2,1]" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - linkNode [187 190 192] - } - data { - id 192 - ssIdNumber 6 - name "euler_rates_gyro" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [187 191 193] - } - data { - id 193 - ssIdNumber 17 - name "prev_euler_angles" - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - linkNode [187 192 0] - } - junction { - id 194 - position [23.5747 49.5747 7] - chart 187 - subviewer 187 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - linkNode [187 0 0] - } - transition { - id 195 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 194 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 187 - dataLimits [21.175 25.975 14.625 42.575] - subviewer 187 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - linkNode [187 0 0] - } - instance { - id 196 - machine 1 - name " Sensors /Complimentary Filter" - chart 187 - } - target { - id 197 - machine 1 - name "sfun" - description "Default Simulink S-Function Target." - linkNode [1 0 0] - } -} diff --git a/controls/model/Quadcopter_Model_R2016_A.slx b/controls/model/Quadcopter_Model_R2016_A.slx deleted file mode 100644 index 7f461495c2c37f501f258aed80ec8233b134740b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 40651 zcmaI6Q?M{R)TMcB+qP}nwr$(CZQHhO+cw@~tG~ZyE~cle`XZ@H?pD@LYVSN-K^hnY z1poj50sy`_RFcDpenSHg0H7TR008^HU0YKZLlZ+6LwaL-CsPF{dk0e|7fVxTIuBc$ zP^C$^VFr}%)QPtdw=RKN7Sw33BBUS!1omk^TUsRUCfV(8-c3q{$ZTHbJWT#x6IZIo z1AsNk;`9hH5YU3qM5(*93sUXybqa?(>q+Ng!$>Lz3XRf8icAJHyjsdZFHpLQ*cRg= zoub}1(&3FrUX&ftR-yHiwT+;!Pb>G1lcV4}fbozSN5DMkf1GwO!%i+Dy`?C{rXQA1 zYXVR(oG1mo!z@Mb+S(NQsSXdL0(q6Z8$-G%?K2fToUB!G<HjyIEnQvwqxRY1=daa; zOS2Uq1$KNp!*d%{yBLt3LGy(r@n%Cpv6BUG2D%S{p1C`_=GG}=A#=h~LSCt(A*0Y@ z=y#C6FMW(Rb7N)fT57RIAX#jj?tOGcZBQq+tJc3q#*IbezqV-MCV7dJ(d9Nw+}3Ou zEthC;Rho?{V#%1c!QvH%U$8RySn_+1z$>u-#_LM;75+Cv?jL5C#{M%x{6AB0|G$RV zy8oY+n8pjr0W-pg)+3qDm)rsorbxQ)1}ad3GeoXNk~J1{w9MR2293hd*naT-*~jm5 zR${9~$`tRxbJr&DgiEX|`s>KS%WFvjLnUN5tUyPpiJL#|I*+zbfm%mXRC!B?@wTev z#Uk<>f?+bXT+X?s4LY-de#5A<gzx?uwDq{HF|(GqX+m*Pkcz_BmNT(KQOA#brxMKy zp9M^2v9_w^ScyPcdWOdQ`$1Qt|0|fyz4b@($zvph=yHbtgjlm__x)Ag`vLgh4?q+B zkSXIo;Y<Gwvj5uwh<dn~+BsX=+x<^)>dp<q1u-CiEa+Rl+ChWGU_p`ddMn&nZ$bpN zm25-&_Oj;Pb7an(sLmRRKNJo0x??$I1`?S2Y<HK3ZNKzv1|LM!jV^L8-IIYWuB7J1 z!n;8F6(M*VCHmo5Ul`@YNi|+h5J^WjX8U4jVA-#Rm<^Cu+NPmf_43mu?w|u+VjoAu zf5EHbn<z~dO}LwCR=TD?<`@6||Fi{7xx)%80{~F_0Rv$Er_I^Y*44(+&YIrH#@^W4 z#M02*$<X$H<lOpxxNnOk-QRsszq8msC1FaA`HtZE%7^EAtVi`G8OgIHF9u6W3}FFr z09Z)Ro%#QL0tn#vq6jFIn3}lRX5D~QRdrw2U77#g{bS4Vc}`}DDDJ<j_?ns<i7$Jg ziKzSQYo4fk&B^_9zn^Vh_BactFRte3d|_g7d2Hi4J;<I6fg8+UIA>4J@74ah<1TN$ z_j%yM?{+TW^L{L2JlgrXn2)pX8Ob*Dd*tzdnHwx8$QsRG;#Fm49jmeAd7J;P9+9`F z3)1#K7uZyHQC3WO-B^d{Cdv4?<#b%Z^F=Dz`&!_K5oY2OEv~D>819+r?#TZd9d?KF zll)PCSb?7Zp%KO?dE^X#^2B(*6zy>i(0hA2T9Xf=#2d))#u6#t!_D(V9n04nU0)B8 zdQ4v<$0J+LJ}8b)w>k&#|Dc3q>gT;4&5mvs4dK7TDS$^F8!9Z%%j@w%4Ee1lc+~$` zbae|>(=e_Xpr)Ul;7VRM|7Fo8;nOsl)`;`_`So9<PiB|oDPN8=ySpG8__8w>^7r=) zYTKDR;dowR*@qsyC4wn}{}Lx(eR!^{Id{sdYRs1sU&qrFyfyXWm_-nM>h#}-JiZ2? zm2j<Jw+u{!#xHOhqR}h(X>-2c&TFo}k-NyRs@6WS9~JTc)ALt>CUkm?LkdaGXK7s8 z)MzcE$=3&bwM_uS=s<Ilf-Snji!aCD8?jUnc8rR9n;WG5qdJ!LMxR;uM>z(rSZ2)) zPWDF2|1tO?3x*%>MrlMh`(T$_BTum?65{8_4u3o%AJ>DH3(J<9&D@o!nJVa!L9*wI zI-r>_D%sb{NL?8u<X6m}OYn<+`u$a}g<FMlO=@L!>%MSiUnc^q`G@Sq23FT72qlp? zB5|kui>x=g2h*IKP96)M5jK_o@=f<tOk<nRy~-x*vxc*6f!DeP{7W8ZuTMaUN?vPT z@kQppcU@h*GLLb-tB~WX+rDtEtGsNxE_lAn^eU^)Xd^x9&y}_eQqc>kA#LWW&jfgR zBJGAaum6Gn(=c8H**3LCn`ugD3r?Sw{AYP5=K@QcS&Nk={O1Dmk;LmQ1ZPKCWCe`% z#}!vxeek&w-DAy9dE&#_9Ppn0F*E(0AB1w~75^M`#qTdhovdP@73EN3tqb~lbMXth zc<l!Fd%Vry?bR`HWMAK0UPLL8{xFz4N4JOi)NtgQ=h^<03oN{dv(09c{Dj9p^D=hC zd*%00mcGdHfCxS9w;<d4x@9g80^%*^Nsu0O4$-hM&VV-_VauMve>N~o5yecj_))A6 zdWTHkDekodUZOWA3}3qtbCt=w=0O4*sYL4W2df0M7?Bho9o`q2T(iJ8O3WC@pf#Ty za)duA*7uYIfsD-b>hQ`aaeVSVmhYD!{4I@Qa->M^hovKKuIEBqtco+gypA{+1%5Go z4Iz0|Y=A~`@l2TIRp^5_x9BGH6~h2^H~`H*yEh{7<iS~5JxaR9DKrT^|IGr2jsbHC zGLx5xMvfCUaXGI?&dh%(^sy!lL_f9gkg50*%YOfn%TJn6SeWTA&XDv^<@tX8Bx40W z2B6aAFm%xT&oo3u1>}2kG|}R_GTldG#*;Wss3iR;{saZYnXbd+0NW&X?^D89MsRqM zE{ALor`RQr^nzx>On1c5<HV7j=qP@Z2o+}H#Z77}srCMCKU$P!cAfgMk>vz_7C&}w zI$WQqMO&`7<>SCyUPI>@QxSBc>v7YXGX$#u(d>p0I);6Zi1Y@vH=7baq4j%DUQa*Q z{FkSentpm+bdRSuvblJ46}1R$OWLA<2<rps_WXo+F)ZUasvRkqEkAipH3Mq7-sW@p z8LJrkL&hZeooe6{)LeGL%?F(vf2ouGW&T){Ni<j<o?Z_ZFIB&p3{S4y&%-a@?DsY_ zUFT~P`VkA>zc)Wr`Ckq+ek41|p?oj=@2b<>=}iA4nxR|fE)yWB^Fz+@`|Db?88>+Q z1%A5ZYosR>QjMF;q8z6`W2~HB%e{T3{=3d;UHsCWlA;%G8)Vy#s|R1J&r|t*&8Ifc zSyN%f@7qwe>@nvSVfqPXx_MTSR(iM%H~$>qh;X{R)=63UqqMKua-6W%hoKkWTY0CS zm|lh+8ryCoei$sVTrIYv2MCG}Pg-?$P#`zIzvmMAkka6<E|9Eps@)wT30;#(psKLH z7^$V!E-{^V{I|=eQ$A~QV}pHzQdFD@i!PS1#}P~MeZS%G=M7}MAm6Z=T##P)<pe?- z=I`&sbQyb!wNoh*<~z@j)oC=tE7K97iFAU`y(p3nay1<8ip8MWXlfx-oi1k73p<>4 zU5pnV5-DC|`h_0Tvq_>tKc>+vRPrGc82#h{VX+|7WjRL<;c)!$T($gLBp5xe+C?Ha zxMTtm1<7$FAg!OxtS|K*cxUP}*JEN<!lYPnBE*h6yPr$Ojubv`b}n%u){gFoJ#Qah zX1rfG?@YL%L`u;+uKo*!W6!9=NmrB!aK1mp8TmswMD0@zpY%K2$S<NulDRRI5_cAr z$+*UPH8^ZuOFSKHaL$Ls@c>OwJ+xtND_hD%l4*rVfgE#Lug~tvqKJV({*X&zfqs)x zx;@}jN*{V8da3$Gs@B68wN2iqF-HH}&=w6CH*X;oD5lU%95Mgb$=BkCFH0}Ml(}vU zZ~T(zk-V7(Z$B*2NM!IO$+SMh$G^31;k$m({$l1&UTu~qJ<klOy-0;j0>FRz#k9Ws zk;V6Y+t3ZYE8yhMs0idO_{jEn=TdF?yCck#-TrmdrK+}Z4hS|rxrNLDiJVaU5xTv! z4?R3ePYfAgm`bM1LWoq^R@`b`l=+IPY~roHC3_yuB{}4PUP5$KLM0((%FnFYwPM53 z8la|?Jd}cAN`jpd!XPNy`C?(GdeH<~d+(IiE1*gh<|Y(Pnu%ypV1H#d#~Y<ZH*zBR ze&{^^w)n-T51(WRZ<GX$<BmjGgw-Mksug2l5(h*Oigw|!<cc}Kv9$T}<&m4<g>QmB zT$H1^`3z}qn|Hd-XxN$X79>X?PUn5_y_Vr+iqU-au{Hg@UoZ&m-2IMckK}bi9`fxM zvYlo_>tTBZ$l?6AINvAX`9CjYyn76Zwo(3m<Hov4=(%I+gbV$`+yO%+4oEqpqnC$4 z!ecmLoy4_n0hrUSH<z}Db;t9KOh}3Ed+!-Utk_AfQK}DTgu_Tk$V^@DZ5gsdXI^#| z@HYEO|43h)*PlZD({YJR$uj&nUWe{`#Z$7jgdWjuF&#Od=8eTmc3ls?ZzQoN%r~M( zL%(+5>n%Knyy@?U4Cv3JMI5~D1J<4I_Mv%#zGq`XX^PS%gbHFK$MZj$M~?4^nLy}6 z>F@CfrK>TLzsx=2r$mv{oG8)IR9zcI358mgkf%!bp5pa72<Xj~PmK^yO-z4fjFdU( zCdvgxRBiqRFz;vgigjV=Uy>utco3j0y5j*k;wYKhtrVb#bIf1youHjg%p*UNzog<2 zZWBH5;*^?Lx;=07<tdlpIKH&5M>CB%=M{?g#@P9kRQxhnTCl2KjW2E!OeUPh8(1vH zGr17%T-+dpGeJ9m%=;v!=B1?gD7atlYyGy*je^ed%6tWcK2NYbHRxFIztL{h@UgR> z(+-B#=v3vgu!*D^A6(!sNmnjO7zZZ5>1joutu}JP7KM3NJaoI0f9Li#eS}Y{BJIod ziAMQ<whZ_M&6mpe8}q-Q7HQNmuTk!dtdws$365ZjbR1!WNbn%XcqP9}h<;z71L(Qv zZ|*z{HTf;Tvw+q*#OH(HF)4bCDRJUhRxdI3&m`9UQgy&G9r+l=kIUfpHpS!#9$3r~ zYR23Yh87>rj7LHORmX;CLk<_yar|2<dU=m%A-^j1I{cDw6~CH)i8X*4I^~LLbd4H8 z-%6>kpL4iq6_evLG5@vwUi42M!E}vYEpy!eU=oS}kj?tEl!_VKG0%|eaS4*ypm-d1 zdDPY748cLhtP~g*WYP`M6CxHG@a-QzMBAV~$){V239;h;L}xs8T>(Mk`Nn9B#s7(z zsUMGr$9^sU7TBTt_uhlfyLeDbqEL~-)7O&7owte4JM*yxU$*Zo;T;8H7QhSENt#su zu~$y;(*ITe(@)1CEu+z%u)2guWF{@vut~dx%D3kRxR(q+a|L)8#_-&15w<JD4NgDA zA?K0JKm6<b=NjT#|6i8W6i$ki=&E<}6}+Lteee*0kI*-!(V;d`=t?jp(1G6eJQ=Pb z(nkiS$?bv$-Fv|U&*3<3q>2x1{Ae^MHZCcc`b~(J?|q%P!D(biN=D5fJ494T9V;K( z6+~Kq6&HoOi!2!wJQQ(yDB}MJ2k1D#LZp#^Gh76ZJy=>qg&-;chJ0={t&wo2b;EjA z`3`$HcRt2LN<3jp(vUS+2)*Wbfre~LTLX8>1H?<K9@F8qU;U13{Ep}T-93_>uk4%# z4TQ)1W^RH3NWOl39_YgpNRHn>o-Od$AeBLyg)$2)9G@1$?IW+$l~9E685w>&9#kva zyy#@*i2uRwhlEe=xFu6sWr?kbCK8PS=>&6Zm_|D24FZ}aR2!TYORzgzZc`eZQvv7# zS5jf9My^~;Wjqys&EWhHctPnTM)^o8fjA|quYc;3q(pv>K=c#~H)43+V*yji$nH1c z2(*&7Cxx1LGx(=R5RI7_Ps#U)4_U2c)<78x@&=V&9%=b&D3yADn95~>Hg}|*MLQn! zzVi026meE4_hFaijIW%<jNRlL;)e&|#DbND&gqB(ibQ<2{91x_eG2~-J|v1_OXBmI z_D(d`<t(t=#Nl|kma;Q<l-$Kyd@aYZPwirdRv5K^-|q&egamv-W6g+ydnQVOpa;9= z5>o?BliY>NuJlPcp;kZ&*6Ah?NWYAyq{P-G4~2U#{<v{W4F_LIV&$4F#qp2|N~lXR z=Y;p6&RExTVpBOxtwTD_>sFmd6R<}l?){J#7NyyN9tvFF^TxM!qEGTb`^z5Z>(B<l z7h*}*<v?(#s}%pqI&Q`fD&anCsj+Mo$5(k^D&IX&_cQ#=5N#h!iCUrK8T}kOe2;}r z-IKSZ6Jg1%qz_6NdCs9pBtJrbgRjIdZZWd1ISDY4l&9NM92_5s!Fv*=$Z|iLk^?pp zxiwcaHbL-AC>(7pf3k%t=Pw3hcYa`uGeh@)f24UAbaS?o@4b;7=t`Mrd~&o)Nfg09 z>fBh<ckf81GdnD|6a=_z`5U!w%m&uvkWkKhP7iF>TSgy^e*iBq1CL&Kumt{R%z#>% zj|+7k`UEigG+Vq{8PLbp33KfPUzhIp4k;)KXS7nMRVCS!lzWTw{r!1<eq+f0nHb-G zn>~`ReCM8%g4VMkAJ`e>9(%?{?In`z#1^{iIH5EqW&403g0>b6az<7J5Jy*l+X&O^ zluLEV{r97or?sgFLYJWg;QaN34WEo2&en5*)%^{+2pTfG|2sBJ2Gi@AWxi7s%a)ni z7Uu!h6xorK(u2zFB2V`o!Xttda2!q-cRC($Mtro)Cy7SL&(Ncn|E!u&vRV8jqmKaE zd)AyhH|Pah*)%+PB7<5A1c#pWjo<SPL=`ukiAr>Sn6&?jvm*i2p15$IA9cu}46Z-# z>sRJj>h>wXn)xAV&gT|$GUZ+O_wSUG;%hP|Gu-L-@ud9V^DH;~7N7njK)6cl_7W(U z-hZs!zmwZ%>c`mJNv;bGgKFM1_!iLE-ROZxK=dyvcwc3e#hpCtmWb-Atckl(HI@0= z|M5y{`s~IYKQe)(y2AQ{v#5>kP3NR1ov~;a97M8khg5BL{;WlMuz2%_B8uqLtBgVK zdK#g6ZC|lE8pq=kG0~h|UVtNdF)gzqIa$<=pR+GN%#ShTH<n>MOXO#oqsZU??-~2S zy5-Zlg|%0#zF$m#**fOaI_6Lh8JS(#+VS^gd@;Y?{>R#WVLUzhaXuQGANzIF3-viZ z{h<J!Jq_Of*PQ8oc$Vsf8RRorlkEb!<_fy5o7XEW&f|As*s_fvsCXHf%vEp2&QUR4 z>4zj$MeBhyZOIC31ez56I}=B+)Cojdu;`(yQiWtRudEPs9koUOO$FUw#a7WgNk{7j za;wfjwCx5x@N|uY2yd0l$h8zCu6k-nHT>9$*0Gha!|I!mC4mT|!A{G9MhnA03qwm1 zS~z?`sNp6B?eol{u-RhJ7HG9Bw7Db{x-b+#RSNpp&|+|nSsKd0n+lbR6e+k0U>B+o z2DUOOEBLno<~h6)G8^O6gbC*tV`<}L6ooe%#IsSdMcxR7L(`C-nh!DnnTtK0uW)^~ zsC`RWqi-&Pzo%GACtKUOctH;$dFXaLe^j+>lA=Or_7Y`7slvKmPqNbQ>-Q1<@9Jv4 zwPNWn27Dbtdf@Le^eH=TzV3poJcMvjS@U;Kk3&qJr3_3-J0S|K$ndrHS_0USr9_pp zYmYA;K(>TUq9%6b&1sr!ZJS4Nu6L14(A#9P-tS$|)>fR2e@UWRvc)0;yRvF}2(PSX zWehNrS$7C6IIJLt`;CtO(*gvpLoH!F>qtAI*Y0#9yY|->=VsLnxN{79gKKt6QlvTP z30-EQpG<Y=Le{qplr7DSN;%8X(!w~hjJg9K@7IKx1S>nL%|j=1a%RigAW3Ct0aSM? z!YP++h}ij1SDoa><YNW0zIzI!LDFegFj!gJbs~^fqE5@eO8dw$HsE{J)T`AZdYMaO z)njq>pFi1ezx$tc+n4^ue0;ZgyVLVDLN6JqV5b@RFHg*!qZ|h{WiDef7?A_pmyuj^ zCx#VJZlIs7|8791gsoxzzbON$i6GfTIw?L`?1b47M|DL<0B5CAVWeLodIh3QrT2ZC znEVC>F#Ou6>>duS>G~`4YD;ali7u6R+MZ@un)rLMb(snQrEMxFaG5BP{xF+LIxX2g z7oqSd_3~sN)$K5O+Z})*VDex=g2bF@lc?@Hqu6753B+$frkrO%5+<-|D9k%9$>#6F zuFrG=BfcE9pVv`2qT=)oOE8dLvVofMH{cFpc0i4-RzuOf8T$ZLO(fBBYdXTCB#NxQ zJk=DOG^hcsaaA4U0i@LeQA3UaE%bosGi=}w=_@&8?K2j}0Xbxx$Yq=wip~x5qBfq< z8rc0ccd`6QF(0xXZ-}*XW=rnpb&Lod^`2(L|98e=*qeNSesQ)?<q@8rkH_{atRJKu zVM;UQO9G+4EOp`(miFST<$SrV9}pE;ROh^~M$(^{k|T<oYGouxjF!NPmr#%nN0_8z zi)2p89gdE$4UyoAm(bmb%}Tl>k;Puy?eP2W6Sx}@QOq7}PRqc*^q-hawwXpNm<+r- z@d3%Hmb<%qaayvDa)#6W;cl$GU2pd;d%IxE*Q+l$fANFGPYestbE+rW1EW<|CajQM zrg<Y`g)juf<^V$72yf)`2Ag^jtPAOx9Q=?J`y~!Zl?i@8xHBA3t`BO!3m*V8@iP2D zM>BVqzI1?Qy#DA9l|hrPt`9Fx9SUv7Fe-EU3l2=AP5pqis}7qtFMza4KU&}+fOht4 zI}=ZR+{{x|0B?Pl-9I^+=>a8h-zHq>120$c_3N|_Jx=vxxFfIARZJd#$4y4!AFDhN zMYmM`xABoL43jr~)j4!$A9m+$L7^tkd+T~%3+HXrc<iyAIqwNnmcqXpL{arFkA{|^ z;8NjL>s!DbP!HQsH#vCsKo$l4e`(;8az>b%!=2D|?%gKDmGNuR_ur4Btu`mbPlyN2 z$93D{1&o*;^7w#yB~<VFf#Cv8+}&PCUKr{jqizg!IjxxL4E4Z?Hn=vZQTti|VV<}V zeoKf3?#Y)z)3|`(8=H963FbI#o`%v#!`7JzNg`Ce4v{^fr@gfTGs4;qKc5zOd?lV1 zd>&?V{c&paCub>4u=)Xdjh5W%5$cbsdb+<4-xb<j)9VILOq(SnaQ-eIjCxK@b)kH_ z&Kf3(Z!hL}@6iaEc6fdF6t#wQjW6nRdWji#+nPrwQ@20hu0agBz`@*t267<kW)Lq9 zL=tO%fzmk{Y8z2<A@#*lmmj7?tPl8^`U9z|->^sM2IC%IpP)%y_sJ&eunM6hk=eG| zR{_wlC~s84PV450LpFZx#gMu{JT90>>AEg2u+I)F3MB_|SWXITm*NiGURFCVs@;QA zacL-Fz%@3t$Hiwq4B1nL(yEM^RZ!8@U1XOhL9CLiB&L!uZCiRkg5|}F9}fw0@YjR6 z_`Y04JSN2GZXb*Naa`cffvDntT%YF%xRBQH?BUNW4?BY5%uw$Owm&UX*q<)2H5|Ef zTDQ((>&k~-Ooo?eH-5}Dc>rZZ&<pSfQAr{b?CXx<27j$x#aX|TrWa_*rK%vbB+_q> zl$qnk(o^Mebderawip&F-S)F7B;u~dtja#&Y=qL~N=(HB(X2L<n_xYAMD28(l1Vsm z;jY(G7_-1#u8_7NGwtEp=nig9+LCH;WA4{hHFN1UR?;&IsLsO@+f{!(-P=F&Utha_ z-`|-n4O4FR?#bEQ&wp<hfBfzaNZCqRK9zDuInnxaM>1@N!+l3}AO_G9V1RsM`T(!M z-cyX>mLIZMB{&1hb98i9=als~D_IVqYTs|}8TJCJR)=!zmbM>Uhq5is<;h-j(*!;g zFFq3%K&)2>ehO5P>=^h3ZW{Oj>?)BGv?Y81_7zBpSaiMscy&mP$@KYID82w@ynd+( zi87uRhvbWb-QsahI|GTtRE%M~^8ma>q7afWZlppIahFL5)>E!&?=4jKZV(cRp{D=c z*c}C0AmQVMdj=P|*jl)D*T@N0X9g`bvvnU6Cq(F3aW)x6n);oPAZ*UDgdO3qlN;C* zVtD)@uY{BnOy74Z!lGeD`b<QerHm|jaq#v}RF`#QQ!?X`{;fVQA@nw?w_AQ2&$bai z4~hR4*UTHkp|p!x_@9rUk)E7pWbNR}S_*W*_P?^G$atCCs<#LvxBELWre<%hylQJz zQKRY#{X4Ub6?G3yAX75zm!T@%FT&dY1!`JTjH`>Q*6V#sg=sZw#<Zkvb~)(Tz6y62 zG-UjiL7h|RfI~nm{hsI2<|I+am|6*VV@FHqD*iO98#&t=FD~i|VohyaEL~b`hel4g zd!vgzL>uUDDxT*2OVVBOd9k%=L^W;ou7k|2HSGskhJP(*o6vX^TbhqEF7+0cR39l} zca+c~KRd#Yb1><C>dt_jy9VFhNPq1e);g-Q!`OZsF<;BN<k!*EQG6EEkTFGcI<fAs zrd$2f6{g?J_Y5orxPmwijiT`N#ofZ%29N;JBo%`D<O4M!-d6V*DpW3O5uP7wtu`{i z6xv$y6ewvB$U<rafb{WFmmd6<;nUC~Z>wD`LIr~s@(4rtMbel<1b!L1&@9E&pCCw3 zH9M_I8s*5r7ma75IU+QK?8b0<0~U?vqFG;5!SL~i>~~}yZectPI&%FvO2V6-vcxk< zl9s|`h(cuHV)HDzO>4%+bPyjAS0-DG98fz&f?O%*CSRa~mQ#y)+1bp_hHIGzd**oy zVr(eYTyLsb+7QfmG9~@B#~wczPbOa{S6+TQ>U<uL0JWz8GfOWM{6ZtApl5)cz~^9v zl(w=j49@`#+%WAnEpYxXyC7TdN01^2&bNNAympwuJaT<Hxt<rb?>e$QMd=E-l{n1X zpfSgT_`{8#6FX&Bu+8Qe=KDRe$sIm$69Ah)!cR}_#H$IU*d$U3?n8GI$SPGTfGi*- zU`)Yru^}Yn5=fitT}?3cOrzdC211xqnD^asThVqhdj_a|L&>V8u4k}mO3$ECtEbU@ z*tjLZ$(2xR?pB&@-b)2cJcwb(R>LSn@W${o#Z!H<)j`XrEMBm6T7APiNJG>rnIA|_ zmof4=HT6@;C}|8?vIZt=>j>--MX1_^6;@j^46=T!1kO|&q-ECjjxDuudFqCsjzDh1 zaw`(|E{NeejA%_vuAb3)OlW;jZm2x~o9<R6!Zf`acs-h%9kZc@=}in0cLd`;B=;^8 z^o<L8lUv(B+PLSSU`qr#<zxfbOcRMm|G+3Cc>iL}{D-UnKMG~hw9ndiwr5tn#SqZ6 zVE&kMKY_t-e2&W!cTpj_NHX0<TQo!%GL(xdOZ|yj5Ofh_#<{aUmJTRO>I=>y?U1LH zXp>V^c*z&~V6D6ua!h=E-P6hTv1rn}V%UT~st$d{0cDfjPxs9$*Jk~X+duRD#y)yH zbaK%px}R%texW0pobN}bKQ3vs-?wgEJV!kGq{{t6NEab3?}=`L2Xj!x0(dX%5@`Aw zeh6eIC!~EZK^0FKz^Z%@Jq({$^Ug4hnIB@&;xf(Oon?a07gY!EGjGG&&8nt5tgh;{ zKAx9<8^No-s;#cYuc!4SEPGhm{sg{XmF}>9p4K$iyY=7J{8@xqpm)IyJt<s&h?P67 z{(r~gBpI!c@6=z{?1njn7<)S&mW}Ln3qvUU_<J9hjyPkIzuWdxAU}6+Q}yV8ThFbC zUunjcZH82J#TRvDvH<%i@+9&^<INs9T#Abhqg6lV{G$4_<<(?fIDQpn*;&>EKw4q7 z8ptn{dD`FGE;!HKaea!kqi!&|tG2T&I?pvnn4A(85z60H6?LTt_E~qr%QsiStmv>y zR>3+TfLR*fdB8ykMFEWr6~2XkdU&xkHTb)K?`$)9O0>x~GygHdPrVUFKb^2ca?OCX zh3q{P`1j*@{=XUUpQO*pNdM5Vx&P2O#be}DRvS2xFE)R}`)EZ^2_G>!b~64|H?D6X zYyU#F{z-P94<#G5q^fjEBU>H&i+wtO<v#kd6Idd#fBgLunxR?%M^m);EM3?Mw9XnZ z_Zx5K6xGd<ci}>B#Btcf=yW7XUi_e|D(`=NHLt;PzVx~zCp=}hx=(BJOQ*+|`W*3p zy*HSx!&#&kBjpnj<F5QQfEn1SI|Tj~QW_>vEc-{9{e)D$`;ZOnoq3%ol3-fM>dItv zWt{qvB05i`bePkrn`PWp<&Qlqk*9>f1-0_oS>2wDrDlRH=3_6Q#jiXWuR0S=rOuHk zdVTPbJ+;Guli}cJNXFGDcf6|&JHErLt6d%EP|CW?Grq$uS64$&M=n8{<iGGF@|*R4 zS)^AL0pt1wKzl3w*;nq$UwcHS-X@s(T+<k-_ll7IH&Pu+Wd9_Bu@@$Ks?&Xqb+b$U zZ56ESy3syYM8rpVNLM|IYH61+jnxszcS|UbDHKxp>YC%k%Ou53x%c=^wNokfIW7YJ ztf*&)QB7rYFX^(Fw3K~CS#!H4oA9h2SN<l+u~N2Zo@!VhH{!*=c+|AtX#8FIYMm-v z`|{`~0Dq$97uWCjs_e_x_k4LI<`PUZ4Cy5;1s2J#?1MYAq;6YX;hUXn@|fR5vq%0h z{`UgRh0B%e9Vh%9tAD-;ch#sp6KIC<EvgzDS$~4qX29{4=y?vn;45u{4q3Iq>CA?g zXqCcCDhu$DjLiZR!&?^fk>EPyiQz9@2xF}-iC3oOsZOh^D=LVaFM0HgANSghf63Nz zd8a<{dZms%@#fvxa_{%6Wg*r$b&0<%UFc!$N*8-q#(P)N(4~8)2e<;oX|F(bVD-oe zIMlyfXl;d9O9JPVhP%^JMp$lz83&=Ls5idqYPZ+KR#eQS`_Dr57sqvla#huc8Ej4! zDbgr>2p<0wJo#;uaRnuo`gGEqQm-$KV*!2kzD8I>q}>LT+B$HB`ooS=4)upocFDV9 z{^D{U#&CVAbtjD9-&JJu6Yc7p@!PpDmh0DX0@zf4g&B1T*lO;N&w_???diIh%8mxB zmIl}H<lR4n*dIgo`)?pL6#wInx?PL)+JkJr@f~i{apyTYM#PWzxFi1ci~)`}zjDl} zWOVr!C_L`-s|*AhKh0%Pd*VA^{Z>j-Oe58RtD!Npv28T<qXc%yU_;<m+x1;{2>2;N z8Qxu|*{$^bGPo_uu*V<0rwHrkSZ(vOh5Iqw6@@yM#Fzi{Si;|vXI+sDPp6I{_vN`f zmh|^<UsWLQO`o<h0Vn3h*c`mD{F36aRnsgY?A>ihE}vbQf?-$=GYQx%+SU~p-@dSz zF1^nHV3XPxr}u3a#O%+Wu`aT*`3?NT$_9=x|C;9CehbdAZ6J^JwRkUU?v7V?<=H!a zz>9a!KmPGdIOa9;iDeBnK98qgs%&|f!*{z>V*<bWHeC9qHFgimi{#rx8>l>qlPjfl zrn0>p6$!hvdZDiQaR0fj=Hk*8wk+4}k*ZPmpGEyFcIpb9s-#ntV??&wgN^E6+R{HQ zT&uk}VQh+^PZISxg?if<AvTwa?}!XnzS>&y7AVwxb+G4!cHeZC`G#CEl~+ws+}xux z_2$<0!1$6#x?+<_X#(R<pfK(Iv_>l}Zo~D@++sWC4+EORT3wseEN+vO#m}5hpVSfK z^<7!U@67v`=GDcUkXQF#q1!$@R+~`p)1WGf&H8e?w9@`q#|m0*xFQYVQH1hfu&oGw zy|OHr)U@}_3caK#9pA4*`!l&{>T|8{o!-oGTyfD#X!Fy<W)hw9l$h@m_-R-nr z5cEQQW&wyV#5n)$S(%<Z-?ExOH=#nw`i~ctd&E^|t)<+EzOyicAXa-}?{lJG=<{+e z@bt#|Oy8J<wT~I0_X8QOp6PpGpUh-zIr4PvcSv6jL?G9@{b^x5>v&FZ*%ZF$;98VT z99jW^F`cc{mDqx`uSEw3HJh4?4#^qj8*znf2WjWz$q7rmGi8f&0NVtK)^7i65&+{f zdO@D9_k!zr8A%pBrp)ddG>fa^I)z#Q*|^P_fZ<?GBD{Dy-Z8MBwqvO>u-`Cs+J+;+ zlnqq2o#J<vr8Ru;@58idL?869o*2)t3&bBfd`Si3Hx9*r(Dc$;&%Z_`jRnEQ+<IX^ zO&V*1>p~1bv|%g-;w&t}LHDSB_@O=hy_?}1)LP~NeIf<*eq2c3jSqB)G_z<Q_KW@j zNRxpGCMcq#i)92mwH#R_op;%E;gsT`=u-AaI?cpl)}*h-Cw))?zjlU0^5K^$w;u!% zI+~oOqM%@lK!Gs<##|3tY&dB6{YKK+k+7QfDnLSg8>qgmkVZYAlmk$5L+;wPKDRHf zRe75eu4mNvaNHNM`Gv%o>&_JI$<(%}!=~tdVhM7uO>QVi;1X=mVOs-r0=X-GF)i?) z@yJZ-@3y*av)h_<LxVw2>2gtvChM1O$Zo|<d+XZ5RYzDZfElCH9G#IZ$2;9sgN{L5 zZDmB~?PZ;+6KAR^zEcK=a3#Lon{+2f5v9x9^_bPR{zRX(_EM<AeAD{i6)R!&{99qC z-C=d)zq;DG>;WR3y6m>4F3TC<aUO6qHxUZpdwMZY__tbbv<Uysv@WsV(>8c5Y!DO9 zS~@Up8XfKD*7l~x*IF6|i^p1<AWeigxB8}3O{c{1pgcL4<k^R=OJ^F!B{MUeY~zI4 zO-WpUys|p3(<tps*Paa?iRJ_vwwBV_aw~-3s4KLX-Y%>igyhiS^f2xqFK=kJ_yQ{K zAkG?@%x!ooVW`x@0L<WCB>e`1EYAHCtGqKfC?Fgu;HFFtB(siLlc>j^%cjnO*^y_% z=MbqnhQVFbHLEDP;rQuoSuz9mPF)ihaEj0~*}D3gT-HpdTY+G1)YzoUYwDVO$aN%{ zHn)WXFkBy3+=7q~zFSgRmIO^vP{Ltrrj4xVA<tG;bPV>7UlXsdPeIe^0w-7Cx^g<) zyetZ(oG(DIl&Ut0$>ylAln#`tvxYo{$sPw#m7xpy=njLewlD4HA)&DvD4Gz)95gf< zvZ0ZpkBvNy36PFzX;>zz43{#4D=^ew=W~P2Oc^{PXOLZ9i8_tB98r~0kF0@Y1I+4t zkf?KAa30-3u9qR@sszp8+VgWd52%By(DHzAl?R+K@(U+;>+lK+aM=Q>f?=MT&nq}C z^`jL4icVYBbYqqWlv26-pd;wD;7=Bq2L06r37<hj?*6WY!7CIDClBaxZ+vL!G)rCV zOlgjE^zFlXe{qS8j;Drom^k8^TE^;KL499o>?B%UqGogMSEfxM48}FJ_?DMMZ2KS^ zFJJ^rAhdl&lMDjX0oKgIE<TF9QA3CUg#w}1A%&_L*u&UDjNdC?AOeaBva8SnnX7Y% zI<gnapp&62&b_Kr+-au}RWUPh{TSVivet};$2|;ki*q+24FCiBkW%lA+@b~SL+?9f za-Z;HDLNZzZ5e%8e;;l`Y6Tx|BWqyK2IdR5zUz=%2eI-MoC+iE4ZYtTP;D`!5vz@< z%x30$xw<_vut5(7PwPs7vl*2}wT)R_Mm!k+?S=!xxQ77lF6yzMnM*y4>5pc%f?`1| z_vCKRt4f^_A_w)Uiy%>{gv&0OH?wnehG2vk+%7FKeBo-dL2GSb6NW$@xG^qfXI)7v zyV;#q$G+$yCxkmQOKT|Z$jmo8w>g(=9XjqG0hxxng67A+t%3|TcI>w5Mfk?td|u9e zdFH>i_cF!7K?--Bo^s}>&(tGHPsHd_73fT=X(8^!0^o&?w^}9>&10j4Bf9Oq+zK?i zdE4q9%~Ieg!#}^XKkvix%_nYusi~E_ru4<wd=Shc7^C-xRa9@h%SJ@g7{vPhzk2>z zvJRJAINp~f_~+?d$RBKEAy;>@@xt^nPIB6=+=Indru@^-b5J&yt$p`0c03`Nbtv61 zji?jV7Qi}<S!rGJ3!TOIzt7`~`SlLFrgzf%$(K93<4pa(rizrG-%IwRa_i9;f4!ae z&4T!~>Hz<qm~fxAMxWOw{$#^^TeZVH!h!smCc=Ds)qMZnqvXUDv)k13j$aoii7R<> z`XGiUWPi4c>Xy&yxt^LEMaCKEsoP|C@GKUqfk6ArLSprnlZRp!xh_G@O6M^0=V$f4 zO6K(~OMld5Hwlec$AlW9H|->CI@Dpys9LAB>rVVuPo-4+v4>k|c=dxj9FAJ28#Hcz z%vEbdeRZjNTxgZ}ii(q85Gc-Hh$`_F48&lkg@n^IR~XFF^|*_wCDJUmxI#i0$J<uh zq<ONEcdcfSwZULDefIS(nm#v?b}JTit<~w!HG_BPB}V*~&#pNC()TSyS1!97fORVN z0PErV{j{s=*H87RdR#^H&M`cO*vE!!w3`O#9vyfspWTu{*GRsKSrEZ}wkcwRVT}L^ zY0KQ!b*I~(?fxBHKG1K)B*}%cAggzY51=;e6_nT(hXqHc-YDu#!Cf2{#kQ3vlE`Fq z<>&V&7)o4q!*9z!AWcEbh~L(H)O?Wpk4f8vAC&jVbQ$}gO7y%BOB_0i8T%fPSfNj) zPcA4>xcTUjx2FGxF<;Uv2HZjfl2;ZdDrI~B7U}Hg1}_gstA~pxqeoj%z3Mv7VlzQm z99cjuj8yh|kusm>W3q|R{Sn}G@vj?S&)5gK_7tdSny+MaeIK7*()+{N@THW=zu;as z5`Fd;7P;b&w?855Z=`un`r1Xicwr1DudfVEw%f|~v{6!Tb%be4Ty&%+6cbv{EMlUs z0<%1B6;!Fsb!`-Q<>}{rqv-7S2<uRFz96|IxR`Z?h_odBcuN{hO7Hy)!_U$&x2msu zFrztA*-3=*Rm8|)xqdtC^^jXK0i>9^;A%g@#IeUws4uQ%8A(U9+nsu3gCW?PInoQv z`x_jo)aFlLe?<YsSgzdk5tk(D-oS!)v12IOfW?vougMpC9{KmwAVM*AVC80I6-CJX z2Rle*ga475adHosX>jMteQ%HIUcQq4WvxIg+Z?U}Wj`00U4`plZDqJ|G^&uFw3v#P zEVz-^M=BVz{9KD9J@pE$Qe8Uf`6w61Qke*#@41Q^=F;SIecXkzXOB6PK-0-5qQKD4 zJA4gK4?`LxpKNgmm!BzWyFz>|J0)4$ERGkoh5VtuFHl%}xn}CoZf#jY2OoPRzI`Mb zDJK1l<cB}-u2C=ydL(sPF^P1fzb+E->d!zD8&qDofPJbW`A9Y8PjVhJe*K5ZqRGk= zXSupP+~Zat?zYIUp5_4iOw_P6wO--I^%aH|{*Aux=V%~9>)uax47jPB7{-=!VE)I; zY=EnhF**Wc%?t*Q6R>a_P7Y79hZqo9>}{gL%CKc4AXV#g>^@UTX1xH~_UAARmQ|c^ z9FG7_eR6gJw;Yf@XD~_m9cF=Gq3T86w1%o5lz>73n%y_30Hje0p$2-m)CdP=(D0}M zX%;1@0G_JuLIIeWX}kb;0w3BEQgZku+u*|qsOWFggb@UJr>USRBxx#X2<lsr!S!Sp z2+UCfNLz(yfrbImTu6*fRCo<TKGv>cZNE%KZ=FT62$Z2!BF*!&hQJ=Cg|d{ai=Ylw zd2)u|saC<?R9|Nh0zN6dN#tB6C*RG_ZIC?F#Kvd98l)c+&TPj<MEN<NdNG$g!hMt_ zzwz&qGj_CBu4z%hDUx`wU)`sg;jNg%AKl$x<l8=t*Z0(q^+tF@g<V$oM<W(i4N+T7 zeH7M}SxNS<LTN|Tm2+_PWs^0hhVo3e&zo&dN?N>3qA!h5z66X#tu|c}*ZA#1^P7;m z+p-~PjIuUP^$bm~8Z3!ur}q-%o8qBVlVpwRlzS&{P6U@F%n;->Nhxc(=%}MXx0dUJ z-Xha?&ff|P4!>q96jp0jnUVCyZBi{fZY3KcJZz=la~s+El}&oslq(#Q5*2EduM1q) z1Ta|VZ&!FWCkG}^@gG{0QN9(gTbTEu$*HZ|PIwqvwI89ihih?*<`jRnY!b_~u_@Nw ztcNiX{p>WQ)oC|P!r!g$?8BT&4S%_sjuiZDZNMYt&l*elQV>*$7=ky2s3d}aWvCp2 zwqn^IP%mQ>tLs#<b0A6+jFwOU*hW3hfh&ycV~o~Ye@3HRqbo?|K@60k9i~L4-oh$U zb;g#lIyKa?6LiD`>8g=C0aOl7vH2-FMLJPJ3~07XLc=)ngQWEh<Uq5BY_2=l)H1Xe zGgS(3poN&zFm-@y#PdK?bWh8O)T<9LPFTLHQy|fE(|{Vn4<pfC5u~U8>xRJ+3t&<o z20<)z?h~_R<1i1NJ36s#aY#6|TOm_OO7a=j(GQ!sO6ph4-XIST<_X9gUrcB6$=oS| znWO(^f?ST|9YoTF@V8RKWTe>T+$?3&Kbra%p-KEu+O=G50Z5{HK7vlBmUEK6wc$E- z1IA1B)!jCwdqXb;Z{)?XYYQJB*$BBEjN5BoWbnvlrK*&`z{jWvqWHaqf;Cyr1=ycG z6q4+>fC>4E%8Nr1a>*q`(}5W}Y%n-SacV#~Q-NSKm`pHiU<kO<I;9nXq#2^&kR1;f z3<^*Lh1TN@R;uBEon99r3O-s9%Nd{wm{jADa`bYFrVy2F!-`T!;H8u;2XH<y<pR`G z+*I5lsaK6G<&g`A53Luhgou_y%?dUOR50GMR)me#%SKBbAL|DXGxnQ7fbF1mAwJsg zv>H+R-K0W<EUqBAl^OYi()GN>@KEbgJy4f6z;1mUI<WlAnGF_HIMBSTJ*ark^efAE zrXUTKnsfwr4fn#479EQi-eNLTJ=_<U5?DZ^{zUdGvRTMd6V1B%UuzGz>m-$=nD`3n zi@*ODw!s1Cr-u_D0MI7T#=nsh{&@s1Pm|AZ$zQ`q#(Ofsln+QIVe(0$6p*d?UYkUZ z%s(!#NHX28$?JH(pj?$5m1;k4<IYl2)Wjcl@V>HS8#viuJl#p$bnAT_|F7-8*lc6R zYSipuK-EXrZJZE7q&dT`T#oRXBzqHF_-5{BCwB=Y#;-fL8Lo+c0nKomtPjL@8teZ! zo{BVmvbn>m`G$xzPnn{ESLoegSqfK|QhE3niS`&BChJYeb3XCBzRf{&KXd!4{pj&z zl?NR1Htmsj_nXP($v^#m2lv+R!}rONmcD*tH1x0PTD(@fbHjf{1KuiI>p#7zFPr{) z?~7>OXSCD&>HX)@!LpRCkxSP^d3F>hC_^6|BwL-}7$#Q-w^=?eLM?dTV1*UGc}+=o z-~AExK%(-G9LC5bqAK+rkGU3nw1AU?7KT^27lqv%9~-^`U6tyiP3p%eL(>|Pl&g~C z9MBjy3M!<Vs=xA;VDqKGaph5wVe*w*0`J+In%h~&T{_AB^hET2B7|nmv#T_v{6t() zX(UKVzi*hU>SRFAK6I3dT-gfCI5@LI5X$yq5t_Ir1lb22aY`}gSm*NfW^)`1a>XEm zqI$U<CFeL>tbv~%pSCWc(ECmpUTKT#9S@KUEwb^zw-K|7h+`O`msA`a!$pv4i^T#F z*-5;+2ewi*v|(#-$;Y+S2Trk(kgp1*e8X;N5AN%B>taj!6x)?~>2VYklmW$2@+<+a zYAU|~D>4Istw<Vrt^(by4Yo;p$!Y{}!EfMp!Eox{{8<G|x9~{)!>hcqJ;Ud(0)n&v zIB>PRHmtAW0I7c3J>Bma0bD!S1!}-5W?CgFsiIVBT^=*owQJ*2MWWUw;JH0_cw$!p zQY~9KOK?AhIcBO4!2?jpUOdu$8VPihSCYGSC`yVtOp%rTiI!6fK_z*!NhE9R)x+`n zz&)jn05$|o@-E0-2CimhbxP<Gp;Xf~nalb*m4Fe2wg_vJL0w|GLCMItDJW2u470}@ z>3mKEwE)W(Ccv$;LT%+SpZnpq$U#v)jWyF=vysqNx@XJz8E8b9-d2IRnQF#GQ_nP< zURM-lPOE_iRfCMZ-otO=>G|KMNmHjXxc9(X=k~6u|Cbk2j`H<<AAcya6Kr4qTyRw} zYwu53VKwgmW2z+o?%q;gP|96@Kq20*we)x!yJ{#q#I{f(p*kQ5NgP4IZ^LX8Y4;m2 z+X!JB@^H>4lD!NqDSce*#BNhs&;d0snu2Lj?KZTI@4;r9Q~!X<HcT#FtPFLjH`}1O zc5OA=IQ3Fx#Pl{?rxhxqa&elhz$%D#z&jw)aSaxvtAcikm`DYHKYs~mPN;im{AZi% z{5^08?qtM<L0U{DJ^rGNJU}3B@IN$_8x*r`cu|SuraS5&NGQ>5*saz;&6)%3GCs<= z!zICb6w`ih8)-f2;h-)x^=rYkL(^_T`j=z&-{=0LdT;L>bUAcSHM#x0s5LTumh9XS z1I`aEtUt8!c}fTFWA=^}9Qp`oKT!DeBV4z%54I+%d*dZfK)+}atxa)%D3V!^Pt2)( zA-LJa^f-ZDrw(!AX;Iq`t=XZy;V#!8*;|%9{&I<iPvvjg6m6mQKkG{=0K05NG(d*x zU8nEx7goiz4^!QqwZ6qPg9nUn8HN?=^sS|r;4!@d-Lf{ePbL#1l+*}=aX~r(_Kc^L zYhPaiysdUJWON4eC#twsAkGTo*ro_Wb$Alat&)TjqgoNDNlx7)q2;xfWWo>a&Z0eA z^7`vX4h1~*)c;s4yPvlXUpWF=ZBv!1PB>lNyt|{fS!~s1)LcS|?SA2Q*&Bgg$A6{8 z8JJzT_pkZVEfTCp&=L>q+Hux&VV(>kV3M4>i;LrIsbD?23XgOBxu!#+$HfRvGPvx8 z;%0-f9e2H!cU+0aAk{!?1QuoeD4&?_aK4NM?a|q;_1j)Kl5PWiqS_kT#g&0e`)a=1 z*ac(&yHG7|!1mPn>EieZ@4QMj3m<W5r^0?L-NWwl9k{_=cbe(Dca@MgPyuuL-|&t) z%`Va3yOWnk!l-52KL_0k{tYLn{w!IlvcXB2E)#Hmk2^S_2r+Gdb<p-3itO8D=q;`V z!LmcRuJ0nZkUHo$&jV#i<K7b$p+r_Sr=5m?b*Y2GTpEb`E^Pq&0Bnv7YEzEJuhY)D zk~@)lKhKr**yB5uu%OJcnmSt>ua^SaMICq8TDHr?(e7cDuG=`-w=EoZ@DGcWZe!eD zHdL=(i#cwW`+p2<z1(ANQ76TzcW@@nwT0VchIn3+JO|suINi2(7TygsOeR%pFib6) z1!&Zb6E4*a6E5g81SEW4rLm>|sN0IayqV;$ykLoCipz9EE<o(qCFP|IF$TY4v$t0m zV37+AkqNN`Vug)RE=v_x0>PRhwhN^9BchOm6Fwo+DTHqYwg!?;CKA_T9m40p?ELHr z;?TPz*;hzPbOEJ%4&!K)k*asvG#E&_j)#h?JgjZ&`i5NBSF)iuTeGh@!e+=kOk#n! zeBxmg<^rJYyMx(R$EJvM(DjA`EBn!+gtm%1?Ap`R?|*vA<}4EAs5GuGh7{IR_<^BD zyYCCw1g&WkgoN%l_^ukt*HbHjFNwoipIjR+Szi``U2%uAOwxCoCi{%*y7TPxK((-~ zl+L>DQ&^jHt~CKO8g88Q*j19s^JV;GdN?VWvlCq4v5Mz;-K>_U?7EE&E}61|cIm5x zf{Lml`K!5xk?gHQ<+P7dg5!?0bByAIldq}lu*qu2yb4;dT+{s|=>8(2o#@o!#ED0R zbL5L})wX{I^0&y=+s<Pd{%gi5Ra`L5`t%@AI|sXREp*STmh)Q<FZ1WTB%XH+{5VNy z8K!&)^U_j@Z2*p8Hw44Nuos9<jwMOLp<Oc8aqg~R7uZjr8F{?U5i5w}@EWIpc-_|Q zMwY%!*_eA4Rt41rr+5F?o>qFG)O6g#0`uV=@7wHj+8CnTFLAVe1UoZSaJW_p<64cR zuT&pOR9RFPr52Ur4z1%$sLa{-zZiSRAkliDU39EH)*jooZQHhO+qP|Mk8RtwZR5;) zs&1X{+`2#RkF~0Tm2@hptnSW}r~8vB9Lbf$X@ql==f{p>gwKPaV6n!=jc`r`vOn^9 zjjI;#KfH?h&Im0^J;W2~csb$j%1IvAW4Y4<!MYV1<C0Mu@j>Evx+E=LTu;n<)7Of_ zVm$+`>C*z<tkbxKYrmg4EKe?3NWAowqk0)+qyPk7M8$yg@JZKz&r<8a-;+B}en#6M z$+pTcS?R?J0l*>u3=kn=coa|P3^IEhO7m(Zg7_V<4K5FR8ZmpJrGdf_QLCtB7Qcgx zKc6+TVWbQVhVt2D1^zkOvsuPYnzlp)5reRL+tW=1z?=Mu&xbYo<dQb@gbzKD_T*n1 z5A-R)5?<aY^7-lvL2o;AvQTRvjkJZgE1Ld0Ut~G!R7p$fUD@VV%mvV*UU!N;Dr4{M z5t=|T);_!RaPxKZc=JPn?%59UPY(wy_~CAGB4PKs<LCWCK*5ud<~w1vI2iVNjxVO> zJVo@c7vOUa6%`AP_S$(<fnc<W&yj&dXQ#J^l=>>nrN!wa(oEg-<0WH?_P+JmMsz*w zF$FfdrEGw+ah3ELLTAO)&El_BrHJ-UK)4p4xh}}ja!@&iDr{!~e6-Z#T+pcbV6SW` zj%HNPg>sqV)%4fZW<qsD0qe6o`U?I4?_pIcKpIdUi9-skq+mHOFiPBR49rSoga}KN zzbqPsrT9XMLe7z+!CCFt0j7=z<{aQvB_*KH>@Ee!gC4+>+%2?`0d>2sCRl#0Q3h0h zsm)&7nx)kpJA0`9TZ3&hYG)lpg0T719Qw)te3|6A9&`+tEyQl*ABg3d2%6kq5oqfR zl}uXk;qx$c#`>;^Ka^19LZGvo(cw^}4$7FEc}n^x8ua+UcJvtz!f54q7ZohQCOY!l z6BFG9Vz+$3yLg<b)JAWm-sMVTo<?_Jgcj(-`LL|quFm^m{|?#NAUI9!?RH&fFkm5F zf^q_b>e5l+AZ-N7As|&6@V;=g;!@uRO`s|)pub%dzBo?QX8Q><(Y(MIUc)GLTY6o( z2k&Bjyc9`{u-)+MtBhH2_IuN^mH#v)c^enQLgBSjZyC;x6Kj&PClMV>529=e5{%)i zgTs7M^4`@KYoH~YCO+W3%Nf9oZ=TwzCkIk;+mj?!q!rl$u%SpS2i+^*;;j9=*v99} z>J(pJG=K!S#Y=e$L}v%ailcS<CKSS@i&8(g@F!4r!s{}@gRODvJx`EL*$olfBXmV@ zyEss#3xvveSFMC!9gU~#V&qDW@bCH-P}K7w)UdJH98B_d-xXNqcW<Tn=>lPV6Wk7{ zztccAKyxDb+z<GzOMHlDA?yrx*Vh*OOzndLz0oEE2Kz$9&QTf~)&AbJ-MbWqe^+|_ z!Av(j)wXwdgZ!~;OY;zK{vnTl))@A1k10)xvJFhf&CNrJxP2Zh6*<>thmOY<@8p6g zec1gsn*Au$sESh{A|ITJ+;*N3k;@nSm!j;J0Ng22Ih3O8ysiqq&xYdY4CJq9Vb5-= z!*8AIaWEA9-u0^GaXp9_&kU-Tyok-)CAvI{5m?sfBR|-lB|haCjTQ<~?>6Wv0t7IZ zjHVo8za-9fY#QhZz%99YL!W(q?Su~Jn_yrl3)U=Pim9iWmq_4aVatmT=<>)xQ}}Lq zu<I8oWd!vIvPHw~A(S~Hpt6uoEzL;~r9tSZ1X8gMhePNYG?hyw2(r=IAPxvs(!58R z05CvnyLjs2%~|P(qp>#Ybr^44V}4FD!@1<?_uh<l!(IuQCfL6m(B9U>+QvTpo=EuV zZCl>foST4o8W(!7pN|79?}0lIb4M%?&U((|x}GxY=9q7NH-4uMtp4pJD9|o1f$Mu< ziA`HAK#KkCWlb0DPUuCd&TS|rim5ve6jzczwcC$D0-bqOaAhX?4`cXS)z(^r$E$e) zo-NYn5fj!6D38y9%CoZX${hn1r<|zAEoV(v#E&wynSUvY4~wkoxR4VZ`b;Py5=BKg z787kdV{(>w`BITtmhMQtfSH;!fBa~>V|2im{zf}L4jHnlh}!zSzsEQ~VrrH%NbbZX znMFB2Ug(gSVRzw|m!e(#y32oGBOLGbF*&-TwtRm)hB@AC<_*F)Jb)KzEvgD}FHQl& zVx1ou7JCAI^D-<rmgj6`$)6N(_-JD=FHUi%_Gzh|$^@ON3U|JLE39|_eq_sKURCJZ z>HHYNxIA}a^xH$n(p+NozZeb=KJR@sk(*fK$Jnx{oZDPc1(8^L^oi3w<Hw*_mrB`^ zsuxSL!WsH2B@tPcUDV_`#iN1`C|hN8Z)5y+{5#O3In0E^l=`R~MG;#8&mf)(1`nj9 zR{E5=-xjAJ4bi<5Pj#)(xyv}VPUY~8s>;<6m9lO89NtxHWmuD7R7x?oY<;hkqD`vK zYDDCm+voNg^bDn!hV#yy{%OYgT`!%LwD+Am6$+XsvD?krm!3a<4hEjTL@_%v0-%We zu3g=1o2qhbh^pWA?R3lO?O?EzZ#CtzZJavvx?P>yuX*OrAG7=}DrHu{yMa8!+oDxV zPZ~9Ko!h%>0u<7k7xEbs*y{xNRNVuY&O+w++sk8XIJiY|e}#muqB*kcY5T8p;->oF zwWRV;?J9>F?d+@`Xik}TZOmR|Y2cY<6iOo9!Pj2H;SuM^cVke`ErtCRE(_KAz`Edj z_%gxF-9_z7%1It@biIh2MSg<D;R0z{WRfFaGh0%zaGZFA7cgk<hg3SavXHn>5B*Ti zy2GvpF@6jAUHf^;(V;K=Kp`s>=Duf-HRS-E33ny_F+Wwqbbv$&uiIqTy3`LTT@hS} zmO^deTu0=iDZ)#!|4`waWx@{;`5cu+M{<R&a9XvS#E|?LC5N)Q?7Bg*laL89!B^pr zr~^5gaNckqn=?q|(ojJ*Ka6>qghPTmhh+e?9~U0-N0&N<ebpt5f#J#n>EF~DIEe`* z+7p4;yjAS3K!mby#DF?_x<yJ#b$_w6)!iyn#~^{U4Bq0B7N9uV9$D#Cb%g@F=UePS zERW15!b6J2F2$5)3KxHD8i~&_Z+YAmrWC_kpczpmgJpjXF*H4LED?L1{4>cNZ;F0N zdgH<fs0N*-?i2bK>}!7X9*Z)$57ub<RbwTV0*t6ja%J!P5rolCYh|;cYBo*Vw>dc< z!i24gd}A|Q#|WU~2O1lnP5d$=k?o`d-g;yWgc1ba#K{XYTG~Ob?18&G-GeW@0!NM3 zUqA{14wO_Hf=>S@cuj;UD%pJMge<iAhc;fAn*0002P#N{tS`;SSc$thC*07(F|&Zj zyCvuC{xi3Dypp7RYi|^-1B>`Pv#CbTyPJlM3!|Rrjka9xk@s#lt*k{%?ypnP)4|Y0 zU7cfH)3N>^pOy*2Q}XLu5Dxrm?nCXk*M9+I$>2x4s)#C)Y^)`A*sxMOTyj&Ms^NNW z{~M|};J2dpzoCjC!bb!#m~ie$!{{1czgRfuY7ef{#g}<ufrQ-obH(l%-x+mJYgidn z-<hjTWsgGCmg2d-(U==|yrp{~79?#|&R-XAj+kU<witpTrtBe@OcBdzI91Md;YvuK zsc*_en!z<LIR^98{YehkTy1TDW|ph6=W|YbEk}mQ3S7492v*f)W&8DF_j|INz9!*C zY~c;hQw^r9;;nBLD{E+jpVyJ@#~kz=r5o<9R)fb$cV*>z&(ED9;^g|^NAef*u?|EK zE31wM)e(wD(*DT+CoeHK?fs6ABFU+5kE%}>#H@OG^lA&1<Ubfidu(A>W^16=5;p>O z#HHSck#Z#G07rDopS84tiL;7uoKW0~vyx+s3JcBupXf)L`9_kfmwa=Vr@o9xF!LsU zng9T4DxVoZehB$qHMGU<Szp>%Vbo>Wb>H1neCl1i4a5=n3r~_Tug(2=*#>~>eAX^< zoZAsx-|uv|cjBi+q#r1l>^-LLQPL$mb5FbkyjTArT8|^*C-ldG1UO!KUpY&=C7=0M z-m}LJM4+m?<8~g)zbEPgZ?fkvLycLAhe@rXqaKlUNwtJKZjD}sVqkqo{B&Tmi5*q_ ztlhX$;nZMy9~?SGZ1v399xyhKvATfwI8}G|zSY?)RQ#blQyq)-V0za|bX5Z3(<PBa z(MZR@KlWH7W6*z#lcBFzr?OT}>L+}Rp<mZN&=Iar90(IeP9__%iex2JzNbG<b%(~T z>|tUmQUcMoWbF~XL?&yD(3k!NgLe*Dd24)YrGG<R)EuszINC-eF)t$#*!mzCaz{TE z<{F!6yblYa?NVHOMfIzt9HXIFRRN5kbkMdSq)7PZ@B8$R4-RF1<x}H!HF_24V3$dX z4$xpLvO>{zo70b5pryq24zX(RWY&2_t^eAMC#SnTeBe717KE^ggB>SR?EI0gn#7(o z7sLl&<8vv9M!+U$h&dskN~KIhOXp19WZo4p#d5hGU#(B&bFh&uGq4L3v<PeZSeR9H zJ<S877;XKdC?Yj<0IG7WT6--!A2?6>S7R%4i@cN5|J<fmS1{>V^j${dNXpk&h?q&w z&r!+Ok8~r2*XNe0)^n)IjWt)7g^&eBfA*rKE16g_yFNTZ*R-sxFo<ri5Dk$~Urn?c z88I?3nOUR(NWJVnV8!i*=FTxlbrT(xHC<Wr#_E58T^|#o(l&pX*-^}P_I?&gx1G*I zQy=g$w`X%(`f4!S`cg+>hELa0akxDf0ns`Z!;ggdwVezW=p?dN!9ex0=%1`6oDBZh zrQv9iE<aOCDqgtbdy$u6W+==Yx}lMe2Hacz+6ppQys+79;RBz$R)G>+41u)q=us4R zWr!<uMwNqMuW<Q@E!QM$v9%2ImQDg0-p9(38BF|;>(zWCPv#YZ9IFW*v`i=^c##ZA zdcvk7choxaxm$2eSj(M`dI;JkfQ2nzh&}i3so8;?fJxdmXk@1JHmG_qzQ2S~U*;@* z_e8W9kN*$sfVSxPQc7&%2dk*xr?*hk+by%$?QOB=M#`3}kw|fJ{hlyr@!IRbmr*cK z5~Zs>H3G28V;uDrB}1jp^=&tmQRpj3e9R0R#uwFSzXsokaFMhrwXK^l;ngLF`51m+ z7ptDk$Vci_nt8vp^Qm9>Vd%1kI7wjYec`zUFK4zjqE|P_$KgzPB|le32edW4S$BDq za_V~OlEJv}G$B8|)v#%(eWu#`kedIF^A;oE8{*)jX&zCUzuGLgg}ev^)73!Uu2fnT zw5gD8<0{%>Q+f5Teza4XLTTR-R}HJ%3dr36F};%j;2$JG(&Dq;W+nv#2#F9?Jg~wW z*^agpGMn%Ycy^XrIAhSzPGB4x&3+3&`y{uy$B>DLRPK5;>H78BKJ4e!7eeL?0`jaB zwJ<g4uwA`|_fm#FqZhy`!L!z^<8mspjj1fXN~%@8CS}yDaYWkWElflyp3F6gn6~lD zkZ$RBdkx*{*72zRwdYE9>b6iV4tYb|1}D^7X*FQA%(a1fTD1ThS$4HflXa=O49|k! zBn{qgQsnqIc~U~Fc7+onUFW8KmZr!2A|zX<g|3zs7_b)5g{V1;tdc8AqN(@tXnpS^ zli0V^8c@=kmRjSGA@86w=!H^rmum?5e&Y}a6qv`*kg@vO-%-n1llMXBXdZG<ToYxE z@_}7&iB@^-sv@g-ybnvWj%7l-fkI>l&Rw}PZyv!HT7tEB)C6TqXu?rRjs0(qEYT-x zgD|txf*K=g_;Pbx#{?X}q#ILRJ3mCzBwjQsOAf^*=CVAZxqu%?=agGHI15=qAVi|2 zKp05#jC-MB9Oo#HxD<*;@Dr}}kOA~>q{C~%0T?@bNWV#}@*jJ&BSk|k-`T}`x9n2z zmSSgYD`S5t^W+5(FJaUpC}ITfrUie_XC-JMoD8p{T~E0t6-{>OG6<xMU6yi71oTOn z2dfpZ!506vCk<q@y6U<UKV-CNX<Fb0cERHSd+BoHb|t;lu4~M}m2}S{T1TW+zc+-v zEz&+Vg6jxVp-@XbjI1u0E?MUgE6aZ^upB-;O$+EHB8E5YofmX$0pU<;ii_z@5nFsf zDf!1tcYZg0<IdC^k5n*$p*0h3fO|LazVJ3V9Gmzn&gnENKqMBw3|>}b5o4}&H?U@? zFXdY3reZI4{^NAreA)Ir7LmgWvDf!Z4cO9lB2chxWtWuhm?wjWn`!j~giFErsamNw zy#pT%3Tx{q8}JQIETUn8<_5jdiec5E?k5~6)9~vhk4x)Nutmq(B++7IguG^VIn!hT z{fW!IMMLg5m@L^AGoMi2<}q>goaS1?TIda(z3Bh223$siVOz5sD(p#;RgE()cV<3) zX+N1feNJS>BaXG78QSj>{hW?$NavFt#2nlP#hUy})=r`5rcBzJCy_C+VtSzMQ+^d; zq}`xeE=8+=RrPq~oT)KX8lQY$!e5Z|e=sC5rjP#vL)zVFq4^<m;QhwBr}m&XROvi^ z=L!GuVwec=ij<#xUBR9Ck)k<3$;D3mL#Z)g7h>y{^M5YGf9KuIo!`tYKjCzJ<9KV| z(4XJXd-Rkh*oVZrBZeZ4H*#>7_{?gKDbAp^@S%jZkUfpaFoQ?JYkd|XfSIsKn=4HB zZ-J_<c}YH_j<hhzLhrb&EuODWz8fn^?}+~?k-InH_q;OxLhM!&Wu?1hGnZ`POV{|s z7d-yu%|kjWPNyNFjo!7`^`Z`_1e91=PcfoKrLSPOEUEMtm!oL`)Ub)aami-aK*X@S zUy_<DR)i5~9nzsg8P!=$L=?~?tf6;|Wl$>amz$8rA3dNk*JlHTqf@4XTiuXKFwi_s zDHE7ShO7tzg;&z2;?rBTV$l6pjha*huhhaKCSSu5g#wXafRltoC!XITu1_9N`4_Xu zE>auN5G=s#a^0=({28kzTusPb{jTUW+6Hq29^FymA_pIp+}f))ZqMv>m{AL+nw>#& z+Tf>~T~kIok$U78354#rQQg&S3u$CEHJO_#EOzLaV*{(NL(~1HG{TxcpQBX82S(^I zit8ApnV#?cv?ja%$Z4pGf^2}T6JL?IQ<s_aox6K<vVFz%C~mFXv%!p6Ra1Pt0gq5i z!A4cmVU!HnV#%SNhKwZE{dBx7si@6VP8;tw1MiH74}h*~9c4p48r^usQB^VkrNgpo zwNtDeDi0Q5LJkB^C2TANAaqB$RF_MztVac`VWFsMp|^WF#m6TKjS-K_0)|CE!w5Gq znrxzm25gExBd7hx&wm*+&_u$_5OcK(<Sz-tSBw9--JrQOsY5frGii+gC?)`qX>}#u z<Bo(yp<5D606uu%X-_6IJ__`n4GEswRhqOaycPgNL04ShuRdwkek*i{7xpXw+Ye<W zjC3801u~~I%CDwRdz$53<KG)@uEbBL3cyd6?*Px%SqK%dgbN}m6dcgw_$)BCGXX84 zIJBuvFL7;iTa`#*dPHrY4CwX@l4>3bzH^AHBcgiv4q7CR?e*{j_<ysCQUWO<e4qdT zgqi^W{QaNIn})VFCg!G!#!htq@orXgf7ueSH}vf2`p=%8*)%aG8kw9-oliLsz`M8w z`1wf{ab^>gZurp-n{3%6Z0i10TwaHSJcF;jOhDr+f0x}*q-NXt`mWtB$5cd#-)Vl_ z4+wV%3lk`ksPr^Bc6t3YeZ5TUc0U!VH7sSFPwQ$_+a`|qF8m%SUe3|<c(q!zcw`x^ zQLoMJtUET3u_MXiQcSWG06D0V->+v-v^B+Xx2;L=2T!k84_%;kzsU%Vn|CakVp2q) z`@A>x?#SByU_Sd=4lK%Brc1(VUOiRh>(!Z80?Z4YfljVoYk9T4KHIND5VoKmjswnl zPogHYa1yOFpd0k+m~pH)T>xW1m7wq8*U`JTO|cr1z|&c}ZtHUFkx&#@Y`qnu@8XUb zRGT%Ya6L_dcTSomST+~_oEo#8MLGQ2nTX7#sqOv-skE!fi-{up3rn!wX(rs9fCPg@ zjr!e&j@<kswnXi{tN_id3<e7BN<%27C^-eN2FId^&vslTCbZ-05SENEQ7^?`cbw;z zMI-hMf{S&Ca2T(s#-Bh5>f!icph6(rL6|B@dIDvJ#qq$mKGev`8)m=;cU^r!6dXJ} zbE5xAD}G2wXdv~ZQBucI{b|9dn@F7<5T(#mh~kxN%x0MC7^<a6>?vWQ9&DdF7ca%v zRJP2gAKI$orrn(oarRWQ)s`GkWE4r|ddj0aCn~JQkl>)1V4r_4HFFBJdQdnbM|C7n zqawy#;D{R-f{xhIvE?ALke>!u%5O96XSJTtzJ(qq#R@EIJZ$HwIApg_8+^_VKH?0` z50{jKApJKY%<}tC6MD^xzq!w^;N35V5m09jc2oKeNm~1OR;r=3nZu!{B%r@pLvt4% z_#0Qx`@?K2U_;$2!U@&8V9aj*lIopFAJf2jI{#U3unaK>ZippR`&;p6bNuJX0TRfX zdv=y$KJtxV7aaftFA_IXU({-V$;OZZy<L^nw6_4ezfJl<EaB12bebQbxmzpN=<+lN z3Xl&Pjco}OXhR5w2Ick-G}tAgQy<`{3f(@$B0QBK7b<{^gSGjdf`cC<&4ZoGi`>^6 z8wBus1E_he$YcFC_=H3MnlG6gLn}-**&5Yhmy+yS3eolz+Uh*1THo}fE5nQ2e28id z=w#V+a#=~s#ghjk5l4)sS&E}gmMdIoww=p3_hF?cYv^ZVFP7R~&<^7=P-%Lmf(uGw zbrT<BJIIE4&ww{u);b`-Dq$$KMM<4@yd%2{pp2rLl_frS)Q3=spJ16qKU|)l&S^e? zWg{Wh%VSRX(G2zLiJhZ<>@E8|Azl~jCGYU{%2&U=jN%|MxsPHoGxzwLyu!ni9y}Tt z{^ev(QzA3qjwdy7sgTjuWyTqCAs6T|ff|4<RIVx03>28l5>$vArAacT5R6~F;u*oP z6XBAjYUUxuj>rLKNjE~zF5-}yf1pvppYy&GvO~?dxzy_Ge_KzKG$3eY{1Q@+sQ$2X zM_5#}z%s>gfBiJMMLwSAMkNBdbRE;Vrpz)(g{f}p{DZ~vWChwBfCb``8L%SlzAX|# zEWBKf?`WLF9coI2`eJ(nE!#;r!@%(4rli;BqQE}D66ldFZ_`_pX4*C}M6)ds#iRjT zdx_@`vQoovP7VBBfdm$+h@Ns#%O|}fxeQ`x$5Hd{`D(B^=;T`!a!bjFrt9q4(k;tJ z#|N@6yxImwv6!Y{oCueNh?u%a#ufmOXFa@46GRi3`97zQ2>HiK<8Fu-Tg?7oG$B8p z7!<FBBA#PB9~=Kc9gq-gGwWf(#bBH1C5A3>Ors^6c*5#m4h^Q&1QSfK(%qV<>)|B} z@Uln7!hoSHy3zntb`aLADDq_b?yE{w#SeHsQ>m5Ki=EZgu0deXA`JV07(<a4pN2!- zErUy^g9?M=uZ!g_3)L^P2@o$qpQpJIIm{H$rQ)@P6lk3NQ&r|rdJ4;Wuw6aU@>*bC z0<LAM9si8$-W<mkVd`sxyRVpjlt3H>Wo@;GLe&87?g8DO#y4vpi8j=ZwPE)rtjjl? zqQ?MPg=s(`D-2V$fF)w%8e$-gvQS-|kcm3$d?b<aOak8Ypm9t<JYJX!ADGYTKPrbU zqOU_PNfugnEpPJ3VM?~?ylSWQDrr^h$8$`AYE6SWiK<8k1>FgwEWt5|PDwzupvR`; zX_>)=UPxYKx0FE_MrSl(&|Ce15phI~aCgf{puz;^B_i%2ovJYBxyyrXTDdBa>3>7R zPq-5k{x8>GjdB6K)3hMy-}<_8Mt%u`4++6>*o#!{gq9viLBdd>GCmra3RTVCl9vv$ zc9lJ|8ckD0s641nzNWW^I(6J5H7g#?4P=JR9)83^RV^MGGUb6kLloCnL2PAB#Omq# zStM98eaM>~(sXO7xt}^sugomkr@*>7i92&Y`jElDsRonxK$H_yeH#>Ta5MIS-n3@d z1>ckO?Yya(&R^8py1_0t6<XqDc*&30dsJ1>B$Fi21UgU}$DaX}f>H~^R+Lq~JyEmv z(GY{01PFtI&Al}dUmn=&=Aa>H$Rm?)j1swU#gz6yw2#CrjtI|{V>2*kUs&E0AQXN2 zRj7vy%y|CKw%U5pj7a*qh^}1&N0|yp?<#u!HITHn!+UnFKX_j48e&K*0DZ3dQR9zK zNB_j|prPX11<I-^!1~a7p$57xpa3rw4DL7MCkdz=f=%a5hyA<l!$^XdMu_SqHw_od z-~;X2$yrm>r$5;qU<n|h(#^o=aSTpXsbG-{c8A{qzlA6$^B`;t>+`&>dxMJug&rYJ z{73})<@{iWTp;MxB>sRK%vwFK9(87Jy((=bd5jSr8Kzi=$t?2+5Fwfu%w43wj#I*e zqk;2Kqk;m3K?Kr?D)6Pjz)p@^hy^6kD<P^!?%hCEgr2(we8np!fk}M{06Arwve48b zu-9d$Cz1HXNz9z$vMV-XkRU%AyY0G}U;!u)<et=KijJYb4n>!)%N6N0%h6>8ZMws3 zx)H=FMJMNLa^>$s=uyHC7n!y>H~56AU^b3AQk)5E51lJt7U;p<mAUSV`x%SwbmyEP z<U4uOB&8R;>PowSwI9KMA5*WEupX%tnCQ#XJ%j=rrPG*1UwEbs<vOhuN-5^4B?P5R zR;?xRk?Dn|-6B5_$cT#wMuf@#$fX6%=eUYU0i&|d<w-4z?5`5G7jD{r1N*(^M{Xfq z!6xKW&ZBQ39;+eF{<Vw9xDb$Em0zE#si*E2?Cv^VJHPJQ640YPy(gIfKAb#!A_?)m zfKXF;%Z@0(F2@)e2r97fLX-A%;b=v2H_4{`wK+nk9K$e}Zd?Ppt)c~cBN)UQ#IL9; zWMjaCRhhfTr84uTa3i)c9GH^w%Fb+y?ZuDEh2$q#^XuOz4Ddbm>Ml>KZNsNg_TbF` zQ3%5A>O#KU9+<_C9ED?c@yK711jUKPBjnG~y;f(|naP`}bCkeY<PBHJ0JM<GMD$sQ z5k>h^K*-gD?i>ZXTD_KDSu+9-mgDHm+X0=4YNjcJfZoKOjjKl?>&hWCEfY8ubEyiu z4-j2iJzj_#JYKTPkW+*+BVFOQidLj#%g@u1ctnT1;aGG9Tj#E|d>{c~>)*~23wL|K zF~ym%?d?#P-JRt7GPI~nX1m#CBGKm?Vf9<m;GBX`_M}|>2dK!2>bCg%MfQ>Zu>Q2k zhnPXQFjmFT6miSB0PpxsBLEIpZK2awvp4CsB3u_sST}97EWKq=KSfn9>tQ?p)r8pE z%Ud()>#px1h|Sx%`EVLZ*slT^8{PR?k@%UJSfRb?@v`}P%7LUaT1%brbxcODqrt^r z4D|!7=K*<wddAPwZH&eL>i34ghQAS<jq}6pS0T8@ebvIZ?WJI`yC_G-pJr!JnM5Qt zMtv2Frn}Q^_hh1;_Gj4&uc*5mSglOVtx^<ji8B|_3MGwlL`7}j7}f?6(f)T#KSAq| z?l->ush`iC{2H}wg=3yEk6b9qoOhaDesYMqfewXxJOIHt{uASr^dwZaroC;g7$$Tc z=W<b3vxjJqGS(0a89^aC2?@RgPZ^rG@%{(e`Jn-u$RO+9y`hAh#>{wuQ1&O1+?Iu^ zc>IIwE<PJ=!Zk}#2X_dI^j)Skb51IU2|<{QJ6TQLu03cNVR&n(%rkn*-OM<BMQD-U z_CZ>mVKjoRW{W-<q;%G13<~Wju<YLKZ%6}pN9?gy>5!0RVB+AU?K)1;V)M`Gd(*qH zRXm77JB{w%*alHOEBa?P^%5AYg=0DbFJsL~5&Moo-)WgiFN=zkhdUT*``Id2m8q_w zEji3>W5-(p;`cd;x@XKAf-2?qg8*7f(2x(UlKQiQZ96QSK;|4qou^fy;4+Ny1ULzz z@SR@dZK&vHG!oqW`5qX$kYeL}oIsA4e<V`c{qaVDZf(J{l|5V|kKRIUyj4ROc%_#m z(&<sD++VUoc`n&AS2X^;O+orXvB0vN!2)=HQaQ*WPm&YEE@zfV))U)dt!|VD6C~C% zWW9KCV`Rh?LQR=pb|=>;p4{NT4Eho^zKLx<l|e8jSWIDO_W=mQ6l0d*SI2`*08g;C zu$$<sbdGH=whUO&l1-Ey49f|aWuOh5`{a3CCfSTBq4YUj$=6+&LQ(DwK{%EobRd_= zq6~=d^Ddr;ps5;60=;&a&)dAme~x?;V163wE^ej}aa{aK3Iu2=&cYV&@?!f}b(*s< zb<cK)c`Jez6V`AZ2lwd=3&Lj&>(Rb{RcwG<ZAIo+yZ}uaPv`G-KJcUfjCO$l)igF~ z>Xt;a<Y$<y-uOKnL?gj;;F7pW?{BWDXf5{ULPz*$@j^h34B~v0j2W$-ZTvj|T{VRG z;=tr_g%ZpqQ+sO&xEZ~hB%3KH0-h`IK)hMDotF?YwG(SA<NVgt!24vR{?!7Xt~S3m z;)H8B|51;Jd{oXQn7ubZB0>=Dv5%FXGOmeA4l&IMtSDDyqDLr08>-w4lJEx;%M)2j zLz{dO1@ZUL!O=Zga|M&gPk6ehTNDwzI=`S_dvBkLC5%^F&8uP(!8Yxuoe2zuAOy+} zgD1d~-477ULZZd-KM4o?Y(AUB(HbPXTqVz0I9c!HK6;ibI^D`<8^Q|svl%&N<E*mj z&vsef)5<|{-E{{VQR$K9ldz+$BV+<QoM_w9beV6jUynYxL@P?jY>H4~I>S(8*23Cj z3+2%zNM%;ia$I4@RnXRF9VMJ=GM4V9IHr5zhK(?Q=rP^-0GOi!6g!=<w5$#m&i1GB z@J7?*GIO574%^5z<soFkVp_bu^A1dCA^jPw^ZtF14pc<XT`Ai?!nJ}ggZ2594Wm9z z-Lao%<qipFZ*4<{cQg~657dkD8sLVy3!UA3w0>Vs8vjCe7uZ6zdON~<DmNsNHPQ3m z7t$m~q7d^U$9~)mlO-9Rn?1gb>Yq0uP?wP~w}`1z+*PqTH^C-+au(f`X<IyHgNQ}U zFex<Jse^LK8vUz*P$;d|{6A%FK0{_Nhx(})RU1RECv4A@{xE!e9`NC?nHG1<uk`Nd zC4`RN^;>UFXJAygX??jshByJJFU)0T5V;m&4^3X(d+<Pzlc&-v!z5A6YXlud=TP|0 z=$ye2K~WTlZxHcjx7zqo{9IPQVyEh`pp4X`c3etsd#GL9gI-N{taWU-9+*javO$pj zb3G`OEahP`{DIN=RN||5aK8aN(eod&aZU1J<+9{3tU|cC+vAEr<Mck>j&kS8d^Jm* z65?hZx2IZ?`%~73D=dJ2dk{tm;*0zaHq=AE8?B_vD4C_+!oi-}7Lilz=2kU%Y9J?5 zC=8)qpB#k4iinlJL@2zF2`mz4YLnH43sW_Qx@xlQRr;!ZKob)iKk2$%ShOEj=aS*% zj-HPE&7=8?^N}^*GuF~DtK^Kcqb+O5Im@y`n324*X=mSRj!hLl*q%gH$&exrhk%gW zkDnkL-gXPfA1-M|=Y0AzQJ307h07$WyB$uiRqoMruwo75(D|yGle7C}r>+&=_W^e7 zP3h&de~Gd;=HmeSP|{ZL*<_}`5eYFw-{u{8ahRM4ukkXs*~Ij+IGu|~6+UX5(*=rY z<*cuD+aSrcV&X*T+BnN~xS5`I49W91hj)~Ax(kusAodED1(x@e*q3hT4!p~q$DN=Y z5L52tZC*<N&R-_ky%m)1cC}ySwX-eAyDRwA**+es>g>vB4r9Cd`k1vZnEw+@1-SO- z_omdx)5@}L=)>3!7a)I^1>}U%@ex1|(r~N)nW|B5H$89CRGxGnYPxCpxCw9^p(E;= z#d)wJLF(Sw60I&5>>J4Y{(~y*Ui37a!*q|Lfv&}4vD#`+q1B3zN=G?LI`#6U6_L!A zP>8^rhp)Oh=+{QTE)3USJ(Lqwc`*o<H48^mVvM81wk5Gilb`bu@-x*&x&Y7Q^Ii7R zNiA{4Qm@WrW^D=1?Q6p)zO1WR!HvH~2n1_pD?Ej!9M1vyr{-MnP?V;TfQsqOaDmt6 z7^8^sWoWFA<RptF^sHsmq;n#JCNZ1IxfX<N0ZI_OflPnzYUbg(KbM@CT63JL25`1N z2eyI?wL!{}XI+rf%zHH|_V1FH8_xG3;sE2or0B5o__>)N%5Lld5J%!Xpy8Xc2uE;( z6}!x=az>mw0aSKk%Ymx<)=Y=n@rqeVYulF9g{1H-Jof@-S*$A&!~B&FzBePBopD@m zx8D>D38S2w(hL^yfJ@jYL}12toGg|tDCOyo5uMoxDO`Y76^VD^Wy+%x2FwkXewhcC z;xB49jlZ<!V?i9FA!#U$D0H11FMN=YF?3U$4nl=(w^pg((Y9D14hs85ZopWl3-E%P zM5pw3>AmZ@c^`#&i5&hx8u&4l8RvV#q$*gFx$$ge!yYJg0I)0-h^Za05b8_2J`$+} zoot;clVw%7|9Ko<?#}5poK?DDlMwIUno7;*?FV2nT)9B;g#$`1f78FBlDE=qF|2Mt zuT;K}wNO5Jp2`Mn4)bLQs~j^iozUFo$=l+hpHbZQ`;cEO0g_oI5K$ks&O7oFL4x=o z<d_C9lAvRLJ=M{BVz4K0g+D_eEwW}I&t)=moi}AQza6N%oP%YSyz0JyY1ty;mvi(} z_I-0|(DJx;O0qgXdQNzr{s5@JAHjLtJ+e@&dv?Icy=<0!&GK)`t%LxE!F}F&_QqNZ z1ogC!09}v60e@1+2QaLAjT-R4DSF#K;3Q0gc%BZA47|}b;^}o0`@A=Pp+ivI_f|zF zt{3|>K(6z;zcb;g=;giyXT=3n>E>1YeoB#i|L(s-JO*@n3+1Na(PG2l0nm#gSPe<3 zRRUM@xMelt;yc34XAdgJJk5CGVF+W!)QGmT+cjv|<k6Lmrf;}$VeU=WFR=)Wo7XY1 zb=CN>(*Ay*n5mwaQN5iRQhj}Wx=_B*tv2xcV(9Vadd(F00sp`K#k#%&yY9b!;{4wS z<NwoNEN)|B`=87BUw!T9lsuUvHO2Jg%s*v@MMgOVu_?)E*|AB<7G(-*@r5S2hL(c{ z`{^0U2`M-k>bptFiIxKeIleG55F*s%SK{N6b&9jUrpGDAM#sh%qyt7UkAA3R<ZL9V zMk#>GNyy116l?sCDX7FL0M<=&p_rhJVz^Tz|F6(e9E!NTWxs;{7t9U!e+v8?Qp(QE z+)&?2+{Ve+!9?HC_&=$g<GNt`@sNXGctG`6mZ$ui?dP2863+j?w^kE<E^3;2dD(}a zk+AAczd5M=G=*IHWj@ywml_H}vYjQnNJ<)}!I`eRqIBe|?Px$TwgRyIfz%d;I50v+ z)!-1}bjJm2@qos>!ccj@x(&-0vhzPHx&1>k7x3rD6^K#XwYFD^4wyulY_Uu4&*nu@ zWsZk^KQdd4&kEEcGY9%S1hMC<P&9hfQk%8U|2-?Vto@12zwY~FBR~Mu|2arUCw(Vl z6DwQS|HgL3ZK-(B+OYFQsg#wWC_XCbg4hqnHbiHaveFCm@5DyFYJ!O1E}h843LK*4 z+PBB!)tY?_Iz7%PBLh<8JhjM1*rG|3^Tz}IaSo{-djaFxX7`u<B3^&vJZ<3mdU({E zjG6Vjsq|8-BSaGCefc3LV0OCK>}3+4-^A2aZ~(I^Dn+MYX4vo2rqNo!pA*ybT;;6b zDrJ$v22c45#`Y_u#g!rz(r$sB@y2=p$M#Zrp=o*`SD-bz%Ov?nNDS+7(r1K3@Q#$) z4yHp=i{`J5m2F<Ws3Ftltv*2`=b-t<ap6R{F9F<e*-e3^Bi(uCK<#O}6B9<WI&u4+ z(FCBOL?MA1sBepB2sN5zMbzKKpp=JPsE;uCNI&k(ftV*RbM}(B^X8IY{xj>;7E83f zW0ng2E18&gql6PiN4<7f;YtE6+oYEBFmAI)eBf{w0Q@Mp;+RH}<bcY{!l=w8kJp8? z-iQ6~9!$@S4E`PV>rWdO&!2n@{anoFmFO;NcB9b7>ORBS+rWRcE3Bca?|nBPs;mys zuAgEZkGG#zi14_ng#ToDV!>Vpw^s+yFQrFXZxRps40o(Dul@I07eN$ujb`C~Bw%b; zSaPIXu|&%U?G!jB{$QKvoW8%mA}Mc1n<)p0?zEDAS*{#AAgo`0e5-y@)`u45PK>w> z&-U|l4M{JSC0{`N3mr@ww!^8)_q6VwC(&od97pFy%$$M7^jy*9DG|j7^qyG^j`nBq zFGE`@q|JqUyvY2@9IzUNjvnikh|-EmIFqB6h;df%;!(D`<bF-;&-Ymr?ij^<z!C@~ zI6p=iqU@<|hW}zEbGp$OC+aUUY)|nviK>q8@P~a5Ihbu$C#;CZ^gIE>zDd=p4tp4< zu1TpBRx-uaRKA<^5g)EkSX_WwsZ*05v4fF4I{%g$Gn!H0Ew!$XZ+mrcd^-~PY4rV< zd;DRh87os!9Ab@mU}T=eu+o^&_(7>~h+RUAL<SqS@$Zy%_9@=y^X+Az@*s0S_I*k> z)x0Y#pL^Zvn<*D!<kRWy=wMAB72^vmZWMl+Q;GTGFxUdD)Y;D7$KB<XH=ikyX}|CI zAEYp6`#LZ0BCqafo~YnL_ADwrVfp}0y|gNYZ$__-FoR!ymwa&B-m*JY*>^~dIVeNc zt|VihX=%S*Lu1XJ<(6K=xc2ow8@*=gm3F;X=ym&%0a$nThD*cscESye&yj{6j#!b* z(aR52h1FFrS8JD0t8fxa0Vj5YwQNR)%XV(4bvIqgw6Mne;kqNtfyOu240=D2K#@Y% z1+x{F5Ci_>vnGxOi)Y`&iM8b)W7!8R#s*=9OyjC~;c69|c^J5wiX)He5WDKmt+KCM zjFtM0wTU78tx2|`tGn6;Y1FS;i=%fH>qvW>GOH6}?et=Z8>g&AKJY3v()p)*qG}1T z0U~nYq4M&5*AOo9>wM76Y{^IkQ|-$+1@qEnj48;jaVCP*;0h;P@lc`a)Rwi;FrU5q zMbfx5`@-4!=o3rVNtLmcllkn>1y;_r6e(7>tJ=i~UY*TP8CIAP@Y04kiA0FM*R)04 z23<b-uJfFdJc%I7@RUEbJ;CrK1;*)OMklDy$IY)@PtV^-nAL%iGr4eZHZeb3i?XLV z7ss#rjuq(LopaLG<4+2EoYvvIMJm~2xD75e@fys5KI_B*|FRJO+=m;n*&gpB<?mn) z);)PvGA^G5ZY*pp&pNUN6biv&ui6TP5(#!8#vpD8nEjQW584#{8lxa!I7iZC4cX$c zzmFjJZZz*<NB&7(O-WpcVB1k(n{tc4Uu86xPZEkr?%)<sT?>awR^j3xcZ;55Cw!Uo zT_{Onx9RT1A$RHy!*Wb3^tuOqjw_?S1MgAj9f?4^&7?P|DheJyYS^ho_{Qf(_w8|E z)I%MoJh&N11v23AisJns4>r4;A&~eSBnz_pmW9F@5|YB-Y(n-mTEjzzUx-*v;G7A_ z#zb-%KfZcpe4XAmtFzaPiPjX#r+;SV;9w0f2{fr~H?a*p!Fp~i$CzeUFrzG=yKr&? z+Gf73nVRchF?WUBZgRhz{=2JfY2vx^xgYTi`L)4v+Ffb=IOJqV7t`v{?d#b5gYf1r zV|nanIeqC@*;D%?J)y@7_k&5_VPw{s7Q<tq*u3kIC>ScTm1VL>x$A(*IHKaU>sZ)X zKz0nwaGkwL7W(k!`@Dr(ky5!taU7(MKZHa~9SqHh;HC^#Yw}C4<VFq3YmmdDWKgAf znJVFH-`cSZ?&N9Sex-x(Wz6+=E_vx@2Va=IH*KHp1>tW6UJh9YYPEu)@+2pUl6hkV zk%W>?0Ru+?0C+Eb1o2%EQjrofFg?IJG(zEixdt>ne3FW}ej!89nv?@F6Z3yX6vXTv zVZS8=(3q9ImKJpp7HvACb1^%=cOQ$=h$nZE`@v$HD};*8@Yh2SuT0+kmJqMDIwWMG zTd}?SrI>BS|J*4Y-)cI%=uGV}#`FT;%h=mjwy7r$smAo30rVv+MC{^*3HbZ!k$(as zrS$LOrj4lVpL~FyKcN@cE?e&C&a6&N0NFBVfkdvquK4T^|J=R<uzWb2_6i_X5TMVY ztX}@O*CvL74+>bFrkz+t+N3{LY@@dsc5&Ohh$DnEP?0MV8*5ZuI_SZ!mEI{7RozG2 z19}s{T|Ujk`<NGiPlybfy~I8BK05^j70$L(pokGjgDMu%*f+Q<@w1Dp{d5f7+J%Mo zfXl+%E#CAk2yj`OaBcr_!a=W#(Yq=U>{S7j1=+%+sYWX#t-Qg|4#2Up#A^?OjU^C~ zG|e9PDC6U7I!ZN=k2ol<AX7dl&LCUrRH#k6s_{k@K1_tkS=<%Z{9c(4sCLx|*Q15? zykor{3dZgY!D2a7h~T}l9(iQNlrrfNz#I3Ft<<!CQsM97?-DFZR=qLN>SC6&mAipA zKU%^BuS9C@3U-3lgD2nAoy2Pv2&B`&BL+5m(lB#obn>AxOGtIQ>ci^An(asj9u(t? z8pJXrBFV-Rh#K5@x0R<yjE20Cd!<LbKp~h*`&xp?LMg1vgAcD#Wjsb8px2wmf=GxH z1SeTn3uPsU(sx~Cwc0Xk5zk%y{31oA?^DJjod${oTtqt4RH_^nc48(gSRj4>!Tj1G zFEE61Hb}IcV}tN%o`Gav(+8Lf^t~JXmna1L-KD^c%lY~u(d2cxyF*z$Mu5;Mg4csU z#Sj=d>YYk}wdWuA8?52Gg3HlA;p(`6+p%0hnW9#~SQ(>s-bk5T+?(7G7%?$vti+Wn zHDMqb>*BG0DbMbmdWI0EbDC=C0;*KD>YZIhP#$Uot`X05z5KQh3D38(GhWecR|?0C z1CGkAOwp|@oon%oOQ}yVvtMxHFkkv4pB^V-G0bJInpIBt_sqak?hBk|MLTk;x)Q;f zK~WE&^@)27uRkbtbUGp-5w8sSRZ2y>ttDX``-{e{R*yof%0EIdY<Y7YSeu%Huxs!Q zknw9gt<PiTvGrHqI$H>s#OIC-WcOnaGwJML2T@0m?V%pUnh&MWgVlpAK)<npwa|mb zh9CxT6x;hYIL>=Jw&R*|gqSm6V46KUS~%+^oSp{6BSV8G2>$qk1~M4Q-?@r)Fhl~X z$k)00-(=nyOs(0x>hw@nXZ+i_uQuNFX)3F$7XkZl4~kxcXJH8}W?9)wxY>wpXU5YO z1o>Bo>Ep&UQ4=ONJ_gHgEN_JSR7mr2*a(tM&_VmTh$3(7aue(wwKh@-L06bd+jwgv z_2)NK;zPu~qwJ<9N<5uA;qNA-hg9N3dK&JNt<mhz-|x((&tZBSdzvj<6~>s96gj@K zvaFp{SN$TD+q|`)PPJwo-dr-IF~Flk&Q`4#Z`6|Dz$`>IWZ4KnsDS{s1zAFn5v@%g z@~VNX-n_;fI@%<cS!WFLha3|vrf_qkeF^r)xOO<qoEC%QS`Gx2hO|FA$uLFGU1~5} zk3X<uSWnMw5<B>(cqa{i3$Y|fxE?K~0<~7?bRZc5rAk5g3=bw63$?|RgDl|q#XJdd z#^zGqAjpd&Z9$%N9x^i{43;Szsl*Pd{~8q&@ih(|E-htJ(J_7R4N(T@jwl;sUz`h) zh{iqcDI$D>B&-~l+Jo9zN|VZfkUURF@YGB1L5Ih=%S`xZVWlj^uMZy@mIsN>0-_Ks z7ZQy+Xf9v|K7{4igNd(j#K<sftokl0PD3-b6*>mdfqLcClO%l(SBr!qeg!6T)Uxs= z?;TE~A#+OqtloB(_f(;6VkxJlNW^+RU+c=2FyPch?$et$=9!iFC3IUKTgL#~Z9V?E z-L{Sz4u^C%k#IM&7_OFNH?c52Xa(_hEFSVGJT~@puiP6UCZab_sAONwplbD$TuX#U zqVtC3OJ?m+^MbobL>$^Pmuv29r4F3uiY1qyQ@~rG^)OCeLjbVY;~~^%Fr;3(=O_!y zK$l%uH~Q5Tzj~zJL+i0=qE^-L$zo2Gqemxl$x^3l_#D)4g;dlh7wgU2;qYY);U-Zm zb@u73ZbG^*_XNzzDfHTmPTdjV#0}MqMiYHjmtD43PZ(eEfa^CrFMXo3kKxR%)3|x? z-=z8=29vE*$Z8qV>}D8#jcfspOc@Sqk$}dOHCzV5k2!lJ1CI!YW6JULS~An_f~?{w z(OZ<jn<(s5kSyp>V78=|R7-l}>CM4HFzrdYVFK3g%jG-wEI^Jb;%}l|%NANMg=f3@ zANL*1?Uj(%h*O2&xbWW8fc@^ZQ32BSfN2=0k+&X4;;fVN0f<zuO1MTdx!sp}1s%wz z{m3ydoFjP)Vt53+u0;u|Wm!3;0A3(SARf|BSfy`Kp0cCKw<@Al+4Wf}el2gpPF!X) zPNS_4;uzp%CK;xvs1JWUv#@*Fg6blR+CA}9rd612eZVUjyy{LD%OyK;hegn6uxK6U zXd9B{)x3qgh02<RC%Mw08f=#6xC(8FyV9<MaVEGDg)|9O?fijMX4EGGOAod_j9v^O z#_cVPfY#@QUzR<$8O}d2lYN33-j1`V-z2!5Coso#jmPkpoLAeLNIf$aaGH8>dT<jK zaC<|>UFM~{4-MdBoH+mGnUP=Ocb-+fwBvcMf_VaXs;PLIP2W-5&sxk{G$LzY9|Cc? zt1r?3DB${WQ&n=8@sCc9xyg3`jJ|+8*EK%FgNWsH(pdZj`2F4Eq>SU>F~b%OryE*i zi9-_NF;D-uVU^q4HL?5xdYYu-1v&8o`8h;oRAMqfi$~YS^>|~E*}p9bFRjJ0<%YSt ztYLCbH-$HlNkPgT6;iU42*&hk`L414Q$SnHAF{;=V9G^;Y&)Tdpf*WmbmaG$492W+ zJgKfEkaI`@>^*~O=8;gSu0k7RuhoH2w1i^VC*>c#`j|u5W8!EFSctR9qK<p{mk552 z0^N&+dvGOq<lnRUA1)}MImhS}Mib`cl7#-H@Ai52QU|X|J=0P3VfHY)VeWymu-PT2 zs1kUB;~Bu;VgPi4;T5yl9$5}1%X%gEYJp8>Br93jE&Kg5iJ8s_*F?Tuo-~ea0dR%M z;ZDBu=&-)MERU`y0oP92DM|11!STV2XPnr`eW>PWwKj3xkSb_ru*uZqRkweE&DUlU zCv*tKVru81Dd7M9@Mesafyyb};_e`wG)79~dQ3rX1s{U+qTiO4hnmo)BVUEj`LG3{ z`d~cnhx`=Am+I|6evS5m6(;Z0?LhDSKqk1&@1*~xM}_>(q&Er3f!?mA9!ewLJ;)&| zfoS~rPl3j?&{;-7e{E0Zw;cPD<1f0#FLL*f-l(wIEHZCP=_SVBdiOI3H0U`xzCuTI z_+kR5C1YZXK1s6(tV!A}15#qI1f<LxU+-)f_M@qdqN&~E0G8p|Jv7WA#ZBz=vb(<< zhSgdf3+3259H7-%u*5RoFy*}*g)r4#)E{yA{cB;l+}=nhYP%V%8jdHiU`(?e&gS1$ zT-XgGIOm>?oanCdhYDdjeCmLI%{gs!6||<yv{d`>`W)uFjx;L^#j?21Ck8!4IJnr` zm+xTZ;ws=oGtlgw?-09Oz=i$=Cst7MG3dAaG(=)gI|m(TKyK4Y8We}3{S&K85?HQp zWZl%cWyHDw;$TyNmI?%=Ib5UitDawSl-8y8Kjfg1%eRIj&I^qem)!xHz0LLh`g(+0 zluA<aoL4lSEA0Y$SH=GAY5@fp?zHp5S;IC$vYb`ctT?aX|INJKnaK92M78(0*EInJ zKRJ<w{63~cNi)!o(00Cpl`Svwgp#wDyGvHGw|fe#^v$XH7N4fEdzu;2Yz0v5dFHP9 zzKsrLc6_(o*?X*=;QxE{II@&``cw*L{CGwHuJz?`I_uWtZ1=R|aI%U*&*3B#VFi4` zy_2tfcp)&|V;Ix*a%)sS^Cv!bzi^wHz<$qzwbtuZbmKgZ2Av|JZ(z6Ue-(BXP*H7d zAEzaxl^(jK1%_5hVE~8jW*CO<?o>b!q+#fklJ1a}6cFhUkS;-x<{R&Q-+QmT@ArLs z)|^@Aob~+HKF@yEUhDk#f9<(k>%v(<rzq*qCAlDI#*=W8=g&c-cdEqM!c{k&KT6<| z`;o=j^oB{WO1yz8NvMJ~Hq7CfkWqBM)tRLDD{0R-6X@1KWQFfWtN(k-?~JJU!rZap z54&Xi-WMDAhL-m!`?Q?X<V1a7;mSXo@L5@OLbXs&R?#vjthewtK>Z>73ge>1<$`Ly zmuQBz6Xk0Xcvrx{b$NLkYdtJb_(BW(?Ia_&YvLzN?Qx4Xixg^tAznh*gqx6U<_7FC z@0eN0*5B+N*KSR#X6Dx#gUgT`Tgn*mYQzg$R98$7`^F^@dPy@D%hH(&_%OvcGRY)& zc;Jf?^Z0CZ6)hv#fREo$QI4jT%}D5Fl2o`G{1fHJv+|B-SIMmoBsAyqtQD*g=K)dP zEWm-UJ~x@Z^*xK%?=*Q?hOp0Z%uDl_Mk-MM`O>z+b`KQg8hNd{#f|4abrE34-7^^A zPd+N+0y(*Kf3AYZv(8Q6CHb(M7&4WkVO1IdS;Be8ud6}C#Llfk4p0d|T_)>^^XSA< zeU}<YhGZM|QsuikXBZi#LP^bg74l9SW?}5q)L*v};;6)>5qAi~UTYkRWPe~s=o)l# zqJD4deBYWT@&v1Sv^}4FN0g8gYDuY3leUGb394~FU>6pMdoac_q<)+jQbAa*__7;w zo{oU>dvER<Y^pKHdpha9SmQF|o1fxBSS0I=$u%SxEFbg*iE$i=KDTo-`U6(K?^O4# zwjayH>bNs>D8(KeP!v^2Mft6{0lCWt*XHPTY=ZY?>Pgi;`sDq@M<aJNcP9w(bkRJH zeqJ%rEgm~IqLV*JpX=0BM^aaN+{}Aq;2duGMszJ{dP8{_fa3X(cHB%OfihiaxjUth z7&=~#o-X7(bIRHAYNE)mkeG#`$QWWE^g2omy(%7ChYgqHTi3^?8YgOrbS}s9%CnpI zUD4eitQo@bhJo2aao-J)D~4@l-OLlU>9Pq8>A!VAh*5SpkaY}IFfazqcxrZ^Q6&mP z3|$PnU)(Tg2&Y$oYZCcJinLlUrlP!tOSI^5O`Z-lu6{2STCxFd@Sf?(q-{?6Ta2O7 z$aX>JJbW18NP6*WIq<GIG9`#lA9z)fI3xtfzRUcALm*rsgQq85Dyg?Ij^#yL2b1sX z=c!!}^~=_AxU;)os^SWJhO83Z3nl`nM3B5?QVy2uFI60pR=j5{hY?-i*%I+Yjm!RJ z-XRkz{zST%;$!Fy#sVn2EYBIH^w8^3*(V=Dl%>)3Ak~Vm3dmvw%e?TyK9{&YB(VZ# z$HuD%F|Zb|LOz~Zap!(fr#`B2z|MQ62B5~=DFw|tI8weY%_-D$Hj=SaDcFIHwa)&t z=)+8tRBziI+j$l&aLEYm)7Dc|lryt8Cn9tsKAAjBX3iMol=j<sii;-~_gm7=a9bYh z04-pG<yQ8Z(Kdvs)kQ45_AozLGMFlne%Ua6gvb+>g2)i)HegRq8aoQw^k7?2_4A^6 zC-ISe;aUnzq3Z;AGVrr4JDsRXFj8mrB1Z8tPC0Gd>?FmjbSyoIhse?>K5Tc#xUh3n z<qrw{==OJ||7Bz&4j8eN(T;|MM2t}S^`z_(%NKSoM(Ump5NCs5GJkFSpmG-vfs8-X z5eX9>2Z5wg^D><)Y62?_j{@^6jdt@FM*gFDoNVBS2`He^^c3e+Y4RvdSr(l8D#Cg% z2RTTwX2&%K1VcUG5(Pl|S7>!8dmJRDuT>axzZy54k`YtaRT6N<wkPl<a#FlZIks$6 zYc>uzBcs^LPJb4B#6DU9+2Y8~k8c8)3N`dmtf$5`+qUW%U_wL|=VTf2A92~Ex<Nh7 zQCg<np_ziYY)+VDn<C$!f2L%v8|cHqkicr7d?9$a=(g3#VWE=JsOgrNqCm5|JJNEL zQXyP~J*r^P6i|#mkDKR^<c$)T(Q!xudy|ENG86bVW6*DH@yV#%-Wpno&P`!````rX z4~7lqttD3fvRW&{H+X9YFLz_F4s6Wynu((Tr`9myj{2cZ-qBDB1u;7b^U*KF1Yc%3 z8#U_&{1_H;MU&>Q{KM>jAAs`y4Szwz05Bp300%JuMothLXKt=v$NY&Ug)W{47>8O| zjYbnBgt4y8DkknZC&(kS)%-Q*QgMxYdrA-MU5Cv-4<5!IT=ml(e=~GjBQ7J>eaH_| zRRC)=kwlRG$n{AP2d{_~QHYei&${Ol&p~<&-0cV#Ehp@a1?T8LqdXX9Fe|qL2Z3sy zJ&b!@N8}@<J91y0)4|*`b@8$H;<IqLxdv&CO`TKOQ<wO7W8sS+g&*MHd+Ywy-K^9{ z!5?msryEkMFs&B0-uV)BaQ43)#A@6Nv6^w$zwMSM^9v<;I;=eRg()F%*F*G0^^YKd zWKvWOU0XDNxpq}b03q&?d|oroxP$4u`It7~i^!sWW^35}GSbZ(Bqe>Lr6-U3kX14b zCUruX-GQrN6|PQ@^UcZ;$_m&KCI6^*%)8qnHSJY^Y>77wrO$p3>F?=vq>2j!;Ughw z5hDGul4T2VF)=rBG2wQxbhS0LGlAJ~IoLrLv?8CV-QLnzmCF#)*ME{z+@I2yii*?g z<ad6wo*~NX#95CYI`90`6=p}-D9!&sve&7evC|3Ac<O!m$Zx67Jq8Z%n^|>S^v;|* zZrWh(z1T?hNTwy|7j6hFCl~q&r@jw9)G<2|q)8`h#Vz%vBhXEl2<{aNeTIwD*nv4U zS%*20KSaB){YGRH_~jUuMU|8t10F{FDPvAQab<Nv;!51})k&oX)<ie6s>t4PeaLRr zE@%wK>DR}W?3pFBm#K26qwo(4_)O)N?(WBVn<^!sNv$Ptisd(v)@nu{Xd?YLyBx&A zzn$K<#_TasAf+2i!UnTsrMh&{OV_Z+X~h~4uyKg?yQnNKP8=!rkp0BxP&CTiAGa5f zkA0d=S`%+k4)Wk<tEdU(hC4|B|AbfXVq-bzc_)0~siwVg9!jq2>gpE~zFuun3{Mu) zu&88Lle>6dZ$G1avuG~S-TU?P+S-)`0VPh&ncgHH5a`a*D9R-e>`Xr*uOgV^S^(=_ zLC(b<&d}%b?5=Sv=frY<*+wzW#Yxs60V1n-hMAi*h|}4O?YdGP=D{kJYiWm3s$)w< zqGmBCMJ&k^WCNE~-J{B{ZpwQV*2fnSQ7I=U=cSb6;J6PbsRTI6=-MjHQOeR(>Vp?n z2%j-A<>yRWf$C#g^7FBej-a!#rCXL-Y~)SPG4m#><qJO#`F(e8QUQ5?YLU$3a5QIh zg7(F%j_2bmS4m=HCvBT_+T7QL(Z5k1P@m|Z*Ox=jx3w4K-vlC0JT7)Co>euq_MZE3 zb6qWz=KO`6R69%ZFw$auy~h<Z6UUnnY6)ZS)eJ%j9aH}DF;KrYaHn6ED!K)fVs)w$ z@a}uHZd)zHCfPW!u$BB;V@E`{Kx^5dCC`&cxcTEVMxqUWy!FqzAN0k<FlVss7C}a5 z3Il_#<I=Nr?eqL_o3lh(=H#R#7PnQ|-T5ZJrvdcS<^jsDAwN3{G|w&RNCp+M!FB%b zUanMq<?dJCZZ{0u&@<rZsi_G)$#!JNTg3CUd-oH&(>KoN+%fc(>d~ti4)<dh%sD|I zWx_K~Zf-Vai*-Vtw}~W^-QC^F@%#e|@X+Y!eZ4aAg=&2Jx_!Q^8hk)nflr&i`OqZh z>Wp4yWOeZ?fa9xugEO#ayOl&%!fqiu1B0{3Bu!)_jb^ddx3%fX$;oi7V&C9kUNcK^ zv(;k@i}Yq6kG{oY-;+s%Q%C<upwrOCR@}2myr?^Bu`a{vXgo90F<82^H0yGkcv8xp zj)2;5(IvuC>gwZ%u5f&V`S~G%)R~zXWb&Tw?iv)-1REP0aFveMQajrjN?ohO9A2_z z5I6O8?RV$|;ZS8m+l{HaJFq?=pe>g0F)^_kzs$D*&-Q?T14hv(YN`>$dOOC`u|C&{ zZdbXW8CNa|I#gy5bm5$;{wMrR$MERV#8h9veZv;CN(u=q)m8td_T=-Fwzih^n^}-7 z001{3J*UNvW-Kd6e9k-<8Bx3r=jP-zFf@vxlp<c=K>rY2N0%RWKB+M!kdxbNxi8iN zg_$5*myf|^J6(ithWnS%Fd?UzN<fa*9EHd2$*`n$@+78{qY3f{UOEM__!$^qEMRh` zl#?-qiY}FTq4uuPnOZoV>m9P87Z6Vmk35LECDI1+kZ>@B0|Ns#cAcWC%0=dx;ryti zL?SYiyG&^%Sr3)fqPMI*x?SM%fqkepbb8fB_4p``{ZUVu6~{v1A@vteWFW`M$yN^& zWB-dq<hr))<g;|H*wjq_HlH8Dv6d>Ty6oM<s-I^EF83Fj+uGXHu%FcgG*MAm(osI? z-+rw$J=IqBl6jOd+4yUJ`(h6jR#fZ08b9RY`w*;E2)k!uNl#jXLZ~#q-~hK>YNZNI zL4tmUq#qt>@jI`8y(1glGXdQ;#cYB@YPC0_8<=)SVoVT-0cfu931L$+iSX)7^QSaZ zBPi1}_fFve)H}GO>fHb}a{&&%;gGMQkx<jDjaH{b!*f__^;&x&8&!?`GRh6I(iUf( z2A^W&sS$wYK6WH&p!494^`{9uePh%Pd>B<{gefjAuK&s|ZWr(o7sg&wQLM;4Kv;{B z%-Q*+|5JI?N(1N=d&?me(=eDvI@2YMD?bTOkqP*7Acb{L)P3JY!itrHZA^pQp=Tz* zUVp9n<mzqY{MD6EPEHQ3j8mx|OZZL?U3lv0&(0Cat*xEiW;27UHS8Wszp{#*xf!fA zirZs#DI_rhTSl}NWY`07=3F&3?xN6Lp5223)Evj-Lzn9e*vYv!(fY>5)K)p`_i@F} zs-|P92fhHWQohalj)gs%%xUEIiU>rr$4R^u$Erz9^mzDYt0DmoUr6wAxR*=Fe7lJh zTvi^<EF>M>@Lutmj2RQ*8Sv@NrtOEkyu2sP2H5$JBQc_U_j@RE(WRO-^DTlaaKHnk z@)mt+JVd=edv{7mSEXtPw41L{Q31h0@o(ost12pNaO|e0Ytg_ScC>RV$O<@_hBs!D z)H%jFwoI#*r>-!)(bFJyNhh%b3*)j4#X;*FDeCuc{iB@839v?lD34BWS~9IH7&hM3 z#tQ6xdfU3Z>%B1)=!|xi;b*ADQY|?46yGLmCQZ@%LAkv2BmUXv%!?$NKT=ywDQ0=r zc_yd_9ugCqg(!l-DxMiRo}Iqe7p~s*BK#Dut&)>}YK~a0x>(CAOWd+EbOrLgdhB{) zg|%>bZDQi==U?1m2YObzKg%*vFO^|v=+^Z^LqH%dfk-i?1XHmu72vEo84`SerAoPq z$^9{_>z=)Bt*cAU_MDRL$9qYSuq-spoUWvr&w1||GpRWrvmy_Tp<Bkc7OP+l`#dO- zh1v|(G7vFqk$RBWnnQCCs!t1!U)#?EiG`)N^6OlxQL^?=GRR(6cSaGv8k0={mfO!U zu8rN}_B3gF#IxxOzx>G^8WLh-^QIY;=YuU4e6DTq8d($Tpv?7RF&rRKwcIu98lu<t zDZ6GRccM<{VyuD7U8XOE#2>@*bMbB9rZ$e{g4HAToD-XsNmk?9x;nx5nsWQzt4SVy zK9S++EtnouB^(=4%%OS+){#OLr5)RNvtpu;SGt6RH+mG_vb9NoRF6`8%E28uIW;wU z0JtcP2I-1<e7YVy(40&bf)I>y^SwS62u=*JVdvs9G}OBk5*uQE^vK%OdT^ZIbsHFv zC9}8Zv$48qXU@08)wVq2GVyT1SI=k(>OV-nd99h+ACsSt{)zY^ENn&AUnZu(2aU=o znY>inKxYf3D_@>gtfV4IJV92xw4p8$w^TA;b#LP|Q7$A94nVG)RBrGtS!eSel~T7~ zj91Z&&V<W|h<kmO!P0&&MXRHC4nLIaW8%Qz>T@DYx&~l-!{Ko2LRP1G(8O|YuMyEf zp_{IdTBfn@g1!L*E~pw}Nv<M}v)E7TU9&$RZFRePkGzJExavq7S0y4SFmmSr&P11y zH}}Qf83S#g1wSn;28bWi*jQFYIQBL^pgaCSabnBYoo@L1mh8g@aE!&(i?2IuK}X4Q zxJh$!bC(yFThm8HK`17oq`l%|E@qut?0gdwj@DDj(>>_I#3MmEL1GD%-172@(&D~e zJ+>_ujjLW1oqcl5D^E%k2qri#t_z~yf+C(o9D0o0(>5PsDI|Ss^CDv9t8NpvdxBVD z?fg7rTt$&sms|Q_z@fs67r@Ub-+D0uX}uq%(Z*7M6r|nL9~N19d3lBK$D#HQ6#Dl& z4$z5mE!n&aM7yO5_jm4Vr*_ZcB{gjsbZi!li}njXat|xnzV^P!&kkB--}TOL5o=z2 zT4gNd6^Jvk9#3BK`JnqYS&IJX_&lcWA|Hvh@cZ7*&ZQ$8`etHNHLAir4sAZOh;dX7 z)DR+?jOusq--IO?DS=W&$27*rJH}MbKy4xi$vMgxlEN!deA!hwlAsp{yK8G}j|9Qr zYD#(|tgKt1Y{AHGlSb{S<aq)&(+ocQJ3DB4QHu;OBO{@MR6nRhUbfj5kbW#H5992e z<yD(n@umpz1eRdYc@zt>4IT(ShaWc;h!gT0AL0$mX*k6Pq&4=&94vD;@?x}q0(q1s zuR8lIzhI0F5fDJ{o=6D^4Q=%FM0WUaJ0N~@)a(1z=Ojy*^{I@ltyY%G>=zDl+9jY) zzD!THvd&6Y_p6QsUKT5E!xkRTLs~nZ`J=RE`sW(r&>I@J8DVp?(3~nh)~&s+eKL#k z*RUlzI#<`Wd~VMysI)j?vLn582Nkj)5&<uv2WiRr7-gcOZ~c_FdfY;A=By<UsD?(5 z97WELbnIlNa$D+s-{l0Amx3wWdxtI4t*_Dzg`15gWz+6M5_6GmsA_CiT-(m$GRKa~ z%Wa*fIP7Gqx(%`vOftBv`Xd6_=jd@BkWwp?_4I6aZS7?F$?41lb`FJ9$_M`BIx|pg zyVanqZMOCFM;+-!@1Jf34CM>(FKUwB3x9zwR6_YOe*1!lQvK}c`*(qGni7kRwKK5R zzO#cv$EOBZhXD97@^|9pxK$me7@(I&YmPN0Y$Pd=(as#<I?*}VX)MD3$@pDDLPGBe z??|cK!o)~2S{u^#-Z3e6a)6dlz!!JjjP|vKwbUD|#G&}A9bsV!7k<#85jDw*@^*2L z&No)i6Q3)O0^BWuWzBn??pv(IK;||e?3sHMuLft2X%hoYJhhtj&W1+|eYbu!;Fe-c z)HuaqX`CqHB9twWgrwlutKI0dyL^@sDxgrbp%3@lD53JpqpB1mIQg-x)i^0-mBvv* zjxyGiNYy=^$KUCkNTumsB}gnJcUHK(Rb64!u6bX&R*86YdLa?{)mrN(=aIUem`VW$ z@tL7W_{iqId|*i-v<g@9$$7--9(7Knyu*8JOC%~G+Cnagz5DB5Qr51nuCh8pz3C63 z#QPuV%G&x8i@ds~2p^Ipd?$l>Dl3O5Gq6tA0lscaV)-iv69So*x6{s`3n1*1wO6G= zGOEZRh3R*@x%JH+N(AZ>xxtAoMklzq4AS&{O)QE>NA<*9r?_0lbzq(1ow?y!j0y(D zI#rn(r?aWp_o)^|ZwZ=X>;Q6VXhU13RnrYe0kN2R!8~29PL+dbgwJYQ=vjh<ciD0I zXOYl><v3PT`%?_2Su<ShYdh(;2e&@Ams~&*b|d<&VoA^v-7@;r<1fD6I48Tecigh4 zMHvN?2vwu^m%{N+Bk7+qhpCOdnYB601mT^v{UtU1A$yd)`GC-y?uQvM9l;BvFzIUS zfO!D7lwMTr;xuWcbXGh{Z*O|M;0S8r+4igJ%$5cJ-YhQlZWe0eiIc3CN)+OA$cv-) z_}p1}^f6>a6G%WJ@a4j(G_rLw;YM{4h6#DcWU5gu$tr7(3mb90xdM}^ty!f=Zpv7k z-|i*U!0)l~NA++=Bt0HcdmgF=)s#;JMUP29uADo%T7&i}H_0`A?n;ovk-VawzL;fC ziGo;3wHYx^jUNgXhGW+L#r&Zz*Og5bH!s$s#c~`o+BJTxTsL$7u1aJy9z@n4(g8rE zh3P-j^4DG&|MourkrznJ2dh8w(zDsd3doHjEJSSRWqpa%s{(kdEtoh}W^V*n=!(7w zZF_O+a0V)AR82^p=`7#*KyWE0gGVw_IGW_nGfwrwZdj4Tj?oxz^-!tA+Ka)N!}LL? zsfk^g4{byyoA8zs-IrmeskPK-0b@r$$H2qdgP+=&<nJM=6(55}eO`TiuGB8lNKqsX zg;xo*KfHiyE?uSV(8EWum<lolj&i;%%zcT#r&<<TE|~N{n7xrvkdPiA9uX4>zdBT2 z$dr5fmvg!vag`Er^;bij{;T~Z&Y0OdLBLM-4iG077{vKkW!wcFejgt1MTE&Aq5=O3 z{}U98`1uQD>;C_vbV$GQB_j~yh%fVRs5nF~|5ucZ2SO)xhS}Twx9$ZExZ_HxAt62T zLq#J0jcJF9gyamfb+v)nS##g5|GQ6lcQ=(^q(7f>Q}Z8~zv|_Wy;bf)?po~shLG9* zH^{$>?k?x9^Zjqm$A5DEyAS>@?5@N7Z&<nAKRWfB-~2A)u6F%5BRTB9D%p1dceU5Q z0pu@#Q)2H1-c=QU1^(GQUj3tFe$yE5GVV@|zvBNK+n<PP{HsL%kBRaw@$RhhHxV!O gKZt+T%)f{Gk2wYmLdW<OhKu;TM^q|$+OM<!0khc=Z2$lO diff --git a/controls/model/Quadcopter_Model_R2016_B.slx b/controls/model/Quadcopter_Model_R2016_B.slx deleted file mode 100644 index 9ddda3cdbd05db65d455a676fe14b5b871b4b78c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 70974 zcmaHSbBr%Ax9x9i8)t0Wwr$(CZQFCko;hRNI%C_mJ#)`@b6@gqUh@8E(ylaZ)?Q7T z?yjvM4FZY^001BXwZGG(R&KS!je!7wE?@uv=O1co>SAbO=we83Z0}^M;AHP$>f~Z+ z>P+WhYZIz8XE#8A`jr~?A|)NmrDT1Ko@drzquX*B+pii)%hI>_{bgazZ7%Z+eu6vA zyXn0!TtO2Af=S(+RpfzM06<+4s=UJOKB{sE1HQ;WuAYTHE(ebe5>300a<biBJB5x( zHUP0Nra4-|y~?Sg7)iUyH*q^en@Gm7l{)@hvT+=K{cQ`BOp&#VjEnM@aT7CaX*Xgz zEeIiPsg+U-q@NL0A;<}Rv<UOZO8V>^+OFqx9HtpWc|ChS4J(D58e-|r1NT?5+R4M{ ztMS+4x*uywr6n4~;!`;1s+F?2HEq7c9cjvMX=S@UW1?Fy3yd!F?d0%LpHL>`;ROcl zaFX$&h`1XHEdSEib6?}t+~)D?)N-6*0E;EGSuO$*JMvJ&bQ;*k$JrZOYyY2BLOsus z?@5eg1|m*LicBSB{lg2mby#rt2F<3w@ixoLzY@auY7L+FY033zcZ79czG-xxK@|R% zHt<ojEhGOl5&x&pum4*cTlfE09n<(pJ77jwQGe2j9u$MXN-7k$%W^6y{yq|P6xn?d zM~}Zd$zah~9Zg5hKDFDtMu_Y*mnct8TQ$W34db32kM}oCKd&i4)Cs`}klvhx()G+- z+qP7%%1R?jybTt3`+D%r$Mhwu@R)&}kgjcIOit#?Dp;407%JIIUPWnLEbC;I5>G6q zED6rH=vLAtc86wo&v)27vAQzw!D`M{e^xQ#4+kFMkfv^6ki-3F_vKpofu_Y_A!CkL zgY0IsXj^UlsO^9M?*M3G>@j8hBR>DHk^TPyAnM^_YUgZeZ}*>bsyp2eAH;wNI;(H_ zYzG4#gAGm2>#cBOy#^WBQoI5A-Oc*@mLv1;q3V>8_+4RNw>!2|W*~vN&qili*v3=W zTJUbfpW!*~`CBsZxy97nSOga+zd}TBqeMSk>r<ngIH~%xF(T>c`fOiJ4Q%_R5VJn= z3fnXct8RYU#7zvKGn|8n_zwhCd=sVd!ZCMK%?j7_`@EuW!2jlUNTq1>-3tJ?e?tMV z{&91*v~{(yw6mr+vavU|HnB7`cQUm751q?yOYeh`REkgDUSM_4(Rkjupj?C2q7Mb> z&QzC9G)cGk0}?L+<U$5GAQpg?rT))LD>`6Ei5k)()Vz=^vQj8lxlAs%yXU9ZeI?N8 zU^o&#)PHNXWeIK=rflvn!ioQuMrpeC^vKWF*TM^aQ6>g%Xu6`$RcU_3y>t8Ibsj1h zdthGQiSd#6%lgN~NQL*o)N}3TYHq2XPX=69z4t|U<0;$Pyo>aY-$~oHH8yP*$_>+V zQWf*h`o^kitLmVVYV+DNN{094OqW?6g-r|JEy@egEtz1zI(h!m5otkYc8B>33_ZS& z@k`mz2cqoO?xM6ZKycuOS(65MM|!$2R`<38KYc~-Qr-|mXeZw9b*?*@mp=IPS(qh{ znC4Dj>xv_?O#M3+0>j7{<J$x0qhjUq>H7831Z!Xhr*k*B5DDDvh7Zrj;{;+Gg8z}v zV~?kMeRauY0NTeP8MTJl%lBM%!Su3#v}H>5LLTD><~PNtV^iPOvsoS^l0fCU!tFy5 zh=2mlgx@Ziq!`Ti6VvS={f0Nh(X)rjd|Qg5>wS5ftLYfBh4{Eh7I2K2?@tGkh%-J7 zWS<C-CK`r8`|dLZ*WW_Y{MOhl{ni{?SLJ^H=6b^-e^r>zkDGG^xPaN7^=Kd&J)Q6g z0^z082JBvzwY;yP@MLR1nVOkO>7B*<5r@<#bcAwUH@h3ZM>=KAhPgj@Il28!ctwHz zrPg9=*URUdD%Ccg0;K`n)AIq9mOI0|Mg(7%HmKs|u(ut^3>ntU6P}aBvIld{P`$VQ z@7=%hMI6MoV^R~!f-|>8AbmdrG2B0`dbz6LPtYt?_g!FjD*;b-{i_a6tia>uUL9Q$ z*C_9h_(bmDYvXf*wt&gSvu^ksC3>0U<DLavh$~ieljT+|(*S?5xhHN1DN#pbSmO<* z5#j}`lb?)7Lq1(SGQIVj5sAiDT5)C-+hQ!^g*BDOI}dHvsd~2gn#3#24z)bpWFm<R z^T}F$Uvl2R@0MY6W?y1yU@P|3EqeU68%g>MvcEt&99^ase_0o2j+7dm8jukWDvqYX z|E!bw5BKZ{W@ik$5h!oP|G`j%WK=leA!a(Ma4CGi8{qoB-76FRg7fLdD0>k%Y`7&@ zw)opzALA(>x}o~*vlh?G{`9;>(B@F4Z$)3~3aq3A8%p1Qd=oSlI<LY$x(&rsSv<|V zk;3yTBYyM?wF*PX@|XooqI$|1_<N&0)E{Bw_Qr&7{CgvO=jGeUr!&6in&kH8WPFdG z45QWihx?5%^V6rZHRJO(ew^R_C20J^UxsfRZ-C9ce8=QzM}PO#yH`ez%$q$KpHFUc zqx&cG^Val!W?YZsZLe(HhDp(JGWgf)PUT5I<oB0l&x@av2lv|>zV{6ogm`k%_-`&x zf0nls{yy*iOTYHegUVz|?46Ka`aK`M&6bPsZ|*Q=$K4_NIrEUB!KFo~E*+t+%P$tr z9Jy&SZ+>}r|16&z`OERnaT6|xgPy!T$D6&jZT{zP@Ezvvt<F$~;FqdoeB4<(Ct*7T zwS(KqL!+J-){ig$y&J&Ki>uGq)iXhMZ8)CDgHeyiZ^&wd>GKCgAkr{68ppGT^AExU ztSbEt^IKnU^slwR4ZFYY<_Iu@qZ!|q;*^+Don0NH);rHdxAS@aF2e5D!|iq&k2I_M zM&PS`-uytg?|7$4N45N30-Q9xe-u6f{QS<m8@oT;B^Gv8ziRD+9<NL?#diKKv{usv zfO!w(%1!f~eC0R5b1XjrJ8%sy!fvqOPIz|_G;$r@%(X<b{|a4L1u?RJ7jvev|MCkD zti7pUl@Z;i%uwI$r@R&yn6F)fiGU+F#4M43DsKJW)gQ9+K~TA%hwy8F)Tt9-w#mv! zTn`QgJ==?U(HCv46D53a%*GRU%)+5rr6mj^&<J;o*+cN8<?nQaOr)H5W9qz1rr7Si zFV%l#{-%6XcB=xRzdPBB#F_SNiz*borxa0`BlBWG2y|*anfb)D;R{e^-=!a*Bp??s zKfN_&<9SGW<N!ARoI|ZeN7F0=kg#*yB~fS$SUPYE5aLmM|1|^TZeJ?%JQ$tR_`4bJ zz$w@HnrS>1u<~?0lv<eOTb^$bMzp0sga1UeNV*O(1W2XX?fO3jY@YRx=jB}0ulu_k z&`*NZ4C?_*xL%R2fc*t?>8w01M|P#5GvXDT1^&fLUm!tl0rL_}ueOl_`dNpHP$<wY zlL6bL6fb5ysCoA6W{WAu>;jDl>Gw7Z4)$d_J%4C`7GH;?@9vGegwCUPaaF!+N#jZ( zREuU<LM=qGC2r>=XubNaUG(Da=+RRshJOc-Y`3Tqt75etMo07^mDEdGdOAQmAWc9x zb?F{**4Zc625-piO*;{e<sw;yH4=G&9_ee;1il}Rm#EIs<xH41rGYF0mtXuY-DFR$ zd%*%rUhp73xe+0`d*57Xbll|}tn5YdTsN=%Zc}=vV5RN$<ccLj=_AK;*8>FNQ~V{` zz5U#o?}2X1G~svI%1~rsPaT4SYVDRoOT9N-PtNEWts};e!g&U;6sIpc9Kts1u6^aS zfxhYT{eX)8eD1G?>#jnsReT)jMn#LTUF+53u2SVMe~d<ssLFNyIpT?95OIB19W$=n zcjadFt$7HSc}XYe#S0m1VP~0X=c=6^3{Y0)JT+E8A9~8#fH)0E=&FvKd_4TRTscF- zXEt+o2d0cM<&N-!A}qWl2m8QX%D~Rcri)kT8|)LVFdTv~MFg4~F!an6cHZzeuBIly zGF+PJfr|C$u3br);!Ximvtr3GpjfYtaL`+BA=oq~7bPIGLIhpZqDv?krr1WV>_w5` z!^Kn5FyLs8m*l}I`zUE;#O{*Z06pg!KR^$qF1+S-Y}F;90xeGn0k@j6mem5P^y6&; zhWw7z{dDaT6<6qcOY^Z&I=!!9Ij;c69vM_3CW3DP;R1NXnj`+w<plBe48z|MaVyLq z*L+FuuR9<N%4`S=#|V-7w?@cX_`Kp0bLYZl$7-_AejxKYO#ho$Dqenyx@A;xt&F${ zbbg4Pc;2}ZoHe!rR34r2EeUP$&WK3l$&%(}*f{B<dJTLf<6HhaVFcY~{(PjvJnk+t zCaa*+`|tE^FFg-0e7Tu~CN*A2_(2ma?+Mt6#udL)@(O;{`Ae{g)|KmD9zU!e@GYnA zhl8=t6Osd-<N#41@qBg&RNq<=LkId7;BteeK&Vd=NECw6Rb7!xmGctyxtND*{3<0K z%}+sCP%CP30~i5==OB8UPUo#Q?RCZIzPxwJgfFEKBp()4$TaEX9pg26kmmNHxGk^* zGh_Uigj`ghg!LrK*G!u5pyPH!TxXSa!oaM3XQxb110|CW6sxp~H$RT<dt{|5W`e+J z1?Buhpn5o#Z`G}^JHpD2iaNfpY{tz^Zm`L{ITr|vV1Vs&p(zK55zip3!gCKXegr<i z3d1Un7rc|}&4Vv@Bmy49qOq-;YSb-7E0xEvbKOFx5Mln@KhLrnH3|UCxmt~QeA$c< z$o(axg4%zRnzjgq2k`UoI+`xjrjpy;F}^L8X(^bLzUeCs$zyZd@$Qd>Xz7-=9+`jH zeVAGO81P&p$$^l8f=7n_jWl@gfP91#!|`kJxF`>+jLJKwPG_f<hGNmx2Onq(MP>(% zERY|8QL9W(Vl8|ZHng0Ez317yF`(^tya=(p{h7a1*WVoP<E;`Dg6r1>`cU@9mV_qJ z54=prvkyh&Q%8IT|K5e1!<Shmk=&OG3>~BBUhn=o8-dBa&Ww6*gJ5}>msV1nz;DtH zjI=!@4iSLiz%%(ajoX<^NS4T$xm4>IK$pfod5y<H*t86T2NK2OcM8}9co^b5^aT-` zcR0IUod`X-@sSOdnFT4I*fkzzvf!v-M5u#RFv?7>FYrFLF0BA_#$0K_DDW&Gq7Z;1 zF^JtmG4|GDm2PVQ&#N}8Z&R=evJMeL7cs`fvfYx0o<SL|l6bw)aGRY|YEWKuI|0&g ziBm%Mno^G+%Kzcm;R3=C4*ty`Y(9;1`O97^lOtosDANc52$M$;ze)D9_V<^yf+3JE zxn#B_kRr3Bt_K~<=oc1Zl{j4DCsu!u8r>Yc6{zAd=4=tTh&qkB(NC7s9vK>fCR$d! zUqq}_)5-O(2To7ZMuZ7dTwUrNz!rgLws38q@7dnYSdkw9b8={cD(oV`i^F0Kfif0R zod+Bx(kw=8v>u{(42M2%H}iACtQ0FL2o!HuVt4b<XSY)zy5LM%)R|z`Y2&jAu>T41 zvo4?L8MTSW<a#?XKupRM?}d*lBWIVDO(e&Ii9DiknE->r$YWDnL`SO;k3+y~$i2)x z12WHx=zpvpLkCFn#1sTW$JIw8nLlyf*A-{it6+30#|!26D8LAI28qy?byf!x4?w~l zom-SfE><^F8y0ay0kdc~JOzuqw^dpXL8Zlx5cu%p(FM1Q>81&C=@s2Wr${?HV3JJy zco^Z1W~d$1VlsAsWCY+p)xMjMv!bQ;68=edciDy!W3i;B^e9K==}{;$eW}g^EHOMa zNLb7hf<7SZo{=}0MvXAQCk@acbTM>13(pZsPwnL^5SGE_T&XuXL=J(E{yJCm;Z0~` zNFO6p8$tDs^LXn!Yy9g(!LXxXupH~;vgn7=e!gcf@GZd?O7oAbFaJGVW|_rym}?TA z01lXWP8ZyXh~9;W_$pc68Nd=x#{*vpto=otK>mI9_&BU_IoRaX2nL;<k1a~5P-)*( z;NRw^xiMhJV9x`vvzqG47fu`uo#QSYUDsB2TW}+2$Y7&LNHFpPSWW!)mpw3rS_!U} z4`s9RC%(`H;OsB^JZLelmo2<X^3#0o4mmv_MlMLj0&4h1CM11kaU{-RIm~XFFeNe} z)<h+k?ZD?=))jO7-5l%jMP_yC%5xo{gWVtyf(euoXzIbR(EbjD+BQ89KXQR)!!vap zNxA;ot$zEyA1_xwdP;HJ#TATi40iqdL*=5@Wb4^x<hR%1tK~Fc86t%~?*e4YaC^@J zY(iGBhI`nIkZ=ujM&q0LhJ0QTqQy6kiOnE|?snk)P8dbBO_zdOINcdSrwo5uP=ln6 zX#++DA7~7^z(}l5B_e!{Pq4!e(4JAjmkl!hZu2UU8S0?TIv9AddO?72mg68d1g=A~ z>RLR|T`Iv&C65?`m7~8WTB3JnrO2uGSg?hDqGGgADcl0fVrL9#6ob{^W5olCOx+MG zGf#wFq%C?xZGW(Gm^r8;_`p`p_NEk=S#mE^v|c}-E%-D)Xtf|vCv^U18guj)EE-tI zb&i8YMS%;+092M8CP-{?XLAjsxlG<f%IeH8p?AY4Ay2Oy;*wcnzoJQ%uId=;43Q6& z9>g1Bfv(EoWnlS9@l0HKkZKo8UsuCbaqJ?}#HSsic*2!IAr4I@eNs${2i9*RuKYUw zVp5Blk0@y@<8LB@|1oXm4cK%(0z)MiG=0R*bclS$m&UO9s5Jr6enz}&QC)1)lIErR z1;c^4nN6Z$b)yH(<2b145=*=&$^3oV{%8zy;wN)vm!phelr^s%vYp{a0JQ5MpqiE< zok*jQf%U5u;>dx~tMNy%A^=z@DBBf`es>6`lS3m5d42gbiPFqPh23jRY2Zwat~ePn zm4EWl7L`~;bGeIh^=mS~aec{SjZZ;*myoP=%PBRI<s`LLVn|5mnRd>dB*ic!T&Ed4 zy8fFEBY{)od9iUR<!uNs$;w!$?-*xJrfnoeH(-IHa&C!3nl%t_vHB%FF_E_aePn{2 zmd!VVLX~%}Qnm26b5e>UbQ^u}AXXRKz~59ccrm$~_duc>3<{SA{m9jO+Y~ex12rx3 zufe0S=~l9^f%09yp5Cs4B=V&v(>cV;KyW2(llj06!*lom@E&2ZNfkVZCEw^$d8^mP zV>dzyRz^7k?TK%pkkO%?IYX0alFa<+dY%zfat9Ppcm}9*2H?XoYB02H%3%3EW#0nm zAhPjrdXpevqK^P~&Xj9Wz(lgZ5{q>t?i@<>4=CJ@>>M}*x$VNcj`f)_HB+snUo~O- z6>{lfAjrS82-&^)$t^<XiaCEb*Au#3j%W5N`eQtRa2xeGwBa-p!da9GiHu@NCZ8Mr z?pf<GEcq{pNK)FDI*@TqM=i3|Fa+QemyB)DMeAlHuVET1^4<5ZA293Zxwdp=oPLQj z(z3)>o8A2pZwA_WgdsCZ4^ai$rH%2+s60PjQufgu;b?tp-=8}QIvFjS!C!~a*SL>0 z=8=tDrZ&*)Wf*u9Y!l%?7KCs^b-e)CzEf-gq^eor%2dX;OWjM;aq*<G_aqN!0Xu)M zBcVqjjBcE1!!ekH9PruCBYGB#pgvs^O*w1=7E`qds7pM79D^|=1_neQ9*!d72IU!x z-old-eDbqs=cOD%uqLCS<Cn<wS9xNShkVC0?x9pe&Zy!<Jgvl*vTxVlB2t6HvWgJk zq!07iXAte$1y11ktZF^7wLX}cC_rkpo9_ndIv!Fnz*}Y$X-OWp+Pgq^8c;=x(iGQ| z?%!L$bvf>Q+_$7VMZiWCRLwoJVnDVAmvvI50=mpvifN@<ivnesF+f~hSnNy)Q`oXH zG-h|Jxt^M|NR*cXP`{pnBL_tcJ44*hdnS5jiH7S9G#_c|qhk{Mx10=2)ilyo!~Ink z2#+IuwLBiH=TQ*;IJwT)npOaB+y!OOIe59;Zs+Oyx)oqe#P;u*Xr}I?!%mUl05@}k zg^Qw+?=FNnMM<A3(J;<J8rxHWPs!(Dv~PT=GRs;k*W>;o7;5Pk7k8%U{?4TR8Y`XE z;pIQwh5>MwTsEn`qoziB3&=^$C&?w%BiPgxKTm?f3Pqbu=@M9(#w9qJ8l@`PVKkAg z=>M(aR%I3=EXjdT@c%^5o<<xU#0TnNZ=`tm`RsWaEwi@2K9;}j1sG6}s{6+Xecrg+ z{|w>j&Uk-bTuw-H|5~Sz|2*b7cd~J2ecr=&Y&F(C@|@`#ayPR~KiD|BJF$+7iN6D{ z*<IrK`9cm&@M`4e@|6{2Y5e4U_~3Xq_T^F4H?D3TW3F3iFk}v+SkkX(2r)~XI_I3f zrrG;Vt~#PMarkQ`nofDp!^v|O_b%>Iq+BhKtkK81IB3csz;c7Ze7(U%t$Qox?1HVR zjcze13fTSjQ&GqSvL;w56-6ZfA%F-uuakkBaa@1}Q~;N=E~W0E?*JCfKz-Pt=`6Oc zH%l?AgP-IwcSi*4w)FHpi<nqje*p`spKrf^n&M&;|1$i<5uUp_$P?<h9<1#XQ_T^N z`!<;rymK%(R}s2v$CW=%)DoP(8Q8=4YRSj`-=l3S-t(4!;&_KU&pba~M6h)!=h9Zz z;!GU2awMPGLnu9;UBvG|;Em7?V~jJun##zMv&_5>xEfHG))T_M6>^GgY0!C^2F4#p zgY-8R>*$D7^hHX)@-<E?GU_&ELlm3H=V*y`$Rn1*Jeedhi(mkq?5Wz*=iB=+{54<J z2k9D}V1fgUM`D~a^*4)VnUv7c1gTYW45%C!1v*8!h2Z^E-VK@kgRCMyG1U!iRX02` z%<dPggaE<a_<0U<!%pR-d9zy(4N$FYFl|I%ocN4Xsfoc#JUH2EM_O<V&VT_sSl&AK z*u3IR8|Bdl1~`)p^6(6%=o4`<qwg3~|K42N@8CFDm+2TAk7WVu2J9D+*@QJ7XR52y zmP9fsW^Xd{A+68TQ0W0rQ;ngTf*Edq;VH81CnmJftc5`?tWzekzDipZrEXqy-SX1a zmvaoM84Rn<FCi=iGyK3GEaRpENGC|o+^qdGYK<}?#EKS$s-60t>L{9&<vR36^a-IH z`=$zwN-&J5m1d3dQid(J0xLAdfSj&OAt)Q?#MhMHfW_k(R-Hq~rbFYNMND}VJ!ycR zZs$+HDo}|k6BAWru2gFL9)e~fDk#gR9Jot3Yy~dxm^mjB5abO#BA5xDKxyD1=WGCj zdw(+n^bF~HP-f&ZFEis_K{e;@ze~b}2L<&-Y9}b0MOH1<EtbjUDabX1ZyvY2sL?34 zWL%WI$nNvXz}CeBaS%llUt5XXX`%3$WOj3b5fB$Z-t**b^b_&a%P<SJ#wR=N!4&}W zfSS^j(2eIm0$XxzRZ(C=3QyDnx7HR43rjoz7nj;YZ4EvCu51;tK<OcdA+`lnf7>z= zVT}&3j3HO-GoEUumJ9Ci&1mspYs$WuMP(CWBTV8>Xz<7}?T<d$^4`JT`C>1#?Y0>f zXOI2rwExkoRcEZ`HNJA*+C*dxE{v^;jgGB~w%3WPv0rWL8n))}xgF+{N*qkDAsube zmT+YPXFMcb>W^C~P%%feeGgGR$<UmowZ19cg`?2LGqS`9#T;lr*s%PLWR^8ElhMQb zQT~z&9N{Qd!Acq~@zI&|uA%y(o_lRxGI=q1?^2L%7%gRz7`HCExWzNZ+}}H8do@-N z`Mw`9^su9Xd)v;YQo`<!=Ta>{_TWn!PV;yOD-KuN)>bo0s1*;6bG#KS((tbmXxQRS zZ9%q!Ta5opFa}v};SK#>no^gaY~#(!a*GLyW-UP%Q0gpf4&^G+r6>|CwINhrG#?CG zDm6aC*%8Ha%rwE0wAH~>%j~YVZ!lqHaD*@I&K8RvkTf%A3x7i1QMq>F4J~U*Ko2U~ zS4b;zT=iF7xUmF1s6|lP);e=9{bc+o>2Do2A{ymR7NW{<6s|`!K}R^9j1r-Wlzk2W zly+wljE-7pud3NyZje}~?`XmHba?19-%CHLXEh+Nj82`);4^8aMoSrMs(!vc_BjGP zzkE8Wvo7T%>1JR_9&MU*uum4}EIlEZm~kn|a1T{d6}he}NtW%^7Ya40ZYl&cPc-h+ zP$aFF%9fia#y}NB5f{d0(4(V18uK=<$n;$-e^fBZjCaKUS=b7}M^aQ9(!;v}h|0ID z7POwm^i$n~I1y5vMuAzZ4aq|^5T}ZN@emOP*A5J{gQ~luW0@b)gr5&9#OB}YL17~x zL4R>kE4UhMbUYsZwo2(6i<wI9bCSvhTYMIH3sLhEPJ5N8uYP8*x1{s;Cg5zB$2CC# zReVcL((cf1PAy}O<Bo#5tDlDoRh4zXJf)2?6vcEN0{VUf-ucv@Pf_mcRvNxZ!3JVR zPD3aTgn81SIHgqRejaX5fil+EdF;BMjxKny1x_ypi0UI*GLYSISO3yvHu`aJ!dLA? zhVxFx<0M<)hFB-OU%a#!AyK<muxt^GJ-3hu#bzl>&oOxR{e&p=Hz9kv4dII7`IUbA zUJm8&6|TN?NLK$7?|zy<G$kbqcaIw|zUAtcgUgO;TW4*MpKyAlZ|4d@JBc9M7$ux- zYJPD?hDqyCo6B$T6wcc}6nwp*2-E4x>~gL42LbHxsKd-0?G~SFd7g^x*t4}d!hb=@ zWRJ(UIA+qV(AEv-pkr|q<cJwF|9I)0S2s4e$tlf9+`mz9$;SP{#=oG+Y#gd}(E6;M zl_~B~RUjMI7F{?q(m@m13M5F1>wgkB42>p2grh{P!5yH@J(;Hu6dQQ*%D)4qL9$3= zNZhk@lQ-#l6=IPUw*q@yLdF!5Hi-Gq1m1RxG{A|xajtA=*=FIa=R5M9hCvlvV0q6Z zqrWa;k+qZX6{C!!_+c!c*!5yyZ5+&EI1^foFSB&xmi5VbAYv4yEn?F0vDMV<uy@wn zn_dAxFu;fjFkdcvY?f~*mxl0(Ar_T~`rAG_ve|?9GH}QO+i%^?plz?-)fR$}H#3q? z$iu2W-{L<Fs(YY=z~)d+YjE*>-9axLj9=_JgkZh7E``Q3`))!g=Zn9v2A-Uq(FUF% zx<bAFac83~ZG_?y53+*kNa)*0ZYqh4(C!FPv3OyTC-j^|&okGrmXioe${=5|=qY8J zLW;WO8Af9gm_U9Y(Hz<!ossW?Nr54KBCoAiM5wgT;*0D@B^fL;6Y?%I9pvG_iJ~Hw zEhid`P;?0V#jVd`jT74pT;xll#u%o7sx}_6+G7`>^0+i1up-$E^c7eMR}C%r<$y0< zzRTGpIP>YS<)vJ`Z+Oy+@B3M?A*HNUG{1;YLnWIUB`7=X&%c?RZR*^=LYq#2?$PRW z<)T9OFL5+wz@4Ns0@D<%+B<D5qYkD_GP;?V@mr(oSO3bOW5J`IR)LP~IS+lknoz*> zcwMDYUmY_nBnJ2{rAWM*X&_Qq#O=U1s|89C4YnUeO(er0{BTh#*Z>@oRR$*utq`2& za&S@%(Oy1UEMtnA*RU}RH6p5GC>I9wS;jzW2nn{lhF7`@jUhdydxm6xPRJo{&ZJK7 zCG)r-N))aLw-igeD2tVXOaTUXF*>D&_8(*dB?rhMST+O|c=F5L;?vpm7!p`Yn2t7c zbm#q1X943qK@Dp?*;ebKG{}d9Cw}RTR;F8#DQ}C~$3{1zYjc|2u^L_Z1vE$D^aN@i zUCMABYhqdAQ=6G^Mve(?5{r|VM8*CzQZeLE?36VNp;VcLg1ced$i)yA8?k12p{~rO zA)UF;vZ3g?RG2#7q{1=rG)^M>UZBPI$zD61zkhDbb}zC&Uz{WG!{CZ>H`t`nXB~{M zRc`-Y#9Wc*(EY6|+V|k(3jBJ=RzmRc2##{X8eW;0Lz0f(itn17{B-NNOcG6L<+R>j zRKMsr5$?x=16T~_$^{<!yq`VdmZ3Cyb)0tsqz>}7I6#dMs?O&8zTCpZf)Vw|2Q8T& zuwR^(H}bQ0Zew{*!wSAAH1xuuy2wqvj=~6cJ11JxZ}~vMbP2>KQuPEOK_>61<IBOy z@0U;U&_l*#-h=7eWA`(W|MPQAq>m!;>yY{M4al{4Tz!h~#>idkk#L>yo-YzYBvaG3 z#UPBZYZ6K-A*g$}O!J(CPu>Q!N^UOH{h@FF&!y!4pZ$lytKqV+QpMagqBt{y3#t%m zQ;FP3XXc0?=@L&*D{yC=fLNx)3n26F$N+1){y$t%!j0#|VDpaAb}QSis5`BN_?xOZ zeh%Jiw6BT{7?sm1o6K8XH5JP|6G=Ck(BJ1g!RaCeRV9`qzl~N!&-Dj!S|)i{FCCXy zv}5NPL+ROqr1I~ta>kRAjZ&Z|B#h1~<)K|XU6>^1+0G@_(G1QKrX+1ZAFZJHG#?Z5 zOO|9v^%pl4F4=wa^~uz%BSj0`l%TG&-(uZfzVG7N@1mqA47gR7BWJ=VeTT6$+A+d0 z=7^`c6@cz@aFQK|g}HwLJWcB04Pr!b>%cFlBE(mKVgw;DT>=Cl%Ac`Z08$_SGx~3c zz#ZEqfV>#wkQ7$-`bn&TE1(434<LQ2#SrXDx?XevIL-%w<?71^QTc%70+f9H&*;CQ z1a3I4zTk5}tWS+Edxp^V5#^{K7nqPJhq7ED!B{iU$X0K4L#2o<pu_~LC9}*#6I?o; zV&D^3Ol3A9NmOi-xYPs-;dc^ipq7~UnMR6Dg?|Z$CNw3>mYGS7QxCejUnhG?ay=ql z1B_O9O0|^~`rYe(F_|G+OIosN_gD^%T0^2}g(scGuR^0T*9IgAeuNAg6Gf}+T1@|F z6XL)SmN)6)1`}dxc{V2zd$fbpOHKAQi36d#^`uya4NZZ}n3X-#?fcX_U4ke+$5(E- zrUnYqb;*x*-$FFb?h@TX)kqa-fvyk|YR0jHh7OX%su)7?@rmiiziQV^5L3v11qa)i z(W}_LxGc4JS~eEt)}{`Xn`q=%-^s|hrah63dS&x;{XGyV2SeGniH|EabC5qn&Yo2y zB`DOV_ER><Wz;KU9NfV|pNlR;0T&!)c0T&jnpHcq%ZTx^j_S=Io^^(Um%eCdvg%Mo zmdTe;Tt`w=aYnUHa88#~;L6L)Os1I#b`$4|(;}3#i|c=f`~nqgbwi+G#=G}=S8EyY z|L`b%u&2a0M!0*bZnI(@Rf=)$*B}{*wMR_|wrAaDW*<hhj3xB|-Sq8kVl~*=lIWQZ zh*!mmP!Wd0(DX5BnZin{#$z9a>_J*D2)$#LDgIz;4Q)?(w$H0Ui4I_35L4G=AtnBS zK|yM5f)qg#pZBxKX21G9(|>F`fBm2{c|1kAq=kH50%Ma|1bfs$>2>0?!)EVHQK#C- zsZt5(>44U5>g3G(v)9_AM=GHg^wcW-Kz8yzmDL{V`E(3|IwhoJ8hz&GFCI503Z^k+ z&A4?<AA`(<M&wvE>=G#$X`N1TP^Yc=P}o(F?*3(k@{1Sk4Y@sj{7|=fJ;zqxO)oJT zSZ2GqGUSXeCikUJn62UR=oN;K_xz;<T53aN%^sE*UYx61kRhx>f>^s8JaD^fGv6Y_ z;Pq6Pnr7oP(pkJOhrc5_c8ioS<)IDM4~cFP8wqd>{-MY*Nl=Zjj{GEgt^PH=#Oh#A z3}z0iU@z?4VF_udXFBA?2QD;;Q|WScvSxpUs6WrzNDq0Vrh84imwOafez+-^IKi?j zWeNGfCRl1^v~4!qm2X`*%byKly~Xuy8Cd4Mw@ljLRuOY!Fg=eR1hz$S#|M4?zNZ!* z3g`OE5eZIIp+6c_oQyD}lF}tMTO4Og+U2I7htUf{2)uYugD1eT9QJx}5zbw%C)lld z{^)a<#M$FAfUvYa-HV%)<p-)TgB|gCJ;jUiP*3PAX3Q0}bhO@Gd9$4R0K06a4_bR0 zJ&=TZx|B50Ku=@zysi$uR8U;m8QVoBC|@*R5KI0@AlSspON(XIAq|95@3iz+boQYv zTSMZhBWUyrj)J%Q?(kC!rZ_Gm$3EBfz8!Awaxk~w&%?(yeq;87#61zZVi`RyUd;C1 zteEGizi-F$v0Zpk_R(C46ITdt7lrabbdhzR%0Al~@j&D+Yh5grXY#?TueR$0T7nsS zLRV-?RjReDp0JM$hadFF2UT8e?-Ta9HySDDYcea}MV7;p;3LX}QG1zkImO({U0UBS z?gxS~&bB883bHl|03fgmr*IefhN<!wwtOF0mwVi*LR?x0VPGtJrvOZa8YdPlZuA_= z-N$wAiKn!hZm)Uakb-jxW)_1K2hPFVXBV8J<foQUG>XC82z7<_X#;-w??LNwxNF(R zpl$FVo$0kS+XJYogywk4>KI~lb&a!mA&u(C^eFo3N0X?m@{;m4OX-O0R7zN)69T7a z8mDO<c7<hh9;7AYQ2ECYngBHkU9PbD`E1e%HSBw1Eb1w!yO>1-2uVUW8F-88E<LXD zdT46yy83yweHpQ@v6BW0JSh$W@EgX&J~&4bqCn&!b#D~iX<rr_Rg-N-Qo86!2D>3* zEW@TLLJA;$?15v`bE4sw`h?+lUlL+zgXnsb0|;SsVm#!%=wdDQe1lODr8#O$3`sEt zO^m80(-CngV<{3j<boI%acfgOTO(31cKy;!1q6wx_i*F-s0_(iWM)Y{sD}Fdc{Lul z1};$yH7(FpfWZ{|!Gi@=Sg6w95=gS*13K#NP-A-Qo0O>DAzw<y47gWM$Ba~X4_Spu zK{D>B$E3*NY8M-n_(<@4RAP&8taqfPK3Ew#kKYlAM)pF2RS~_3f8$w2q#^#Oy*pR` zNeW1GdX=X-@+D9KKFM)Gq(-8UBCsy8&4ciR`$c+AS6d%LMx?b85CK0yyV2~<+l46y zKS3N!(066%fQP({RqvUKN5O{>jneeW0}E_h$b<-)-x3gj<v9r)SV`^<9278JuLY_W zLIMM7MVT!pfH(`PR@E0JX&NZtJ?=#yF@^|N2liSZkiZBgOGZ4K5kqEG=culMoJfu> zfjsNBESl5@uQi9vI^yX|Q-6?4Nl>?cK}oRs6+9c0U=+~T@s<TFM6E>{>Ts|ls!Y*1 zR^7!WzLzD?yZk4k(OaS%H#YG>Z$||eM$=40`BUaTsQM5>Z^*IaDc-ZfyX^$k)!XDg zDHFbnVItH<1Jqu6Ync{rS96w03GLykyTazKgK;ojaZ+xD8-cQwlhU?kMH@f1;fak! z@2=0Nn-i<l`cG@Y!{%WzSgZKvdU!7F76Qcxvwp)TjvmDvi6_o-JWD>*;<6&I`P`#v zZjOEP$RbRs5<;!%v~Dn-JB#}ix@+gf;UV?jZZOd$z;`H_Yz+*DTR43Ki-Kt@Fz^gq z2S*i^Pmc+S87O}q^<1Y+o$j%;h!uI&5itGplHLo+65_gwFbzrul%i$97r4qV3*@0G z(T79&k+6jfcvU$Cm+FG$xPvRR>j)_!<qH+hU)YT1H+>;c2;Nvv6ce1yfoyqh0t$9T zvOVoM?K#3t>RuSp|GxhLU)RvXAg3bVtc9~Bu#0#Nvz5Ao8(7j-J%o)p5R4cciws72 zT>Z^Ka3C;5IL$%P(iQ0ZD2GdK#}WO9`9y4OHWvavH#{-VgL5t-EOebA7kvq#m9Ta; zqzIie<aW-v|5m^MFv&hvHrB;hzJfKbGq~Tkmny84RcV`Q#O>Lzsb&!2M~x%n#b6m; zA-74^4k>Lq<i?+7i{YtvUhS}T$+(NE(6xJnBI?)ic8sGz&}pSZ6Jf!9YAPO92!$L> zl8es)xWQektg>o1t&m+U=<_!eV(4+KGPfkA%&t-mE(UR2MS(!RD#7dktQ-esy1I2U z^E#pJsVCln`r2ROIcz2iW*o7eOgKZ`2$ZL7KjsUE2QC8)>kaJf=>V5q`Yzgc61N8{ zPCsp6xZb8@@xn^h^>HqjtXRj@?pw*pD%GVqH8GgRG;I0J5$eUI*1B>dd$bH;Z4F@O zu1fq|B-rtroW?)6I&qQ)X!%7(rqcqP8n;CrVPYpbKS0n|7@$eSQXGRY#1oEAB3M-M zq7i8{DdLOF)syzzM8n2$#Q3A?{R<(j4+)(E*A-#$5}wo>=yVar%DGox>CFw|`wLC) z6+NU%(^e!ZE7f433c;Z7^zr;mLyGdQIM4bqRwQ~6(1^<PtEiMhrZ7up)D$8a0+)UQ z`<dKG5<;Lv2=nFmM*FyLt0y#iNz>;QY=rVr!w;w@+iLQnP@b+HcRa&utxL+RLVv#C zrj$=Z=%*SxnL-Mm8XGep_pk#4d|!m~h)xPf_3Z3PRITKVeiNDJ(Dv+H^&C?=jjdI4 zWUTXeS2m4RJqMgn)?f2Vre=-Ju_D)|aGgs^oS?mryrv-9y;r7EJK?SEyZVYNVW>3I z)x0^T_C3{8FmhCCC*#Nw3U^hP7HD}!3W8wkiAck;t?15TEZ$x|>KWEW4Q<ljEXqy< z{b5B$cZCaM)MN<O933&wMx@vo+K*72RYH!A!PeO_s8@6aiE~Hq%wOt(DJnz#^iXvs z#-SQzZ)GT@^ZV+8|H?3qu%Bv5B#urg7i7p_98>FX_`M6w>j%{|N1P(S{YjigjY;Tu zrn+Ct$xu=%%w}yGb=tn*u41-x4pt%r-<10@a1p6FbWzU1xgUNq{3RH7yCrC>g1Q{I zHu>)lz{=e3)4Jq(YXetH(H|ygnIfMxq~NGrAzn=~=FlM2MB%Q6tMD7^Fl1irRso+- zJht5aUjakTRc=+$RlRNYc3P<s1of)J8iuuYGaQcZ8MR$dO4-)-Lez2z9^GC<M@T{| z&QbG0gv8#fX|Ql70^V1^t-?bFSK%-~mbSJffGR;UKd{Wyt>v~l!Ct(n10Ve<-+a}@ z0XLhXOzWZ&cYgB$Qcj#@8+vLB^Te4ww0j->PHFhbDCt)LlSfiPDAjtjCr^(Z)Pv;j zaR*3RpV_vBdIha?T*uun=*U5(qlkn0MlA4s0sN^Pju59lEeH6bUEDAR$BcMcT;U<E zcZ-vue#JU1=l{U_LyX1DJm`)IkM#NJYKyh?4lMbRAX>~%lbA5f5OLyGB?^`s=VOdr zw7;o~dOegQayyV&&{Y*2$LtG0Bgq|+uPAj$%gfpnBZ9KNnbCVZkyG2~9`T`IZ@c<@ zMPrCu5wwAv4MbCU#Z{RPQi7p7BD1aW3cNhwY}&?D%SBcBL7No?Xzhv{eoJ(Jz=Lr9 zB4qFI$@u*c@sbiZtUEMKye)qoAr8*L>$xcktd4uvS6Tn=QJ)#7pp)uyy46;OiIIqy zUhe_f-&Qt@lnD8+dpOosCV`s>NUztiDP<@dWN?*#B<g1{zB8z)S4oH*A|ytJJs2y2 zfh^MV9}<ug=fU*ZRPRd}vpkKkmoF>JcP;n_2Bm#um5q6Fpd;|$N)Ow%!e3g6EabGc zN<GOzm0z70IfbXc#U*|S;`i^DGBD4PEYVm&i-+`$7b+4v9k1tl8=lX5^H`k1?)gd0 zjbW8_j%6x+f_v8Jd%c3+fy3+Z2*a|7rRaIW*CQQ%2(skiZAAk11l?IO2i}50U=*m~ z@DH`B+<&uo{xdl<<pTkC*7k-$TUe^;fy+3DObT#pVePDRzeM_bE7y?vNaKRxbpBf; z#Lgk_bzGAr4`N&YM=CK^gma{A<0G$4N4Ony2i2vh52a(-90r&E)*oAHrTN!+35d{V z@w~#VTArGZsIqC4anU&?w$x@=R=C*Y#veKTF1iPhG-&!+MFOGYN<0t@S@s411gD4% z@5la5fK~B%C-5Pkl%u*}rZS~Pz(G;}Ni3E7wgCAw<O-?qQ+Nn{(c#(h%wt=@DM`?1 z>>s{c$A^?@Ov1qC`OX*N<6nJCCludFG&%xO?YIzrB2Y-fC{?RQn=qjhe-tS4Ohr2_ z3T@D$3O_^p(1at@=z$UJ3zyzFoS~w0ir80_)$*|OE5A5`(#sWU7tfvrlH0*RC5KO) zOou8>;+Sn8fv1_<y^a8_@lL-T({(uf&~rr-qBA5CP?k|B8=|`mi|4CAj+~Ig6r(Ur z<6ugQ&~D!T<4^wKd~Nc7p1do#|GqqcIC?GXMiBp)VDF_Zdc0bmo;El3H$U0E1n{%A zF6HJ9;@>S)k7ZC_q)Zg1P|U~ee$>~M0gadK|%bV${LC~ry5ujZ9*G`fUs_%qAz zd_(nM@`dZqn$P4O<@L`UP!Z;kUf<%J`h(3}UN$Rx1ch5Zt4#WBjdzlt`R-Cu7Gr!u zx@~2WNuE7L%aY!v?xb!|^FOs92KyD!7};O2xnbC+^3Q&{%}Tu0aUW6Yi8OkH@lJ0S z=mbgH>UOO7IsA}y(xEe~$Oum2k$<b-#Fo-sH{7)T=I@o-$*9a?4<PP=DtcXq+g`3~ zF7LTnk3I2gOBIV|x9Ge45KSqab3H2S>y)A9A3Ci$O|RLRuYr+})Ar*4;qV191D;d$ z35^Z#*t6B$YY$4k>y=^_e${IuM8LS|-W`$ts*vs<wGz4FHf74D#QZTh{G|Qkgyx;T zhVy5O#ep6$*WS1$n<P_9<bOV8_V92v-1=bI5V@lS*_-Jw|JB6!$84J=YHr%QD8Tn- z7|}36rvKaj!5r<=-BU9NQHHvIp>nY8;5k^CG>Ti0f{8Q7BVF$jsQ%5;5G`9654Ol+ zfg~!Mg57R+rca;bnHtl1+|8LRdZi`#=_W<Lu!PBVuOBqi4RR?P*Rdi=?=2G9gI%w# zMn;J=FbY=dW~!^+|Dfyz+Tw@~h)U;mnV`)+>HcEy3f9VeWjD4__Gm!1D-$^G>v2L^ zCxW$>K%6~?5{5)B-~d%1O|JISL9R&d5em<?ikY6faBUu@1L)~wLAkH(1?ejf=n!%P zV)tuU0iJmee><02T(jvyyh)-8M&-1Xq=tm~XF9uE9EK!+v}if+OVf*V_SF~lL%(0E zy`SXvgs{sA)#5v#5Hvt@s66D54%G=%RH32Di4^dBR;QyYtM8;{Wwo*`HA&T#+Cp_) zWAkpW*VC%B;`N}WhVfqFO{GnmCH#c4%vQsRD#Dv;c3pwn4UjKc4lhII#G)aNeq6@g zqiPQ>OB$nn)RP@mjk{y%PH8bDFa)~f#_^)8aO)X;RATdtdXCCXLBs*W1II6ElT}ZC zRJ4*G6W2T-9e#h=%L`co+jR{o$IK%0`L(y3M}p5Z0)odRe`?}Mu~WQVWUrKbCrcEM zg*xrPie4dHn(L078$GkasmVEJ;*(silbot<jXnMvs2}ui=A*2Y{0O_I=3PIlW*b>^ zKPzV&Szhj(uY)Z7pYeXyH)OZ_-7H+4WTL{=-7KHNKaxhgSk(_`_iTftn)eI>*)y2q zYo}g^jAwYVL5=@X(mjM`GsZK-ZLblPR^9uh8AZ!5JSMnf;xs+RDyOc^esDL{Ai1gs ziE!Tp&Y6{wsonO+muVKZ^)h=hOj%~T&yWty+&W8qflqaP>__1Jl|I}cOtvic%Zs$` zVGsmOu*{{OP-u62U^%pw=jBF|^-p$Ka!5V*V3BmnM?=maV6@IXG_E)T#+snDM0F|} zB;w*Ff%z4E^%~LR_rw$Ly)Q-9V~PfvhDjKmtH@Y<w-Mt<Og!>HM3}Sf_0dd-0Q76j z#=j7Jx9EZ{2xY*bw9~~1!WL@l+GJ&uVDqbMQ}R2qgGGldp`i<Q!t`R)-FlvWb%fl` z8^jgN%n2jgG$_84%?DMB>FflI=Od5O7Ye_7MDzUSf=l)WeU(54v)^)vp^)U8m6KU2 zRZzuOqMMc>_60b>_OTP#P;FF>H2(&hehr_qz2y^!aU%Mm?Gu|T4!U`xQx4mE^^2b` zr;vGLn2>};+Jyzi423`qkX2M;2ewb<gcW<MQL^c?=Rj<~&5h<w8_(nhJ{7uuo^A{J z3+QDJA!y>Pci(Lb3WKk{m05P>luoWH^L?D5trJ|vz4uch78$7W7+(lD9;|k&_kc<D zqt=BZe#!%dBNEW$3l1@xf``GN1n7)ZfEKrla!GE#*`QCbShx$ynF-2$YS8slYva0L z3es2q8CV#{f=NUvh$*{lS1BnHWh1{-#*eUoQ+%Lt8wAD6g23a7V&a<c7xgQ-R1}ll z%&r<Tm7fX<;!0bl)fUpS_sUiar^=xjiP)lXq6|sS+S}0v*Yk<<P<Qe>gV?13y;lr_ z4|W7ojYZI|dn~Zax2BM2M#u)vooYjpdaooF?DY4B?U!nj48#~wRV?Ao-z_i^&LhsJ z#>BQl>57x>(qK{-V4NY>IvWe`TX(@473kxgY1a(w@REVe#fX>vXNlYsmxgqO2XV#3 zqOq;vWrB1~fBhb;+?g$GhpW0Cs29FRXX_3jQZ_;q^OUNN-f(a;4R<!GM#xIWOrzQN z-M%s#VgSp>nxiU6G+Q)TwKZF;*3ryGs<9xo6mvaYpDNe%XlSuYLnO@{(r($1ja0CU z=OD++k}=Y3OLN}e8%HK4%hkweJj%f|UAWB&DLq7tc4#@2h6RF@k5nVAAG&O;j8{ld z-w~>MMpu5P+H1ynU+{bsuL{s6?xlO<jo-^|ipnCHo}0_@fZZtw4MkpFCwZsq*#Wu# zevGmzrz#cdVyW_4JWGLI6rdpJ5_z2})*6z1B|rixNXnEB!iaDp=d?_tO^+QNCny!M zkX+~>aloSwwnr%;lO^sP2*F5Ac@ffEOzg|D;zCliPR668YI`;dMz-Ag#ffA`R85;h z)#E_yRHCmKgDIkInauNd-()TlegPZ5Eag+r{t0$}$(jV)8T1%(aeW&jt5sO`&#jg~ zb4l#TMNQKyJgIsviDVS0t6>c(TV#cwtO@3An2Vthi3D(NP5t;nMgws!VJxb_+Cl24 zSr&~qO`1?-U-M!^+dT4>7-W!%k)%XHMjV$Cn&*ct4aL1H#kMw$I34m$`(xmp2v3^U zbfh5%)r_P`eXLQ9<cSv?cwzCf64XhhEGBr^&{l}y(3Z1V_<F#U>iRJ1A<`Xq+CNS1 zfgEj9$dr)Dc94YHpIQD0)=V9C8tSp#5MV`~VUjTp79Qnz#0(ssKY<BNJ%KJEDKk;z zhU-e_5;H<!NsSyzhgeSvx6kHtM}{P*s_3#@!%wT!!E64ah9+FdAGX<ozpKnhOWw~+ z`{kH9%D7x)=eVastly}s&jZDjoI$4SPbZ(O)ZRm8E?K_5pX~CQBg9OiA)4EE9$3$c zktu-uWRgX<6_s6=!=*c5z8BJ3HAcg#>50T@@zrc_209fGm@misp4<wgHY5*sNRcH$ zCW`S@K0Z6J=h<T5v28URS>QSA?Ty!lp_d@K|Hd%SDlfl$4|`->L37N{Di*6SWM#bi ze=Kiw=_FG)dNZB>@wg?+^c~0Arj+?P<GFIRwPXJ)=4(6XuetwgZg9@s*tCGLdW7-! zD2y&N2wg|e3bdpn8v8CLMCQ%NT*7n=qr2hns~5#WR40Qq`<+!aE(T8`5~e;wH?4~N zFeZ+~4`@hnl!zQ66JZpaE_fshR<C<tVO__YvOyG1m0Zt3wnr4Eu?r3$Mznqotw(52 zcKY2gFx(M$_@<N)cFkECLC?24)@TLz)|PvUpD{n6LiWsiCwj}n3oN-uu8RaZ4YOge zQ*>AU>rokVb77PtnwLG7B$=h-xr{%QuLM|UQn@ZF%^j@7=F%@G$2a4W(sPWb8>2BJ z;ueeRoNh?>7WZprySIbmhAQ~Qa}y0EZ?C^(CWgtF|L4o$CSLr{eA$JVpK+tzpmla+ ziOac+-_^$uv=u*>$IVPFUnc|5Tx{>`W?#;N;SEoaO4GiN{dPj7eIiG89CP6=77#Vm z9TRw_rt|#?n4WOI6`E?sBx99npQ}<gE!AOIuAm)~)4+eR^$$Rz^-S0(I<~Dnwr$(C zZQHhO+twc2wyiz3aprr^{qL<?=TxmqCB0TURY_$foqqaBc>F_cws(0|2lm-7o+8bS z!xiOGrUE}ynIf!MMFOR8LCjKBdX)dKHn9`~W>j`onu8=ZL5>U*$#gSo$yjgYL8wMC zw8;_LXk8<g%G>Bdj!Y5gTK6fr$@izQ8q0^b+&+pEwFG{bBE@J+qh4lakv36DM|{Kd zU*G23OINsu?N@|LvB{~H;SfQ}tD1$R`1g^FOyOtjYj9DUZ|$Hbv1Y!1!(dS(7-1#u z4!U7UO|xZt)%K^jiTJFpWRuJXE`btwc!h6U@Ta%n(Nft3fW1k8+XMoXT^Td-v0Yk{ z8!D=NDsIRXiYO8JGRfvf1B;{m75RlAGSMF98qeV<oACMZKtOl}v0IoE`vHG&kP26k zomf#AMTjZ{&s%MbJ&`-?xQqtAw0o!>(_Bb7A@usRGwt2lf}<K@!Mt$-j)0R-9yZ{( zS-S^91nzp3?B^FnjtE~&%@$&gHlCObW^!%u)x8IVdy#DhY9^JHi^U&BsL~C)ad0Hu zjh89P!x`lR8}esBc?Y~362uk2WK4z|!!?wl<`eh5C)a3cH|ra`_E|G%6|C_iVWj0K za&L1I%fuTtA|;_}N<b2W@!`l45LNfP{2=WUUu|G#>V9EMsoeSETWqfpABo(3{)xyZ zfM6B+hymdB19Z7`@az$RriCvL>!?7TKWlOkDjB)Z;Xv3w=xrH!pVV$$3YYE)UXI1C zT@`3$JrazaEN<LPd{=MRuRQ86D5^m~(EDXFKa&sZm_S*0fL=dH{;2xE5Np4!uBB2J zkhd9zqm0EHLT2hf0CrFkgCM|+(S?!>@guocHZOv!sq_EcBLSeE!2CVYDTA_=+L7NH z)n}|6Za#!<)wl)QL_CD0QxX^(0(JIk4~yd9V>tLHX6#M?5ETV0hq31hs2f)HA^9ye zLW(h*WNc+E@Y8+GuSVJ7EKIazxY(T0<hU9(Mop-R%fLA4aXVI>OPKA~!~V0~*_90K zMJXmz)4D(f6-j6uo%Fjx7_Thp8ndHN?SKbv*{?3?`>wg;$?{JDk9^>7(dT^79Qd&N zP9U`&ANo`i?u4at3lFeTa2GDs%5=$9bUod*c(r+WUxj7y>D}(r76vyHNS2e{1T6L) z>Xp1S0tL@K8|juVOZX!&IMti@Bj}bg0ti{lH^j*E19KV<A7au&U$X)Pbrxa8I~Zym z9hx%M2OpXukUSxW4n#mwPN$_-%4XCFjOXjP4G0GCl7K|XrK@))u<oxoFu~@$gsp|3 z)3Q7yN{ilUt(f!?e;eXgrP~O81Kq4UTLW&pai8_fO1%7eDgRiww};=&kutT`r8VS} zrfYI=I+)Gt0sE7(rYmc;xZ7o+Z6fb+C1hojeKF8Ezv0W@G6kKzSBF~6EIFq{5K^r) zyX+>Uyg|5Raix9ny8@wjX_@D2@n5nu&!B0L5@&RB)j0Kd@Q`O&k!OXS-ek7TFKPDB zs~}(h^{f_zjk&1G43=EJQjuvFKmOMXB$6bQ(+Fh&-2&TS3fUraBV&UssnSnY7>pLY z?<LHGJkFAcT#B;pi^1b0f_Q*jnrwQlJ{#PYJ#)x-O7)Y-5bMc$fi<&?m|P6=Y6emw z9;5-?$j?Xwa0o$e*@F#$YMt5(Oj1{MI$s*dYcWjL{c4;o7BfM0QCKBz&A`=Vt-NTE zqlTRNH0bt|J_VF7vVrgbHV-y(J!9vOfzhpU{Q$3b7dDfiEc~6d<w)5m&iDu<5lRwF zd=gU)OWaS-nJx-GA0#++Pxo?7^S#E=8d+|kM64!>qQ%;LrCtx!$hwf<AEs>GWpQGV zyhf6ULP#boxlL3W{)a^bNxT@rsLyJd-Y~iW0y73<{s@JUQk<M9k2F-$i2ouHkG6;e z?Ul>|>jQlfMdvVzhA@f>&u=V-s!EV%oi2*lYTl9rYh(-_Jy(66I0^fTPK$XQC+?w8 zf=FeEd%T*DBb_Y5+=Kg}xPVu1zW53HipP7n_y<RFwgct)!GJtfxbZL2u#Ig)ahCb; z^{b1+N(}5lN{2_bq6CCvY>mg2q6E&vT@rN)2;yK98(%qMu6g$L76hH?kgGdb3!13) z%sZcb1#uyZoea^lJY~cdd)w!*Hu3{>lhm(M4=Z6~hgODGdU1vJj~cv;to^_DPz&9m zGo>hhM`5eEW{S9A%p0SP>^~C7wha5VlSB&ZA=Ne=Aw>YdB-iBp*vAZ4Yq7;;01TyK z)X~ZV^{>GcX=u*Y?rCim&I&^tN2Quc$Am~!tp)7Hann=DH|B!<h8JnN7}X5$W-;@) zJ6J?`RL>~Y3|<$rnU0e~e$N|vuDAQ2FWrOvQ%Y<P2ufxgqH&VM!>`Mk9wR{+Vb&*@ z@TRzx8D?9*1!Np`B(v~K(Wxn+p8eN=Dee+=kqmK>9OzrCCWtGZFL4o#vGERa!22>d z_tnz+yC$ZPt7XurG<~Q;V4Z+<gl=Qt!DwSBG0F0|yfGH+oDGOkN0-Vwj?Z+}-iG33 zyREe4I8S13|7AOBizjS1yC<VOxW<wG7W=;b8z^wFW30t62I5!}n!Lkr>bz`27+9Dn zxz_~hJUk-zU^Qq?jjay5g8(Dag=`$<4_K85^hgfVU@o{&Nk&cFdHD*y_JT&8e<TW8 zCQENEEyF`U$6!%Z;|)@*!}qp6Dv*C|Y!|9h-|LsqH8?7v?rktNT@8w#Y(ls@CzF~{ z35V>Nb5}KGp!Y-nifOJvaS-kRhXp@r%Uql}KG-$9Y@Y0zW%+^o*|EwURfh?2Yp6(d z@Z^d7yJ##dkQwV5XoRNHEMsYzqf9xS?Fno`X2KGq@ikl_B=!!c3QkAlD{O#>g0~^v zYH0|c0eo*mGm(eXilYC=XBdrvW=ot_Qw9m0;VOxNmRFxlQ^_SYE}`*~2=mq0PSQxT zKUc>vCARX1JlB$xGLc4EJa3N;)0$FlwbYQiU8W?);(&mLGNmAfHmH}9D61;r=c(et zLQCg_M{#i9)cxRpJ4d$U!UI$N=Y_$vOLa0>t`!7=w9O7`MF_OjTP4JP7G0l4IKd-! z27Y*piv?W=ZEYSrSJYX6`GxYiKH*97GN6TJZsF$e3;>S6H=%scKm4eH2@J94mZJ0> zw9@oALdYZ1KbqCTKrDh$(#AEmC*}<y^Mv|vN9S<xwoIX15lUXy28U7{(I*5pBM5BL zCz}JN)b(zRITD;b%9D2bbFlN+81D03RvXa?{jYXzZdrbvy}O^At94`U-Ysu0&dB-1 zF0-?&b^r5kcVOym2mEXY{rIHNQ)&r`TM|8j<$%rhHB(0c?2j#Foni9twix_TJwvDA z-Qwj=N#9-IRBXy$njoM-Z&)Ac`i3CX0(O-yPC35dQcO`3c#06IydS!m8mk;v=^GOB zl-mJkaEl;Cuj<HjaJvRq(6C}LYC?@2|1_+@ghq87mXy!JOiE5=F{3`&o;wn(RbwI* zg|9*FnoPyd1aN$ngx*B~ligwqnThcw%)nd_Mn=Y2_ob1B7-rJ?+FmMhGW3u{PKAIU z36zp!I!V97B1hZxP#lN5+IHp-cy!Dl_(+6=+3NHVraNhfcjN`zAWbHPiCM0@U2UX2 z30UOTaaa0T7<D~cWCpuuOip6rlLN{k-ZcAe3DYDBf1x|g`11DqHNs^!;|8SsdWPDd zPf49_XuESqH&e{Ybl++Iy?D2i&(K`I=HYSYXZ;PhUsQN@!lLWGVKoV5k4e2-O2Pni z6Q>OFem1g8B@%JY&-*g|2eur5PnZ&Pw(&H$K>w!Pz2*k|Q^htp)Y^4(18L48^RTDI z_jw%T=X3B^z~qv~Wz)fWu>A9vNQa0O*CtNvxqagqedrNOrs{A%&CmHXC2!dV^;^u- zrJLg4G+x(V^cjGGPiQ`J+P86BppvfpFF)V#FAZd`-grM=xIz@^{nrT@$ANZ`szkor zEst?u6k&(wOEne1pO>43MJ7CX?~>uxtF`yB=B0)rEF&E?5Z`ezVWNWW4EQn%Ec4op zl%HQzaMg7tXlPK-d1y(Tj12briFga@70qRqUmFfMH(MWFW=$;4;#_osZH5uODz7Lj z$=uL*UggG`>OS4mOMq?Becw9<^8!`Oh(1`p(KmM%1OS9wG>E`4_~Gtwk9g2|&wpGY zG%Kr!8oo?&Rml(;Y|eUK4(CBE&Sh$E0KGroqj(xcc}R4;x3mI_>)$EZp}30QNv4Cp z)I;`tpAj0K5-s50^&O0FF{&9V{{m#a^yhHXU(*Z~>2ZNXpo1wQ>bEQ0x;=}1(%dH7 z#X_^a0D3!N7I1<C(z>*D7f2TK?@1U+=MoRA2c>$9a7WD)l)0k!9f1_iM)J}?(-u7a zpvrcLd45e2gO)g>n~}IwNM=z|rM8it@6$ADWqw;pJRUZU5pylF>9^0z;c?5tSG=>z z_PrQ|^#=<W46y@HTo@R97Jq5F51k)cY-WLMc8P7nDLufR-lWVm2hzz}SzhGoYjw30 z25p{>e5mvXL>RqskdqGjT}6Jn>+||ow=8jO>%xn}YOGA#DDgAZMR!*5vmA-Dw}ke4 zu>AJ+D1bi~%O3oX{h^tCD?ax7JIXdjn~o!g33D0N=|q2SO*U&K39N7?BMBYol}snO zv-p0EENHGwa0Wh4UqfGx*%s0>HQaxXVqjnM$Ve~X*Y{n2C-GnTy7u6UtoUjTgPX!^ zQ)YBSQuB{J`8jn)Bv6pSKl8rGBhBbB3iX@(t!XA1vK#i*{Y%o}ir?<(QZ;b?^dfZp zoP9&2-i;b+<)@i}^Up)fDeUYuc^&GA-aYx6q?!=G+V8z6T>61(x9b}ow}ip^hKkKM zyKA3+14izcUoM7lfi{v_1kdSYi^xwA^E@t~I7<PbdH}-Q&1{qhi&VAE_jp~ur)!cM zZ%raYHW&}7cQyb9Jt!L?_pt=xO(%#aCQeX(GM*U+$%dAY#?Ur0V<m0yMkgdco~Th% z!bYk;KB6$h6ouyq3$%)DSV{#(&Jo#KV8TLF|7+#M<xt6SURxfl^_A^>$I$iboM~MN zv*EG6Fwo*_u=$Ge>YOQM-B4#0VLhYT5v$wcRWB)nzxHXChW9tc5TueYpkPF~+7*HT zG>HylgFD|OlA5pX2Y5Y#^?!1IX$9+35f<ecwB!NKH$?~I*Fj|jKsxV$1?v-I0l)&9 zvZn`t1M3qgb5GzL)@ANgJ0OQh#)hX~3^W9H!v8d@$A<Cx47t1mZH9Dh90xz#s~-=O z`6gz2>-O3lN5hj2397KCN9B#Jxb@h~d>mL(rjuD`eH+C*9p^LB;eIRANY}4t;;GD$ zKwp!9w>5JV-K?}YYmE=L+&r{#V#d<YfviAcq<q`1;~;TEP|VAZpP2mM0J=Zr4mJ6( z)Zi-t=e!CK@VX7Y_W=vNx5k{HN}JXDyCj2G)DpC#fBb3|XYBKW)~t-#dQxt*-0WNg z&DT?aayq^@T8H$uD0##HwOy$j@5RH`Q^ENc8*eT-9^0?nm$h6?ZUd0M{SJKi9F#&; zaOJ17KTOWN%BsGhRMn-?AP64&bKU0lBkbvSH&OjMi?VUvqATiFA{{EjXZ^m~_OBNX z_sc-8JDP_D1h6X>AE1d|dD(7RYgXPQOQa{_D*QML2GlG!y<h@mO**K+l3p2h^kx#( z;s(Wy^9iVKib1cwK~mIVS=p(pW;2xO^4=hg??%UWcbyi!MSU4o^@>`xQum70`pe(~ zUQ2Jmba{CN?^1QJ$MeyLWvxaxY<ptjO4aoX_pWuEDl-6zWRtX`4$Bv36Uddy2%_H8 z(zS|AgACN3&5Ii?inXov&oXPJ4c>^Yi06Y<EHmDW-uS}{!I5SV(Q56z4725Rq^OMU z{QYH0S$r|0eaz_?OXz3vDz*CJsCuuzao8J0d#iB+UFb$)3yYTn2Zd_^qeV`~J5BeP zM1v?H2Sw3cJ_8R;jK%FEeD1e^foB60@+_i#88xNYGPLV0{P0O=_gCffvk#e9rwySb zcHQ@3aRE%H&)U_jUz^{RaT|Q@XFn<XQZmlg{XJ``f`QQjm*eE-FRRJg2*!6no+u#; z$!Ji>zX*-=+_U3hG=0zI4ohW`r8V4thn3E+{Ai>DS$a)wHVD#r`T7$N<39*NM4a7f z$(drlPo1)FUyvS$;J$Y_Z^Kk+U7e|AdAVcKctv@E@v~d-mne)K^D5hJ>Q~#LF1vrA zeUU0ZYAeq1i}`2>zARKpncHd_Y@>%{brcW5Ib9{{e5X&Z@yo<!<z&^yewK?}HK}yU zmz5IFz)$YEGbZtu+=!Oo9X%nX<fLTr&>cJ0RU)%$wbnspGHo>q*_bUVdBxA=q!j%U zDQxMO^&dj=ii6T|dH5K<h=I(C96j@jcU)!?-JWNPej{viXA7H2>zuMK9H;XVLHOu% z%*LF-?!H(?+aL2GU@#pqh=fA3>qnj}GHCf<v`;5y+64bKo=L7s7C1_mi(t|N&ICZ( zcg&SYvmQ=t7FnQ}o*s<Qg2+Lpt)lC00S50d-X1vp`b=~c{Vkw_ETW@vq=m|hZ_)ut zgRPCy3e=v%!@3``%Kh^kUL0V3oj`jjKzfJE&7=40#I|{0KEqD$pnONZj9Ff590X2U zNd-^f(0w1~SMVYmK;bY->a5r?EI{EzL+8G%D2-wmkgCN52e`xhhR6$)!~B{9{iwnC ze#M{B?-Evh@Fu`JTNtV}?ohc|8+k<}b0z8suLP}qfL-Nws4hzDjVeI8&xUN-x+;Fe z(iP(f62E8i3^gZOk~Z*2{u<K@KbK*}Z#VHLM4aQKB5Zoqk-e`UIq#Yg)VM*_w+9*r zQQ$>UtLn`sV5Kx0>c;cdO>rVt*Nr1lGF3Ms*bZ*lBwglnzTG2*EVHB&g@6gyG;6k* zI@b2n#M$4|H2DJ7NMp`5Ce~oBixyWkhMJ^^5=$?L9P9;NN#+#ILP2VlV8sR&`bq6{ z20bI{wmla$nIlIR>(QROK3GC1{hPCUw!P6x(c(@v98|PqY=8PS*8j{z5~P?kHHK)U z$n1m+EDauQqn@`3!(jx4m$g`Qjc;XX5B$p+(P$gnbHRqL%j!Alh+wh`n<}<iV|rI- z%Ng3uYI1%&_+)Y>SVzwB14&(6*Szos#I0i)obo^AB#f+bYzp*ab5;BI?7b~+HU;fL z!g!9KpdVwmX=uM;E^|J;(dR)1Om?_s0ZR5l+-L9FkgI31XPj+ZvuC_l17pVIri43V z#FwKB=|9GfMk0U{kx*^oD$+=%fB?ZiMlaSJ7%x?grm$-Tyia#s1K<xsQjO}bO*stU zDo}DZ5(rAXd{8O_=#NPlK-?EN8e!rh(gd-Gflv$66@7H7dV5ciUf$6h`m)oV0<fxI zoX`xECO4~E_UKIqOl?F%9N+?CvHmYP^~Tu$N|qOC37@9WcL8gyj<L^`jF=<P_|jQ= z<T%P01mId)lTk%L5!X$6A`!ril*<I*VLZe9_qUc!0(dQ*JOOZ$^yu!BNNYOFrkZtt z8~Q{I8Cu_>IhTmPpPP_gQr~UVRVuS_v{oGDW`jwT@-LkT9~_%DTsEggX1%nW!pm3* z<|Vo<VMmOS8(E)~B9sGdDUpf519rTAumvlCg-InQ669o3qRuXt^%7Ej37sw8j6Qx; zFpn9A_}33LM!IqO##D&ZUN2W%!j$F`rnsIp$$qG&x;d}ewPL){K$R=7=~=Z#`R1ai z9Wb<G5lk^QEDaTP6C9O*;gbY`w=`_ZFujH;OU!+71+jjRRs2`A0F^+=m`EWy95iX| zsBLU6NaW<o#WTM>rz2lHYHEj~I_Ip%ywQac`6|RWq)40^6^s}Ij^kSZ%8GcD5Z0<g zHrg{j35XiWsiv8FlE`?!1luDRA$vS{rx==$rI7&ZXHDrwAJ|^~UXl=(qezetcQLiO z6-#(HgZJ+GwPLywF{tK`HVJi50dQKp_^0d0v5NuiO+1Ouemm`5e1Af`<(kx3J`Dns zx#Cd>Ttx()rD6DJ9>+yZ7Jct33o2NC|JegKfDEc*U)7OL=ZPc~2$H5S+rx$(8roDF zvrO<3%>>{sLBB(h0(C7#9l(^f2BUa??|`|nrbT1TnpE+)IQ2p>;x@H6PHeFt*zl1+ zRA4e~><yxbF8)>36Y&BkfnRUXgZG1;Wy52zAnGLa7SSy6T3l^int|%4z<6H463`@d zS^%v9-%NsD6`z7-V<iAj=s20YC1%07W2nGCC447gU*ChT*2l!h+nKCF<Kxap@~(SB zK2Y|1R@b6QDMvo#SORHC8eW~xIyM>9^uFjUU*{yc*HKu|ALx1g^#7Y2wDsX(0HfZ8 z<jJsQM`Ho_`gt|xUkWrp&>QwCU~{&aMwGt`b*hJMOQ8*=2+}SPqWd@Tq~GIpZBd5W z7lT~S$F&V=^B?Z71v(YZ3h5W2U^TpnG&p9#LFoOt7W>M7OKfWM(4}xd#Vb6JRZr1{ z7jCrD-@!9U@9W#eQ*I8<UmTIW#L#Y<$%+Adz7MCJ<C_b}(pjnE8_+Y}O8x6m*Bwma zlJVgLUFN`UQQ+ZrqW)d7P8yK$G25LF#99kZ?SawssY)-Ni0<`Mqa)Yrc8{*NJ)7=` zpth3vpOo^tI9H<ziS=ZkkO>DzNH8BW@Y{Q4Z0dmpyJG#nM6wekpE7>~_*jMQ1CB`g zOO_*BOtc-;b+nXbS67Hbo}$`uSF|?k1~;H;YILh<4lM&VdRn4<sFLd?ZfC07T3_mX zZ1`wz?ombXnoy6>a#^qw0c{FcP<5dVqM6;-@@=YPMN%_UpdC=R51xz&*}01NXl|ux zw^S`M$|~B(Cwv2DsnABs-&+Wsl4D>%iyI<q4M`}#VAn8pQG_9|JE@zbA`~yCH3hmh z)&wbDC}%|4_B@HsBqr*^f9lMez@-@7#c@S`MlooGX6rUeTmP0YWYxx$X%5)VNF)lj zqDg9jRni;#(YxpbVHFEBzOkeTgMpv3kfotJ8;p}rg$xI$Cu+^tP&c}+%3hsXeC<IX z%TeQ=^2b|a3FEIs*%z8&tpp&*)$7y@p^eAN1{Y?L;|e|-{(-q8&%Fz`2_zbrpVQjt z@2Bh!-$$6-ZW=RP;hh39z!DQ!#?OyoP8G=axI~8M8C#$RXH~Va2V&2hZh}ZZI=und z%^RI(%q~Du;n#l%#P1+sD~$q`>l@I2GB&s!yoQ1CGmNV}<@t7TJubO^yGio}kkzt# z7E7~ZxW{e!WciPJ!z|VH4UOsME^in9Cw#VuWwdn7Blb8nCxC>GGCP&+w22;>McAP* zr`)4TI7#JC2=!k{?1-~8EMxA_2z>s`QgH?pFnBwALjITTF?}5CWGmsEQ|$Ua7$LhV z!x2TNDfJErQ;dO798=upS`<hZ25NXUd}-mZK?orvPQmnef7$YgdbAPTawHX0BPH#( zH*UEG>N(P42*KtI(O6c7i|tgHjgy8`25K^R%>gL-OX3j10m+Vu9y4;}io;TDaVu7b zOG3qbjRp3><4r7!43B@-l;%)XZOBdZ^2Q4Fe9+zu=RGDY%YY^shOFek?<Mg`eZdME zt?5brDYVoS;w$pfh@=Ws3IPjfDCAUix>Dssg$p-sS#J?r6<cMix=y>ZR?!<)J<kuB zf<2$Bgm<%kH^+ZeQIk7qM_a3mcHKCh%Q>G{X-8dE-Fxplaon|GvIT33CkqN%y9iTd z#b}?eVGfFn{zxvW6%iFX^Y}`jf`n`MIY*|pa`Rm{>-(_W7B2?GEcb=wz**OV@g`um zS2Ti&Al{*!Q>NmdQ&PRRRJ5wfvQjL!EF_iosD=QQLPcdd8vj!X=O;K=lIm35aqmLX z(<kA<*nzFH3(jK>LWUoXFQvKy0oCuKg#9ZEa{fWO<WdKLY>Ax8A}F85>VPRxOYDe+ zCPnO;1-aK^k<hXNK60`O#+u_94TGFT#4~y#jygih1|CqI%S&(h>jfiqJQpCPKH^7* z5RMs!{%fWJSIcZIW0tL*@txqYI`^8>F&z^s3A>};QqpfzMUc4|{6a&J=I@U)bK(n; zy23BJeK{f;Yk@Y#;9_uO4{SPKl8J}Gp_esQk+oJn7BCV=vk5ke!}!N$J@t%3Y^uQ= zKP-FW(SIypK_MWu12QHwm7x?9Hs2)LLKIaLn#~5aFl4dZuQ}gS0aW+gm627KS!?#L zFyWXRNw@v4Is#p`D7<4as(OXiV7mIeJUg{;WNAd6Db7e_!T=TPCw&$K<{k7_c;tL$ z#Q^~Ln1M8~$^=f-HHq&4kl<_)^p-i3${i7<z1izLb$4H!Y4|mTZlG{zo)~&TLALtH zjJmS_N;E@XI53N(lGr>iNG~QP3l0Z^&@@r_94yx-vG|uW$3t=oV_m+NH<Yu3u%&e- zILMHYEM(KzGN3c^S*eJ!S<>WeJWi_-oB)gQt(Dt#NX6v!FdTgiv&}w4`J)~OaHcHg zlKc`Lec~;+vMK*FWHJob5636e^qnq_SVJ~o77XHiPf%{W4R^}A<faE@w?=EO<X~gB z7}<uGyi+Z6bbP4MWE73CVhJT3-4$$kf+Z&uTu2_wgoAF5R|ALngYBrQJRhSKqL64U z*3zxOLazGj+%ygzr;J9~UXbd6_}s#Sez?``@&5-i43(XbTnUC_ttu_l5KCXRu?IiG z+CMHi+8~6MMHTaQ*|N|@5>*r3|M+)7(=2Rn#1>(itN?q9%-0cZ`ZVBWwU@Cqm3-8d zn8Vd1QoA-MY3dyYyE|>7d0vV0uvWSQ^`SPp&uA}Y#Jk96z66zstl~CCB3VS7MQtX& zCa5x-1<+uNSHzrlJX2ne(+g=3KBO(F*@HLInoKNVP+wOVWnRPkD#e=hXYaL|B*_>= zZ7-qtr|H&w%~I4-+$MpnrKT)8t0Trini24J9(Ww4NGx;eY#GX`&Rd(&ij<bVpb(X~ znq@SFVWim`%n(l--(afRE1bY^S_2JVV9E?&p0-XOaEO{_9JoApNWrHyw(nJ?;vPN` zwj4;d;z$VF1M$v=n9lN1P+QnTfnUr6@}4k9IQV$jq3-^`4^DwuTTPSK^UVnz%f)bh zqHwZ91;IJR*xP!loErBSs2Es|Mzg<{RC+i>G!Uji7m$F@9(0|8ia&iJEQ?JJEILC- z?s9=MuZJ<S8iGh1(^UYIn9B+{mD7YhonBhQLX>Q4N#s(#40?zLtZ+>9LiuD>B{Qd< z@gedDY}*C?3_u5vZW4z%@|W~|pCbITL$V2rv7xA-nM^s$KlyoRC{DJWH0FK*o$3*| zhnR*4SkSjakdHl33qY8LnG8tYOpq_k2O>Q@YC3?scWl=Gv&YdFEVLp&2d{RaNsfyv zZ*orBTbY>f6hyGF+DUK^DEL|38>Vf97^aAsiZi@Hq6rMmZq#v@P2m0c2giGZ@8kGY z-ox+tF39n7aVM<E=QwLORpH&$%IvhMp|{D&-qk-ZbMt&=W<T!LV&#ld2Hnop)z;3g z%`WDOJohF$=Q11T+D@lrHK5{}*y2)d@k)bp@TxbX%<cz74<>Jr?yTu_=6-fn_x%3{ zhfbONg+rHHhW`J<p^3TvU*XX4{I8-KLpv)rm$W;Se)(@#`3d(1ZWBsf{%HUOqw8GB zQuGxyQZF0u*Sq>IHb5Zl0De>d4>&Y{<qUQo;%@LSpFWtK)taXAuG`g!6W^9((J(f% z{__{1<l<S!z0#geX$qd<qw3@2irv2zP~s{YzHGqk9zdpmGs>O;QT~^w*4kTb7L~8M zg(-v{blb7PVK2J&J4L^9#oGofg%8<`DO0EsJ`4`Os4DH@9h2u!D>m3IXnyBwYu6;= z#j3G9&!+WHZ_m3c?@a51Hk8s#X`gG~4Gc9VJFNYv{2g+C19t{t3}U4|_MJ}+&>tP$ zRD6&{$=l|0`s?<uJ>`f4S%h~)P8``TDZ1x@ikIg4$dhM#43R8Sg)NYC%5RuY5myRO zBieP_8RNSR*T(Ohd#PsSQd;h8{6)BeD;hEF%3?L&LXe#pbZe?4Wr_S0*qRs9oweS( zMK921$20&`T5l_aEjEd_r+wEGz^^x~E{E0%?e+*ZrM~$*U5`lUh7;7Ivrs0J0AXnR zY@o4)f2ebf7E2Ml{Y5q|CnjRddYK$fr`Vl*dAUF*-Eq%-nEdg{F4!wH&iYS4uVM1- z^%VR9St4g(c=LhBY-jsF=x5(Ey$_~0^MR09c?xl}-_+emm$$r;Uv>Jh+xkea4+yH$ zTWcZ7q!2jq;_?YR<Ny-pkdK?Ss)2?N95Px+u@0a8PlMWhqj^jQ%FM-@N-ii+QAAZV z&NSe4_#OpX54MJaOdHEME@t~qK&0Di-Mscn=z%Vof&EN%BflYi`CG5G2WCfQLzDj2 z)s)!XoPT~poYLr<pOqlSjjxCEY`b0=!)+_pQ*2i4P59Aczgpu%qYR;_iw_*5ChBZs zPKVOrtkz6npA2C`4i{CD?+x&G!y+AdVK!)fk$lQwDwq1G*s&+@v|NVTtL%W!HH0H# zXA@+~>KG<576UjMZtNENb)<${%3jeJVlIZdHbd+@Yw>v=n=s5vESXI4SPZd1XUw_) ze+-=Bk;SQE@MsM`V{uf<tr`&@J2DQ1$d&<%4-bchqc1Y~lYK729o%Uz>er%qMc2^g zlT?|>?5(b)!T~h-47Zj-!|zU!7-UV4nDewvkm?8xvnMt;L6_qq!|(2>VlaBEI{aAH z$3D_<7<S6d3azey&c#HA+L<$85fA;p#z!^Hm!vAx5O_3i!%6Xg;K^?!K;oD|MDZI? zvVu}&=S7;?8H)xI!^BmW#?U2J-qE9&3U#2qmO^@;276_?e{OHCm0ch2Yf1VVOz`=j z^m~Yi0U6`UpGf$H6oHaEcjZ^jB`{MUQ(j^-hhH^m482(-L6bzo-ls!_qU}7IbAfuH z<3ee(kn&Frv1w89@t&y2e^$l~#UaaMR%$+LCrJVDt=OaYmTaCvMEux>-E>%4aSgyl z{D>aM#Qdy^1pL9tQoFjUlx~J}1s=_Tx^@WPwe+a6yX($wI6vYkDh<&jUP#&geIJYZ zA-6|sL-<^q^NT0DFn4{P+2vqM#fd}_ynBUz`)WGG2tB?aeDMhT^#<o~3;V&(@BRv? zBEM}%s6_X(|J0W|QO38ys|%;i?)!@<aoeXTD%_!hQDc39QTH4mwOs+D-AFjla!z;3 z!m8t-lGy&KsJ0O6BY3q3jCx7VN7Lym(1cZQjzVfHnvweEjq?}LX*d2gSVfX6;v~0X zmEVxsjv($O4+-=U9ju)o)V*l|ql86m#nH*V8UUl1cWlMg&K0A8XZQZN3!`+$`wxFq zjt<1T{OdmQA0GK*)Ip$iLkX=;Jx3&C8q|wi&*$-yf0taPgGn>thACIHp(3Q;rB?YV z^eP#QCJ;sLff03hi!9?&_oxR-)00Sr$Qka?{2u3UDLW}f=XWhg^yP@XWOC)sD#V#* zG>z0oxlJhlPd>)16YpUCyyyw#pE*i0fe+h|CW);|$BOPh`LZa2&lYaYQN~_tv>9kx z2PuR%6T24m-k};vbQMcFpMJsKPZk9K_`JrsT|%jGcdQpp`?WCt2=@|rbYC!~o!MK% zK%6Y?k>ZTka&h4q$fg*lzygA<czm%WtxDiYRH67ogrnEy0k=^6QGziC2uE*7E)NJt zoIsqg{|ORMj?~voWD+}Frpd)NMHOP_p6LZkIAu0;{AKc5MMk!%q8*#Pq8+<DmK9<j zFFs%U@%EaDLC4Y?(^h-a#l^zoDJhK`Ny6~OqL~6dLRO$1g;g*e;)}FZMhM0fk`3a1 zn>|H75<fh=qOJ7H2#A$gp}i`jqJ%QviUbnA>`KQN4cvj!Ztbl4E*at2NiLUe#YG#5 z)>$%6E^Q<jLZs*QIL-f?>QrxLSH@upIQJ^y&gDT6o9bU>JB=X50`HJqJ;@%-9w`|m zJ4+CoQ~7#!JgZ||T=i8xxj_)CTGhFM_p2qlMF?MuRdaVfCiU^^Dh_E|J-iIqz_`eT z?oO+ww$iUcA(kXyH?arK0K%Slkc8x3tD`H}x+Vo=scFovWz4d1ij3eM+8#cG>MTY9 z@u<A#1b>t<X<wI9Zxk=qPC4vVRM5L<xaKl|B#NNNA>7VeGl5IU`w(H5eTc2+cUBCs z!QI9DClHUcqqaqDV`m#|i?dtWkD+4kQE(Ej%VDLypYEum?{V0&^FFk{YL1`K?u|)8 zLN^*OR`1Dw9qBYhh^9#*=NMu$%!b_3-uYhnR~UZiPJXba=Ur6ts~sL=m;7Hf+R<Ta zGuQp_2wS3hXLFcsyK{%E9Vo3yjwc;Q&t2_hM7@cW!7tkcazUb_>jq7B&a-Aue{N1r z>pT$tg#<g7$6ZXTe^u>Q_hR^@dPZ~kJR>sISJ>;wGI`-b;fkO4A#!i&d&w}{#=<&Y z9MY~k+Yno-=ml5Ld@8N%3&dTFn~=AWQ8O;F?|N4bI?k>-;;Yy~8yU=9jB)#suy0vN zaF;5W{4SwiRB~y;JF&1Y?+XTGdUzONEDWho)1|^4+manMF3SP7*p?@*dLzaG_HWx| zsDGLMPX|h^jsJi9_2hNL2yYJiDexR|e6YjRyr}e?yj4L+7YQ7cEmk-P+a>IB#&^ab zGId8Q{h$}1S7Q5NSI;J!@N0%b_i_Zt7Dmx~Qk+z3fg)1LqU%5zM3W5sUKNW^JDX56 z9D4@1E)*f7S<D!<KGIx7i`HJLkL{hi5LFClHMK2PmHFOWM9AhhlAs&z#|eBsas;8~ zRlAa5;qTvOr@LWMss+rh=2e?;jcO&GSShg;g_lGlG$|CdJ+an-WrV-t!IBd(9G3ed z&MWutPnRP&F<Jn{JdkXrLe9cj#aP{E5bOt<Vsuz<piAPO$=&{$Jz2WRk81*th3i$1 zYb_^nJKtL-;zfDb<xw^iS(^bsAqM%G%Y^bW*pQ8Fmid|zq!x(f&zlJ4q_XHD>QzKp z<$(}HWiU0M77$P@#0&ffYy4R2<~-&A3#&`LTNt8=K=?j9K#|7Ow?!@db4&_sAIgB) zXn%QUH2?DQQ~|`U1L1#2lmh^93-@_zTO%k<-q6y^>}-S5u_Y!9S(>-<QKBWB0vRZ* zI1$JL?`4cKac;f;QJ=s#zzlQ$9li>tAtt!HXd&*y{|z7aA;K*Ce}Yjl@RIZq?H#-% z@48}tY#G8#M9e>}&Mq)92pY^qG@6z3N5V|5=!N1|6z4Vd9We^QFb6m|Kf3X6RNfe_ znO?-rTNDA^7;A4N$AhoPAE2IBpyD*z51@#RY^?n0`)Zd{eGZ3!F-!1D73lNN%fzwU z9}69SIvHNkt+$PZ#-Bw!5+X;jCj#Kp1%bw1>aaKbl!7ps2FMctw&~jr#`cC=Ql3qD zbDow`1}#^6>4Z6fP_*e5RCO98+BX*Uhk6^n^kkyvt27=%7<zd|f;$rFN5YGfL@;<T zs_25JH;AOmsUQttP8+BP&Jr|u2%>Fc4)!Nu(bNRHBbZyKDK{u1SS&r3cj{eJn?<po z8z|<+SI|6QR&k(R_??5yU?eQPVl)6kP$-l{_=VuKf%(gdKmepBo@wJje#q~BKq-x( zfbf;i=;IL!1kFGhk%*5^mCD=aMErF%^&_(`XVv)3!&&BOI#|!l3&Lv}2tw2m34<D$ z(zo<lK{kO(kN;#tT2|+!{tL+JK=3J}NLMU9=u&8epNP4k^euI#x=TdNk&l!XPix5X z%o8kMn(2OBj6v4}o2N-~8>@CQNSac^Mp!~QpMg?%Di-l)UeQa^^}_+=TG^K|oMS3s zDlCV%psUy8eMN7;-u;0|hJKW^(ITFr(;QKPH~1xS2B1EQfxZ&v66TJ83yVG0@w_Oa z7wBLhCcoDB8<)fROLKGR)fPq&9h?CPp8DlON(tOS-SF?@&rUWM;p8C^k`5GcQ;k^K zJ9&}Rbn1arD1X8?sSXxl%NJF0hOy>7oN(+f8q}mwi3M+bp7gS6nh<Q)iyw=IhCMx9 z9G=_^S9rA+el8<vMwOD>TlJtnSXg%`2e2siAWqj46>w}v<gNyLHhGW)`Uw@<0w6Z@ zdAsNp3x705$DdSHVYF~mE+TAqJVJ!1dSF64NW#>Jjc+yh5m=#fB%z$suWw;zk`k8f z$Fe0~|DzKSz$5gPADjKc$e%=WK4LE#(	Pbm`|7ZuVtJiW^@!RDrx1IQGN<#S8D# zD$i(-u8F&UZ3Jl(c<}I6bU*F0S>4@%6cy0fnCVfdU<R*HOYoFte#iIhZ^O@W7BL@w z4<Y+8<lboBmwl@?zgX2P*5_B?pO4l9mj<q{gD@xVuCs<bs90a58GI!mYKrjmhLsD* zniNET+plBibFhOw9HP|6U&^F9!TuKw@E6%yAvGjlkGgT$FLBp%F&~*Pe%EvGMkT&8 zt8=~y*)Os6il4RBr5|4cu9vQ`*P|v}pDEsyTpvoFkLJ2{yr2ik(8<0NB<@lnY(Woo zcikuEM+cngcg%NjxMeZNa^7=`g|CA5az16ev4VGgxMgr2nU3GWW7s*~vHVvNPNm=F ze_xD#%YVH<b7&tvGnyI8J;;)r=19(PT}23>PSg;e);=cb?;rc}^aY{XaHy;L4DFM@ zKLQN?yVr#CuMT>>bO`e;^(~f=!*xr@<UL<N2I%1a-{a{AfN}rd(+!AEv2nyxT)La& z4=kE1T{g+PgdzOo16TXP(LR5;2i_f{v-XFCqH#ekkaqHG?3Vw9b!w2Gp~R8wdScQ! zv!jAdVsWiky;QfcA&Q9iPVcY4ygXi-gy#W?g8gBRNZB{e9(&XwY71yB7&pg9^awX- z-uB<H!ifJuE|B=rxPnpO*ASE4>!0wsZ|M@USe^)4W1kDW;MR4_+P!Pj;|e$<iz(O7 zs0!3pK3vg!=WFP)lKY{r4o^MsUG|4lEBGxnEL|I-LTF<yJ`L00ilQ*aPo6R$gYWi+ zUKwsO7f^HZi(eTYA{9LayQYpn>oa9^ld`#+gaz1=%GBb@<#v#AJ{gK_F<bzn94hQk zlRatqOEKp}fB2(701WayTreQ`FF5A37UUPnE3nH&EDsIKJ&u{rlgw0e^JRMK9xIUh zj4N37M~kaN7YJJ`A?+;Kqo7o>gRDKInue_gl8k&+rS3m12R0ksHdEo;WKG&t1Q)1k zq2=OC5ut)a6(I^TZ`Df+A)sL0?iJ5A)NAv{7OP<6;uS@}+la-x89&R*VdzLwyR#>5 zLnWnT6Z9LHQ7-DSnre$CZp+`l<uQBGCT@Q(`NU13fJ@nbi{Yw;k=s8FrPPXf4^a!V zt9KVFDFJ9;I67+CcX?u24b_|136NXIYNYGo<sMQ9__HopiNPhS`$so-BlP^%A5v0H z5ybe@SxN{fcNqx36g3)Les+0(A5EdsTA01AOeVxVd9l(|kyu6HclWOnjxI6h0jPNN zj(TwAdxL&H2<LBlyKy8jZn+mqsk4u<o7`T3?-xR#2b*n6Rql+h3>=m%65j&X(x-(K zs*3>DtqT)G&)8wEK%84UtHvomX4o#2&!{PP?*I5?OxLCEErK22lLnI#xf-c>*TL<1 z=8|poYYx2km501ua+~<{+5T@gd<JZ&EsR`Gu{tr#_2cKY`@PK?Tm13yiK;!D!JCt_ zc9NyMkmR)Gz?j1%!HM0;mE)m}r&(xXD^-|TXvo$5)vE{K9S-kLE?=xW@_V7924SCI zgE~3DlTQj_PE?K*4w{bl{JJ?|GasZzS5ne2G_ENQw?<ciLq<@dxlrP;RO9P*p+Ktf zUE(i=%P`(R7WMc6iAL90PaAPm9qcv!*nvbVQ3}J(oOxM8voH?gh`SaU^&RjO#?9JM z6RcTuncc=yd|x}MQ5TKoZmN?bpm8+aT+PcUmR>vLI{IZ8$2YnO)(ANxR_G$debUD` zmR(boPObLCchg7}nI$j`e{!DZgY?J8G`5{xuDKs}*WK9I(sd>B8aCM`AH?-*4AZsL z^=l0wsB;xjF+Z*nP<cLlDql}?5!{$U;^m#N5`cG=aU7rev%3&*veyoh7dODCCRb&o zw<|=m<5Qwj&(1pn`zb6eKw{D_hioea$0^CFcS*oec3SoWtPSxgcX!Tzd6_>_Gak0U z;~aI#I6+6*;4Sgl4;F2SPPv|ckFsaGs*kei+-NvXC$}YMJXU`7<~BkS{!dref3*{x zbRB1;X5JQR(~q*v+$jI|=5ya^W>+r(=dy|!oQrP&jeynXDEJ{1tdvJC|0%PH>%Tmm zT!<Yp=Nk1sH<~H(uVf{%Tibe0e!#<;7n>kkPOKX{_(2_mfy?HoZVi9`b3iY4;P7SN zS}@ic)f+<Ao-~+P;w&%QK&tFc2L;zFQO7u3VJQo&phQgu`xMpSq|?Z(4`05vw-GHT z-}4D&ALpsgp7rj604Y)!`L+J}i1FSOS~|rU$t;hZXz+IGHLNeL%iKLGpo(}vgS5!! zmvSCt5dYhO)x-Syl<~g%)!G3qY*GJpk=i`JXBNI<HMm@-YX<iGY`C*&vdwIlsxGaG z0ImBk3EmcIYEZ3FAqlXVS!cTPCQJIdsmDd_`ngj{7sn3)#;)%@{q;(e@33@KHEWmf z)n>k?0eH8<Y;FWX{#kIN?4X5vx&vfj>h^TC3(#XxrO>Hjy7H63S_LmP;*JX}{q~LU zwWo#y{Em)<mOsi#V{7)5r#9lnJiy=dh*kj0D<!SdZ)cA@3Mm3V3X%{&eL|ZiW0&lQ zI%F`l90XK>y|cfefD96e<gNO2NJIRHqZwYaPc8{QN-LOA++Hj?25A1?8_KFYR6k9R zqJ#FaTc@Z6=k4$1Rhd3d-G+dKvx4G)67015n&D+rx!~_gM+yMKlVIr}=uuf!!_$d5 zcWPMkllB=SqxlNQvqxKbas%Mfq<yoFS|TjO)2|=L2ZkJEzQq&_4feD9mokm(4~N@R zaSI?9CtQU)e?L%P3tx^*>`0Tea$=Ca&`xKn3@}8#>23MBP>Kk<IF>B+#-h60_T6!& zMqZ<YkH=|IzdH>MgKHoh{;)LMt2ry@D!!;n3DRCB))&NUA54YR^iY1#BPwS{?89|L zm`SEluZNUMqS4%Hc6ltJ=d<(g-;p>JQ{jpOkygSoLN!kHJl={xX^>732$WFassOQr zwIQlJHvmeY(HU+MNia7EeZ-GP7G2@LZx;jIh>=1Ev<B&Kn|2E{XSQu#%JvLL(_uoQ z5NB&vP*adX)~BRQcvgFDIHK7#wf$|K0Vvg=Z-TWp0-ktA1tV~OjUR&lf(N2^TgnYy z!`EEKx%PE?H)7AIhbqA0v=ORqB}SnRt~{WLGg>4SJ~mETXU0g?%aaCsv>9N{n(9=9 zSXS_&3Vye{e8jVZRPJ_xRQ_a~t2~Ch3P<9Fmo7<9{%95nmr+OclR~$%tx7r@%!(mP z*>L~7Dv#ua;i2-gWLB}wKReW)$Qx+m(Msl%ftuWS#VfRFxG#&>xB-AttI_*jLZs2v zK~hNNJJ#FMc~dH-GkaidBuo>k@t$zLIdJI`|J$W45?dY#SN!;I;>1xUQniQksIrX8 zYjT-L6O>XRE~iRtZNYe5=?HMR3g}-<MbvnBtLllkox+K@UX`tqpNZTZmtw7ZC9tBS zmKrz7R#dS+y+*5lB1i~j?zJ&-yDy}Y*bNKPr7Ni1b@$CYepYQVvqq<TML#8pYGOIY zV?5;82uvxON0jh|^10?>I25cUchKS3O8^W0Bnzz?6a8H8#C<Bw)x^|QWQvYDmeg|X z)>bvML6hRT7ikIDpRAPXOwG%hhm_#{jUZ}BJ(!fcE#AHaMhdt}T*cv~cgX>L8wu9R zF#j~9FXn)>^7nZb{XUN|E6AWUUwO-<;GNK(K`Tfh8;1N5Z>SyrcghS&2LeKntJ2II zqx8^Qj*)(4sS<Xq0%kfEu1|bP6z)$9fY{WRF73+xX=o`z7!6vLRH^M6LH|bWO6oMq z$r9Y(b!f6=!m)xd>!eZJ(#GCPmo~*%XaTwes~K2Zb0Su}KzUlikw8X!!HAz1yX(1X zg85N;6Bh|*l{)zxLyICga#q%pIzh67jB3C)vMBZz)*f($8rX+#vWT;~JG78$=jXm$ z)Xjt{XBs_u`{tm0=A>%ewus$wkTkx0fK^xK83C$@6Pu2V3cAP^l~3Q<A8%|>j9;Q% zs5(M&oekXp&3j2iK}MA{vad0yL|p@=W#_aORfGl5TUm=T5{kbS$~2`Kr<*!T)6NIM zL_r3?Q#MruwLwM$O(j*NhB@9u!9-&zl(mtXvO9-5igL1$)rESp&=GsAv0QST;Wy1k zYoxZ^sG*LM?AA^dneM9oRdubIDnjE%HCfnLn`WXwk%iw#UHM<-iN^B(lTCFUHr7yf zE&H$R`D&tYhlsU<TZcNrC_*lW=VhR5gg+8(W67l)-v_XYCKF;;%(P}t0EDb9VbDEL zUfLlPq99`r8_fb;L|U|yFi=h!S5ZjmT~&$46HvoTh&OqZ$7ZpXFu-Iz%x6cE{Sd4) zE_tiQneCTb+q#UrF7*8-VE6fe8T=2?X^str71UTZ2_kqv$2!tJuAPIdZshQ&2K)2+ zZVovoxrIPciPGSBwz)vdP?-87Nq)wlfDLe2Qmbk1A{b0T2o^k8TDiD1!?*z4%T}$~ zQCvcJTyVCxT?@^#lntGvm)DxqGcw3bAT$&8=m-kw<dF*>_dR9V<h)rJ(-uA_3b%?} zEtXuyst|`vEw;W!g4FYO`i-O2jO2tF3u_t0F?(R^H3PEP`rd&p(INBr3Qbr)qG3!e z2FB!q#Dk=<;)|;@uzK=Wl;=c4teO?Mebh)TeR<|?{WOS#7Dhj&l9x1;k_OM(R*hp# znQ5PXkJtj8k&-;PNj23wHt926)K3dK{encis1*6zpvIx}&TI18b=wOuNx8{TG5<(Q zdYcd3melLECu6Qm_sO^{7QP39DbEm$KB3ihIaSDDfw85!$%;0&wC^0Gc$UJJH=MEB z@%uCmC}~6JYqd*T%F3ci+qU$ouETl_!sy*I6H4<@{PisroIea7JPm1Uw-%7dCh*uN zq5HIDz?IT<ABU#%*oWVjN$t8#MAtR`(7Yd51#^Swx+PXgkcG2blvTFKU?x1eZIw+# zrjdrbStGVk2um7VY%=#8<JC^W*+HerpX8_oNE|%9JpV!*I&H)64ETy4@>4A}hz=|? zV9y~$|C@($NBiMzbe!^%N2trAfW7bnI$pj#y?B1ZCehXDq55SLKSV^N)JY|>XPd3@ zgAjhO9kX~LRrp#%`qm`15LFU#vQO;)`X)bq5T*5x6@OG*aTr+!P`)CO^4q@Rz=mJM zOae8JoAWo({X3|9#|p4VT5%v^t)w_CRrx9jEP+Z_ae%!cUg_@1^<O@VGgbL+3oMaR zmx2RK0u|nppyFWBmPCd7$?;c*hlT{I-nFLUa9U@I@?G`CuiOM#_<y?G|Eo=+(p4Op zrhHeT!yth=d#(ImD}!Z`e(i)DYibs7uD-!E1CsA+5eGK(Iv#-)ZPR}UBis6$4}b9m zFyPpvkzxbZ!Q?x(!<@9N=JX0((}yMbFde80-i+se2qN1&j!;$hu_LJ7i6Z6Vu;VNP z<gPU>AXh@fMkZkjJ@luCFJppHef<N}Xb%ZieX^(bgUOWW(9Uz%_&ghm<@%3-?;eS@ zM)&qkCdU!oU2ms5dVrTtjg47jb_{j4;UUO+MaRCuz}~Edp6V_hS1;-x>rUUx5DlG+ z{1z3RzMz+c=l(fO8~ocHd%W?_&#ig9Iivd81aANSx45Hw?uRj>HZkgV<U3kmKzQzn zP5~l#&kqYz*8<^G_kXeW&Ow%RLHl6anzoH;8`HLJ+qS0N)3$Bfwr$&XPn&z^{o)t< z?Z*DO5jXN=<w4y#_f*ua^E{bpBcw7dZmBobqW%!k#s_B`02URH%+P1;^*|gVOLt2a zfs&ahUQMp)?!hd3mrbAYLl-)4=v;<D)`kJp@$LD}88<7@r{ng(&SJ-GD@Y+2ROaii zoA0rh`PRci#=`}N=9^r0xN}_LEc8Pxi+UpGE2{9<PbJB`f(Nrs-QPITBjRo%x_$My z>fSGc)FRDnW4BJV>YfSpa4%RtB^)hu0$>RmcEI#L723VV*T1^?)!+{r^%{l0B6R~} ze1;Pf*!Y&=PX?E1N9eqxREHKPASpmcFjI?eczcF8cGruJzT!7}{tg$_pus^3e-~_Z zc+%?3wtTJTM8z%#T<9YYA{G%0WMs_m^nCEZh`ONp6#IS}AQPvseA!>n)<b#*;>$e! zUF+&0wD)^x@hyXS>-k3Y>4KZZQEJ~GbhX(M_`BMx66Ie_?PphyFCljbKGVK{3Qs*t z_c`Mc-L1(graRc=P||L22CB4xyWy;?HJ5$Rytb2kk-r1~5M^2sZH1k_cbfc*-`m8y zkT_3j6W|etvr6?<?8&z{N$FaNI4k0LmJb{c#5(CC2QC0A304r5`w(=O^KleParAse zpDItXwojZa!NDfU7Pt(K$$Ks4;Fq1p-Z{nj^7+j7B~Jflu_t!&1#kN0?r||?`UTdr z8u1o%lcKa~@D!oiD$yo#zB;Q_Nk;IO&b}>{#URTxczZUd+Gjr7cxoPl7jGOiepyR) z|1$Xgk?(e;XW}{YOj7^GL5iYo`r^CL0lN!sV4O6ZfFj(d8|=WavOfy?9Ixwd*ANr2 z-C@2hD`j!9b$hv~UWwB;%C5`Q9nSqPkHyYhJELlph3WuJ>|U3y+~n9{Og3G=SeYZE zKoy^|?gYkM=97t9*9wCw-M9AHM4FD<oiTEg0~@+ddfs4E4~H`LfL^ml-)Q`Y#+T6e zZ}ZHHuvz&d8*cm+S?5De$lNo`Uq(yLk=4aU{%fh^M@HEZCO`47^?pXz1*y4n(E{i- z{SL2BHwPQ^BzFT*gUopgn65{+GKKlT^Cv(R`W1VgK2Q6z>Z;4oD=vY;r{$l@b2g5R zm#MQn=G)VqaLX+}DoYlIY==5Wq0d2KS<Wm*^{_2H&es+T)q4IKWj`2?;#}*EzT30X z%NTbc{T*-dMcnbhx_3pnFUI)bz<D#f6TzLPl*@?444MF+uGihQKC3tIhLAqv!s5O- zM*y3t7{tOB+0y*IMP=&6&8FSCQe|<-9ATS-%-bTn=l;6VqpR%|@%485H-x7Ap_^s! zkEtnt5!=Jo#$wx4sm$%tR7UF(L=;zRQpA`ODK{*%-f{*=g~!kd?^?M`)v^&wa%<DF zQS0eW9c%9eV~AH{-UXw~5ySPwW9lTdrigJev^4bW?Z-v(j5Zru{L;-wst{8fA?&lA zz>^C*hVlL5PREK~_2^-Er0>>s&8R9Y6E?p~7kFAUF!wdkie|4k6`ppD<cbXz&yDUw zC9rNIt?@0x3B&k<Mvtq~g4yT%2)Fn6>95V6)7QQZDc(!LRhpf5Z?7AZRhj|QFP9Di zwhWI|I1&ORS&(rjKLAl9vfPNtbUP@uZCkncq6OxOb;=QMwonckuW@?T$#4ypm6G6Z zA${Pd{dd6UJKiQ$O3gQK_ZQRg4a;$gfw!+gS60X)gDxP}HJyaSyuD+OY1|;Py(1qJ zC)WCnwRw-$kNUivRH}QP++T|9vd)tXO+gazR3}E+WG1n=*Ltzsi2Hk2(f*o6kgH0F zga?Nso$S-s1rO^Z11617B<FTLop1x@sFSf=<38UhKKtrFcPA^anUCV1w|^IoKDQaf z;}qI5^+55AT?WW)V|<fG7Sl_`qZ(lze)vEY>{2`WwINbk66oDByRHs=oCrE;<FlN- z8(zaJ{1m+~IG&;(=+`wl6XT0kXc&S-jM^P(%Q@37I&JlgdO952qcMYcb%YQ_q5jj{ z8-kK<i_!@G#SKJnCf$}9H-TmDSXq>AGESoU(<ocre61Tk0AW3gz=@C~g=z1L*5oU@ zr>CPfH16gTzx&w{_-`r(!*3im`Vx=X&dg)uOuEoDJq*Jqg5BJ;!NdE}0d5s*jxxTk z@(C(K(QIsA!xRkaB%k)y$63ie5mY)e68<J2mf7$33&veRZHMa*WI|!FrOxuD+YbV> zLe5Nr&zGSXTk<_TspRJ6yyIhFDt<y!{B#TQAa(}Z{>CvgP;Gb9Udm1)8)HD)0Y@T2 zUOfREtk^>SNtfINlNM;Yr~-J7A_3h3*7H<ud!`nGE=;j*z68}KSk<Hk+*ZQnUj`$A z6*^^uSGm4;w}XI4-?Bv>)`Q%Rm^rZfDnH<~keLK8Z6U^*30iUEC@G4vYGb(dw!q^G z8yyH*x0R0hqggSmi83W5G)GNo2FGc^z`$%#nvl$ekehOS{htgRa(kJ~*K{(*7tXYi zBt<8S#VrnvP*9lH%F`<|{MbzF>zL;G*$fF~Z3%O|CfH<0=KdDN7YM=+Iu?0f26(r& zdHW&MZg3#!s4+tZfMC{w#^E?}84!8|59G#NtsBE4d~*>V#ur2HSnVYeB}2@o_-hB} z^q;N_ZQ>k{F{I=vzR<CzR#T56K#3H}T8@xw7jn7>>N#;7&pRb*O(OjAj5BVc`*4rW zD^pvrKa@)cJo&EG<d+LD`XZfr&~hJ7hroX!>56vWQ-<21Wy<#3RpwAYo{gdr<WS>7 z^i%ERKO2Wi!%(zPZj)w4CB3kPijG6M{2CBb%v35`>HFm7)#^lu9d>Ug%Pds~j5=b4 z$LBD~x+9J6tcy$c%VrkOx;9yeoFB!uc1y+&^<W@d0Gn_Th~D>N0q8GDjljyIEK5=% z2L+1(_AhksnqB7vrOaAuWyI~RB@Dazhay@9lb@^ewQ^dT9u3uJJxc3vUe1<<L3Dl1 z#x58YDwA|0@=_fI<F%9>6LK>UTTXwBj2iBgEn~Cnv;sGD+(Jl9I^L<SY}qgA_>ys) zr>fJeb=6ld){Ju|0_=2ekEdBbwlI8&51O}XyFNzkW?4m4+8x+NZ4kR>SvfZ~Xg9XI z8oRRUx|W<bSfc`}%U|<V<jOlkX*7SCg{edUc0J43aU_iL$7}PzPc0Fyum{=Hr}EON zIKs|5LFjR|>PVWBif%T*cT!|JieWh8kk)G(DmQf(UJz|-G~L9uT{aTlUAPYDsy4sc zd3VK6bSKoOx`>}f%4$`0Bu3lZAS1`7qslH8LKaiCm&T*U9C}~5IL+>>Y(vD2*8S7w z#-hsp2L7P|Mw5$VgFfj!f%3lU<8gO$RNchdaB|wX_}C@Vi91fn_q)1tXIQS~IlFf? z_`*FjU3qN-{dI$VIHIGEnri#h0!kr=$F_e#m%M_37_mBovgf0~+xbh4K?PJdGOr|4 zLkF?!Lp1)l5HXvIvgoWAf`Hq8IhWvbC;5xm$K?hQ`ex8O(=^4SfoK)q%wZsjPxrfq zFA{B1CN6Dnf8}t3gzS}mIWyuoA_c{+PMknTl<QATacLu=prlV6+xN!Y?XnO_4vC7M z3<HHoco!nfQX<+_S$zK!8eh1hXYhkmA;bq~QqQE6Am6u=)6QG@jR%&)PV>7x)`H3R zJ_!o^J|r2e#~)i^Z(Z@a!cl=e|G4-?pG&a_5;AYRa5;+aSMgsn+j~8D7T+>|dqg6B za{pduGdiL?z){1m<AX6A#*~x^tD#~49KoGOD%0nT(PI6?D(P0%ET@RXHJ!g_nS)d| zTfE%xaY1if!78QHF)JSz_p&NtT}P1V(JY`q3~Yq3lw8tugDJQYd?;tAY3lAA`#@hz zw>78Zk^I-ru|us&hfcGCHY|RX2#?=maW}lC{YG|7SqK_CHL6>xzjoMf*CtgSGk^AM zb%;w>j&TD1ON~{>b643sDvfe&PnvNUX5h@q4)Y*^T*{=&@lpML3Qq1;gV4iQ1SFQ* zr_cl;(N=5oPv5Vb^u2u-hA-o@$~gr=Axi|8BhARb(f$ey4tEvPiL)kxx?xGg5(7(q zMu}>$bu8BcWalOEq+F|LKV<bgha*$*X^e-+p{TM7p#EPtQI0Zo#1#HykWzKz5=t#D z(n|h(@Nh&!f|JzX(+u{^k5(S5X^Iiix6DPnL5wVgO`}d<r#mlkd|EcPgn`(iKRZ>; zCuE|~z?a!M|K#vVR0~I={59LFV#_+?Dg%UQn$T*0v9ZVVm=hY;b$t-z%40@JBmgEd zA;aeKbcn`3#5la{c_~rm5$GUExPyIKvNMIPCmx0v$|6z%5$ne|+38B(`%G78m_yh6 zHUf+K=q%Ph>rl#`#7jF0VQ1+u9$L#<E4nUpEn5@x88Z*PUv;%$0S{50&@PlZRI1F> zZ-z^WSh!D)OSRc=UjJ!*`x~cmt{+q^KtOZ%l*xcbl-|aYbA*xMkml;ZA4F$AE3N>c zz|F@CCqJ$Wp@54Xo3bWZrkwtYS$1}Dw%Y?!CeE>QRLC;lZc<hAqwzN3HxoM>HN2{v zL6cBID%|#_%rWb1IZ%7q9YlLPpPgm^ItJ6}mZ9kMk=D%Y#f{8ttk@u8BbHec;zOva zD@bDMyx7w$|CQbr#l6o11}_Yi*&f^jL?_lv|0o5xbRYd0-{(&+te^<+#cc6szW6TD zTN$79na`h5;jx^G&>CW}OE|%9iNhna%YBp2`MVXq%`aSc)ckQXv3y^slcE!^9rlL< zIemQ9XN@IIu=FH$FIEgV6k9?ipO~xfBWqAxWQXzO22hS7RRPP2h^@SX;KiNbEie4q z^IRY5Uqjj17x10G>mYPQUWVLclpomh^Lx&u9-I{BW<*5zZloTb0R{}TPj9{a?*mQc zr%G_`mqrnS`H}wrKHd`Fz*B0(x)6GFyGERwLO)$2PAan7zmS3oeA<0TiqF{%%Y7CS zW<Sf`WPHncF_a$LQp;z4Be(OZ<UE(0KLcv%i_f2Vpto|$cK`-o?T9nZHeKWBONncB z`G22Q3dkgSTW}t?vMfJX`sND*?lD0vYnlqSTZcm%Pt1WKM=CbIMqur?LIJ+~p1D6k za_LZEa_J8&KssJP?JqzNUl97Ch`mSzesdc@U_u#{L9s79;2fnV4SV)$BTT{S-Z@zp z-mbO}tFIn*-Y4(T0q7c*6#6Mct`B#+2R1`mKS{Hct%r58m~;kpFLQ<*0Q3|iUx$Z$ z^-!5grTL|fBjT@9`u;JDZzk#cwuMWbQ{CP2ftZvW@f?iP2KFZjgt<9bZFyK;dN+>w z!hvYfH0S1RsF^?<$4P8RbuByH{exfiH=M+0h`r3gj`RUiW13q2E+$PjW@i{%*(L`h z(Sqj+X}_8I`b^1q=c5a06-S2{v#G#HtJ{cwiH~GV(e#gy^N#^ha%0Tho(7e*`y!;= zG50>6z#0z~7k~XqWu*VUP9!S`y#=Z&?&k{VxB7%d6wj9UBi0WTG^5Y=-OoV&*cPDV zi3vqMp1UOQ9T-gdO&X{=1X*Pk$cv88IuYNF<s#(xdq@^Cz_q-^!+0lap4ocEU-C1v zPx&;JvMS_F6M+bMrKwNJB$xcip*NK>0u*@*YjUx76WNq%1n&_#d)#&&(fxequ8QFI zZ-mTzM=MqQM_{0m=%oaR8jA3#Tq2hDr8QMQr7g-xaEVhngN<HkA`&GWLs5mIIzqTE zN*k-zvS2V?gDM+bC@KdfYUmcfjCm}RK68H)G=@K8Vp6M=QKBr0?T>keC9zbFWDEt6 z$;kNBu98OJARtnR$%bUE<=ZFI1|>l96SM%yMFe78Qsj#4Bx2!>nMw_0scKj)Y^`Ki zO?q5D&;MVM7X?TsxFIo_G^ow$Lc^%G34!cX1i&2!wf!~4Cso#~2DKIFQ&KA?CnP6T z+N{FbsNAR-)d1U5$Ke3jkx>oViR^z1!0uF7o1q)kKii`@qZ$yKQCQnJKSMGh?%*2H zWRfWi%*{3OF-)YZ7NS$pTF0L@kb=YIL2a^v?H`k9$fA?7T78G@Bii1k{8i5KL5FNd zWzs8?<4S4hHLUc^<}SDG)bi9aDlGv`Z<{28=T0+^WxNEE-c(VVt8MqGh(Kmb7XE;P z-d4RLJpLenR^Fo5bmbNX(Da+tqVNQx02*PFT9ZWWl4O4uh!#(xzba>L`v?(86@Iu# zx$}>JR5AF*c@5_D-hRMtI&@?CbDI@EHJ;zZCh{yy?GHkK)gn5w+3`hSBrWJh<T@GX z#(4e;Nzng_U^ZlP5jzThRb=y}#X2xe2ORO-Bt=I!WOHy!B7aqj7C?2EHb@l{J+;5; zQ8n3Y`DPWEW?gj(KlM0yD3~U|XW)N}B-bI*+3>Bhf3~GP(5l-Xn($^tps6ur(^Nrz zr|p<v!t8EPW<`M$LPh;rTz?wo`=DAL?N!_BggB`2A|tg>%#tEK#q3qZ|G~E4Q5OVe zMMreWqIA0M&Q?HGjkx9}t@^o1ZG8OHS|C-LpjA(3dQGp$LRx)ltYH56yHQaq80&wj zRMXq<)&(~xjh1u(xls%9f_|&42>?|zMiq#V)moD6q5G*oFi$C=s)PUBb9m{c`hgCZ z!b&FfFAe>?KE+Bf)us1MR{bR4UIR&emHSiDTB<I`5Pua2AVq3_6#x$IuY#<uVnO(? zSeg|DsW`nNt(63+NasxMrLqNuu2hta767T>rv-GpQU$3fO_9=9IW{4yE#GVcQ%&kf z>ZMwKL{=AB1B>gWg077JU!oiUf`h5naRHh@S8{skFAXeV^h8%O0V$6lYb5#eLKx;E z3T==XqqRaQQ+0L=jZ%R|T4*6^n3Qt;sbuO^Z)J^B87p-I(+K+WqhUc+zx69l#q-+G z!g@bQYz1GVNFxwVqv(tcRl{U%r+sPcVw$jm#hZGxT+dTj^>d!N{yfE7Ow}TzhP?4) zl*;B{>CY3MMv+Zt?Ccjwg*qHuSJ@>)tP0LZn4~daG1>r<9Y$5Q)00%d@lQny39D{l z#Hj>B-Ao*as@CB~^$G%(V^}3%IXaC}0U;?7SHz1^#HpMmbwpNz=v$K2OAfLD1aSow zJn6pzdtKZZtt(4dRl-<B32?bXHiU6106+&|Ee#S@E!vVaMtgJ&s~qpF6b8&<@@TnZ z3!qiIE^)=r3_@fLvN)ChEmYRg5=N<9Oa8Nk#8kGI5LZY8t<(vtn&cvCAwBF}Bh`-s zrFcsQ5nLkI!vLlcMdRo{El3OFKW+R+gHi(;W;LSm(hOyB5lG#*4sDcb=PlF*VI^+H zVzuLB$v8h5fsFkXRm4}X8bxhKV69_|atD<V<)h|cIT|VqT+`e02b+AohOge7YDNuX zBU<B<M2I}5_kl?86P{g>U1#^K>aFT|*g6t347H3eOK3$f9Ir!@4K5$m4>fA&=eFde zG0#2oy**%}YRRTb=^wnQVo|M38nssbL4d!F$POwuPAf=i<UqNUKh(ww5<)8;#_>e8 z(|{_ggtfy~i-ol%233mu|0{%W!dmlN5<;oNS}o7jiK|=TN%tiI8~b6cAWgBM6^&Ye zYF)Y?YH2A+p%soRfU&PtiL2FDqz2Id`})MyfY$$8NOl+^I}BYb|FfOn{!n{?szPW5 zktdYuRS5@YgcqO*Z4&aMM$v|+LfhUZ>P><UZm)uDWtzeR(N5D3-AwnZFka*WX%*}b zU9+H$)JF89zNwCV$R|b7I5x2mJ_ssFDdA>9Hnf;lSCWA(fgs|mv^doZx$C^ZH|i}j zadE)e-jf58S8>awc^l)wOeo6OGOQOp-LPXGohNR6%QEKquH!YdxKSM1z<gy^c4& zqpmEH_+kQ5A6FxSY_@}ij|Ibx7VmGpw*3X(UJY-@mi=O4qb?Zg#+{K?#^$UgjuY9^ z?O2gDid*Bpywc6r{uJDEOl3q=0LD!vHDKY|9b5qMF@_m>x>^U^fV<L>OlNmyAmweJ zSJPOr&~|w`M2ee}S2Qs|tganwWZdift_2DOd|68?5TX+wchSh4aRy?ze%LrxV?CmS z+@AE8?y=Wtw<sb)HZ#F{bvjPVx)zVxxUZA|&U+5-qYU~@5g*2_PN`jcmMgB=8WDU6 zX{xQk!9@n!aZ6dKeSNpP6x)#Nb(}T>?{j!bW36J8mTrZ#LzhG+LE?$Knbjz_xvnYr zGhAmDp{`k*>vBC(X1&i<w2{Qt>{7(~D0!oa`3WS6v%Gk4ab0j}-=;KioiswF!oima zOCe!09~8ur7Z1tqcLZDRFfHA-pL)gZVT+5Q=tKBV6G#xz^U|vT(fxLb+0wM~StjuM zZ+9R8qXC9Kfr2fo+0`q_oXy`mpki$DnJi^pp*02eZ<LWfI+I;!!3e&uQ#m&?*(W{b zuU2E#kCMJC57wF#H<@&}0_ULWpoX(6D106l_gEOGauNJ=Y%Ba_@Vq>c$9sbjZKr|z zt$w>H`Lsxf6KnA8TNglG1<(Th5d{5XKU1TUa6Yo`!F|_Epg>vRDA?gtZHDL7%Y*mG zT@Av6ncJs_d6Kagrvh4GEzm9OvPM3wtI3A7t>bNQIyFLhG4sC!oSuGOwyYIO!jI1> zvoA##!}d^!E;!$+gZSeAFa%(X6zubA<Rt65yE6wIg>a*`hrbTtOB;G~PWY^Qb?+=y zr1Rap*7ajg1y5Un<9FmqVpBbhe9_r!ajXpovMx-8IebD9#<0NW@=l4sckMg7kXsx& z9oRC07{j)iZ5+n};#c=GBtAZRrhUCUUS9{Ok3uHg?2-`qyuY8Or2hG38hm`bJUk@a z-9J2h+;hJ!aVyBl>2=BZ$k4Y(9lSOyEOc~qByb&&Mh=&x5XkX$dwO``$Wat~wuctz zW9CHeD>#0#AH2Ng+(zBqydd7MJ&UfLlo9+Mhm%TUd4X^08M>HwXdd`uOZ2HC)x$HD zPQM=#Rx`MI9-m{su&`&S(E9mN#sr<Xlhm<6_!J`{|010x_I0OoIF&=~i}WfhA*az& zBJ!hV01)riNA@OflQ1vZuG50S!#%ljby^;YU4plmk3OL0i&-XXr^I*XweN+^$F$ti z75MsYjV7{q`_Mx~>+k(%u`UaO>4*b|uPCSVcQ?WTM`m(&`U|_mSw!e&l9$tmmX}x5 z)Hz3LRIF?ckwk6#J>Q*(`Qrt_4tc$0`CCeWvG9(Q-SEN?;@4pW0i;k&UW`i2I?9nX ziz4!8L3Trj`?$^FPN7?>=iOk3sOU+Qs2+O6o((44=bX70Yv-3Mw>G!Tb^OgrA@%9? zkgPN7eTYGP<eRhr!az)Ie{CA^$lc`()!WXLjKLrAN)cjJm&g)bK2DYXQj{P=xGz$Q znl;)g<TbVuh5LCLdml#4Dln1<`n7aL<SAO&^Y}@Ejf_e@1>O)TlheI1Xs#=)ZJ!BL z4C*_ZT6yv>3}46m%psV)7owSW3s;9*@V|h7jGbhPK_NGsY21r4uXksze_kz$PooP; z#+zDh#bDCk4z%>{YL`DYal6*U(-LMuWJ=79?{3kn8Z?$Ac=yU|SWk+SSoqT09)`u} zeY#uur{BpuAnD=){;;*;U6ln8bE1T}kdu<^%cS3YM03|VtMPpL`W@E<{`P$U_0aGA zG@IX7V(9-vlncT4N8uKYN65~R4SKktET*Nst_T>CJq9Z50Tvesng)5*BfNsY?&~+- zTDY^Wdxq=0<V59<-Jlhg$tiO~1Qxs;c24p{v}}QiRUwf5_R8D#1~gT7FVi^^0`9Zy zN{IKpK!QD-%;<gZlRqnK8%xxDo!^<aZxTYm84MQ>#~u&QnJC+<+!0@@9D7`gtHT-( zEuv66!dsM;%~5|(r37EDOkcIE%wA7`N&OC92`Tri-jDqfNhDz9Sit%7BsE_Kih^1+ z=A5oxr8M0oVE=*Qjkjz-`{WjT08o6sUrO^IC=N?+u?GOfHUEL)|8xK--gpZD#nJx* z#bE)UxWyg-6sP?Mio^Z`#bE)U_<TPA6mPr*ymiq21I7Q11vmqsHyLebVNgor?LSZ) z766L>cb0*YAm7{T+iUkItnDAf<lcvqw`{37+#)j_T!V0SfgZz3dpK=yY?E*?f7YOw zJGa730X#>2Q}>J!egQ0JYSS0Mle8bs4v@o?s-G(g6)nRg_&ZdaCINptkE{#>-+<cF z9X6q#;$bcIVkl@~U}4Jsk>M#8f1AOxAY=wfIwqAkJ8KYRG>yCuGDv6jhXI}g^FF!^ z3c2l^j^ECfIrc9F2@Ndm`PgtK=LPYkJT2n7)N9UI2@?vYv0p5A2oX%`y$$usl{i>3 zoq6F4gB`J_$3U2TT)AQF!WW*2#)&L<9}!$dVP>383IXSV#o;9{Zs^LT8ho;%s4;Md zbI3zA)^sbyKg%xt6NZf7kJ^76smM4V7%SiHCj$ryaqlP;>dx5gxbZ)1q8R7*uH5Dz z7F$n-aO7*0?_R(u7lyd>!D2XcI<qIuEwQ;R$&L9$OUsvJMFa6}dvHF{;m>_2<*s{f z6o@)Na4qWDAUmn0jUu<x{o|JZpv1t*u!TsJ2}E7sbU^2(&<HmBfKFS4Og+Fi!mzi% zusK0)P&GEPWpe;~fzGxp`dOk@N$eI`@EdumwXUuTp!8t~0km;U)hR+V|CK>K^e1wI zqwElzg^qN0sLOLM+=ULy2w*I(9}9uFQ2Jc%BG~yRE@m=Ht+$s%jD0B|kx+GrbA-Qw z2(eLlg3N_F>h!p8=~D21LNk&gb{_ig&;}cgfzo^Ik|BN&b&kbD>fZN8Txv_<zpU>f z_(5hLlFyIr>a0sp(fW%1f!iMDazQucbz)#IfTajLF($u8!0IH@EKPP22PO@iSzCN3 z`7>iD;0pXs6f`3G3*HD78Ghgl_17p5SrGfG2NZQl=Xc@lc^I$xC^qVG_BMCYSNB4{ zUADOIjK$tm6v`O^7;R^p1KTI<LVv@|2`OzSKa)AWEQotHVj^~TV;q7wUHss!x)LZ5 zlnU|y0UhH9kbJiW@&HAQEb>5!+BE~f0A!gkcnf%k3fm)N1aOH-gHr}?0bF860GIeb z9l#|vbhibSfcwWKCJhE~i3e{1Tw+WBmzXpdz$GRP25^bP_5fUBLw5j|81o;O_}^Ha z|MiZ?)I}bUGJFBNMv(>sxWxZzJ_-nfdx$jvloNDUpHNys(YMvKJsk!<kAPAFbHELD z6Y$>+_6q-hZm^GBw5itB+`h?MP<(1|li8}&y#$3DDCQ48F&zc8?zm<{r^(xI<KAir zmg?~S1S`-ECj0h-x`GVM-zIr6Pkt+&NtdF&(-jRXS-`q!Z>oN3-<Lle9_383d53&v zRlm8RDwD>@1vJSBFZq_w)p-;ktJf2kY2nWGe;hoNwAt)d)gCLWT_Ba3)=N~qD{ivs ztEoFg8?X-Q^oJWY=sXv;4)E*Q;L5g}JS^2FT_Zqxn>1Ee+&4vbV23ie;UQh0U!cJ# zIg;5!w~(GwEul`#LD2}PhbNU*c;;}0w1f1rkeyR`I3v3x>9$RjQZuCW2<zN&CYDl% zwdb?N{wplaNfgu`T#;SK6x0Ae$Rb*czpxG^*$AP6S}r=EpDVS3+TsLYl)v@JE-KfW z`PJiFl8a~;o`4ao1H>1TgmonTmr$`#lg_VR&650Q!{a?ar$%!!DFY%l2JE!#5;g;N zTDFKLmwJ&=eQKprsTtO7WG0gu{%Ml7I{%}IjmpMBZonLu@9QR<+o=uEXc!#nTSy<U zoRn99@f?|R$|A9%kfM=<!Jlhya4a`tyXV4Zi%Q85bVl1OvyAQ1-lrw?so``EQ0^=x z{^*c^-&$Z14#Z$&`6B}|)g~--*f1~(U11ga^`ycg{5*`)M068fOoCupmrH_nHpC_# z%=&i7u%FQGV;$<lVY=+^gV_y(UYqz?x(tO>GlRSO${<PM^X&a6e_pHncTh0NBhI-f zuL{;=dX$MCATXJ-cnKV%$f21Csmp8JF1k}V?Su^nyuUs>ATVHfIAJweHUAqbOp{9V ziG)oPw3!Ybh*HW0^tc0XS+30LcY9RorDq{AVoDHgrRDJT`;~qXq!P#+x?RgM(C3Zl zm;dO7P5qJSPW*9|KrUXW+TLcGtDStk&fT@E(C22mo|QHoD^HVZph1m`l@#`pCB4Rh zonZ`qZLiEB>*O&R=EB==hjna<MWShWJL8dDVN6eUqTpdoNyU?PUJ9KkUNeU6N+TR> zI+nSuhlk!XC25x@tM%`E?ps?^K6u^>^Xiw%1C~w?ytJ^@M$krN9UJ@ZEvRZ{gZ?D; zsvww^1~t5TuzqZikR$}B4ksCjU+)N%MCju4o6?)n=vIOiSw@iNX~mXLwrRbO(Odg? z8h<^6(7A(6p?CnvFsA+<Ppg$Jd+Jr6Z<5JSPcWy;YI}NaKdhB8IdRHpy)K$)BW8#4 z!mFIP#}-!TWZE9P2XZY`9=qQq6&XD7j^Ip!hCZ@IYYGPh1UR`}DpoAA@r>YPex42{ zU>h=<sYM`xw(l+TcdX5U9@2%3SEIg6r^=jI^6=QNqH8bwa<zM3hw$pRtgEv*rQN3M z1MXE*5R8ZortyykJE_i|FY6h)-t&AK*FPwu6XZW(DC;nTn6{FH;be3KBXvnbSxAo; zOqNRDbsRe-7iSzwmco9=LtYnV0fr`_c4G(P$VsnZ-*WAU=@$Yv_Ah)I$^%B<LPYbL z7sUAuud6G~1&<rw_+I~vauFTWR!oTD_Us1?##GjEEKg?VI<WDlDk@#PwhUskE3lC; zA)36Ebw@$o`mr8rerdafgvP%S+$zZc622&FyMT*4!g7f!Dk|qYFgjk@|MN#k8z4M} z;^=giMMl7dOjU*&Y^%!&TkBG^w2buyg6FA8IW4K)U;n`7YwbG7ZG}pUzM06-ATs<i zB9pvAYn#~)vHCqOPrP7xHWr&zOcrt|XN(_feqf*Tl~B>^@Fhn`oSwb2lqCi>b2Gnf zgo<&62v2Bq2p(gdAUJ6p1wurI<O=|a;(t2@>j&_&E0n-X#Yinoyk%nB<ngfG%2v+p zbGS^Ez-u62)uz>@n#^_SaK;|R0&g(W9b-NdQW_&p`_XQOXAJX*!>k1|3!@L1>d6r} z3xjdZ(?Ey<jOhv1eUY3^8AITp`28?vI=4R*Z$k9oc15RvuFywNt$6LlMYHyL_1q$= zrdY{>XaZ{?_TrzMId=Vu$#A~fwJt?YJmcGQEyjXRN;EDr%UQ|5P3F%e^heS#<6Csi zY`1DCDUCJ9Nx{J<Jmr2j(iv;c>l=8ls3WIjv=Ty)R}0H|eq*BMjg{{aYMEo*)RU*T zD>(En>e$e<29$_I;lKunM+S2OKSm`7FTu)@(2^QmWh7MxpBHr>&AVF;d35sFjl$)w zt-lqs8$;y&5=B{!Rroy~hwFEos;oF`UCM;F4_I2qn4J#b%Vk?ie;EB}yqP2fIGfVW zG6Cxkq=GG3uv&cF)dz4OnIuI9e&#%zB1?2Z*vSL7lY2&KiNn7vkXDG4b$*%H2$+D% zz*|*@RoSg<wk~xSxzqdrxFwTewTp0=^djst3o7QS<%M%aC4mKHDk|ZMvQlqzv__E< zSZi|Zt~Dz27}<~wODanOO>jKiH2a$H7X07yRHuide>#?w7kL|D)*Da`{TSMT`^q;P ziuOS|)fOA5{+NLiIGy2)oLj(I29IAB!d{POY;ik~yMcPEWp_na(T%>hAdxExxlpzT zi6LmRpBX|QN4Jl+<2&D-?qxWmzaw=W<4mGc`znm(9m3J3W-fc**P=qWd!?K=g#1Dg z9`Un7oY6l!yA?O8Wu6rQ2Y(@FX1CE%5SSoWp$QRL>9~9Hst!ulChlqwHiu&he&g!7 z6H<pC?$!@2a(BJD0yoDL?(AA3zLQmU{0ZY)>tKg?VBi-=ivGA32x~ISq^w;^R-3f3 zF$@~m;!j64y7An62SjYzyOAwe*Ja?6;8?)8imCp!4PG+$JdK%qH-<ewP#;Ay$_fE5 z^jHbpxUtB}DS4non^@w08&K^A*F3yySQ=3exK>VGWYWz!NIV`#0Y?aX<(1#2S;P89 zr88G}CKL;pYn0q$E(m8ayk#Sd56tLiDSOBmn=i*R&t@}vV%@$U4!<(M8yu!7Y*bzf zVG&8jvx8K9k%J~w6Bkm=Ja=<_opC-3%BYThEGJ3{JRh!fB9Qpv<`G5e2BT=#c}E7z z*H~xkeY3Sjcb@K<@o6H(HKGK@XV-b+iA#9ocNbtp=(lHrHR#DD*kP2Eoqs7S<J8c9 zphoK!(k2}z%b>~L+d5p~_@W=wGx+;HTOR8eG1-d-rFSm9A3eMS@$r;rOwmVRY&-ir z>^rJsL~Hnh8wdaAZInj%Ixq@9eT;<*LnWQtw@2oem%h3SC1I10SG{U^uJm+HxgG5G zf}%4}(ZZ9*_U(`j<#?qMHl<}bHr{jy)F^DwX=XX*3{jR$16y3weiUj6jj~Q3hGwgq z;94yK$nA$cI9}U@C0xQLp78jppTlx?n2zgQDKRn5VsXJB!v^Pj!s1caDNBAQopCcw zx0CH%)2TZh+-gL-P@zi8rLsb;`a`-dSR^_P*EkE5+o?iy0mVXp<L4y*0%f}YXypRK zV|REygC~zLQ>>*qd&2GYAu>331oYbl=`=4ZTz^clz=zOo0hX6L4qO*>*>tls#M8MC zFLbcL$AR^I@Abj|!$T}I!$dZF20R^%;>*O(=H#CJY3cvwgN#*r5tO)0-Li}^c0{bS znc#MnVuExm&FG@KGm8qe-^5$GjEDTpEP*(t^^pMpaAUr8-WJ8b3uDWj%YIs9It9?z zprMp?gIO%};KAGR82@bLA6pvic%s-L7kL)n>pvu^Z!VF%zx)3DI*&O$e||54<;y<E z{ffDaKkO0rSg=1#>47sF^UdM@R{Cr6Fm8kY))uAEHnrkoYh+6M#iIwN*7NL$Sizn6 zPWRqC;mzl~)}nO%Zk6KQLEW_jq2tOu$`x(*xq4A=HA&pflq~yudS~m$^2piG>qa;4 zB`yWYl}{Y-GmI>$oSu9>-;Y~e52tO5ljU*k&Z8y!scs?UokiUH`}6vR=tq?ivn*HZ zN=~08i;?5<gP1JWOuimOyXhoIGVN-s-$&P1hR?0&sV{h<=2UX;K4qPglHnqPS@Nz> z@kj;tv<30{-2x~GUDnWkZ36J1Z3b#$fzB5GmW=i}@66ZTBYXq)Z|gY2M9f>RXmMTt z<9sK`Xu<NBuZJ}l``G$5RjFPCFSDZdTp|9o#_S#@bUA&e3;C5>H!WKc_r_?p(j3$8 z{P=?pRjl%YScvV?c@*6wA%xRdH+g<p5_|dazNrwy{g;ro1P3!Xh9yjAKZ_Q%v3MQE zO?4rb`wt=QZiXgI9Y`&>(m|tdGPqyqSab#TH?tKPcTt{<%w4PcU4D{Wj)^T;U5Px> zE;FqP^tNy0XP~zkgTKb)9{LrwO&=7W7?yPQ$-6K$E$M@Sn=xe9`SUTN@7W448ciuJ zirX(XO0lS$Fb5#C;3&N5=HSG<Gv?ql?2??7wnl6gqcSw3$^@%|<GR%5;KlrL>eEHW zEF;fltrJY8c@`p}m*JjA@vMSVLVM~k&MlP{qs5J_*3YO-IA_(uQ?gU3%r5TizGPJv zNsz%a0vBCr;H|lGf2IPnt$tXkC`60@w8kpCQYT+^<<DcVBbw`R>=ypJrXsHzHHvGy zmbTTZ-vK<e*V!ceUEYR^-eefgfy1Rmw7QE1LeEaOG>$H~HxFDX_@yY>z-|^jE@wzt z@*z#eNea{d9sA3-SMs?$NC21hxTNagK`U31F1n$hUYj0cjh$@EJSuLgh@B2sma0NG z>086Iz<?v>^YmPY<DNo|z(u8@rdy2=cI?t`+5bYzX)GI2w;(nW1pUBHXD4%(5J$lg zsk^mJbCc%cB%+BZ)~m=Echlf7o$vW1;TD(x-YBcC`8b?nkksSsf4mj#c(1IR9c%V3 zrvkX^32sb%5=|}ZZvJ>y`RZU@{=N^dXN!cvppg9VWQ8MH$I)qjIyfqc;E3$3lZ%#$ z(aoeih|OR=9opWo=SDC!`Vh$<j?m}+Oa5XficaJmYiM+0T1#%^+iS#Eo9Co}JvMuT zcvt6yV!tqQy@j`b+V-n+?DVAX^n8y>dl-_<i;nrh^5w<L9FYYGfsoF@a&B^9L{I~$ z?yVeGN8mtqf&5*>y(oaf3AA&vsCu@Sqz_ny$Xu4ZWFIJ(YgG8_@M8>(%Wqv!S{sWs zEm_j)=c$Jvlcgir5loiA9g?#aS73SRaknW_aH<GLn~2{`o_lOpRhE#-6nWON<hp-0 z4bl~<m_qfe1}Y+1Yg0pMxa++|O(Fg%n`b^gvl`-yc(_`qhn1Kj>Z9?3p@h)v)Pt~) z?UQF8VhJYHKoo(j0Hb*(8J=h^S%eG6j#GW}O&KzWvM$~<g91|PZwC554P;Y%<|GVN z@2nTl0pP((&S+r8E<L8SG_}3AirC=(7F#tM`Cv2*nMj?4|5}Y*^nt+E_SgJtMIP}> zT_3prGpV=ndZlm(43<WILZ1xK$_4r)7a0e{g&2kzk`>2Z1{tq*^oqQLSDd<+xF!7> zvtr|s|4KhjOU8ZiYXudH`v|M*1E=YmRRluLlc7H}eRONebJP3vZI=V(P%G0r%W%s> zj4=qv70A?8qS>?^Uf)CO!G+e|bgQYc*F!>0Qy;@#OAH=<<I#o3p8RjqL$AkQSkKcD z-1O$_i}YP#Xe*0=19_PA(^el~W1OCDxWhjLR%HPPJ}~8{sj9H8MS3d`BONtG@X<I_ z<^?rmd|p%Zn3hi}L9r<xDhrI-hD7BT%bhGP3|^rzx(v;m8Byr3(VCAhMU4|fvetPv ztrnyc{VXn>2Xd#_+8BaN{0`x-BCNdWW$aI8btAUGg=FfGTHS(SO1X#nu`jt?vF^Zj zsy>riqM3LdsoV%@1N<Z3<>W*7Fti<lnGVQ1_JmT4PC-qKV|w7`yk!w($t>K2nL&kE zoE(hyuxDqie7Eb*Vk_IXD_*Oa(sOKQHrNVrL3_dEUx)XOnW|L#Hp;BsTSZb@oqI)3 zQQAn2)JnN0a}g38ycr$|AtJS{a3cp{-z`0i0eGbiwaUO|3h^?N20z&qI8?+Xw>_%^ zNBLa{4l&wcDWT~uMJ1~;v?b02ySa!`TAV2xjqc~KBIu(ee{RBEDu#v_bh4P-;UKC= zrogyk%tv1voUZ2@OCY%%hUaF5HJ}=hrXfR&MWCq+-kGurAX1dYvo2m$2q(#uFcn=a zl*YH!$`qRY=}a80H)zcNVfuCW>*P}=F(gS!ZEb-g4x<4d8@f27PfKD9Zr5i1=IpXx z-OJAm!-lybB2zIuWkt7i#r*mcRkVlhcspDc)mNfb_^+PhxL_27F{Ol}yIJ&D=03N| zD0bBNhdiEWH)|iZ;F5R^h0pzy^qtbou^)Kv4J%5(lE~kJTNBiMFmX}Q-z$GHXlX-= zEa68wQ>}zZcqNUW<}*Q4yVGUWC09xoFq~lN;<`)DBHl;)JVevet083sDS&kmnFP`9 zx?&V75YXey8Z<Cb<kHUbu|SeK|L#cdpM1M~9ZXEj5a?3!X?Opw@On9WZ?V&*+WBaP zJ2)9BDanaUDJeNgIT@=t4)gSUJNLe~@|?55oyp0{-rm~E+QgzTVBzihaDTg7nmE{S z=VV-35Wxi>criweiNEN<8kzb2V;AW=;u|~D%|6a6_qnQMsy<%WXIJ`3n_aoEfq+uK z^Pooi`NU$?9ZEpnjcoK=!lz$GE+j%^@9A&JIH|mk+O=)qDjzxiTN+c$$3e$v2A|p& z;eA$ocD=1!1hH;N0c6le=C)9qfFRzE`-1-cElnEyOsta(hVj`<#BRm6w9?7**^ZkJ zLw8h8T6wyT-)}EA*n%>458b)tPOqLajHtjh2i)nLIE00sngI@klA;>&FB$DOVq!P4 z9o%np0zD%qP6Shu!UZ#N<jU#~Ij<iu)E@^M!m2E+UqysibI+R@cg}Z#e6RZ>eX~ZV zMoR@x!T>^OqVRX=$t7L3BhD-P8D6n2_g!_|oJYZ2%8;Qu4up^|3$`A7O%EO-hFn6& zVVx~@mNUI;enlJ~9LfDLkJ9Y#8!>f*Rq46+@BdFkN}gpUNN@~YXgaG~OH-zq50Kjh z07;?R<$2wa_d$J1?R%5WZSEJ+jeXR0jlH29IkhSW<7cPVE@bby$P~A#huH-NG2QjN zB%mD8s6y3odu+=!L<G_ceB|c-zcH!95wNs_m~5(*?S2AE^Ys`z@1X(BzfMkr9f3~B zvbkrdQ8f755DknIoMRN+O;yL8&f&Jvx=_Y1ClRoRt$N7sJ;LL_c5wPM;9&!|e4WlW z?5&1Cn&Leqh?HDfGG7EGXBWHM1fTr)NczBX)nBNQ`&zw2{{u%+{|84gM?Q&2`4}ts z_2rh54EvKIIQkL&{KR!c19El2J{yuc^#7}3^TrOGT0&%+0vSgox}1T&hD&^*lX5R? zHO_ERMhgBpox+%W_@BR^^-uHL1+Qx{yFkj~{x62d>u;{i*9g0*l64f<jFvr}JQ)U~ zW`D}x0I$Dv*)Q=VZJzydYOGQNloYah`#kK%^&tWq`6y7y`4P*<P_nMn_kmq<@h1y9 z`BuIGRFJjcMG(Dujy@dlLrbR96!wEiD<`Zxdyt#NEwF>d?)odTL($@c)53?1AOc^h zciszxs-F4dG2gH2nUB$opL|^sJ<$b4--l)57!q^H{`m9jKZ|5}!Q=SG6BSQ?ezy5N z)7VZV9`&9NV4PcAE|Ct*^ckMXj5F<;<z^O?v7|1Mwcg$ZfXlEIIFqF}ed1N^CJ%6I z;KG^a#4Y(gGz`hCYb&{IsK`0XC_xqxY<oN}LU4Lcu^tS{Lso0O?J<vKl<DYQv&8LZ zv7;mBd-5m+xA1B<#l#{6Ug!tp$Ii!?^Zxw&oY*PQS5`YUds`tOCvp@&Kx{GJmi6rt zK%{zqz1-FVgp&S$xcj~TA9ufQr`_^l{uQ)dc8!=qiu-c2EsOAAI<>3$@640a3Kgd* z!L2=67tmj*|9`vtsf1A+wcOBi5KAJh4)ROHD%WG7#_ZYr<_iaXfa}_`S?;^(`MwkL zoRfp)<9xQWKYhAK4;tq6ccMSX=+={U2w9^y-6KCjZ$ynZ(_DL-;5(P$!<OMoA8Tog zeYqs7>JnylwmX$m<Fk;fH!Ta4NP6^p*rTOzU?V-V#ZT%uo3CNe!I-pbbe6nm&7g=% zcrn3LEw=yQP`G>~!^9vVvlUjnInBDEP5$A*hv8BoVKtCcrM7f=!E)~o(m{v92`{L| z99g!f#I1s*k5)S%bqMyCFuOlyiLQ+4Zf~5cv42A0nic(AGu9?RjR}EBLIzn#xxWR1 z@>Z<uJyowEMkVm62_Y81Q9_t~God&Q@?Eas6sUP<@R@`5w8*Kpl0Ag^B3!m1Ld!p; z{=<0&;L)B?3CREAa+h!$LpWPvsHkDo^w<@XN89&jw67zEq74`FOVw+c4*xx)7$bib ziOx#QU)iU1G9;sKr3}uqtoTEQyH=Rd`>q#RQZar!^lOt3Uwz+(>%<@2J&h&txM;(x zbiQ|AGfViSeSGw-qN2kLTRnj*d}J8p-QR7^K!FGul0-PDG~-u8QWF~0Afm_`qCa?@ zR5$HD>R#{cV2Ev;9d#J)22>|mcNJ-}70GS#OLP2cc~tL~LkvsX@_H!;eI^Gn58jW| z{=k<cpKWL)Up3^1FrK>Z+f%}?>VSYf5IdOY?seuNf`zn#_T|zcH%|A8Me?zy!sbsP z-+F$oA{QZ`0Dno8nW3tX77U4MHi{51`19|tH??UIjMIZxvXfzR&fz_{<r|U6;rQz? zUZr`&@swVr0G2U{u;hebnJpT=lMz6Q8SMAD7`+cD$O{%MO>TQy-~A<igDi?@lpC4I zzUG8{gj@<;--JVyo4v4$SCkqMpcS9}z{@Z#?9;Fnh3EUQ=i9-kk1#a{iwj<diLo32 z*?JHMO5_kl?<PzQfuG*4fFYW~N0yLZG+j#&jZLiqjPo|d6dGN039C7b#^2bjoGnzV zc<+c$+ZJo$G)SxXt+vH0e2Kjy(zb8a#F8F-J4}(TOV8W6;X`G&7kXoNmo?Ml;*f@# zD$^uLNZ3h!*R_G&{`b`DkEg`_1-%=1qWMdleH{$`&VrHd(7L?B&qZ11n*PhrJk@Yo z=({{YB>w^7EZpt6c++#EQ8p)_-lLqZG2|}D^RO|hTjlg1*xe^0DR!OwrLrI+jdssV zYwD=O<)VuO8I-`bfdug$%I2hEw;-qCEz4?$#mM;yd9I>|^|CQjooqU*frKfeqVsdB z<UF#O#6PPaG(tbzC@AoLR5yt6ow49GB~{B&;E{*85q~CgDDD<bBjk`2wbg3WTM_<J zBo!OC&HE-33qKT(!=((lC6|gu9g72j9s*QEI~HmOv)<24$dC0*#Hhhv-%%wF3ayOA zr6(;}G4PjEw0D2`a|Y2pkVVk4*gZ^ljEEHw^!t&@KsJ!C<~$GiMuB!<nq?ayy)fM; z$q9H>?20%z34L-)K=XPU;O0>4qIw{Xw~R_4@Ss8!eAl=q*s~4evtm<{EN;Pps^Qd@ zjJBWLt?j$aMmkv+3V^T4yHp%xcTddO({ym!4M{mi%y#aQwS$kBFkMVEox2WuFUX2k z2=LBAYVg<_A;cqr#|eOV1e_z}agK&uLu!CrRt8(B&WNNAG%j6gtmjHoHe~<Q!Z8&o zWdk)aNy>o#BM**GoQZ9y>0UF}f5414J`G~5Cg5!6$HpevP3jv`+Ri*UzC#1Ycjx=v ze`A`^RV<N>PAk>XZ2}h8EnrjjP-$3MRn*dv00_B?awfB^Aa8Y+bzNvjNHJ0G>oH#< zsDN0z4!y+B5(`yS55uPRXI|MdZOT=V6_B>4j3q=RsqHIQ29)RYgkzV7Eu+)a0#l`_ z5l2+1*z$hRe_SMaE)9!q$R|u*dka0NygT9QkLCEY)E`5Kc%`88VHnEPzHnu1SR!S1 zp^3crj2jX=w$7?5S<8C)6^5g_jL1M6mIVb{kZxu)0%e?>a99+UV!I+l@etUx`#Ogb zXuPl0$v)4RD45SY%A3`qY+luvxJ+Gq#-@4uAx0QXwTYAA=Qo;GbrIDhP5h=JWp0Y< zU;Gr+iW8)biQy+htdN+}rOFYOlxQ<iRtT_sYDwWRMb=n<9k*IxGVWMPgme_nhvthc zq1GZ4T^f0J>5vr5u)VAm%5C#OC27^#mEnn80SEn{Sva#5n?uR~-B31*V6KDMRmEkT zwrKzLNt!BGM<vTqs;m{b9R`+5sjOVKtw?zjiYE!?1+3yf9qB*as?TMD7P#B#<a#7= z@O-!f$LnUgUtwYB+#EFMW*brvu@2|k_V$CT8_)VxOs3)AckVG$yvsId4_t{;=Kju> z82bI^Y+74P@y^H%l0~S5%N9>!Xvfdr&JFv4M5!Fu^`ZH`#nNxjxt_XT$?|cxp<YP$ zM_NORw)aOPncGkaCM)Fx@;w+sI+!>L+Z8!*`Cattl}zsy?e<mGa*LU>PCJj#;L_C; zK>yk7{CgNwb8Fk&`!}ThyXb+|%tNE-fgQHjwVr)|O}(6r)=ZMoip#zC#rc?x3!U!Y zIr!FkX3-W->9OZk)(!rCL>5{M-3rG9#Ui`!Lu!9g8L#0$y|yRqrS>EJJ2gGr3l({C z6|b(Y7q~si<cZnuamSTb--MM$>GfzF70^nz5{@!2H_3Vgy${OITT@pdCT?+<>2FAR zDNry}ARr(ppqlJtN$K&7*c%KWAaGY8AV2}+WMSiCZDDIgZ)9g{YGI~i;><wjZe!h~ zbKyk%EB?FN7hJ$u`%+f=dG)hByA_{}A=TokmmJ7VZ*nkLs2Vxffrya`4Ul=MM_NKf z8Q8OT((A1Gj{Z@+=)NfN<zwc=WqDmOjk(X)Qm?zsyyd5y@c7GpiEAEu4PVpu+Uv$i z_AYF5roz&zR>kA%(;j<z>GBHR+R+F*!FrXh=>11<<=Ov5**8Rq5;R@5ZM$FFwr$(C zZN1iO+qP}nwr$&<{$@7+H)l4p$U1py6%iSUs+;$Q+!dx4I_5!)9pyM{JkVXC34%{@ zLP%sWG6kzg$HPSr-w*v-$Sil9bwO@|tJ%v*b>d-Burt^)@<r5cVnydxdXM#P0$orE zrcKMcwM-lCfg9gC;w7p6H}<oiWsl9slqo5rzG{sc3o1)qs07O&CXvGQfz^$y2sU)u z$W@HcUla^KdY~QtP22bijv|pg8l%=MeHvx!m0xHYg-8Q}m2`$}$a9h%$RE6hE~`~5 zO>ynon;q_zB&~+{m)0cZ^W|@U#7u#*F|X&z;mTQ*mVI+H<d$N`=L23~ADt@^NsJDs ztH(zr!AeNfYVNvw6C-5s4zIjDOGff4uTUmY>u^FJz|FD=Q`^Ow7T!B&HbnUTo@LaH z1L~n|96lxS4bh&vg%}YG5A#J9oLCE4lk>zb-=4+H#oV0Z6>B=s#HANzyb3>Ed0`wR za4=J%@EJk8?~lk^Y)PVskrn?f!=x1loAozHv8@Po+w!k%GDl&$<Xi&b3{`kXX0$L6 zb_6A;wJU^`$jVf*AY+qe3m02JLZY>OA1)W4);zd``tQwWrFsY22yK}&q~wv27y`Y} zHg(!KFJaVfP^{z8&1=&HhIF_$Yj()$W0cimn2L=oz_BHVTj4{P61F%PvM)on>;?y% z5d>F%Wu^R6Z6x0$o_8>z<&4ODxS=Uvu1p7dMK}GgOFL#43ZbpBPfKb=gho56aSG{* zCVy1J+V8yUS$=+CIxp7!2l!#UwyMPrajGS<a2UHEORA+3NG;?*`%*0VOl8M-*tcSU z?eFq#JJe`6@W=um|0Jf37Y#pzTG78?g<ntXu7k_c1VW?%c_F*W;IsKInHxBfAQCU8 z$JQuyQ+u9=4pMH~5CC&0W2N;V*0@Wpv9-Fn#rny$z_|R)L1<#NZvyy3N`SY`^8e6j zmw-}t=`XrEGR|j)1z;}cVJ|bvMRw->Ogsb_pYfqGVPu6QB$u7;WJX84g^+HXnVTDh zMQfeD(#W|pnSHaY0F=t1#wxC-+`Cv&(xR`{vyLvYKeqM~k<HpS3G_A_%4$jg&1z9( zKWz<Q*{8NL84FsQI4vd7bL*ze*x^GcssJ~~Z`eboLNf;#fbGi#xvJVQYA4AU(Lzeg z2iR%>yG{wfZ5l~1r_WdpB5t&9XDphJd<ty@d~4SH8n^8<Q@?5}Ei9~!mkTtS(NlcN zS%9Yg^gn(oacLmdzN!ftC*F2u=rJ_uGfNpbAfn}F^v)=09=ZZ{I6}%~N@)xcDZu8A zsHTT9=s>^Ct8kW6vCchuD$EqNR0z)rjqx+ifjsS=kndy1&YeV^H(V`2!-1g5`zM;` zFa-P-cfmB*1*1w5qy{o|$+>)h*HoQ$;;Lqh<CeA1BxW78FO{HTF>jWC+~mLgR{UoZ zNA1Nh2fbv<^MdiG{SN}3OlXjvL0a``xOJZlD1684-K+znKCFFG-eI6dSDt0EKUHXR zr#vwN6X4Y!WMKhyRV2?@*S~H!-p8HVQMh!93a?;oEx(fIIf1GGt~PVS4pufk!=;JR zU6BJDX-M(ZJQYqV)Myxty{68A)o<aqLB(ps9yq;tPhyok@s$8~PNaAcws27X=7K(f zth1$gxnn0%P32OhOokFIo~ykHl!VS4^VsryqPF8_Z%5tLG(1A&46A(qxaUX30C{h} zHZyQ@FN`04>rTFT(L_AV#W8S{7j59~65ZCsHj+%Bh8Nd7dA_j@&hl=RCPgD5e2tly z5s0r4b~v?YU#E@MuLIyf(q1J1KJ*nl)4*S^(wArGXI5q~4|E(4tzT0&WV3-F(lAp< zQEq8~g-kilEE|=2S92%@N+0QDKjYVX)7GNSd~Sk`rKD(5tM`+uX<Bs$3p|ToLoZPV zFaW|IgHc?z;w)g)ftpM91DA2=i`}yWC#_t=yoE~^YeG{j)9lXAqsm<=!(KO0DcmNC z&)5RLz*Ir7N7Y~FdYF*rVY++66PBof3Mtqa4$vNitU81EkT+($pS(t-5cna&tkQ@n zO*=}LPwfh&<30F($Ko?)$?-EW&_^pv?yV}NY6K|!efB)7GB;E#)3#Teh6^cB<BIXe zw&FUB!0tb|Q|eD)2IDOv?#hQIIAcT5<eW~agOrN8q2;H^lnd+1;a?SZvur0L<k;28 zRE25b8j~d+EPcUNs!-Gv`?Kf4t#QN<z#Ce$WW|!P#vDI)n?7Cyo35Kv)IgahN3{fr z?VMl{IuR5Y!07ISHk-2BabLt5$iX@8J2#@B76N#xH){r}C8`zjPMm4GUI$iuTub$D zTas%^M77CYa9&5QVUows<oS`TQ}g*16xA0aGAz{gT`R7F1uJ{A1OIoWX5MZ9F^cD# ze@rQy8I6aQ|0ki(F7$USfm~YDk8s7a2?)9NIHvf)d(@0EOyAT4Y$+!yuz{uyV>WMd zQnw$6(qfz_@Xrv;aQd7O(o5wNBKq|griNMwCL&fK4FgQaF$a5J$3URC3j?WSy%~;m zTwJ-(&b;}|EgG6rTv&-c9slk1mA3f_6h=3!l5%+sUA8+=w|eLjs(_I)1BfP|D$2En z8c1#m5^i#gFkW696({ah1I#P7Sm~F#&n61jAg)LtGy_OTf}_&e-sCefr~siXf&FwJ ziwM+HKpPAdlx=y9zFZJ9P`LepAlQ);G$}PMai>^4%&5CK2DS4jo6v2aq9v@jyWd45 zi%0HS>XB7`yh<!|7{4evb5oJZy`(@?zUio;M6XroERZbODxcRO76_95MWlL2kc?#( zsXWwdAK#y+N0*Vc8&HwHK6w^mD>V^Y!kFQCkW_k9!453Ja*D4m{dm=>pw9uE8Fx8n z%yvxcnYD>`0b>~H)AbZ$cdUe+ph}<&jk-RC_h>R3%9TUGe=P)Nd4MafaL@kz-V3nV zrzQ~e5@<H`_x-8%J#E&^mVrH%8M&mr%DR`i`fzuJZl7_1Tl_Nypp)VDxL7`UscQrA z<qgQAQ~CRP(|OBJLTo@S^rqrYKWNl5y$r=VK7qQQ1X&#KOB|`766S5Gut%u&%+km$ z8sQ3Rq7t$~Ug$>Q1S@;x9Qe_vV2?ie`ac$@EX_RmTIn3q69A!n&UM2@TLP@k9-Kwk z{WwBE-#}3^{4*rMm_=KkP!Vd}mm4;!3FqIY#R#d;Sc@AXQS2*YaJU4S8$jpBITS4< zMk-X<BDEBc?KRhFXS>npZ46hvV;3~bQiK-fYk#A8?HZ5z9y!J9WpOYRYbfeiwXj9D zYywOTN4@kTP$cD*U)TgUy6;1W@vO~9wER#QVsSAd0pEexgi+&-cZUJd3DW?Ok}ByB zYXs*Z`<VGr9H5HDoaCY6^KZO>e%uOf&U?2CjmwoPN?9W_099d{gO<>Z{Ht~q2km34 z`?v{SnC=;YFXH@fItabdQ-ooSL>q>_$3ev@ZQYi135ouBR>pXiYM2v!B095Tq+3vg zMZ7nil~BAgL-oswtmL|eR=^=B)WXN>IMUYxQ#%aAR~*XboFsQYd|L>!yL>P(x_ktW zqWly2IoD(~C+IS?6f}`5vBw>u=UTNc>MELuA=pKTc;Dub^>?j}<2S($VNyTwPz_$H zbC53Z@xj7gD5RAgpd6(~L6(0gWkqexix2_e>R$-gb`b#3Fk}<&2&_PrFlx*DaY}$u zz_%+&1<HX|0^bAE3xp!Zv6k#$GL-bUT*hyO?1oHBPr%qwHlu2mS8CSwA6C$*Y;obb z_e@tMmF6g2@E1ExvGZv+3FAo;Vl}P#u`2sMd0QA+!QW~5{*Jm+=03vT`58!(>Srnl z%~AvhdzQpK-=cBJ_3ODL`r;~%hPzDTWNx%NU$xvBWVUvbg>i0i`#e>0n?a<UNW+%P zMzoMc)ZLKEe8sxm{vP}lLeQbGF}K`!j8+>#;tk*8eQIzaJQEEE`E=zb&Z(<?WTm(! zBv03JMPu^Dt^jlHd%6L;;usk_dwTaTE*sk%1r&)1@(hQsbsbr^#TQu>c)bw^&%-?Z zUb5}qA_d)PS}QRiY~<4Zo8r}RYD7*oagP|^M|vPNlFU#<J-hhyU>bYtkUkZUD&t@& zg)HthKJ1+SH7Z{Y<3Ccsife?0$$eJ27S0>>lH`R$wt)CV(;~1UtiL{P(G=ZGe?2X> zMMdo;BGlVCUM%6ER5@{|Xv?$bDt3~Yx!*$|rCwSioScL>n^+d%K6?^DGpuEGIk@1L zV@po{C!0R;Hr4;!kboeu?54xB?0c8O*z!K~&bE25V1Hv!+u&X;T7{|VD9MSYq+Lf& zBt!z@x+rgTeN??>w2%BT+Whi%`5VP+#o@0CiQkio*s0)*2`LmLl<*8Wz?UFoX*0Pw zDr0^dtp15|H71$lYp#;h5!F%~g|uIr8N9jt$h`C<MGhM1oW5!yg2)7d;~*Y!99~#U zYd7m8uQG*jv8{P*oC!u02{Zxq_>@ciy|S!<lcXsRonVKAyYrbyQkut0wE4ck(@`U! zYfBYNokPU^5YItap}VwP{RjAGM8dV%ct|Q;UxMu|mOe@6OSF9iJXCc8R~rS(*SMos z_<n`fGIYpT3I(W6q1?MP?g99Uh^o<zG^~gS${CLSbIt0iWQC-Z^vMpt*y7?uOx*bp z!ZMhLE6-|&yg=%fwq7o1m=FA0;{LsGQo}|jHQo~$3Y}=Stc$JPKilLinKt&6dr#bz zGmzR=@uC4dx32ulTWp_I#&>5VSle}mp@yJOm}WwjSQC1M%`vk^dQ%VE%{#v3X%=d^ zwzC2VuXk}HRvejsL|Jb!HKxp%5(gZq7h+On+ojYT)g<GEJ4t`>I}uMx&8qb{Yyc<G zG=j<Iwlh*<+#wBR*qvMc>0K9jI<lH41Ij}?C5)dPkjCu(O9Am5Yv*1H_9MPqR?<@Z z9AaUR4mFE%0Fb&-a$<L=S*}hNslF7DW7%u)DRHzEeFsY66YE!_0v}&p2J*VWMH&Xg zZ0!Ssuwn0kxI1-#6R09O;Q!|>5uzZc2LD08Q&;qi76xt-{rCmUH<m&Fnoe{iGSc2w z$7_4GYq@X?o+kT+aiH4$D&XTaGPfb`Hh=X+m%Po5KuvZV!+V-N@_y_D;Vz)SxJt7` z0jYax>0chiGf#*^C<&oJa4Dlz4uWqd6;b2SI*bR9<_7ggkfpE9t<+>A$<p}>AVq7x z16Q)wxH6y?xZyHk!lz?@;gvkL<3X+~5ZJ8>4$|BMzkMsu%g>=j;i<?jJtZ>>HCN~e zIz0tKQCeYC(CgNJ0<kyhd|r^Agp&~B++*dne6)vtR)JBY3q}gJyiLc4n-qHow$X=< z84WuzsQ~XJ>~+Y({g##pqS6h+pZgY)$O4YL6@oM7=Y$QFY<q?QaOwID`M9eVZi+47 z&67;_WYU;^VG;#pRf@l5n#X_&!X;bo=o!i6t9)x{qbnhm3IE)4Bk}|eNj(KUj-c4} zjWt6w)x%l8F7J2)-irnop3Mcdi>2!rE&KbU?sRlxF!R{5AcrW7Y|(DPd@2C%Fw7Y_ zu50pk4A@!rjN)q=OkE4m%2~07^nhFZRYLjbJ$s?xPG5gXz_mog^-!?0L1}U)TcFfx zXeO7+P6bX$9fI32o-B61$U648iJ~o>w2`r*V&0Updw_>CV}Q_%?JxGN_Bx=h8E*zV z2U6rnTsrgi+av#a(u7l4P5sE;)!L=5-FL5HlmuZ6@z8$g4GLGh#r?dYqZch6#Yng! z-b@|E7j6W6Om~0-u~$AHjMxEes!9g$DF3K1{%2JmfuTm3IXsU)*wVCB*)BJGWSXY{ z*~ji(2iUSr<)_c3R%tItFMKse?|{)s2JB}lH~d1JuSDLKhuaxga?EX-aa79`=i>Iz zV#E<idez{9%dqof*o|?2&jtO`6<CVYDD8=0lCFBFK&w0}0}26>SfzfbAwrCe`tj}T z1hkNYR0P}Uc+(Sg)kJwCS50w^t!`8Sh0GaPth8R#i*D0xoP|{W*?tF5bkcwqOK35r zO$Y%`5feS;RkU)=Ke8xAE$Bk8R=%jXb@|LuBpZBLT_$Fj_5$5d;~6~nCnrqeGuUFx zYp|P+aIt$rS?}C4o*eo`M_4>__Z=zNChZaM^z8`h0M0#gZp5+$XF7-GY4UQ$Dy*dl zpSorO=)SW{t^-m?UntN)1ocpfmx`n3(e&z$YHLuf_#@k2iE8B3;4#$|DGb2}xD>8N zxao)|vu!3Lt$}%V*6z+om~+4EX{vWVipriy=nEN2yG&CP*7WTCYa;=8UXH?x#>s~E zxyF@+Hbk{7R$`pYKKK23H)c1M+_E}Z?-5sAZxNDJ2F|dhuf|sgtAbEDio}t^*UOmN zl*l{HVqaiXJzOpiVfBLK%zF0(!THM}wCn6a5UmlDZ7UvkNIKzVpV=C<Q^J^q4v?V% zXobTQ`M|B(c8D90k(%|y>Y?QItPm<U!XjUsb&;165Q}FV?meRC+3Q`CLa(OL>nH!Q zE=@k%&SsAwEOE0T!JcpA0NFy{U3l_aV+LmSSow!>d<816KwRg?sjE(wPK&Ln>Of%N z6RbpNUUblEtD6ygEkFEe+n+s$u=KRcbBx&=wp_R2Md<2<>uE#sMd77DmOMGZWEX`$ zw(YEWE|rm+657LXc6{EC>|o%h5idENkt^i}^2TW#-mrr`>a~<I{%YH;FL?L7(VL_2 z@D+KTL<yiWUD)B{>A{;tmQPH8I7;*({3deJ1)&J89SZOFcFbdaEzrV>cx>yw>G6Kg z)c~v31XeLY$L|~fKGm5`_eStQmvS$8o@uKnwZFP~_Yh%`UbfqI%b-^R;P10z5Mc+- zy!wo4$GD%ka=?ImjHp?0yhEFz-I~aopWw98gT~L+xj9xubwRf%eqa{Oye-Nv-O54L zA&y-n+k?wF^1W+8Up7I?*t008XSVz;k{^wFRtighL018UfrrzeZgbD<K$>s5)sS2M z$czwLvU_a@<sA10Lx54hju6-)Ev*Ees_o#`EVH&1Ed*1YlCHEvuQ>SJl7Pwp{tDh_ zAnpHI52{z0WI}M<%t@0`%0gf14l~cI6`x7<i44aY{hJ@-SRpjelXhB{o@f%uC<+^g zjJeU*`r}t8pX%E*M_6Tq2^?f}T%HepK}%SoxpsA2<{^F&xN+Bj0xDXu%qDw9GZI+a z!7<FxcLt&Z@A4VH!+@d*pX_{)A>wvm-X)#u;sglMV{7z-%@+Mk*k{DHgl2G?%A3Ir z>!bP-re0%2ehX@lBV`)*$Ij6JwJ$D28jDyxXD$oo;4u>PqEL@m)e9m{-RJ9!)iq(V zJ)tGfW}QCr)Ez^~(Z~MlO1;{gt`J&JuN}rm4V%2yrpBzt9j@gf$0e|Av8$?nyK$)$ z(OTt*W@LkrOc^|i-O_1rxsal($z?+$KgYiZERebkvM5viqG@V~)c(m@5*Z?cFx(O_ zz%I9ui?0=2-A6*4uzB|bi43VNWJG-0lBAA>MfV6>`%3ox@EGsX>!^$pb%XBVj$FPA zj{MU=UH20*iPN^H)Wy`YFF@W0Zu65iaAT<7ZNp6KxN1sDNb5!o%Y67Ix2dLL4xC*# zt^ekXp+-BKzv*J4eb;lyE$6w*O0O><$=UTUX(r?S{$4;Z1BQ2YpZj(2_il)qC-k4o zqy#kV9UoY!sD0i$DMmcZKsG2#h92K-V?n$zlEpjI=@xIn&K>H%*u7w94CQ(Kycae% zo#uZ7O!Rzu@M6l7dE!B3l|U-J8#_P2#--lh`|mJ(VRd{t_J%T`M+Wo(L~|mmEZ(Zv z04>UV(u%>AeKSmP7nnt1rJ7296}@sT^R5}i9ZRh(PvSY-=4O(Ss~qP3HoJy35rMS# zglQ9n(a%scaaHMQrSSQ_cDuZN(|kJJLHd3^p4nXN&}{VD^5*!J`V?IJ0RJ~epyxNR z>+y>X<o!0R|0hNuVQXslADEz_u4Z&ffn17)a(Z&6L4|RVNnTNWN@`keY*MO4g_1^M zp-H~J<)GeSdPZtO8eW#>Zc=KZ<v>xMKa?DV7%l0Q<hXd9@(kVVIQiK4*yMt2z!>)N zFB&-oJ86n>GN4K#N>VZ9n!sZ+8c8yMP19TmHfW<b{uC*|e;a&mCX~GRYv?&30092~ zG}z41z~0=#$iP~{*4f0-)WFE(KUPQ0@mK;gAb{>}mmr)Yb7etarK8Apis0<M0vWP& zV9v%cVbPG5#8}&t36%Tq89llyc2u|-0!m^Ck?Cc#De_|!4AHwWK0G!ib@&!-k7;*1 zFxx`FFsC8DCm~2i6x_{@89kR^ctE6xXBzh?Sm^-gq-hCaQ#RoE6>)e$cx$1nw>=`# zv?5FMlTb2ea|s#Z)(tl4v4bCA$tr2j2KY=E94ZP@@q8K=`qhGT>PdcLv8OVF7&F89 z?Ny(j!W=SS*rpR))wB@eTU<wRXKJqaUcmo%K*VA6u0nqUG4|Ui{%1h!tzFD4Y@O(Y zEey<T?VOw~jFepL?Hx^=oa`L`6B?W7KB#_r1mT;naFd($LS0FT`3N(LQ~1I5<zQwC z3C+Qp7Ei=H7^n1+TjdWNTxt|#@EV0{P@p&7%~g1;6Yrg+)pSAJH8|eF$uE!WVsVOK zb0~nNzOm>+2WWoePRb6x>lWS1CB*dd0O7c*gOsTX;f2*zK6ipxBoLfsU&X*z-7-h5 zBiR3Thv^5=$M@Hb)!#<`|8hs#&dkC{z}CRp!_&l3{(t-U|C63~V{$Xnu9H%eWtEaN zP@@zwGm{O!Nm>gje=9X9)1)F8=SC+<Jvu5aI|(UELjj1TTxo1pfd5yEXONqu<CD8{ zJb-DzpZX_1agi`LPoBx<v5ph=|ISf2hD8b-006vkKmfG=>4THAfwPIJwVm64EWXn5 zQQF{K{@KY99AI)I^A8$y)!i*N2~lh<3QneZyuPNd93dvWW36+t0f(63-uaq~`}~eC zB!P8cmxgY3c6KKIil)Yu5VQOKX2**6vgG<_(!CY$cA*uNu2W%_`qiR^{8HWC^7I0H zHdR#7@n~z#gCic)iFvl=Z=h)SxNXaFu7xlxNH=QcBfMklVly7<r3D_Y$b++?QbgMl z*7@UQ^yAj_RO}k}hb@!oV0roKY*~N@_hR#lB4~qiwPGL!hkz3cV<1~b=58EFd+S;$ zWuj=bipJ2BoAfwY4tZ~@Kz4<7nD*p5d;2UQPl`5b&e%M4XUycu*wB?AUfZF$Ltr>k zOvV_s(+#|xhS7FZ!^59g3p_-}EgyJd9lzPvu2o4QoIWa+55siEv$YmSNZf5p9%Wwn z#q9-~G4ADALP*uFK4BaCac>d>vw9$YDQwgFsyPD$Px(1EAyfsVC>H)ec2PAej_TG* zZM%YPAZIy}yJz#;?IM@p<kn5r3qSIEHwOmuxy{yZhtu3l>Dhb*D=IJmKg*}1lk>YA z*N6SnGbyV-D_Ua-FDGY;aR1855a#S;>@;~@3!Ee18AhxJcYa~c-P{@WMchrh7>dG? z6YHN{ndx=Ja1>eD(0pO-1Td~VlcR^nd-mDBDl=vLh<s1cfYi#dqk`(?#-7_1SCb4U zb&`?CaD1?fC(TWqs!@xCvAcMq1@%;xNqfpLGF5!#p%O;|Lz4%5os0e3l}<Y<(qan$ zx_KaoCZp!l;l>Hk)&2SHIeQKxI0Hu+5)Jx+F*}UNShH;SOh;r@AXkqQ`||I;NprW} z$y^@ms}bKhd*K;U>sN5~EhCmbl>7{{Qa|%p#^TU2Iw$XjqsnO2U)$<pU)`|mOU*** zsL`H$(eVUj(O=`L!#$7_sai>*pn32b4*KM*_5!f-_#qX`1Me-n65#rFe|5gUk@Wn1 zdrqHqv)Vi?TVB|1bFpA-p2#$!!P0PVl@_)GAZlulqu{1rcQbnw=KB6NaJRBhaqzOf z)I&F48cKq_G3$l(l33#XbF|UXaL{Rd$rVc=w0c3W4|hg10D9u`c=Wk{`Kp)4+<@R< z_Rt+f!u96q?px{e9WTPe0P7~IA?#<I3T%mOTl{GOW@m{Bi(!ckJc+t8rPTN2<~T+e zdJU2@EzE0Y8A}T9(x>Lh4DN^?A`hFpwpI$AE@y`7X8C-25N487KcBU_e43N|wS{@1 zlU}q{16f<QeLa7gK`%c+Dd<dZxYosF`Md>4WYblNHYu&_Zesp1PG9qrRRR-gF3jw~ zAl%Vx8@`tsVr7z7clkpK-jMY(adYf3J_;hSwvmL&TBzdovg#~WP1P|a8aNuY^`&}H zBGwwcHHA-|ZcTYGTb<&ETdaQBlYh;+5yg7Asi?o5#K9=V;Je_Y2#aeBn$+r&J1wXp zh!tCig<6sq+QV^Q=m^iUda9!y$)#L3B4v=YZhkdYs=_Z!53aIG9nTUrzqu8XjQG@l zWHGH@x67Pob^)JqjUqaha+3A{XJ-C*&ypr{)4r32*7M=`<S&CM8^deTq?#_mZtqvP z1-bZ+-jR~6cArf=`%nGV?+Y?W9+5>(gz%v`m*Hh-=lS76PP!qw+xy$w+u7y)r0zLx zs<m3S$6FS4Acc*yNCs2i(mOlL1a(bskkZjrisZY&KsD|wxQfs*TgOnu6p@7N!z5K? zbtLe-+12W)7|Y8ZTyuqyXM<>6vc61+WILy1Ft|2p6^+1djG8!c+u}tvcy=syJ>B*> zWRXHD-n~hqi-Y<LxrwHvQ1#GJY@ho;VBTH7HkUjCDX0T@{NH*QM6gI?7D^YC_w*?Z zhC_QKlbqJ}KQU3AYJ?GbDe9biR&HX$iqF0nl*hVUkT2Ot%pm8{>+5R0nz&CPUyZkq zIxYdzyw2aw<I>+WIs6HH-*N*+_o~=Ixkw@Llb^y<3F$%QfQ;zF7HZ~xRzPLv<;?&z z=^g%64yM+H8FT&!vVpY?&&h4VzsV-}b93E@aZ#hRob@jQLvUWYYEcomWyZn6kEB(( zxnZy}))UNiQ>i-nVK$fz4|;ZnR?QDG*4&rz>Cq-!mu1D>WPYoh8NM!0d8aO|fU?zD z__|rR-9+EZB~$eSEKbijCaZhtbXNbAoa*)dVMb&5Sf0oHE0AfY)@tlDQ37wz;+GM< zK<m9{1^rO%+>=VECzcq-owLiDFC<Qx@WXD$Ron^INzP;dsdpwUBvNQV&r_>EP4f0+ ziO`jqlk43TEsu2p|0chLFX=e@6s@NFh1N=A{Vw29@0YOP>_Ulg#~7u6Rf%aAo81l9 zT+|bhB7lfg5Q^$c%OMopLxH@7|KcEwu&WLwWa<}@b3g*;XVDudbBjcgz<`)2SgM!e z7`VoBKxLQ5C(!>XCv|#6Dz6JdG{~(2Iw*rfeA+s84O97qqxyi8`qdwl&7XCzR8}Ds z38`gN{#|ImHOlJOyULOhL!ai%U}iguar=e(u3L^(yZ`aIWabha20xFYI!z}xtvH4^ zgKwIrjUi5fC{QvZR|cl(FUw<0flQ?S@}8IkD(XgMGY=++964OHIoGL?`77#PRWrL% zng9>Q+flFqtaLM9%#^^#)Bj3}Mxg0$|D05b-dsaiw;R~#wwK06#2NJ4ebx0FPQ*I{ zGEG5u3mgmX#nh4<3m(PP!XD@M;bYSed_;AYxY<8D<?CP^PS-;&bpRV~^*u(dqGe=q zpfVl;b2Z4pq_m>76&23F2d_s;vPtL|mR&?zgdOP|Atgyfbur|9zQE0nW{Rds6xd_A zkVcJLV7)Qt>r3|{Cc=jITf%nly(Dg)(?+Dmds&^H`$%3}TM<i6St=u;Rti|S=QV2- zxqixP1dZRxiv&^L$*TmF>yk59po2ab@nt~WX@JW~-WFE>5H#rDd;2GtWpeX5-BauT zC^DJ1#eeg6GLm=wqi}ZSQnpt|<i&Q^MSRIDobRsIQFi1~hWJ99p(ZS616uOh127WF z@*e&~T>@P4?@Z;~?FXdAp?28QPo{xIhf6ky_<Vu}zY0c!o9+W?jgtbu!dK@sH%X|r zJo{t!vd@?dCpz2P>K-eDOK$Cjj0TU_n0*xA62#^qp}s*0(!3o-dAPvy@q_-cQxU6# z_BmJVmqY{&vMD&N#Q8S-So)^TeeV()`nCzJGS2YOhF+d*bnHaOtX>+r{@~KUhk4H0 zRw5K(;0GmzrY+oUN)Y+(miTP@bnSNL5B=C{;<0PUZ4Zg(ehkmO1D<^(#L31-*0oV2 zWcgsrkd1x&Qm$H^l)K;D6Wz@BrE=WtS0h+{*Lo%Qg7Ae9VIa{gccadKrc^VG%^&+I zw&yrACNw=Il${eoeJ_7}n0I)bH#sAO=uzr)FYojqe{zy1h!-F8XjNlEIatB#F8}*O zV^jv*v(u2ep4#}&ND`VHqqfB!K^oW%I0&L9V>sMNujW*Tmo}R>ZtC{z(C9A6$BK%F ztc~G{u0G4^WwlQA$NBA<ugG~U!+@9zzsn!1JUIV@Y&pLwaol+;>{7T=xO@z{YB<SU zI3DdeF&FV7ACvRk_j7yB8TQbO=K6So;uZJ>|2b^yk5)ExRKlcZRB{m8jeZ*~sm*2< zD|BGn4Nu*#D$9-K?QO!1=5Enu8;N;R-TvAXr%W!RkK}YGy@B#(yQ3>St>I@H>=rwk z+*Zh1<3<a>W;>mpg-XP$3&Rhn*TRzzwe4^j@gi_LEokAa$33<Zv_w=OtxoN_t_eKu z{u+u;Pb99c)f+LiSBG&RKHfTht%mkUPk90!PG^^^@EcIB{gLi5F~=F+*kl@?ARbn3 z5+$#1D$h9p5Qk{YJ;M95GACfO0+LbL5A+^`2Ep=MRmBNGsB1=A2*~_4J`TEVqC|r4 zVr0a{Ww3vA6+E;0=&LSCs6D_#A&-G%qBDm2a;q+?K}e)!r1^_~WT?R$S3-2``_8g* z$pXi0Y87PK(H;3KVsYo2XhtaBY(N>4x%dfZ{`ltuM==J9-kC3AGE>e5aeXd|C1pOB zp7pzO)-_0Qg7O6_QC81DlsDDHh_<WML=WyXQW16HH&HftBJ=^(xv)eg8jLL2=?%&D zbIwiSDU1#J+xYwwA}ss-7s0p>2SC&Y5@|dwuJLycoR%El5Qut6zhPkK{E+k<nV@cD zHdpqPfME6Y<p3M{#?cM6xXtThwbk~cZLq&{)6hV-x~|s!x;AhgcNKXgn7c!{eIJy< z$FYkiZ2u*?=JPUZAQ^l>l&fb7^KZ3#+gD-z3s>ACbTo+xMUuGW&_|Z|87P@jd0b-o z@B4Y^=#t14e}nitc{4ie$Bmcrec+n#^AZ7hR6tu{8fT0!9D+C{V#Zi<L?jZCe1I@4 z0tF>vOGQmPD=Klwc%fOPCbLz;dL##9g53dLU{<;bRJ(EbKOFE09;uT9#&ptq22k)y zo%Bf|W!%ybP8^tVW9$@>Oj=lZKD+E7v`%Kuk#SaS@3FnX0&PcojJMkn=td##^<MDd zKe6Sc1C^p!sO_MvgIUfNF-Mj^EO|jP8$%yg%$j<UTYQapcHZXma$Tvk)(P$*%Xg<o zAYGZgK|6MDkCFkp5&*;!HKeCYAew?6`&UGk?zTEXRfLN4q)rR!`Bk}3#I!_qB)V=~ zzD1X>MNfE&RmAB&;x`l*AXjlS9TPqDJb*c|v}?wZDFFJUw%>VK{7m8Sc>Xb#Lm>)n zMEghTo!WPEM<Y~q?nV27(=lpBcjf3cf}MYE&kqM{5|DdjWj{GNB$gmEI8uG8p}$WI z2GduZ$qLqHNw_B(0NUyEjr=6T<a|k^C#11{gc2ejq`XLHPBKM1cd5<nlk@O+@{-;v z7sd(Hshrd+9yCgx#A{WZE{LQie4Dp|Qt=e0y$dsct0g?dITm}u1?}V8XSV?S9WZ<M zwQV1O#7XWs8KWp#(4HyK)ES!_g}MQ}mm1}A`s19->?^k`v`NR0bY?K~bHR(Z-6G^o z_FDp)%`>!+%_PCR;NrE3*iwNr1aLpJ>6;>>KzUC<S`Gu+9Q4PMGd0>f2+*kan1<s= zPG!6M-(-bxBW?&b%)kWZUYG;NM7cKF0|`<Zw&0N}GQfB16;DziIj^13TgrjZTJ5xr zZIEn~HHjbZ7}Q=$3Gq*L@xLfU+Wqw&_5}TZSVs%5T`IbMVzX7Z?Jc<|bWLUK3&K%U zVm;<Z=0YtfAsOW8Yky+Ic;m;Q!j53IL8mq$!pKq)rh`KoG~q{Z$b5vE3ENLYx20h6 z^&l2jEJb8zAP|=C9w9EsdxE_e-xrKCF}i07KGj%52Dnb^$f8IoxpM~^xGFeLGV5Nz zn*f{qD}z}<MsRqiuobDLaObbW&i|hO3BTJv&#nH{C&T*?b5YlFfhf*;-fg>nMPCAM zi-z)ts;h>YgF-djR_TyZg5X9ChpKCanu9~#w@`ud@1~b0SXL!?PCjJ=P>3oewemmj z<vJW0Ns<AP$Ct-nR>n`%-<cdaD?bKgKNs*(*YbgA7V-7gTw(^m70&0atl%x}BV@`9 z(TEegq*EiXht5#bUJN@r6{ctUX6A=~D1|F)tdYhIplCW_HWcBU6V2k!QYXve$4@vl zatz}oHEYup!cUl~=uvq~O*C;qBufZ+R1N<bJcQu74QNj_UW!c+SRXlr-a*)$9`nVd zCFL<g#B%qYC7*E5b)k94e$ua$b`U-FWGtGIKrmr;1@xAi|IgulDjZ%{)|8OYxrPXd zVV}TdJf0cv?@5>WpBM8JICAVnGQ!@ftigBm+d)D#2nU#k!TFRHoh|A+lq0A!O<6|z zb5kU5k$e1{Y3S<Lp{jT7H7CkEe6_&EF&rZQUDIHaxP2Coe7g@?_CAl9%5`1f9kQq= z_GXRRHJELNi(uod#7Oc%DcodX_M<5yw#P<eDmdOdhQ4kX8m3?nR!!4c#s=Yu$;mW` zbkk(UBrSg%(Kz(Fsmv`!il+vHV@#3hu|GE1V-1Iu<Gcw@8e@u=O#QGWZ15*aj?6RE zw%H1d&uwVa+)h_|Z*x5ahcs!yq4Nx6QE;(T#*fIyX>|$tC)<V^GXr$$q2EEr@iw-C z4nRhcFG^#DN35wRHsUj|>;Y)HMy#2=hA8tO9%{f7aXCUH3EMGSkf%Oyi0|^->fd$L zNN+cTjL4t$r(dg<)D0lN*RnwQ^_SqIYGrcEJk<4G1+P~`vsl=KK~K`6=LqnoH^Vud zCLYz>!C1o#J>Z4(YnW<Z{Ca;CZ3d)Bsfcsg7A<kwiH(Rzv@7_@Pf&9K<W*CSbl~f> zF{tf!*@07d?az$Tr0^Rmy;~peCZV*~=0iA*&H_Vp6c_wA^dZZ#vi*=F@S3KyKjr=O z?+$|5N=UWGY22Oy%aVAFqoSyA*B0}jDzNM3`{<;<C7<xD;w1enwYDE%J*2#;6TRua zzK>3B8tJ}uPQRdj8NmG$^L9TAO`eT%G7|G$UiEKFE_*s_di@z6oQEx|sGf5X85-}Q z>h>&kvgNTFZOde_vjxqf_CJ5>c-oQBTd5`D9PK&Wo4E-FZxOv15hoJTyPA5GYwiNk z$#P|O5@6ht?_;e4iFAYiGHvVwbFNb2e!1s<A-+hOIewaW6?N@_J(sQ)py4iD4WT<C z%#0a_o-_?O?beeq3Je1FR{%W!i{|WadiLNS1|6?74j#NWb(@cqqEJ1tM(AQH5UflR z+zsccUZryy@?Ew>tzPA808(o<+%c!_HpF)#Yci;KiV~FtvpSKWoFk!itHaZg;IRVb z^Usf5rtO9D9i)qN_58M}=AxkYG2h;I``pZTHG@f8pVd7+8~Vfgf?*^cXV3P8W2aQ% z%6hbvXU~pWRYB;H6+Ry2s<rv2mU~4h7tfs?Qcbymy?XFN`8KZ47nX)ASeRYYb+*1i zdSbd#14h#|nGsgo-=w6B+IEd&K17Fgz{u$ddf*CfHK<0cTXSIVAErk-M{z<W5vGS2 zp{mKz*h5GY43%6?duJB>lx};{Ty=u#=`l=oaNR{{0_Hk~W;Y=mw>hhoFMDbnzwj?L z9r?SSn8%VE#9Cku!?rE$c+h|9n1U>tD?fY`7(~DM?!Jt}Z_Reh=o3HqGM4P8ZBp@H z{l}U35>a&$gxm*;#0N$(2?!(YWLl(p(cUM>745|82rV<5TUp*5Nx}ggQ+rSstKp4G zswOMsthtc@_5`C1b%QC2xsk?rqBSUMvMSHcu;bujtk31>(W1jyDcDyFFY(DRQ4`x_ z<@|VEl5v`fW2Rx{WMzEAlo^F7Y6x2$t0Wu4y7D|!=I@vC0a|adBj9#t!IdtS{6BZ} z=aIk9@D??K#dR$s?wQ{R9&}QQw}w{BgSc|qAzT--bytHJE{18&NY-OAV&PC@9OJ0Z z98W(Fuyn*Ml)!{Jv7>c53=HYzVr&tlhoJj|hD8y=H1Rg^)giJ5ldNUKf(x+ew%H!~ zuHp8cCJQH1V6OTJo%~h^nuJUo-;7d+M9)R5DgVNt;4gcj1-w^dW<|}>k=D(v#f&}} zqpljHWz4Ph!mDgSho7JKho2t?DjEjd4hJXbM^3fX1HHT)0z2lt4FbJ%zbEKh-3I#L zur{4ag-C4e0{Xt*!<yP`pbOe*D$hQXV!Zb(tREXGRwIXqa)Gz?Q;bmPNJ84zje>h~ z%3dE1yUyT~dc(J}R{25wiuY%fxE;Cah1vN4DDg(3;|S+H5gC7i5&I9icvx8id9+<7 z;s=A4vQryX+6Hn;;!Z})TfcX^Tv&8ZS2J3;kbsEo^KEWi&$@W2zhum!R>GEpAi^XF zC=GqDi2Y2LRnhJ?*C!;HD_ETp?ls+O&ve4n82I|Iq0@^4@t8^<L+%CJ+^3LE5SrmG zjgvq!HG~}E^qFY9UUW-v&ls@2R^x!|otPik5KjlVAwmF#r<I^{3clqtRZ!prG6(j@ z$CzLz1&3zGBUO*3qkAUDCwr1t{qkU|PeX0R5Wj*#MTOCE=e+88HU0RdiHakl&vu`2 zc_GDwiSi?&&D-#Tnc<2M=Z8WXae|qn|4$Do_|aYePbuPJFnALdD2twnpgK_{H2j5V zWsPfXji@|2{^Haifbc-p48+C$KzkBaz@J*gRcwGuS3`t=T2Xa7fXbJAu_lL}xr^S% zf3}A4F9l{M4lg+QZKLL@=Xb#Mp=N_ld3QLKgq~)s_Me|vvz==PW+dujFmP@9bYGPA zU1eR3SfGu5{Ll<hsnb;afb_VPP1-IFvv*j3JN*OUoaq9uO_I-aO_Pm4o#`Ha7xOf) zw6A6O%@lClN{0O6iVY>le!AGGF=W>xktc?Ro$;|h17#n&tY_oilb0ulJt+80bH&q^ z7S1fc^Z)BHmt<}j)Sd;ogZTaN6B|(P2GgGWXtP3%V9sj#LusQtwoc}ziTt3R*yqF{ z(#^-suSaOL!_O>R8`XhYzTJ^sq-*;!c1JuRGIDQLUr%}Bk|TcbEgBrGK*Hp=^3g$_ zH?jmN<mM7O{hTM-E24yC&TfL(kVfB2H@rX3^eojMssYxpqk7~{*L(|Murg(XZmu|h z*vyp8icy>Rqz|~e3m2|=QQWbbgvvoghWRlMuZB(~dJn1UJno>9ZVfL#s;Nn-ISm2b zamBdnxMdID5Z2(6brdW<UoL`mH14t4D|q-Z?zXyHpTN*!W5!11D%@(VyP02kK0$k; z)(E(3dntQM%Ya)^cXXuf*73g;FcaD)sU}JTD*uWwNc_Gi0~K@X#$)Xb{ZQP^t996& z=Nrm%XcC@ylv~E`3Zyh#G>cI_ty2@cRF$CV_&aakg&x#&DY=eiYSMfctQPG&wf~J4 z!!h$h=0z6M_A-KCB(Q|E8@&SDO<i09gR6}|T{v@sac`Xz6r-4=825jjrW9S`U~aIp z^b{>o2p}nv%n4HuGf3kdXsn_io|FIq`(@_jD2e5p+D*xv`-?DXf@O~8N<5@xPc}Ru zxh3uk%8-uenFd6<ZLHSi1s9*r+L{SrbFHcUyNA7MD?lGKbo=^G9&NE;Ezae33kSYS zUm##DrWopekbph8KW40p-@w5ns2yStIBRcRD%x7xU3vt=8<2^&z+vr$1q!#gt-6qL zjw*c&EZ=D8QA=1T(!w6>w~S|`=QwDFn_g%r{+_f9c4krx{QxO6&*jAXE_fX;1$^Yx ziz2~A)$qfkGbYH%ZZ@V+o7Qys7oTTBu~b*@j^bJZ;;BR{>i%MQU73YB*tR9}$i+Sr z28`C<Q%iJ<65pXmIFhVyXbBS*eN%_QomHXyj3tRBFNuIC=8(zf8b^#3Qs=)o8evkp zd49`?D`ik6wZ|&Uct9!+VbSa54-4MfUegKW6ZxzLUx&s+ukuMdH~eRpH0ZXMF+tqZ z<RkjkvOzC~uN>fJ!y_^aQM?CntDH$R>v{9`aI_PX8(Y*BCN27AVl2Y4Uyf@})bG>$ zmhL+wQC^m-=_fOR3z1St+gW@aKi-=4WRLyE|8Iblhk~;q?-%?g2Lk{={skAcgzSC+ zZ(C<QWe<B3C!PNwi$jTaRvYvP!#&}18%R`F5sadlipywFM$nBP0BUd45vTZMMPV;z zZnBJK7Neu{QC$trGdw*f#2X12Nex3(ii~|~`}H^xKwVHxckM_!+4!RP!f}kRSk|}d zVQ>lLw#5l2w1$+eYbBD693wG`q)YjM%Kt*Msbv0ur==8{fUtl^-CJ^ZCsV#g^2Rvc z5ELhHS?e1(-B~p3XsH1iHi`-yYu_)ekZ3hc@INf_X}D8tL51daxHI6DA`g9qXRsMr zO9|rLu~yF@b!}gquZ(bR7q8(vG~(6}H(JS9%1EPAuL9e%WJ#}1WkhPJADk3bT=|>z zm`>Dq2OC>*Q#C;a6^LsWS=(oLfhG3*H9|k57lOq!rpttFzmHk%@bDd)md$NH>N$in z^YHweceF`75Otq2i}4lo2Jo#!2tM|DGl%DcEc@rV-c5)_z*@ryzbyt!-aXU1)Q63C zJ(xAyAkuJVV8!~cU82M`<}7ca_2L4dXn!KmR|rN<AnW;Z;8i!#)N+Pd$!Kg{oxzw_ zIm<U2TWx}^hT~U3&iDTX7gvv-__6+uC@}~C0QB#O>N%QNJJHep=UKF{BRN2i0(Pqg z*`~LEh8XA4p<v*a{{%R_-oV`WCKTUxbtQw^;xc8tIB^?y^EpcJaHQ*ch+KuNiOMXc zC@HVfjuwvoSm2$;BfrmGip5z~n+xuoNR9r$cG(-kRgE|tC!en^fPFJXWK?Y_A0X8z zfEpjwjO5L(ISr#sV{hz{zRl#dEfA7rtb*S7D;HM9@0^&Z&+#50`6wR<e(cvUNRD?O z*!Kgt+L~SuVYziy?t|1zGny~~+4f6yUUSp_8I-{A4MyXilHFJ)NlLzS=aOr93}8t` z2UgLv0r3;-QN+eYguRz2?0}xPH{3LyQ^#HA+}6(N`Ug{me)<g{qpi2Y$20<{kfXDt z5k%_7cJQyp#nI&Lv~C)^#^N5EdB!WI{HIh&{Qy_A!V4eU`+5ldzb6bI+G5Wd6aYXJ z48Z?J<84fw4U7$(4d|TBU2F_(4J@o_?QPAD)ZVxjb@0EVO)iP+j~E(v>x}7>>7|oL z1LH{H!^iOAiwx51Oj63^*F=ryV~r=0i!P<=|B+7o`A|12z3g20kn7~@<nx~PsdmbG z;8=0teeub0!qe1ByLXVX2L|YM8=74G7pCJEfIMj(aV6=P+IwVY>IV;?KKKnHZvGwt z3UG_1&Cngx{$m(rX+hBTr3OB*K(Q(WqS-UMJ@=;>Mv0~8V7$O<`uv!W8L1QY`=M~N zS?6U}I$gmsTF78`G^7M*sI2t5-{fe=Z-cx9gRj$Lp>mQz_u&JXc1^2ts^Y_kC+hAx zQL9Sgx*(sBL!zJEOim8IYIbh&0M9o+%ELI|>ca2t5;FZ<f554wFiPXQXID3=TDK=I zTe&C3y6I*OInxQN8>$ZnhD+UO$vqMeO;{7b1ubHsczIh3<nO$k*EYIM#P%sZ{w6R2 zBI1Zk>_P~jHAi-6PfblU`7f{islWGSBvfb!NynKpkpu}MOK>M)YGPsmZexI*qFAF5 z(({5?iLwD~1x$boI$oI2A>p;Gv9WOq9F;SC_gkUF$h?dYXV>cbT#l{3_rlL8yq8v3 zgB!2s?6#{6lA%nU2TS4Z+PhihLN!pdZ+sXmz24Bt?Y7xoMI~vU*u;|3!i$nHp#6!E z2smzv%nqP_&~ll?w5c-+=M{~6#|J8~?=XJsa(sMTyxhOs(%9kvaod5)xk4@C4j32F zP8gLEIythV<Gt5NeU(gQt_Yogipnbh{ZlAoXG06NEX{Da(T81NEh#qsTpnKG`!<bg zAo;}OPgpVJA1H%1aAcH3A%7Lu3Gum}^7VDdVKYKLziyy~MQ*16rW9eIxA*t`PujM- zySuT_n{Z~g+Vr%|Bwa3)Q(tR!a+q5eB8k4ldB0}E$t_PrTwGjvpD(hPr|eY<|B(uC za4<ajkIBgMY@Y?OkdM{@%gt|1SfZ?wI-d$Y)}yhwQ+{$FWivYZoop|FkFdWr*I`Jk zCzIU@<T%C#sV0rEFAZih>_)IVDCjLOrWOjjV85i@n9b{L2t`0JVb<z-n`(g_1sPjw z@bwBZ=rN5c4wj{5UG1z=RKnstQ&D()-;d`i0`JU}oSmV!7Jomfo{~jTKz+=d9E+9{ z!-fmj$Y;`FhLhIEJy9R6JNKvfy_5VoY|@s?^EM~WusBJB+yx}0W?0J8LZHWpp}|Tk zDh<cLZCE~y8^7*)6v*HwP7qQ|!Lv*^GfCHL_&L)`XK&nxkk)^qkT%HKz%j(OdaAsy zWrJFSL%qE;P~M`PJf@%r4mkSu^(ufzrjq8}lUlmn-Q6iek3vZ@+@`osm7Us4uhQd# zdN`l)5K2mLhN{ad%$ybmeZa*<OPXEBy2z|c9s@T-TqNW}nUx-YJsxybWo1=_4&MJ> zD35||_WvPb^nqWDLK%Ld%-lLwGeRRK5t)6B%+=96Z-t4s9)OH44iV7S(MeHN+tAch zch|~5k;2YT{rKi6zO|<q_K}EZG1D2lG^!e7bJD6&FLe>%c9`zR7;Ao!#B_*DRgsAR zTK>$ds3}j>-A+svI<8F$c0E6@H}RhQ#t_)p*2Ru#Q3`)p;l;?N*|d7Ss<pp;k3lHQ zN=dE%i?`56cdBPXnzG=&IU1{SzZlhIxpT*;R~E+Y_+%mh5SGN1=E=}DVl?S`X`t(H z*ETKH-2T^dP?T@6bWUDON&nQg@)acSp{^g-F=`|=$iu#xj{{5c{ggud)ar;4VYXiY zqv@+nm$NoT->T-O(D{Kf>*UV#B>(*UJpT`ZAQ%6LbxSC%ay{HW0Az$`w|BXX-bZZE z_xAkSczXKUUcc3)w-(2{0TSX97eV|42YjLJ2)n2<)(89PMbsdO>^|BL5aS1OF!055 zM*3ea1Ei^6#o?5iqRK>?hlrrQ9`4D8k2mio?za{7q?u};p-_|%7nQ=#kPvJ|#0SUo z5p+jVwXtjqgQ)wT+)iG4XNP1e<4^+Grji;v(=1Ip!ygO86aivRkc=06oFGnt=m?kg zf(F<A0xBfh%ZR|gZ?f|s9iN{-pGO;E%`%i9(a3fN=w_w(rweE5X0Sxs{GtzH?@GXD zn(aGCaX#n6f!<!Fa_)oy*_cVXtAFs%M{ZR$cb?HH1(~K-1U+Dx^DT5Wi$F>^)Y#Zq zFW-d=8??eO64*YgX8p&;_#ADc(CvA6IhpHPNIF6yLJ;L`4TUM1wg1A%Bgz!uoO21n zh_dS*I#o_yajL!o@PEMpeFhh&<C8T-!>Up*EXRGKS9eG;1%I35dz&3nor%S`w5h2q zJW~q{5&og25YK8k1-fAtTgY->?;uKlMu?(GQN{<l{L#fO>G@ynoq0S|>l?r=A=xMU z%}>^mwJce(6jF@c&5y(|W3r50_O+qhlCDr>-}iMUu8B;Rbd@B8vJ65L5u;oT_sGq1 zZnt~y-@o6P&z$+pd_M2@bKduT=6T-dIq&lvIs?DF)R)Yu?*olIx|(B_2I3soWUv$B zogH-_VZ<ibJU(->HnB9E>A59ZW!iMjN0L=nb)UGAK$YW5#^%)gE7%Ivb0_A9)0^Gh z1D}`?#N9(UVeE?Mp5CY$4K+29egkNmDLC^d13oyt6DvHXjUVd5U9komPSo)<(|aL) zLQJw!j!!DqMKmRD`K(f=#Uj>RA_%&F36{9nvuvAw1gXwPF3!#t^fOO39djIy`jK&1 zT}5}bK^|wzmOCY+X2E?qQyH=#8Lw@=!i(i#I=Mha&1o1!V`4a3w`ijKLQ!KmqGliP zWRH00L?j)&LyAip+ox*e%D~=~&z~P}Px^eT!WtbKn>V=-W+H%*(QspCIh&uYo0izs zV?Np^aH!X_-+saJ(^{5=nNL}X)(Mqxt5k`WW674QTs6&=I_s&jxKfEKf=m&;Y)JHk zEWZxlZDqk(TYC(-m~!JJWFG;0_X_YZ=$R-ZoysSgIyrJ~o#)9ST!no4hONXx{3<f) z*wcH6Nv6>`vE<3n1HA{aokHtl{xvp1+{|$dY7tVnVW!ysj$$%uJJp3Z6qm_wGBXc5 zu&{Wn(45hd=cU5A%tmUfCeP|aQ01uhq*BvG`vxN26Xh=V5EkW+w2zIfy0GRWaSS1- z!3|!a-aK6%eyF~oisj*3<^J`N4q=8a4SjTL6%+R#9bUP#sC{z58IywHjh4Qu_>>2U zTdh1p4fm-m6K<t{cfcTpJQy~2^NOUyi~H3hh%#|G#kU@nFFNxnCx&>e&nu4JhXtT2 z9!PHp5~`r_M@FHa9t{50G5ge>gy=C`EpCaabS#>jGUa=J{!-Z@+nm{I+)e!bW+k7n z^tJQq+=bfpQic;!HUh`%qC5&O!o#QMyazv7OeHRA2aYeLKfC8h|5~NjCN!UL0=jSN zBY{rjZt=&fhds0Js6)oaZiz_1(C8<y*Vc7b(KjSrHb^8ku7T;FH0~5Hv`jd|@n|SJ zZS*N#U}Kx^?Q+ZqB}cV1WeKUwxJ08>A8bFGD>-;U(AOGLTm7J+{&SwN!;4o$BEbip zU`0Asg0aOsmK4AqQ!A|}J7G@2beHV4D92@r&F+m9FeN@~(_!Q2erxu@h{HbrdZ2qy z_uxy&fFu;*#Jw!TL9End_lqI+pcGbVGYX2X_LbAe#1!R)dF4tqX=1T6#)a~JrXeBZ zzU-2tYR)y52L&%b3#p%V;y1rIWBpmzaOPx|RygY@;mzBE*B8}2FI4y+aHBuy|3h#( z^r9Aap=VJ!p|fO6%=-1l%8}m)mkW`-H*?&aY|5allN(gE2n6Z^!e8Q@#@@y7jgB+* zX8>Pg6!0~KcW+JIayk$$?ntyfuwmHC&UMq1{NjW>>KV`j_E6J~08WTsceA+Q5NFnY z8ivyYXdYa*i=&}%(d-JT^}1Sr9ws61Zu@w~&qJ}pwq+avTKu^RG_DR(dYv9tdO`<O zQq(UDnL-4UAPEW<oxIc{5utPR94(hbf9#@()6@qtBy;MJlJf@?BHLBui)4SX(b9*> zBvCg|TrTZ)9y&_MIK?8@Rwy}Tj5&H-yDcNJBY?3nP%nRkrWK=74cs5;?YW(YFT(ly z=jz>YMv(>W2c0={ZN!~8kyhDyrM{uRBH(7CBd3u1#A{gEsT__t;t$44Csx`fTdHtb z(@pJ`Cp9AX%LF()4w72Bub<*lkvy&7&$2{x>C<po!Of?wGn58FddV6Vp^!UpUQyLr zJuhRS_|VUXls*JMu3j9%UBw&JlkBxqCF))m)mXi4b`g5~P{QdryYIa0k_O1>OUKVe z-vcIq510&*KTpJViJq_9@4w6h>gPu1=A(>P;g6;o#Q1V<uoe8$SdLz$Xf@%Bw>W;M zugo2urq_IP<w}FmhQ~6j1aEpf=~Ywt`$pDP)zi$J9R<%5{f>4WGID#S&*>&?%lu~E zpadN#<SmI{Z$j9)l?5NZo^eEZ+DoAKnMmJw@=XO>&rr|H^VM^oEi!m2QOOl;nCHRQ zM$Z}$RPeloY7S{w1p>#4gE?_6<-K6qb9#~d426a4-l2is>nw*xlt%Jj`h#i`6{&G( z&H~+Kr3Q5yVejhy#Vb4Kjq=h4+%vemthB4YotKwg0MeF3LQznuvo^Lrd`O$C6rOaA zlFA}0SVx$V&B2Z}VnHZeNvNt{PDZF&3@5Dch>$5Pr@@jdE+tnWT>Y!EMn!FIp*&ug z@DpW8A<`u9SVRF1hR_wH=B2<t4W}HHHWXd^fS|&1XRREHB~{seWMPR@rxeqm8CQCc zAfGd~hDaiF#kSkEAeaxvDV+_WiVHk0`R-M0kGCe-Pu17Ag+y;QBS3-#ar0-ti+DhS zMQG85t@m$q)X0aOe}6D2R*iGtjGZ<viuymr{0~=XxOJo5lj^R7_jfB-$a9^|&z+>y zt!-pXz@tZ&s6k@#Z^ldR|Kp|iZ^ldhe{{SksVFFRs)Y5;TSXxOB~%am`UCLK+&qA< ze;nJv5~RBq%Gk@@1Lbwe3FW<M8;oIlLCn{sYFdG2o92b@kLFvTRN!M9<m&hLC`+zU z*(3nb1-wP~pwfV={7ckne;^R*?d0zEt;-u1H$kiuC@B2a=_z>jFarQxv|SqwYyrW& z1Q%7?ByIJwym=R9TYrBku?B{Kv#xd^T?5~Od^G}K4mcTVhZ8Zli}UT&C@>71NVEe> z7}^E<yR;%O7M#$tgGCO11N#^0Jz(lPP>RhC6-wMi-IH(wW`HB<JB-NHZ^qTZ0C3=T z2VhR#6UGHM1cxLy8*Uxd>$~K8Pk<840I%dW+iwYC6FudQJb!0h2PT4-Bs)YH!=H%T z0{&GtzbsI|NU%EI>g48GlW`aFd&d8tBfXfukKDG8{~Vdk{C(uM2{DGz0QX}kC?LSg MoCeTbESq!jJ2;iKI{*Lx diff --git a/controls/model/improved_lqr.m b/controls/model/improved_lqr.m new file mode 100644 index 000000000..316a93eaf --- /dev/null +++ b/controls/model/improved_lqr.m @@ -0,0 +1,22 @@ +% Given the state-space linearization, diagonal weighting matrices, and +% update period, compute the discrete LQR model for the system, described +% in Matt Rich's thesis section 7.4. Unlike the "initial LQR" design, this +% version defines its cost function with block-diagonal weighting matrices +% (instead of purely diagonal matrices) + +% c_alt, c_lat, and c_dir are 3x2, 1x4, and 3x2, respectively +function [lqr_K, lqr_S, lqr_E] = improved_lqr(A, B, c_alt, c_lat, c_dir, d_alt, d_lat, d_dir, T) + % Given the block-diagonal weighting matrix, index ordering permutation + % to get the controller in our previous state ordering + perm = [7 3 1 5 9 11 8 4 2 6 10 12]; + % Longitudinal is the same as latidude, but the angular weights need to + % be flipped + d_long = -d_lat; + c_long = [c_lat(1:2), -c_lat(3:4)]; + % Q, R, and N matrices from weighting, given in subsytem components + Q_sub = blkdiag(c_alt'*c_alt, c_lat'*c_lat, c_long'*c_long, c_dir'*c_dir); + R_sub = blkdiag(d_alt'*d_alt, d_lat'*d_lat, d_long'*d_long, d_dir'*d_dir); + N_sub = blkdiag(c_alt'*d_alt, c_lat'*d_lat, c_long'*d_long, c_dir'*d_dir); + % Permute subsystem-ordered matrices to get compatible controller + [lqr_K, lqr_S, lqr_E] = lqrd(A, B, Q_sub(perm,perm), R_sub, N_sub(perm,:), T); +end \ No newline at end of file diff --git a/controls/model/initial_lqr.m b/controls/model/initial_lqr.m new file mode 100644 index 000000000..9db5ec115 --- /dev/null +++ b/controls/model/initial_lqr.m @@ -0,0 +1,8 @@ +% Given the state-space linearization, diagonal weighting matrices, and +% update period, compute the discrete LQR model for the system, described +% in Matt Rich's thesis section 7.3 +function [lqr_K, lqr_S, lqr_E] = initial_lqr(A, B, state_weights, command_weights, T) + lqr_Q = diag(1./state_weights.^2); + lqr_R = diag(1./command_weights.^2); + [lqr_K, lqr_S, lqr_E] = lqrd(A, B, lqr_Q, lqr_R, zeros(12, 4), T); +end \ No newline at end of file diff --git a/controls/model/linearization.m b/controls/model/linearization.m new file mode 100644 index 000000000..75de8cf7b --- /dev/null +++ b/controls/model/linearization.m @@ -0,0 +1,130 @@ +% Implements the nonlinear model and creates state-space matrices A and B +% using MATLAB's symbolic differentiation. +% +% The model physics is taken from Matt Rich's "Model Development..." +% sections 4.1 and 4.2 +% +% This linearization assumes the rotor orientation in the simulink model: +% 1 2 +% +dx +% +dy +% +% 3 4 +% In some of the internal simulink files, these are indexed 0, ..., 3 +% instead of 1, .., 4. The order is unchanged. +% Note that the final result should be the same regardless of rotor +% orientation, but everything internal to this function and its parameters +% need to be consistent. +function [A, B] = linearization(m, g, Kt, Kh, Kd, delta_T_z, rx, ry, rz, J, Jreq, Vb, Rm, Kv, Kq, If, signal_mixer) + % Symbolic state variables + syms u v w p q r x y z ph th ps + + % Rotation matrices. After linearization, these are equivalent to I + L_EB = [... + cos(th)*cos(ps), sin(ph)*sin(th)*cos(ps)-cos(ph)*sin(ps), cos(ph)*sin(th)*cos(ps)+sin(ph)*sin(ps) + cos(th)*sin(ps), sin(ph)*sin(th)*sin(ps)+cos(ph)*cos(ps), cos(ph)*sin(th)*sin(ps)-sin(ph)*cos(ps) + -sin(th), sin(ph)*cos(th), cos(ph)*cos(th)]; + A_EB = [... + 1, 0, -sin(th) + 0, cos(ph), sin(ph)*cos(th) + 0, -sin(ph), cos(ph)*cos(th)]; + + % Rotor positions + r_h = [... + -rx, rx, -rx, rx + ry, ry, -ry, -ry + -rz, -rz, -rz, -rz + ]; + + % Gamma matrices select force dimensions + Gamma_H = diag([1, 1, 0]); + Gamma_Omega = [zeros(2,4); 1, -1, -1, 1]; + + % uT, uA, uE, uR + u_c = sym('u_c_%d', [1 4]); + % Individual rotor commands + u_p = (signal_mixer * u_c')'; + + % Rotor angular velocities + % These values assume no motor transient + % (i.e. speeds reached immediately) + omega = sym('w_%d', [1 4]); + for i = 1:4 + omega(i) = (-1 + sqrt(1 - 4*Rm*Kv*Kq*Kd*(Kv*Rm*If - Kv*u_p(i)*Vb)))/(2*Rm*Kv*Kq*Kd); + end + + % Variable vectors + v_B_0 = [u; v; w]; + Omega_B = [p; q; r]; + + % Rotor velocity + for i = 1:4 + v_h(:,i) = v_B_0 + cross(Omega_B, r_h(:,i)); + end + + % Gravity + G_B = m*g*[-sin(th); cos(th)*sin(ph); cos(th)*cos(ph)]; + + % Force + % Rotor Thrust (3 directions x 4 rotors matrix) + T_B = [zeros(2, 4); -(Kt*omega.^2 + delta_T_z*v_h(3,:).*omega)]; + % Rotor In-plane drag (3 directions x 4 rotors matrix) + H_B = -(Kh*ones(3,1)*omega).*(Gamma_H*v_h); + % Total Force (Gravity + rotor force summed over all rotors) + F_B = G_B + sum(T_B + H_B, 2); + + % Torque + for i = 1:4 + % Force Lever-arm Torque + Q_B_F(:,i) = cross(r_h(:,i), T_B(:,i) + H_B(:,i)); + % Change of Angular Momentum Torque (assuming no motor transient) + Q_B_L(:,i) = -Jreq*cross(Omega_B, omega(i)*Gamma_Omega(:,i)); + % Drag/Induced Torque + Q_B_d(:,i) = -Kd*omega(i)^2*Gamma_Omega(:,i); + end + % Total Torque + Q_B = sum(Q_B_F + Q_B_d + Q_B_L, 2); + + % Define state vector Lambda and its time derivative, Lambda_dot + Lambda = [u, v, w, p, q, r, x, y, z, ph, th, ps]; + Lambda_dot = [... + 1/m * F_B - cross(Omega_B, v_B_0) + J^-1 * Q_B - cross(J^-1 * Omega_B, J * Omega_B) + L_EB * v_B_0 + A_EB * Omega_B + ]; + + % A is partial of Lambda_dot wrt Lambda + for i = 1:12 + for j = 1:12 + symA(i, j) = diff(Lambda_dot(i), Lambda(j)); + end + end + + % B is partial of Lambda_dot wrt u_T, u_A, u_E, u_R + for i = 1:12 + for j = 1:4 + symB(i, j) = diff(Lambda_dot(i), u_c(j)); + end + end + + % Set equilibrium values + u = 0; v = 0; w = 0; p = 0; q = 0; r = 0; x = 0; y = 0; z = 0; ph = 0; th = 0; ps = 0; + u_c_1 = 0; u_c_2 = 0; u_c_3 = 0; u_c_4 = 0; + + % Binary search for equilibrium throttle value + throttle_max = 1; throttle_min = 0; + while (abs(double(subs(F_B(3)))) > 1e-7) + u_c_1 = (throttle_max + throttle_min)/2; + if (double(subs(F_B(3))) > 0) + throttle_min = double(u_c_1); + else + throttle_max = double(u_c_1); + end + end + + % Convert symbolic linearization matrices to double values + A = double(subs(symA)); + B = double(subs(symB)); +end +%#ok<*AGROW> \ No newline at end of file diff --git a/controls/model/lqr_err.m b/controls/model/lqr_err.m new file mode 100644 index 000000000..fff65cd53 --- /dev/null +++ b/controls/model/lqr_err.m @@ -0,0 +1,19 @@ +% Given a set of weights and the state-space matrices, lqr_err() constructs +% the LQR controller, runs the Simulink simulation, and computes the sum of +% the norms of the errors of each setpoint position dimension (x, y, z, +% roll, pitch, and yaw) + +% Note weights is [uv, w, pq, r, xy, z, phth, ps, uT, uAuE, uR] +% All analogous state variables for x and y are shared to reduce dimension +function err = lqr_err(A, B, weights, T) + w = weights; + % This re-expands the weights to length 12 and 4 vectors, respectively + state_weights = [w(1) w(1:3) w(3:5) w(5:7) w(7:8)]; + command_weights = [w(9:10) w(10:11)]; + [K, ~, ~] = initial_lqr(A, B, state_weights, command_weights, T); + % Set the LQR K matrix in the simulator to the newly calculated one + assignin('base', 'lqr_K', K); + % Run Simulink simulation and return norms of the errors (no plot) + sp_err = run_once(false); + err = sum(vecnorm(sp_err)); +end \ No newline at end of file diff --git a/controls/model/modelParameters.m b/controls/model/modelParameters.m index afe8eb6e6..30bda9a41 100644 --- a/controls/model/modelParameters.m +++ b/controls/model/modelParameters.m @@ -1,3 +1,6 @@ +% Contains all the measurable parameters of the quadrotor. Must be run +% before running the simulation or any other functions in this directory + % Add Library Blocks and 3D animation to Path path_1 = genpath('Library_blocks'); path_2 = genpath('3D_Animation'); @@ -11,7 +14,7 @@ % Define Simulink Runtime (if logAnalysisToggle is selected, this will be % automatically set based on the log files time) - runtime = 40;%max(time); + runtime = 40; % Model Parameters m = 1.216; % Quadrotor + battery mass @@ -63,7 +66,7 @@ OF_Fc = 7; OF_K = tan(pi * OF_Fc / Fs); - OF_norm = 1.0 / (1.0 + OF_K/Q + OF_K*OF_K); + OF_norm = 1.0 / (1.0 + OF_K/Q + OF_K*OF_K); OF_b0 = OF_K*OF_K*OF_norm; OF_b1 = 2.0*OF_b0; @@ -243,135 +246,142 @@ if logAnalysisToggle == 1 % Pull VRPN pitch and roll pitch_measured_VRPN = dataStruct.Pitch_trim_add_Sum.data; - % Define setpoint timeseries x_setpoint_model = timeseries(x_setpoint, time); y_setpoint_model = timeseries(y_setpoint, time); z_setpoint_model = timeseries(z_setpoint, time); - end if physicsVerificationToggle == 1 - % PHYSICAL SYSTEM PARAMETERS - -% quadrotor + battery mass -m = 1.216; -% quadrotor + battery inertia tensor -J = diag([ 0.0130 0.0140 0.0285 ]); -% quadrotor + battery body frame origin to c.o.g. error radius -r_oc = [ 0 ; 0 ; 0 ]; - -% mass of rigidly attached load -m_L = 0; -% dimensions of assuemd rectangular load -x_L = 0; y_L = 0; z_L = 0; -x_L = 0; y_L = 0; z_L = 0; -% inertia tensor of load -J_L = m_L/12*diag([y_L^2+z_L^2,x_L^2+z_L^2,x_L^2+y_L^2]); -% location of load center of mass in body frame -r_oL = [0; 0; 0];%[ 0.12 ; 0.12 ; -0.04];%(0.04 + z_L/2) ]; -%r_oL = [ .115 ; .115 ; 0.04]; - -% acceleration of gravity -g = 9.81; - -% initial dynamics states conditions -u0 = 0; -v0 = 0; -w0 = 0; -p0 = 0; -q0 = 0; -r0 = 0; -x0 = 0; -y0 = 0; -z0 = 0; -phi0 = 0; -theta0 = 0; -psi0 = 0; - -% ROTOR PARAMETERS - -% nominally equal rotor parameters -K_T = cell(1,4); K_H = cell(1,4); K_d = cell(1,4); -Delta_T = cell(1,4); -%Delta_T = [0 0 0]; -J_r = cell(1,4); Gamma_H = cell(1,4); -for i = 1:4 - % rotor thrust constants - K_T{i} = 1.2007e-05; - % rotor H-force coefficeint - K_H{i} = 3.4574e-04; - % rotor drag constant - K_d{i} = 1.4852e-07; - % rotor b_z axis velocity thrust adjustment factor - Delta_T{i} = 0.5*[ 0 0 2.351e-4 ]; - % equivalent rotor + motor moment of inertia - J_r{i} = 4.2012e-05; - % h-force xy-plane selection matrix - Gamma_H{i} = [ 1 0 0 ; 0 1 0 ; 0 0 0 ]; -end - - - -% ESC-MOTOR PARAMETERS -have_motor_transient = 1; -% nominally equal motor and eletronic speed control parameters -R_m = cell(1,4); K_Q = cell(1,4); K_V = cell(1,4); -i_0 = cell(1,4); omega_0 = cell(1,4); K_E = cell(1,4); -p_0 = cell(1,4); p_max = cell(1,4); -for i = 1:4 - % motor resistance - R_m{i} = 0.235; - % motor torque constant - K_Q{i} = 96.3422; - % motor back-emf constant - K_V{i} = 96.3422; - % motor no-load current - i_0{i} = 0.3836; - % initial motor/rotor speed - omega_0{i} = (m*g/4/K_T{1})^0.5; - % ESC normalized pwm input factor - K_E{i} = 1; - % ESC turn-on duty cycle - p_0{i} = 0; - % ESC maximum duty cycle (as calibrated) - p_max{i} = 1; + % PHYSICAL SYSTEM PARAMETERS + % quadrotor + battery inertia tensor + J = diag([ Jxx Jyy Jzz ]); + % quadrotor + battery body frame origin to c.o.g. error radius + r_oc = [ 0 ; 0 ; 0 ]; + + % mass of rigidly attached load + m_L = 0; + % dimensions of assuemd rectangular load + x_L = 0; y_L = 0; z_L = 0; + % inertia tensor of load + J_L = m_L/12*diag([y_L^2+z_L^2,x_L^2+z_L^2,x_L^2+y_L^2]); + % location of load center of mass in body frame + r_oL = [0; 0; 0];%[ 0.12 ; 0.12 ; -0.04];%(0.04 + z_L/2) ]; + %r_oL = [ .115 ; .115 ; 0.04]; + + % acceleration of gravity + g = 9.81; + + % initial dynamics states conditions + u0 = 0; + v0 = 0; + w0 = 0; + p0 = 0; + q0 = 0; + r0 = 0; + x0 = 0; + y0 = 0; + z0 = 0; + phi0 = 0; + theta0 = 0; + psi0 = 0; + + % ROTOR PARAMETERS + + % nominally equal rotor parameters + K_T = cell(1,4); K_H = cell(1,4); K_d = cell(1,4); + Delta_T = cell(1,4); + %Delta_T = [0 0 0]; + J_r = cell(1,4); Gamma_H = cell(1,4); + for i = 1:4 + % rotor thrust constants + K_T{i} = Kt; + % rotor H-force coefficeint + K_H{i} = Kh; + % rotor drag constant + K_d{i} = Kd; + % rotor b_z axis velocity thrust adjustment factor + Delta_T{i} = 0.5*[ 0 0 2.351e-4 ]; + % equivalent rotor + motor moment of inertia + J_r{i} = Jreq; + % h-force xy-plane selection matrix + Gamma_H{i} = [ 1 0 0 ; 0 1 0 ; 0 0 0 ]; + end + + % ESC-MOTOR PARAMETERS + have_motor_transient = 1; + % nominally equal motor and eletronic speed control parameters + R_m = cell(1,4); K_Q = cell(1,4); K_V = cell(1,4); + i_0 = cell(1,4); omega_0 = cell(1,4); K_E = cell(1,4); + p_0 = cell(1,4); p_max = cell(1,4); + for i = 1:4 + % motor resistance + R_m{i} = 0.235; + % motor torque constant + K_Q{i} = 96.3422; + % motor back-emf constant + K_V{i} = 96.3422; + % motor no-load current + i_0{i} = 0.3836; + % initial motor/rotor speed + omega_0{i} = (m*g/4/K_T{1})^0.5; + % ESC normalized pwm input factor + K_E{i} = 1; + % ESC turn-on duty cycle + p_0{i} = 0; + % ESC maximum duty cycle (as calibrated) + p_max{i} = 1; + end + + + + % ROTOR LOCATION/ORIENTATION PARAMETERS + + % locatin of hub 1 in body frame + r_h{1} = [ rhx ; rhy ; -rhz ]; + % rotor 1 thrust unit vector + Gamma_T{1} = [ 0 ; 0 ; -1 ]; + % rotor 1 rotation unit vector + Gamma_Omega{1} = [ 0 ; 0 ; -1 ]; + + r_h{2} = [ -rhx ; rhy ; -rhz ]; + Gamma_T{2} = [ 0 ; 0 ; -1 ]; + Gamma_Omega{2} = [ 0 ; 0 ; 1 ]; + + r_h{3} = [ -rhx ; -rhy ; -rhz ]; + Gamma_T{3} = [ 0 ; 0 ; -1 ]; + Gamma_Omega{3} = [ 0 ; 0 ; -1 ]; + + r_h{4} = [ rhx ; -rhy ; -rhz ]; + Gamma_T{4} = [ 0 ; 0 ; -1 ]; + Gamma_Omega{4} = [ 0 ; 0 ; 1 ]; + + + + % BATTERY PARAMETERS + + % starting/operating battery voltage + V_0 = 11.4; %12.4; %11.4; + % approximate hovering rate of battery discharge + d_V = 0; + + % DISTURBANCE PARAMETERS + + F_D = 1*randn(3,1); + Q_D = 0.05*randn(3,1); end - - -% ROTOR LOCATION/ORIENTATION PARAMETERS - -% locatin of hub 1 in body frame -r_h{1} = [ rhx ; rhy ; -rhz ]; -% rotor 1 thrust unit vector -Gamma_T{1} = [ 0 ; 0 ; -1 ]; -% rotor 1 rotation unit vector -Gamma_Omega{1} = [ 0 ; 0 ; -1 ]; - -r_h{2} = [ -rhx ; rhy ; -rhz ]; -Gamma_T{2} = [ 0 ; 0 ; -1 ]; -Gamma_Omega{2} = [ 0 ; 0 ; 1 ]; - -r_h{3} = [ -rhx ; -rhy ; -rhz ]; -Gamma_T{3} = [ 0 ; 0 ; -1 ]; -Gamma_Omega{3} = [ 0 ; 0 ; -1 ]; - -r_h{4} = [ rhx ; -rhy ; -rhz ]; -Gamma_T{4} = [ 0 ; 0 ; -1 ]; -Gamma_Omega{4} = [ 0 ; 0 ; 1 ]; - - - -% BATTERY PARAMETERS - -% starting/operating battery voltage -V_0 = 11.4; %12.4; %11.4; -% approximate hovering rate of battery discharge -d_V = 0; - -% DISTURBANCE PARAMETERS - -F_D = 1*randn(3,1); -Q_D = 0.05*randn(3,1); -end \ No newline at end of file +% Signal mixer using rotor layout +% 1 2 +% 3 4 +signal_mixer = [ 1, -1, -1, -1 + 1, -1, 1, 1 + 1, 1, -1, 1 + 1, 1, 1, -1 ]; + +% Linearize model, load preferred weight set, and build LQR model +[ssA, ssB] = linearization(m, g, Kt, Kh, Kd, delta_T(3), rhx, rhy, rhz, J, Jreq, Vb, Rm, Kv, Kq, If, signal_mixer); +load('weights_modern.mat'); +% Set control period to equal period of camera system +T_LQR = Tc; +[lqr_K, lqr_S, lqr_E] = initial_lqr(ssA, ssB, state_weights, command_weights, T_LQR); \ No newline at end of file diff --git a/controls/model/repeated_opt.m b/controls/model/repeated_opt.m new file mode 100644 index 000000000..bc5df87b4 --- /dev/null +++ b/controls/model/repeated_opt.m @@ -0,0 +1,29 @@ +% Change the size of the max value in the for loop to change the number of +% optimizations run. Each run (except the first) picks a random set of LQR +% weights and uses matlab's fmincon() to repeatedly run the simulation and +% minimize the value of lqr_err(). The weights resulting weights are stored +% as .mat files that can be loaded in modelParameters.m. + +% Start with weights that look like Matt Rich's values +rw = matfile('weights_rich.mat'); +sw = double(rw.state_weights); cw = rw.command_weights; +x0 = [sw([1,3,4,6,7,9,10,12]) cw([1,3,4])]; +for i = 1:30 + % For other iterations, create random initial weights + if (i > 1) + x0 = 100*rand(1, 11); + end + % Run Matlab optimization on weights to minimize simulated error + options = optimoptions('fmincon','Display','iter'); + [X,FVAL,EXITFLAG,OUTPUT] = fmincon(... + @(weights) lqr_err(ssA, ssB, weights, T_LQR),... + x0, -eye(11), zeros(11, 1), ... + [], [], [], [], [], options); + + % Store result of optimization in file + state_weights = X([1, 1:3, 3:5, 5:7, 7:8]); + command_weights = X([9:10 10:11]); + error_norm = FVAL; + fprintf("At timestamp %s, error was %f", datestr(now, 'mmddHHMM'), error_norm); + save(['opt_weights_', datestr(now, 'mmddHHMM'), '.mat'], 'state_weights', 'command_weights', 'error_norm'); +end diff --git a/controls/model/rich_params.m b/controls/model/rich_params.m new file mode 100644 index 000000000..b0e94dbf7 --- /dev/null +++ b/controls/model/rich_params.m @@ -0,0 +1,389 @@ +% This file is the same as modelParameters, but the parameter values all +% match those in Matt Rich's thesis, so the control design or simulation +% can be run and compared to his results. + +% Add Library Blocks and 3D animation to Path + path_1 = genpath('Library_blocks'); + path_2 = genpath('3D_Animation'); + addpath(path_1, path_2); + +% Log Analysis Toggle + logAnalysisToggle = 0; % 1 for log analysis, 0 for normal operation + +% Physics Verification Toggle + physicsVerificationToggle = 1; + +% Define Simulink Runtime (if logAnalysisToggle is selected, this will be +% automatically set based on the log files time) + runtime = 40;%max(time); + +% Model Parameters + m = 0.656; % Quadrotor + battery mass + g = 9.81; % Acceleration of gravity + Jxx = 0.0081; % Quadrotor and battery motor of inertia around bx (pitch) + Jyy = 0.0074; % Quadrotor and battery motor of inertia around by (roll) + Jzz = 0.0135; % Quadrotor and battery motor of inertia around bz (yaw) + Jreq = 1.376e-05; % Rotor and motor moment of inertia around axis of rotation + Kt = 7.3956e-6; % Rotor thrust constant + delta_T = [ 0, 0, 1.176e-04 ]; % Thrust constant adjustment factor + Kh = 3.4574e-04; % Rotor in-plane drag constant + Kd = 5.194e-07; % Rotor drag constant + rhx = 0.115; % X-axis distance from center of mass to a rotor hub + rhy = 0.115; % Y-axis distance from center of mass to a rotor hub + rhz = 0.04; % Z-axis distance from center of mass to a rotor hub + r_oc = [0; 0; 0]; % Vector from origin to center of mass + Rm = 0.19; % Motor resistance + Kq = 110; % Motor torque constant + Kv = 110; % Motor back emf constant + If = 0.39; % Motor internal friction current + Pmin = 0; % Minimum zybo output duty cycle command + Pmax = 1; % Maximum zybo output duty cycle command + Tc = 0.01;%0.04; % Camera system sampling period + Tq = 0.005; % Quad sampling period + tau_c = 0; % Camera system total latency + Vb = 11.4; % Nominal battery voltage (V) + x_controlled_o = 0; % Equilibrium lateral controller output + y_controlled_o = 0; % Equilibrium longitudinal controller output + yaw_controlled_o = 0; % Equilibrium yaw controller output + Kp_mahony = 0.4; % Proportional term for mahony filter + Ki_mahony = 0.001; % Integral term for mahony filter + + % Define Biquad Filter Parameters + accel_Fc = 10; + Fs = 1/Tq; + accel_K = tan(pi * accel_Fc / Fs); + Q = 0.707; + accel_norm = 1.0 / (1.0 + accel_K/Q + accel_K*accel_K); + + accel_b0 = accel_K*accel_K*accel_norm; + accel_b1 = 2.0*accel_b0; + accel_b2 = accel_b0; + accel_a0 = 1; + accel_a1 = 2.0*(accel_K*accel_K -1) * accel_norm; + accel_a2 = (1.0 - accel_K/Q + accel_K*accel_K) * accel_norm; + + accel_SOS_Matrix = [accel_b0, accel_b1, accel_b2, accel_a0, accel_a1, accel_a2]; + + OF_Fc = 7; + OF_K = tan(pi * OF_Fc / Fs); + + OF_norm = 1.0 / (1.0 + OF_K/Q + OF_K*OF_K); + + OF_b0 = OF_K*OF_K*OF_norm; + OF_b1 = 2.0*OF_b0; + OF_b2 = OF_b0; + OF_a0 = 1; + OF_a1 = 2.0*(OF_K*OF_K -1) * OF_norm; + OF_a2 = (1.0 - OF_K/Q + OF_K * OF_K) * OF_norm; + + OF_SOS_Matrix = [OF_b0, OF_b1, OF_b2, OF_a0, OF_a1, OF_a2]; + + % Determine Initial Conditions + + % Position Initial Conditions + x_o = 0; + y_o = 0; + z_o = 0; + + % Velocity Initial Conditions + x_vel_o = 0; + y_vel_o = 0; + z_vel_o = 0; + + % Euler Angle Initial Conditions + roll_o = 0; + pitch_o = 0; + yaw_o = 0; + + % Euler Rate Initial Conditions + rollrate_o = 0; + pitchrate_o = 0; + yawrate_o = 0; + + % Equilibrium rotor speeds + omega0_o = sqrt((m*g)/(4*Kt)); + omega1_o = sqrt((m*g)/(4*Kt)); + omega2_o = sqrt((m*g)/(4*Kt)); + omega3_o = sqrt((m*g)/(4*Kt)); + + % Equilibrium height controller output + height_controlled_o = (((Rm*If ... + + (((omega0_o * 2 * Rm * Kv * Kq ... + * Kd + 1)^2) - 1)/(4* Rm*Kv^2*Kq ... + * Kd))/Vb)*(Pmax - Pmin) + Pmin); + +if logAnalysisToggle == 1 + %%%%%% Commented out section until logging is .txt file based %%%%%% + % FNAME + % if you know the name of the log file that you want to parse, set the it + % here only if it is in the working directory. Otherwise, you may leave it + % blank. You will be able to choose the file to parse through an explorer + % window. + % + %fname = 'sampleLogFile.txt'; + fname = ''; + fpath = 'C:\Users\Andy\Documents\School\MicroCART\GitRepo\MicroCART_17-18\controls\model\logFiles\'; + + if(isempty(fname)) + [fname] = uigetfile('.txt','Select log file', fpath); + end + + params.file.name = fname; % file name only + params.file.path = fpath; % file path only + params.file.pathName = [fpath fname]; % file path with file name + + [dataStruct, headers] = parse_log_model(params.file.pathName); + + time = dataStruct.Time.data; + time = time - time(1); + time_indices = length(time); + + runtime = max(time); + + % Determine x position error + x_setpoint = dataStruct.X_Setpoint_Constant.data; + x_pos_raw = dataStruct.VRPN_X_Constant.data; + x_error = timeseries(x_setpoint - x_pos_raw, time); + x_position = timeseries(x_pos_raw, time); + + % Determine y position error + y_setpoint = dataStruct.Y_Setpoint_Constant.data; + y_pos_raw = dataStruct.VRPN_Y_Constant.data; + y_error = timeseries(y_setpoint - y_pos_raw, time); + y_position = timeseries(y_pos_raw, time); + + % Determine z position error + z_setpoint = dataStruct.Alt_Setpoint_Constant.data; + z_pos_raw = dataStruct.VRPN_Alt_Constant.data; + z_error = timeseries(z_setpoint - z_pos_raw, time); + z_position = timeseries(z_pos_raw, time); + + % Determine x velocity error + x_vel_setpoint = dataStruct.X_pos_PID_Correction.data; + x_vel_raw = dataStruct.X_Vel_Correction.data; + x_vel_error = timeseries(x_vel_setpoint - x_vel_raw, time); + x_vel = timeseries(x_vel_raw, time); + + % Determine y velocity error + y_vel_setpoint = dataStruct.Y_pos_PID_Correction.data; + y_vel_raw = dataStruct.Y_Vel_Correction.data; + y_vel_error = timeseries(y_vel_setpoint - y_vel_raw, time); + y_vel = timeseries(y_vel_raw, time); + + % Determine pitch error + pitch_setpoint = dataStruct.X_Vel_PID_Correction.data; + pitch_angle_raw = dataStruct.Pitch_trim_add_Sum.data; + pitch_error = timeseries(pitch_setpoint - pitch_angle_raw, time); + pitch_angle = timeseries(pitch_angle_raw, time); + + % Determine roll error + roll_setpoint = dataStruct.Y_Vel_PID_Correction.data; + roll_angle_raw = dataStruct.Roll_Constant.data; + roll_error = timeseries(roll_setpoint - roll_angle_raw, time); + roll_angle = timeseries(roll_angle_raw, time); + + % Determine yaw error + yaw_setpoint = dataStruct.Yaw_Setpoint_Constant.data; + yaw_angle_raw = dataStruct.Yaw_Constant.data; + yaw_error = timeseries(yaw_setpoint - yaw_angle_raw, time); + yaw_angle = timeseries(yaw_angle_raw, time); + + % Determine pitch rate error + pitchrate_setpoint = dataStruct.Pitch_PID_Correction.data; + pitchrate_raw = dataStruct.gyro_y.data; + pitchrate_error = timeseries(pitchrate_setpoint - pitchrate_raw, time); + pitchrate = timeseries(pitchrate_raw, time); + + % Determine roll rate error + rollrate_setpoint = dataStruct.Roll_PID_Correction.data; + rollrate_raw = dataStruct.gyro_x.data; + rollrate_error = timeseries(rollrate_setpoint - rollrate_raw, time); + rollrate = timeseries(rollrate_raw, time); + + % Determine yaw rate error + yawrate_setpoint = dataStruct.Yaw_PID_Correction.data; + yawrate_raw = dataStruct.gyro_z.data; + yawrate_error = timeseries(yawrate_setpoint - yawrate_raw, time); + yawrate = timeseries(yawrate_raw, time); + + % Pull motor commands from log + x_command = dataStruct.Pitch_Rate_PID_Correction.data; + y_command = dataStruct.Roll_Rate_PID_Correction.data; + z_command = dataStruct.Altitude_PID_Correction.data; + yaw_command = dataStruct.Yaw_Rate_PID_Correction.data; + + % Determine signal mix PWM values + PWM0 = dataStruct.Signal_Mixer_MOTOR_0.data; + PWM1 = dataStruct.Signal_Mixer_MOTOR_1.data; + PWM2 = dataStruct.Signal_Mixer_MOTOR_2.data; + PWM3 = dataStruct.Signal_Mixer_MOTOR_3.data; + PWM_arr = ... + [PWM0, PWM1, PWM2, PWM3]; + motor_commands = timeseries(PWM_arr, time); + + % Pull the measurements from the acceleratometer + raw_accel_data_x = dataStruct.accel_x.data; + raw_accel_data_y = dataStruct.accel_y.data; + raw_accel_data_z = dataStruct.accel_z.data; + raw_accel_data_arr = ... + [ raw_accel_data_x , raw_accel_data_y , raw_accel_data_z ]; + raw_accel_data = timeseries( raw_accel_data_arr , time ); + + % Pull the measurements from the gyroscope + raw_gyro_data_x = dataStruct.gyro_x.data; + raw_gyro_data_y = dataStruct.gyro_y.data; + raw_gyro_data_z = dataStruct.gyro_z.data; + raw_gyro_data_arr = ... + [ raw_gyro_data_x , raw_gyro_data_y , raw_gyro_data_z ]; + raw_gyro_data = timeseries( raw_gyro_data_arr , time ); + + % Pull the measurements from the complimentary filter + pitch_measured_IMU = dataStruct.Pitch_trim_add_Sum.data; + roll_measured_IMU = dataStruct.Roll_Constant.data; + IMU_angle_arr = ... + [roll_measured_IMU, pitch_measured_IMU]; + IMU_angle_data = timeseries( IMU_angle_arr, time); + + % Pull VRPN pitch and roll + pitch_measured_VRPN = dataStruct.Pitch_trim_add_Sum.data; + + + % Define setpoint timeseries + x_setpoint_model = timeseries(x_setpoint, time); + y_setpoint_model = timeseries(y_setpoint, time); + z_setpoint_model = timeseries(z_setpoint, time); + +end + +if physicsVerificationToggle == 1 + % PHYSICAL SYSTEM PARAMETERS + +% quadrotor + battery inertia tensor +J = diag([Jxx Jyy Jzz]); +% quadrotor + battery body frame origin to c.o.g. error radius +r_oc = [ 0 ; 0 ; 0 ]; + +% mass of rigidly attached load +m_L = 0; +% dimensions of assuemd rectangular load +x_L = 0; y_L = 0; z_L = 0; +x_L = 0; y_L = 0; z_L = 0; +% inertia tensor of load +J_L = m_L/12*diag([y_L^2+z_L^2,x_L^2+z_L^2,x_L^2+y_L^2]); +% location of load center of mass in body frame +r_oL = [0; 0; 0];%[ 0.12 ; 0.12 ; -0.04];%(0.04 + z_L/2) ]; +%r_oL = [ .115 ; .115 ; 0.04]; + +% acceleration of gravity +g = 9.81; + +% initial dynamics states conditions +u0 = 0; +v0 = 0; +w0 = 0; +p0 = 0; +q0 = 0; +r0 = 0; +x0 = 0; +y0 = 0; +z0 = 0; +phi0 = 0; +theta0 = 0; +psi0 = 0; + +% ROTOR PARAMETERS + +% nominally equal rotor parameters +K_T = cell(1,4); K_H = cell(1,4); K_d = cell(1,4); +Delta_T = cell(1,4); +%Delta_T = [0 0 0]; +J_r = cell(1,4); Gamma_H = cell(1,4); +for i = 1:4 + % rotor thrust constants + K_T{i} = Kt; + % rotor H-force coefficeint + K_H{i} = Kh; + % rotor drag constant + K_d{i} = Kd; + % rotor b_z axis velocity thrust adjustment factor + Delta_T{i} = .125 * delta_T; + % equivalent rotor + motor moment of inertia + J_r{i} = Jreq; + % h-force xy-plane selection matrix + Gamma_H{i} = [ 1 0 0 ; 0 1 0 ; 0 0 0 ]; +end + + + +% ESC-MOTOR PARAMETERS +have_motor_transient = 1; +% nominally equal motor and eletronic speed control parameters +R_m = cell(1,4); K_Q = cell(1,4); K_V = cell(1,4); +i_0 = cell(1,4); omega_0 = cell(1,4); K_E = cell(1,4); +p_0 = cell(1,4); p_max = cell(1,4); +for i = 1:4 + % motor resistance + R_m{i} = Rm; + % motor torque constant + K_Q{i} = Kq; + % motor back-emf constant + K_V{i} = Kv; + % motor no-load current + i_0{i} = If; + % initial motor/rotor speed + omega_0{i} = (m*g/4/K_T{1})^0.5; + % ESC normalized pwm input factor + K_E{i} = 1; + % ESC turn-on duty cycle + p_0{i} = 0; + % ESC maximum duty cycle (as calibrated) + p_max{i} = 1; +end + + + +% ROTOR LOCATION/ORIENTATION PARAMETERS + +% locatin of hub 1 in body frame +r_h{1} = [ rhx ; rhy ; -rhz ]; +% rotor 1 thrust unit vector +Gamma_T{1} = [ 0 ; 0 ; -1 ]; +% rotor 1 rotation unit vector +Gamma_Omega{1} = [ 0 ; 0 ; -1 ]; + +r_h{2} = [ -rhx ; rhy ; -rhz ]; +Gamma_T{2} = [ 0 ; 0 ; -1 ]; +Gamma_Omega{2} = [ 0 ; 0 ; 1 ]; + +r_h{3} = [ -rhx ; -rhy ; -rhz ]; +Gamma_T{3} = [ 0 ; 0 ; -1 ]; +Gamma_Omega{3} = [ 0 ; 0 ; -1 ]; + +r_h{4} = [ rhx ; -rhy ; -rhz ]; +Gamma_T{4} = [ 0 ; 0 ; -1 ]; +Gamma_Omega{4} = [ 0 ; 0 ; 1 ]; + + + +% BATTERY PARAMETERS + +% starting/operating battery voltage +V_0 = 11.4; %12.4; %11.4; +% approximate hovering rate of battery discharge +d_V = 0; + +% DISTURBANCE PARAMETERS + +F_D = 1*randn(3,1); +Q_D = 0.05*randn(3,1); +end + +signal_mixer = [ 1, -1, -1, -1 + 1, -1, 1, 1 + 1, 1, -1, 1 + 1, 1, 1, -1 ]; + +% System linearization and lqr construction +[ssA, ssB] = linearization(m, g, Kt, Kh, Kd, delta_T(3), rhx, rhy, rhz, J, Jreq, Vb, Rm, Kv, Kq, If, signal_mixer); +load('weights_rich.mat'); +[lqr_K, lqr_S, lqr_E] = initial_lqr(ssA, ssB, state_weights, command_weights, .01); diff --git a/controls/model/run_once.m b/controls/model/run_once.m new file mode 100644 index 000000000..e90667285 --- /dev/null +++ b/controls/model/run_once.m @@ -0,0 +1,33 @@ +% Runs the simulation once, optionally plotting the setpoint errors +function [sp_err] = run_once(show_plot) + output = sim('Quadcopter_Model', 'ReturnWorkspaceOutputs','on'); + % Use position errors but not velocity + sp_err = output.yout{1}.Values.Data(:, (7:12)); + setpoints = output.yout{2}.Values.Data; + position = [output.yout{3}.Values.Data output.yout{4}.Values.Data(:,3)]; + + % Plot position and angle error + if show_plot + close all; + % Separate position and angle errors + position_err = sp_err(:, 1:3); + angle_err = sp_err(:,4:6); + time = output.tout; + + % Draw plots of errors + figure; hold on; + plot(time, position_err); plot(time, angle_err, '-.'); + title('Position and Euler Angle Error'); + xlabel('Time (s)'); ylabel('Error (m or rad)'); + legend({'x', 'y', 'z', '\phi', '\theta', '\psi'}); + hold off; + + % Plot position and setpoints + figure; hold on; + plot(time, position); plot(time, setpoints, '-.'); + title('Setpoints and Actual Position'); + xlabel('Time (s)'); ylabel('Value (m or rad)'); + legend({'x', 'y', 'z', '\psi'}); + hold off; + end +end \ No newline at end of file diff --git a/controls/model/test_improved_lqr.m b/controls/model/test_improved_lqr.m new file mode 100644 index 000000000..33ef15edd --- /dev/null +++ b/controls/model/test_improved_lqr.m @@ -0,0 +1,4 @@ +[lqr_K, lqr_S, lqr_E] = improved_lqr(ssA, ssB,... + [1,0;0,sqrt(10);0,0], [.5, 1/.6, 1/25, 1/.25], [1,0;0,sqrt(10);0,0],... + [0;0;1/50], 1/60, [0;0;1/50],... + .01); \ No newline at end of file diff --git a/controls/model/test_model.slx b/controls/model/test_model.slx deleted file mode 100644 index 35a8b396d018cd92f55e5327af5b488dbafddcaf..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 163681 zcmaI7Q;;q^&^0<Ud-mA2ZQHhO+qP}(v2EM7p0RD)IPX_=>eTt_ulg_2>2&(0d!;JL zN=HHZ4=4%{5D)~AS&Fgby;66o9xxD4I|vXE_J3AeQx`)MLl;AOV|yo41t)t4QzsWo zQ)fC4TN~dbUHM=Jl(1i@bKaEr222ndKNEF2#wdV?`X=)V1g+&I#_!G`P#GPWPRc8f z@7!i`a&5fpF^+&GooE=yoH!f=6(+iASZ;KzcPNf+gh6o<2-8xa*esX4WwJuWp5O#n z%6>ksHHnK*7R+_5B~lFQwy<ooIiz7UcZHSFRUMV1@EJHIaCmRuFe}Dj1YtY7OV&DK zY--GG>P%TB*dH-Q6@_31EO5PmzV*zk+Q4Y`(gRFef#nY(9u>2P@^_gQ+shU}|N0lO z-}Vkath{T-nYbu$&WSKgijwQQ8dJHF4_%4zWe8P0ma|Rp5sFV`w@91&2-tA}KFv0P z!*@AE5s4Ow<6G*1{;T)UqGsinR(&nGS%JJVqOA==?_s}PXX1O++`xt6C;$57GrAoH znqT&C@AqtyESRwSU+|qe4LlD3l^$%4c@6j|>NNi6X)pY<B$w>XSmUw2!vBH=E{e8w z^glSn|APki{|}3;`~L}yY5bHO2qTQBKj~yIvO!=a6|&n^Ih7QDKM5ML?16}*$MkOU z-)PLv=3{4{x*c941a_J$<Y%Ytnqq;*3D3@_huh}gx0E32gx~}SZ%#t#24=1uTdFr@ zrBNl`Mhm<HJ-C(=`jRy`jKD4k*Y+|dCv#;L%qs|Vm8@m2qSS7d4YEp!XBJbI1m`<6 zE9nxuBQw00dn}$<T^YDwHD{~ZHT3wS!6#V6nOkV2aR2!Oxi)^_S#cPMn3J_2yE!e| zHd{Yx``rJX08R9Lru6>;U-++){ofKG>fvH)=WJ<j_diQicXj|Shyej~Uf=S?4jL>5 z3yPfATjADv9U`!`coX8Mhc)+(BV+nVb;d~izOcW?9m^>rkigt$v#Ts@^SOIHcrT)M z1i-y;M+OF1`j-<6?*i#ph~RCM=!au{W|SQ#)o?yeBpuz5<%^+#WxpI^)=yqxn~HAL z!%v&Ig${g<eHan{39pK8qBK!B?ry4C;hOf4SM&q)zhhe^Q}doa1qSNY!~(+nFE(dO zTUQ%PJ8OC)8+&7G6H7yLCqvu+3FoTE(tA^^k>bnO@2}pR_lYD~stgUN0QcdiLejsp zI8^FXBY87UF9M`O2M|OUASpGchh2O6HGniLq(mc(`6yZBjhMQttE;Lj?e0&W{Az*Q z;g}=>?eB}sE-vrl*D*~d_|(X5Zq4Ep?(6!m=XaTXd{GBJ9xZ**+lI8F^0jcw)Fr<q zmTeG!!5sMp{7%bnn|awzEdOrbgOPpe$9<N~o_U>p@G(!PtecCmjnC&n@wzoy&DZOX z=@q%U`9RC>)w6}WNt}3*V%Ie{%PU9v=QSUoar=WnqC0v%FO1MKFJCP!EyhgmB4@ki z%jeF#&R^=Q4KNKY|IH$bK=Q!1xJ(7}bwuO!g4J^q{@j8O&b$=>c;(Q*^Uiaan_}qn z#im6Am3~ND;g&mGS9Lf%4E1=y`t`sDuh_kD^>BLe>lx0=>k-3e$ziO2J%8J~HbnTa z4=(v#(WhIeGOu$DZU7OVBH+!Y&Fjex?M1g<{VC%o6uMK^m;NT<?He_5%+;w)>pBC} z*tUp!T#`~2pnwQm%q_THArn=!`nlippGCSMiBoUb+W#abA(l>=WBK~I1V}t&wBmb7 zCMhaA^uPrl(|37;FTc2`th8q<!oHL@yV{OZIVGLbh*~E-e{VK1Xn|TtBGN&RU$hHA z$FXYw4Do6ZNBF$I>u}xOpLB}+FOe6?e&a^Zc7K<`t$;<`PV{079uCP=$gnHb(wx2~ zP54121ISlF>{PN8UDHIG^yLak$^$usVGh<W+kQ+ZFJBnbi9e<`!Kap3a(nQccOQE2 zX=;@`yhTnUcv&~)FD!fo6Ul_0vgE56qP{)mtoPTA4m;M3v00eSIAV=&Yq<tI6T}?F zHqtRw%Y<?P;@}a%bj&|L>P>uAFc(P8j@R#C!@EE$eWJ#P6RZ#<dFSUJL><y^#NDyo zoMz<W;IY6oizlyMkCe}8mJ2)Xoy>TLJ#3hoGc{`1dwGg3z7ew>6n3$U8>roH+sCE{ zWij7&nJaW&6~>oO_EUnJyYt(+Q~l=q!;Yh!tSec{R>{ED0Gnq~YdicBQSN9p`)_Ri zErWH?+iQ2g7A%@9d#tW;P%-K%>vUpKylk^Yr{xWov9fqyEWkg^&bHNJmY05Gl-u?y z9lpsz0&Cj@P(4v=nCegS*%1b(v03v4x^A)CO8}$pBC_|#fxlBvR5~X3gmS-8K2nSP zhjTz<;&$ifY1AW9|90$r8^EObj$z*&T;G!5DKERBs*AQ3?@Ryu+QZO&XV%A}H+>mm za)1%N(SH(dcx1TVfsJ^~i$<Mdg0iWEqC}(aRh~vaoOEg#m9Un6it_F082!tazSmb4 zZTVu3@4x$ba^#lh<D0nG$1k`0#nIEg{h4>}KJheky<_#U9lz+ma}&CF>z|Fc+dE*( zm*}_nFvsrk)st6tTjtHacpF!?bG^e~y8F%aed=P*`F&G%?!$!(NCl_A%WFIh4F3JG zY<T^Cnz?=&iuVp*3@$ncxY)CN|5$v?;RCz@SAM-ChjFFMOueE0`iJk`J=@jz@6JKy z2M3Y*Npqm$_LCLI9v#CT>z|e%W^BA!H@@k;@0MQO=^Kkf=Ps=RhkpDchdcX@-}tXT z^nP<!ZntPdu{->key4?Qi`Z`7%~<w+8G1A?ep7zG_+Q+Ezq-i!zppO@S#|PwBGE>@ zF1eu9ZFcYP<pD{9VX5s89bZ3UcQQ-%i{@{>-o`&of9#tW;pcA9!w%DbufRz$sJgm) z$FO%_ijGa|IbKqC2IHNj1prM3(N&yAe|Etk59ZzH^j3R+0*-2_HtGI-S>Wk_{rKG8 zB&@mS_WacKg`8KNbH)BNO6W&+5};iLbNBFnroRrAVh%Udsz)pm2BJkuoJ2h0@lV^x zyn8=wAIOSNX<iYdlKNV58JE56*y}?uywIvTwOjCrGDG|FOngI}n@Y|^4coBm(iNpx zT)`SEsmegn8PWH8N5?$`6KICwX%%p`h|FkS10;o}>An!<>k75E3g;K!m_=#j3pr+H zln)pgy%<#N4>Ul1OOD0q^^8=6Hsns(1(8NR)qk$g?|JTG{I$R;+Lr_KK%<Yn?K=_* zsG`&+x<~_~*a1Z&NR$WO13VFc6Jd&Hp?9ooA|oLcF*tq0A!dF_c_Nol{27vH*C>I9 z!B;<|P-`AoOK_Ue&xUqPp)!7d^ttbJ?kRXZ9FHj!+gwgmUk}(_p9gajvvSJ|e<B1) zNL1J#>~+%TZz3QnO>e`ytoS22eEFa6_1yCB2K3)Xy?d>zP>IqZ{0TY;wXO4{Fmk<^ z-r|V&fJ|bl?2!SeV3*8M3;J=d98tygQ%6WdXqQWoc>?As#U-@tP<j9G%VQetI#R^_ zciE-_fZzLZ8EIjvF})?+*EKX6{CDaZm5J{Abc=-$?UMBLs_+VnT(_%GJGIwq`tn}* z^K&SEUl)(;x2h65`M)}Cuc{*|sn?aXGzjg8R0ZJ^!{jy|p(mVOgin+v-5)ihy4epB zSJ}eBM`{uOY#N4k={!gq99=LC_~U9w!m)V8FX_eyvmeXmIP>!R`=_gGm%6u%Wk;^8 z_x*F-q>oi|z3#h3;Rh`E-|nn1X1hFQ{2aTp0R9)hd-^H9Q|I3W?eKF?ubFI$^XN|k z)#nZE*}R@!G5y)Yr_>H;BO2FfgpzE$*;Mdw+PBS0<_-1rZ3#z4Wk3$O&2~pI*H#`@ zYm=gfn75ZHV7}t#H`)_N)b+aV4AJy)pePM@HA9a5qhhDZ@}DTzISZ%gg)3QXA}85t zN2uE_{7{&rS{*i!1N5xTJ#k_n2wU3XVo|Uxxk|d`4{?U9GR#RsihTnxrC2ygF7}~^ z)cviu9#>bPPndUHVwioZ1|0PjC{At`D_?Z*--bql1-;t!>8b^l(NikfhT$PYlYeUV zLPXDnupQmWEW8?HPehQ6O^C^&j96(FcL^!9=TE*Uv%9)_P8bHRE_o5%3uYZh&sVNE zBo=5%FT=Ssc&%>4RHeZ(H6CqGfPu_Ot)f(mPW-yBW0u}jINrRxLSc$G7c}3yHzbXf z58~eDoG?N};==f^q0WGNtT|%tZBkI559xZY2)i_koYQB$L3e_%NHY>lY~uu~T$PaZ zu?59%ydP2TOQpWRS3a(yZ&I$^_Ju#G4_2~~Pyfy%gn&~3*JrxQm58!`sP~&(V{(f_ zpEffo9=o}sdrX}oZ_%h%7l~gapLH>GJq&Bm56e08!x=1vK%aT}d!E0K&$pf2#D-fw zB=5{Js*Uxtj00b|G{7XWrkh#317DU~ULkvav3SM3pR8ZbN4<|(61$ND3k#U%^$C)C z7Yj{2%3eUK4Q)V>KOiBH3&+;9MKd%m%G3cm4>$N1MmnlLggBs8)VBb<{{E}bz6jVk z*-JZ9>6$?Uv|@=jX-KiNb(JCwN<}~E&_0-@msGBMHHqxlKP*CSDj^a!(q?Dotprh- zr>TyUN}gq)mQwJOu1JNF4X_Hunx&`UQ|tfo>a}tR5nbdmiD=;`Y|HQa#Jb*~Tv)tn zBl*6?8MX%bMW^;3Q^0LP1Z-alpPk~4JOXj^FQ^3R1cMM1xyw0wm^^Ij=S~+jWzHCe z#iBQ>Dyij5RF9diT#s*nBIRR7e%Tf^I6(tJoto7d$Je##h3sFTl@&$$R<)c?-2>kC z&;PN<+jUS3_~+%bn>NDg>v4&ABl&y1e0cMB-ver2J!V8c@ce!fcX}oC*mUWH3P8ip zLuMrmJU#G_KchKu7fv|FW0YHHXEkc=rJ<qRar@#EP9jThLl+q|XehPJf0CMD0hm#W znzlZ;)2D>ay!a7fc)JU~DQ_99uhYLNa*6H8(|(k8%-GNq+RgTnsA+xpsDZgpz>jV8 z8_8d2+F|XFe9uGDR`;)TpsBDnoIEjqyTI8!+8+FL57CbFPo4+8Bz+KwjX-^G=Zxd! z#fv3HZe-rkFpHy)ZJDyb?aQz322Txw;*%={)&~&;wG4HSjBaOQ(Q7BB)-^b_>6x3E z@RKj`uKo>-4J1MBZ-L$V+W){wTKlvFOdHH*3Ee>V{~?GHvLeuByBiUlZFB9ifp$J> z5c?@bi{dTzHMk9mpcPuQ{j?L!cu1lK^k}2Ml9f?nU08S?6Dz)ytR#3>uEnR~2XW|n z6J`oS`==B@pT@q#@gK_I%$T>xox=iS@etxaoj&Okf36-427SmS%a;DLbkdPAgIjG8 zv~GN%X{U=pl%kJImAu&hQ^9)y-Yo4?i+>FsBqGEV={KK0OjR|=?kQnX`asjOx=7bu z?8dAve&|?Vyh5|%e4Bj7nN{2fzhR1_Ywa({CHX)Vt~UfTP}bKV?i<aJ8rig^N^wim zP(NcSvUU%dDZzr?%oXWN(zEmS4m!6aN!0||5b>8cAMUiH=9Azq;bpj}rjQe<xWv{^ zi;(re)&aM8m~PZAULN^r@_-74Dc%epsj1&Cb5mgFa}8TIUm>YWdC;=LHKD87g4Zr# zO$^o|yf?lXio~6^R>Yg>4s8m8diHFqnlO<+@Ab#k<xm|fIcuxv*!^cA9uOFM)ZLm> z6Gl87D0g6SLJkQqXLdF#^o$H^zC2!lN4~BqZiM9A;7;m!3HE4(>q*zU1v>W&AEJ#w zUcTp&oaniX^+!`AlWuVy*uyXa<vZ8!gUMx6F@6tg*YiJM_GKv?(U#n^RKuYQ{iy9U z4+gC$uE^_{YLer}ISGo_9Z#jiGG3L3>*Bdf1Gv_Qz-d~>fscd%&GxVRkwT|Y*f?wy z9DD8ZMh16?ur*MX4m%f5h0Eo+qFD&PhlK@qH5V1lxF@oEJyIk2B)Ll?q6<v*;=iX2 zDzn%Vb4kM2+lnyB?T9%M*}E1Z+ceF&gs|Y#`vg=3ZGU1wHUhUkdrrNN2AiBAL8Gw) zvyK`SE*!Xy6PCf4=EQ`aguV>o05sK=FP%78y3TD{dvC1lwqeOokpd3|h6i7#I9t8> zy?rsnU~g|GPvr0a7W~>ps*Z)?pCX1A8oMtNKYy=}!Nn~KlZc`3Alf_=lC3~m=}R_B zr#lbOZ3<wAILH>pCR0b04(eDw$@9m(9F||3uB_bA0UW~52q2jMR=AB61P$KuOrvey z7W6siQ@&%OiZ?#mpR!4O)&2B-uCkuC6K7^7z%QZ^$;oKhOpACgUIE?q#>Y}A1!$5` zmBAZr`hwZTn-CX{GN9ESf6WtJ4o1#EYr9o_YKZ*cg;(Pu^*Db*|LX#^ZIDE~+&LP- z5gLQ*L0#3yvlirm+YCiKq$OAv5+}OK(z}r4&@+@rG=Tj)z1l`JMdEfLgasGBPj-h$ z5bi`I#IC5(SR5IB86+T^=ker06KHw+$uyU;kvR7`jy6{wmv^jJ4Gc!NS;!|LBciqW z9`^vnqHPLxnBlQ6(iVHfwfl@e%P!cL_@dlnqxP4}OguL!TcS#6BY&LOxV_^-_;06} zMH+&9-WL;=-jJn_;ATTI5-M(_GZ$JY%{{_wZ5LLPcY(7WrGpr7!X@m%opa1Ab#!PT ztHfmmYn2I7vf?ANvo31`-Vmel+9`wkn}H9UM!xIeC`6aNR73Yb**HUBvgmH`_nq>d zkv&zi;2+z_7$41#$DEx96&(2Xsl&XYeu+&+d{T^x2zPik%q<=Bjyxd4kvB0gifvfV zS2GoxBvbdD@D#6z%_~@@SR~7GztDD)aRhofc)QOjCHR{HrbjjD-BE5xAq!oE@Fp-K zyeo8ErNP0^Vf1vM$NF!YV0LlNIoO+uCurqByfr+oZeK&}@Vc-Nu<7`Sh5K|Me{}I( z8RRlgSKf`cJ!gEar3bk6=veO<dXL54Qj9;U=fz>o_&Kbh#9)^Uki!xtW3<Jo#MrQC za{Oj+Wff`PI=`5X06?sNt2+c8cX>{4QQ}XWwndfnDDPXj-Lpa|Xx@e-g1OGSPDP(j zn6UhBE3UU;Q+V5wuF5CXy>F~ovl&s1+GttNQhm2`&NV6ABPc{B0uhbIG`t1-hh$~Y z@?wsTuel+!f2!s|#3qq>uBWmKLbY%p&K3gUOA)IaN1?~$F-|h;=>s07le<cf>&YW$ z^>#owjdl^~X0E%N2uWTItgIXihkkxPeqXC7B`JE`H{=9syR^~ny*Sg=52?8+b%BIc zWyrWQ1-x!G)S^y<#f|@@69nBiZXi8O&y~n0^`r3#)Dm`+G0yG;NO;_c=XS0?=DxM; zte^<Y(btgI<|9UZ#gRcBefcXJ^a~H)PmTM&aS?j&dH-$$H&OWCgCgz;HQdh^-<Zp| z_L<i6S75F^hpVM(tSC7Vd$%^`D_eHiQcD-y>2jm7?T`pznW4XN6aMT)z%Wg%-oCC< zj?IIJaGKqoc2p!C6%cW6l_-`#T-&pJ3!_V+rjx3t3PVGf>w9Nsw!6}-T3}Cpk}E9y zD-kR{kwrd<8c$cxvMAGY_xcBV_`y#XOZuLUZt%3d+T3Cg_vY>NYQS?oIK66*yu^UI zfE$*x;oW@pT$3BFRGYQFC&TS>Z%W|-aDgwJQ>}i)pC4HUWG|jU<Z-A^;G}W3wp1me zb*<CE#mp|po};u|K=rtoPHVFB5=l!?4q@c|HoX1XjMH30@|wP4Sq24N%(hW7-wD(X z$g?e3ErRRh8cJ`6);kFh6Fyi$C~HDLQ#3=s_YHz*%Fg`OXZTT(e?!`cFjek_^$BG_ z$M^Zaa6oj9d-pL2_YmZ)CFl(ME)UnER2d&~UUI=ngU$g|El7PrfZK4>s<kk&SFM{{ z=%TeaPnOZW#ueVH0a=^)8Si2pS6Hi)i#LLfo>Dh4ufliGLCl)3RVspKo(1x1R>WGN zr}!MXlg%NDlq7YDpe%0HFxDM|yYdkoF(k#?Oib{XSSJ|?0$INAKfS+e70g170dCj? zt)BbVjQ5GT*4$WZTf-8h!XL@4F-rXVYvypl^3*P5xL`(k6WNh}p3q7VppCGG-I0yr zeF{dG+hz7>WO)(e2Rg=u&+bl@%Iuh|nHbZ%J|o#*o4(Yg)&{T>pFVTzSs8aaV%R?i zqwNYa#Q{x&{!BtYt8vlHeTUt*U_ag_9n<qC?$mvjhm@TE;?X;LkKG#2TDLt$VjQ@6 zx!(9RbbO!c?^mM}?~LML%QlqqJI#y}+{z>}BMv})y-IVEo)!-gZzqvA&mDerbCcC` zGoPRPT!wIYS80X>C@>G(?Y*y@yuO*WeZrA(m!qtD9vN?su3DJR(!A;3BvRxSqBb%a z5xkW9uhS;-W6-Xve<ZNxYRju8NI6E}9jx6}_IOAQd1rvhQXdhrFnSADR0ki=#6xaQ zH6s@Me|ulYx~%>8kLAz$APlM{mi=Q=pLXl?za@D(6JOt6|2t{BaW!k^yv=wn9j~cz zzGU$q*p1<-pYn<$`!mXS;q2DN^{qLXcqO!1gw~$C-=>lL^ymEo&aI&eGfr<cw?+W? zn}-!YSk6_VxkWvxuvrZvB|lm@q|M60tMW-Ra>y%@3kG7Uqgs;u1#Q$eci95YiF?@$ z@dpa!Wr)Vk-wnYW-)kbwZH#mH@vw@OZ!x#nFX_7wmkXjsYCfQr(nfUlAj;@y1b6Qe z9T9W9IBIz)0$4x<y144@jAIZ|t3>#?80kSm$V++S9uPcNIlCf%zsOt?X~(9~)}3$> zp5kD<1T}+x^8KCh(&n{+&d6^t=sWBVwkwk7z+ixbl2B2ASA=PQ-+82<NgSj{n<WfV zZk<U^0vQ+*4fg~w26o;HfpWFIN+7#=C(n0R1gGdLI|T#L>%-{+?Ja>%0$+5mYQ{s8 z)X3bX9hn^8ISQ}>E$*$U0%O~vO%wViRvNY#LEUQu-1kCCIlSeV_eF~`3g`7Nr%=Bn zsmt%?Dil|ceyr<u1c2xB7UA#TZx!iA8%WZ_fQZqAVozZz@ENSIbz_XUWcJI$z(|2B zR+7m{mLY4XC}J~%kSwY830-m;X*AzQGn!ZaH8Iu;7@lF^(8yzu84E9;X4%Gs*)}Z0 zjkBF~Hfw-`-mq&#ER?DePGZL9J0Qyi$Rqm3@HfaIvTfN4R@}q2vMh5uQFYit4QV~3 z@%v}?Qu)m~ETxocKaRzqPGKOWsLV^s5s!_MBc)1>)d;Ea*tE)*YH{~Umc%YjBT!*B zAR;*IHzep`r`B6t$tLy%4qSHWkoRbmmx|4g2xSz@kSO)qHtt?Sx|D1n9iaCqi8Uz6 zZkGiAV``|s&Hv3pZY;rAfbuTb2)aVAR|rkkHZGamZTe?*p*j6;LEFs?AcctCbjY(h zO6-#oW2zhd&q{hbt5${h4+c_sUYUlLSFaR^oII%2=P4MS)2jQ6roN?2S>)7RzB>EG zHv@Nqg`Xe+f0HulBL5HJ)Qo7r=<a$zuYqu77|@I7tO(G+C$b1|7G%98!8?ux(6pWf zRO!J=vd=`j<e~v!FqezHAwqXfG(41*jGRSyr0$t^O;TIArp5YL*VfF!^hwc75H|-+ zyIPi#j}?{*mnJT7&d7%XJGo(@V2iDv7mDZA1tDK}FVX%d7Y=CfD-YvLV012-1rL7D zpj61nsBv|14pZC`P0MbtIt2pqbTq~%Mi&t#T(Px%rLDQLo<`tb7>ka$nGd2#cOYk1 zi`dqJXDw^4&_y{ddL0jZ=BUZe#roQ~oxx^;aJ6xDmdNad<Vt95uK%gOso%G{<ffU# zQ$yP5Kv~_-j?6z6nqGr@X;@q<1X6AFJQVHK0DIj?fc;u$<Fd6bJiy9L3z0OFwv?{n z0WB#f$`B?ikQ{8|ahS=5N%k|wG)+TW!WJ-u>Gfw~IS9}!osHr+Td>XYOOjE_@J3Y! z`B<wdUd9SXjTLR`QGvI9;jZ5D(-IIr>J;S-W#20y{W2nJn=pACYe?{Ka`=a^*088g zCT>lCn==SHTTA$zR1TMt_E$2PT0@#naOF7H<2}iAt*)oNav~-I8Ms$U9N#4lvmLJF z?V@Z&Z9gpd$+!uE4a|xwPpsEcl?8+5WxhW+M$`cyX7a~IgdH}~WK0A{oTt2nc8Qx# zv^>8O$uRG*3L>>`U&cHqz9llpGa3qcaWb(5g)zbziJ(l7pqe0$SmQpSt}Ddi5p~{{ z^ysnGw8WP9xc}JGsl%+P0!>7e4j30ywE+tJhbrdgZkv|+m930DmS)K8_BpCF^1xwn zl-qoYIFtEm`+6ZhBhY-N7e}_?Z=Z}}t!w_9X`WhaDHWG-%^{f=F=jv!3-wL6l#fjB z<7D2&l~ky$HXDG3ahL4iTqD%cnM6f&{9(ytea~H0L*qq(km3o#X?c#IbxYNHb00GV z*-Ri2W-a3WYTbI$?H8wJF)e@&Tr$%=<BL<nscXJaCToyjGmX~Zy{iXhpwS2Pcku5U zL3V@4Y={B)T^thk;ZH*H&~#HcqalOX1+~rD_n(2@nNy%d+7K*+BH4iPDP+59A+|=X z<8X)%)vBLtN18}-nSn~2LL4m#P7*W!MX*g!5;3nY_mbfPbR=4xQh25X%~&__>dhm& zd$sfhmq>G|NDk!Pe`iO2**NMB)=|T|#qc;ss(#LQ{N1Z^|2;zeT_T`|&uFN>n2FC( zYFJI-8w52=H)x~OHFER7)*06GQCAUMahJ_#0+yuv7a79th@sOx-XH!{^x>O2tmJ*` z-M&JZ|B5*Cf{5U}usLq*y^uuLd>&KGglN6`1z{m}2`^d*7KotB7_K8;(dU0mi!P+u z0|4#=UHW3U8}bZ#yenRNy6eFQYqAJUAGFI}j@)W-bA8(7(JG?+?N}gaBi&~+D~Y}O zhhM~zeTr%MA0zL2Jp<?}eEUM<=g^<)=Gg9u6<+7ipqtxEDZCeEcrCJ;t?-w$Wh61< zjYr@&CBvlq=tclQ#p61_k)(U5^Rrw>p7q<{q!QPT5Au-|Apg@SIzQ)QLM5|$W>(CA zrpP(NU;^;K_xIH+T0cn<Clb}MZ0}9w$`ZiBkXTD?0#iQb77K7m3B);LxWi=N3!!qL z8QOqnPah_Llr@sa_({mRfhk3<Dro&}(g8zmh3Q<MW0LstXF3z1B6lv_rVpOREbTlr z)uT(%%l0GNfWtbJSHVJ007OHdit5PvbC;X&fnjRo+a}B`UAvX4pd@xA3teAQl}3;u z(U9r|WCX;e2ddtI=0<i#3iNCmmjwv~(vvL-wDW?HcD08JTp5)Gb=;&|MshX~+he;U zVX%+lrZl7zn|cOVTWll^^cUl*?~`0;5ad@)yT{pskSMn;udb+ZY)|v0|JhY-fbA8r z+raRFv{WCs^$LH~QQ7R59<GcH49}_NjWpnr0YlcT%VKWv&ZLxqP)4-wC_SfTwM)<` zq25zbH=3t8^ei)cFZotas1c&1+pQlL{ec+k#5DGTwFo?TAh$I^kLAm1_j%koc+kvf z;)<SDhk3O>ytD*6QU9|f$zasrOJXQ28;;K2C9D{s<bQYOBc=u-o+fg%v`?l939$vG z3CZ_)=A(;b%ph{Q8tz;FKf2t1I{%#%YVWVi?kKIgRmAKqF<0Js$EH>VA(wx|EPml* z_?eHU3*Taco3tI1$f<oBTj-lfKoT}A;9b~-59p4NOCRh59U;eFVv9Na>`NTsU@CT& zog}g&?Ch(o?JYFSP5`!0*yZOiewIDoGwna?2FHKH#s8eH2)X!$hY)h=&~oG@%CgRU z1da|6vTxxB-i00fCTeme9QeXaA!ftDPmyb@(4J*5pVJVs^8_nVvgIM}5dWV3$9npP z;;TCNnG!Aqyuk!L!df)W5OVb4W!nop>TszcX5ad~47`JlPZ&eY;s-ru;fC#fkuBu8 zIP?<pFl2?B>KA|{L}KNqhg}=*xVGh`yDJ#<0Z$6ldrouzt^G8xR*1*~p43vvv3M;8 zgPLU*Xz&=J!kA>d9WBl?1rmM2&hLg=j&$pT$>00384E51i4BLDog>@uo$dlCv!N&; zWYi)gTDfGyhT`2_5Z)rigFc^$6ew-!ZNv)ixSl$Obi3y=69^ml6W*dY#}gj)Jh}j5 z-h4oNu6j?R5H*pS>;*1Jn!uE%Wn<kXxJL#w4QycD4aIIK;xql{8}SR{qcGmJ)6kq! z!^`oX!NXseFau^ctoIl#^jKUe5%m+wGkn4T$`UlDcMVUbRw=_$o>MYl;2jDos~{!0 zxNGmL!e20`EahhsI+$CQ*>Y24@~P86Q^FM*TWpLiF1xAW?cl7i{?~{!o6Vj!P4LW0 zpJj8&u?p1Kxva(rCVfb4WTV})6PQ%IW+7=+G701|Hwnc;G&Sh<=71tYlo}tq>U6*< zvCV)KeI9H5uU@1xnuQoI`r!Mm_!$3p!!b0`0oqcKac&>TpQo{C&&rof&OyVMp!4@z z`<ErNb-g>=CYpYqr%CDjxJDWj@BHhuF{A|(K2PXov{S~CswC>h?MDqA_>;`BcGM)D z)~DRWfw6OnS>B|$gD<B3wv3<dC}2$qHQc|YIR!x3ass8qyc$kmfm1}HFwGY2LE_9y zs*0M-h@BLJIX%F&ktpng<=7ek0)d4%879T{zR(Y1D(hYc{$VW8Q20W^P@(nT`jqJW z-td3!l<&ANNNM7n$Z=W{vj9t)p4M*}kYxeAFc)OOL;ZZbFou74Fp@)6^$mKe5-C8y zZ|JRaijbd|dp>7O$UKQODKHmz(VH>9d|R-tWUK+ICzByvt+s+15f^`38Z)TF;jK=K zxJ&b%gSX_(2V)ODo>>gXd0kNl?jWhRmt3vNIP)sBt(^Gzwpp^KU8uET8Ry%PX&@29 zC3TmY)(FM2;=r|M4qKLE{_6~?JQrHArqTKwjA2Cw3~DU3t(m4_POwrt$b{v<U$7>g z?+ofNuUMDm<R|r#uM5iz>I?E=(6Tb4GA7V@Gi;pjz8u)HbUc7A=a(t@C97nC36^Y< zud~9NHjj+rF0lCWk4wW$LMeCSuS-#N+R^tEsIL<sb~wA5r_Cg&6v|DaxJjb_g)Xyf z_qSqB85SeiBKK{RB_us<28JH8-9(-6llsNPuOn~a?b}i^Mjc(}5vu+^*w4|Otmd7Z zT~2+yI!6%(nigY?a>%Q#WgGXD?`y4OXsMFuh9H`aG&n!uz4FT*KEnX}Aq=k#I$@5i zZU7P`+P34rrlh&BNfN8SG#xy}8(n7p(8r(^)_M=bTkMzsiO`na%FS8sa46#2yI>eq zd=;V7Co+&&c{TrDwJ6Z?Z-|RmHP7H|f(+Z%C!UbRnfWCdEPp-wq14u;MV^puTuo}z zA%d^;cE%_gUk^%uaZ*$2K@!H{4O>ng7~D87#-7&D2Xjb5LNR9`^c}H9oob!Yqo1SZ z{$V5<0DF({>LtbXWK!>%GrXFK;*;qT+abSCbYQlhMVmpW3C1_>Kw87*n~@@a<Ec=r z<`cDN(@vh`KagCgy?Y0|+*Kr6E}6GR6>)AfW8q3|ba1gJQw}a=s+XBT{YN=cD7WBw zoZMoxry|*`Bf`n9i$fMC!*=R^t}6PpA%4%-I(!sdtG4Ym7||z1VmGisEf``*vI(Y| zC>Fn@k*`lff5Ypwzj&JE8Lg>e>45jWx8NDQXt2$w6*&nYQZ3dSmHW0JG#(XWl!P&* zI%vH}CWgt&fr)OA;c9k)(Bd}m4u}!dsqH0;;{Vm6GOv6qd<jG9JEu)b99NR6h=dZ% znjmhrcZ+}Wx*ZeVAEj2>DZEzECg;SjeF<f*x1xunKPW>z`|nmM4J&ZLS62y~z>QT2 zoQ@pv*=^ZYam{E6lq~oMgC*eq6$Z~3EI@Lrf`1I)xGjK!!5A!n;A?;}Lct7J7t`!( zfMdi*aQi)Ay8c**H}Vs~0vTJ(1A)OB{ErY=^ZWnw{|sw6V6c07tO063tG(#647U$0 z$pkrs1xB2!JK~1vV_lsHssbhp_Qwm1w$yVa%xr}Bnqkxq;8+JuYZjjUZ#17fhfN6% z2jRFQW{yH-KRFBIl<<9(n|IYrKsK(ZHZNgTCTIgADWJ<R_nNV9G$-$*kxE3D0GZOm zxLgyTR0>HLunf&rI18MELi59NV#uHyMoAb#a6?Bpjd?@@9N8WtA2b)1+2A-GiwO_S zonzbJI2TG3eXV)KV^(UK$O$f<8KfJ`CQ*<x;_$vhP|lDJA^4P;!<w}Q+N=?6Rf`s= z5oL&$pg_FUC6Z7BQz))TH8=h#2U80QEQ&rjPVW76xiiI0@eK#eM^!zz=PfQwhrKN> zlcDEuXgYkmqQXm=3sn_?#tL)p`ZAdL{BB+q0kxu|UM9h*!BuUJusMwiEfx2Su$Q7s z)d*;}5<Q<)2rcGgx+=7<!Hp4_^=3zt--x9#Y{ucGmrz#W4jR&9iWl_ZrC$6{4cFN3 zcZ0=`7#pqGp3P=1Rt`rbI9nTgq`rO|GZv!ru%(?l{R4H4*EAN(M|PEJrx5RV*Be%i z(~A{Ovp|J(*V@X^y~RCAtkZO}2_^6XhbgIHyDUaYHKT(8Cb9-4X+SYF$AB8HxRho| zb~cAjeI~5ZB1!DW7=Y@<ezuCU-AclW)C`3X5>g69G7OlE#PR?!h9pwU@wcLlEEqA{ z7<BH<4qVMavL`1>qAuHO%87{uJM~kddT%ActIE)){P^z|h_k&cAGfxH^N3YF&);YU zmIg!ySp*hCuUt}#g`SzFbf#gYl&MtgnU3(zr35PXj_Ni*b{9R0o#4gxap9_%vl$ny zT~52qVA!UEl-#YXQkrZ^^#SJUIVC(s@vt5pITf9;{-}YN4UGLP)XE;n_$LE6{@ZXu zYEQ1;L>xwyrwWLuV`&1%0A5sF;3BGw!&Z`U@B%8v^^7hHkpd3*ng(@i?1BL@%c-&b z^VM_a{->vssKCBHH5MZ9N$4lQDOYd}$3^()w7@8CQKh6!pjUP&4|1?4cIGA(Qs`S^ z59b2`qvnPh9{YP1WLjp<?;7k;4YAm~9e1JU+9<}j(Y^lXJV=2bZK>U7NoDsDD|SkS z3fB(4Q>@eOBswHTbDpXN{%EX23Im<^gCAH&mqufxKiPNUk3OM!<QZE%+FR5!=F~8C zHFB64GfL)**LqMBs0XtKhVO=v&7;%Bc9h)fpmn8imM9AT!QKEa2z15MgD=Vn<u`6q zMw4Ikwn6%m(=AflDC0UN*HA-)t$Q{^Wl!^s<*g4+)5L9mgoxYU%kYFaSf)>om`Uxo z177uLBDqHDF?5Rv&8xDXXsFWPkOms;h@C7oFUu>v{Cp!P&n_8xqhGQ+`-%)px*j|( zVQZcjcMO$vM;-2HsOKP<64LOLi3ALEW+oOF#80XTg%Mo?0%0~mUOFb5_iBO?Otl6d znt#V@qjqSLT<zT<k&p{H1YXUw2<k4NI*!<7v36VZTi)({Z@0UzKk2*K;!&bW`L*aC z9xPtr!dc4&zuz|-`X0D(cB<m)Pz@lTnhE`+{BgC2>XGb_Cm>^*wyLvL7t4XKuR~mp zR|NlT!!@WQW{ie=mp29@ht`XWmv`P}UHIY`f_emVkX&+fnvGGzbvooRu;hGe-)+N& ziMD=ixxzTZS5vnTR`*HcI6(D=LI$U*SynjM@B*<%cQ_42{_5qoX`#@&1){611F`7= znP%YyUXJW|B1&2a=O{wRO)JJBD}x`3G_vDOFBX#015<^gSs<srZA^>yV<czlXsEV1 z<aa{Cr6lWkHkUY0%x*2Uw85>P-1M|K8qoE&&|yo&wERfb_O|2-c_uf9OlBkh&1hl^ z6}-VYn$10)?YIrySXm%1&?*I$%B?S%$Eu+2LSFTXE(T}`cW67-a1OPkUwRf(Ol**C zwzR+el!8|*^|ZrPuZ^_-$FZo8eXo%-qado1F!)-8Y9xGMF*o$zm)Lek(qHjmbY2A2 zP29(z7|C3CPLE>P`vZ;afe)<}is{p!N`=sNKr>-$2k4R^CEUVl7cSv|8q%<Lp<x)! znb7$K?o8OgG^sXfX&0n5GF1vtazo5&h^AO02XoT=an~tLbbuF&+Y!$pgdQ`^Ic%R6 z<J*)|u!eRwsFeo{S;_+tqx-dZ;^&GmVW3gR%pu59a`LQu2H@sn-KjVQ7khEU&(OY@ z%+IvI|9e$fAy396>`}ofw8mw3j3WEv;1psLhWXR6Gzb%S{mz3}Gz>716oHU#LY<W@ zfApy78$POpz@%;({q(A(g+beMP<|mc7aF-It!ue{Ot;@F654H1RRaj-pNplx?H%1& zbYK1)+qYg)BZDT3m#fCfKM*1?>h1w)UkWJ`DKG||{*f-&n^A>?X#L~>hbUO>LV&6* z+=4~1Idy<T5i&O+MA@=Y&Ji#KKI)m&irDH8Rk&k`yUtfYpxj9KlMlr4_Q+rg>GQ>z ze$e^u9!e1r0vJUG3ahyXRoJCQ8HuG`!&Cgb6o9Fkk09D{mtTJi3>8qgs|C$U!A7K| zb_M#4i?x>BVRPK!9JLAcU|j@rB!U*$E}7EAOqljD>O6ysEDg&7rjEu#>MCE`@<UiB z8OWZ;w&6;nS-c<E7vltsb6T^7d5vX^xt9^ntVsOm`=hg&=!(q6k(`=C*RDv@enjMT z_?I1rT-!l8jr1!-EYY@OuavNh$GoQfTH^7aTdUhH;_IBx%!7RfSU;0?!@T`raUB_3 z)CSl@H{1-BLH!|qTY8tC3?3Go3|ZY_v<H*tcG%7+_LYD{y|U1LoB*F$lUc=b&5U8W zEgbG=tueUU*l-nd5C}!IA1WB+Ql?Sp)zjoq+m*>bpe(q7_r6`9KNb<uWH{NtWPvJr zHhKeR{IZB18CCt#w4Vw8o&>tB&O^1j;Yj`9%k(-&GxT?8;}y#OtInH>N_F7fWh;tJ zD$ePR_|x@(bie>}w(>6&^HmmS*XObCk7IS+l#!RQLMI061p!WCJ=~^}5$=M*UZDFH zv}gL?+l2N}J2~8RcZ7?8M>xyDoj}hg5!~CJ{|eG)=>#fU@3t7veK7w<<|)Viab;+g zlt4-?ws@jgD^V1J9P14a`-PpMd!O{FZL+da)lx3wxq5%4pLue}x&CK%V}_rt`^Wz+ zo=mVO{*QM8TnT?#sq}>m#INHu?cyH$PSTea-)!pNi(MW<zZ(u7b0J-{{3#;EXaP?% zYhEUVNOW|vi?>l|z{RcBip9|_L(nDa{HuHjC6hfC=%kQg&}yYq2Vj!Ce`v40e=q%k zqrR?|MpWK>X=r0Hdh2g}LmuhQ^z*k(=DQ!;fK=izz2D=v&EEHAVQls7g^M`x!9d@* z+j-I2{IS<pr`V*QEwgZoO=AYEPYYW?-22|4TB>Gk(YB158Fg%KN3!&PR2!qp7(RMA zahC?LYh$%)P9n@@5SO|B-)^M8^-sr`iY>Dw4O(x+JW)l?EB^4IOi)Oa49hSs{|qKw zon<nJF|z{9&{W5kh^wjyA@vK>kl`pkmn2aX%xQdz$JzAVg7=?P8Uvhbw8Eh;7w>}p zvc2|Nbaez(Qm;Y%L#0sano9wf<O(m2@0A$20jJ72gaw316UO6_Rr!r$seq0JmQfD7 zEF-Itipz+t6k^Y@wFpF#>IdTOC55n=83aa%VpiL<;8l{%XoP}iz-va2su^CI$)|u! zP+M(6Emxk&bj^`f24m#c4607sIY*>Ieh4tL?u*uC=PG$;Ca`3@%LsC~epHH&bRXEr zF9XZFE@%@{X^Qx<scIWm_86j)sZ!YZm(gotwpQWHE9S^9Ut3oqfb>6s=UM4DTM5lB zMG8q-c7wnx(bga`>yu2mmV_?IgbG>CVu*ioc^0q~mj_doFn)nXiwP?>T}Nm7j<V*j z#fc})E2_a#yh7IiA5*QeE7bu%YfR2d)eqGGi#mYzIIcH?rHBZ5*Ncb@K8W2Y>`(~9 z6m=(VDtZzNaFt#WsL|Q8Oafwh`H~*QP84>^Eo2<uLetot@)SIYU#F<-K^u$BVw5H_ zE3pHt7&Mm=+s2F}2#T!eOej^P9KC76K$+@JgyzJYZ)SZe`hot%HesWnIjKTJcYLFw zfoQroL&`d0dNbb$(#2R=sHH#tS<bLO+w<BV<F(@QtT!<-h_mzMA-b_<i?b$_69y}1 z11<VkGT_9dAs==c<k2($3(*RKlsT7Qa3fmqft(ILnOgCo6m-ddmx|+XjK#$Z!>>81 zk}h~#VA+i-cuA!0sf5@g!!aZT!nVQZ{KBRFPU-Q}lj1*A3k<kNdGf`$T8{qP88jdL z*J83l+`9!xB|zW<o|g|*2l3o-vt|;^xPQ{TxN{*#7+kIMyz~+tTgR@NCdoD&2J%=v z0g(3x#$%R>EF$Lp^|+}Z$~=^l9}YQ0^KMVgX)N_@T8@4SC5skEpw$>dBhS&&QZWJ2 z$YBRV2Ehgylo>!Y4w^`+Ax)L?^H8$h1RG?@c&<5HIixp1y9(4}4i8tFHS;Gz6Y1-# zb9A^xB%kcGYOSy0u>8N7jQDF}O486pbQ&Xio~Q5kQ1;KzKne>2YMNL-Y{h&n6L<xE zDT}+I^z*qraUwKGK3xZc4`QY_!y^}iJ7$s%VNt6@MD3|Pb1Y9GAH9+cZ^k#(q`hBW zj=q=L!sG47zPbnb={4irf%zn(eQ9Qlq^twV4hp{`u%=v?Fxi`*;rjj=2c0n?Q8<qy zh_eklDLG2ku5*sIPE5G9i<OQhl<g)~hF;JvOXseYRm99s1Lw<%VZ3((Bi}!=|Gss` z5Srx}MiP|gA#}>YB}iTgmx6I`1oQ+mI;#zK3PJSrBXJDO94pW4SkCdf&oF9Pw<M|C z0jgx%!YK7DImV_7cN+Z{#a+-4VUjK|7^GiTf2zE}@V=mevh{s+1Otw^!Q@DAthlrL z?TF42SHP7_4)FfqBV7)<y(PftjfmU(O%RM7O_vw61H8L3F@t%MtJ2ldpT4(daMHj? z9vG3;s!M%aO&1g(idY@J<fewr$dFHkn`{#3%eVPVrKh2gTT+8$Qr%P?N|GlyZ`E8{ z(e;!k*MVY7<ZG5$WLxjXXMLtvy3gC!`Z4rFF<2OjXA-hDJzO?Knkn%%!zIT&Y;;i% z?q`i$94tQZY8~?dWB%`tW#`ln>TD{x{xh~0Ni-qCIq9%TIx7Tv(<>pxX{L||wuC-J z1lwwEt=#-DMVmFN7FphW_p!M3`Q4046coF~S+da+eec9-RWCnKT9QAzRU~Up26BQg zHY*!33NB^0<uiUo=qi=<k1soFtn2H~Yp8ai?pvo=KYe_R7B?bhu{pGMp&3z0SE&~> zo{0XoU3*iq)5<VD1GY&qC&m_F<KgkseUEm~4g;?#$&PM$^8Ks>dqH$m`281;xrsoS z$U?lY4bVNgB$P(3+0G_c2{e`SS*)6k*)z%b++E0<tzWplBFF?qylK9ew{bR$WcnXc zwzHLO-JWD7jSMw0Cv@#v@!YdFhZe_34i$vTLOrj!`Pl@88GyBaOTUz~$zFI72AWnL z37Q{V+Fpj9WaycbYebm-_0Rt}k}!!W@~1Z<v}JcF$l%-RjlsAl$n66k<(O4BY%jrE zl9*UadlX?45ZB{9pJ_-ch0hgE6gZcFI(DHLlkqOV0kqK-#ym<zapASRYzpA-7N|?W zREr(Jw+zrbhCvlWUKSS^mC}jvZi2Y^nYq|^a7}x-4i^|!@w_Om^(c(R1uM_>kSg*e zC0tiJ@XX`}F9aR%6s**~?nmvVeZ*Z7H+2j!V)D}1nE}vs3%p6z!gqsJjoN44w0A*{ z^C}@^2JCp%5E-FF#Q`9iNd>)9T?ixb8=%k@1y*^|hjWfJVE2-tn|65pf!)CDdM99O z3Zw}EwrB=JvTBW=)8c5Skd^y;m8fC?X#fZBPF1kw#0-j~V|Q<-SzuFccT_3dc3x6P zkYy8x{f=427w-WI3d%0%N&GrJB;y6;3RH!Umq?+)`$(l1yEhR*S2Z#y%TaRQ4u^n+ zY59*ze35~RfpvJ5b3+h%{1Eg@;41JAJ9+G7k8v*QTA`BI31PG2Cf(4Qix-t7n3QOE zd>@DG7Z&9Vc(>M16f1R^lt~*G^zz@GuI19@pad*7h@&0Z(RNQ<Kx22kFtldUOURb; zo)&ax+z>M@xQbO^!(x;et$dcX{XV^N{O+Nit}O=QlY%^U54U_)R3Er^OI~LeI5%X# z@He3t73oZ^5QyLuE->sJ0plh{A>)rhptOG{lHYbX*R~P#%o+aB4dJW?`3^!c4oj>x zxVoErSJQ%h{i5}EXq;<x>Km;i3ZFNwSoHY<^lcIWXEa*${O{&2#~4(KB?gpC5nBr^ zX1H5quO-I{!&Y2)!UV%Rgy-N1DJw+f7ibQ{+b<VoPc(@%n<}uTR82v4O~MIwBU+X# zqMEmVO(z4TdPq*QY|?v}a%cyie*t6pib~*2f}f4rkeK+8m-=4OFzDq%csOLTn096c zcL)}l+YLIZ&3h6jbL*OhwNw#2j3Mio7C4q~!2A?4+xZu#5`*v=N`F_wUBy2Wf{wX@ z@L7rL`2lpkqlIugg1d~v@#f^Yr|JE2@_FX5?o;MdMqCzxftHo7*W?p~{R?B1-=u0D z5vdNAa6gg)l#yh|jxi1Npq2`iTiJ#bF*n$iBNaHDILz9Wbc9RMvqfE%+$87t0ziwG zH2rd>vam@DzBtDK2zk83X&Kh#L1MTS5zgV0MTlVrm3ih3PpGi02~UOVI6Q0Zcg$>G znXqi{g+ZUT6M><c5n?1<HItJGhAXvXjXJp3iAzU}(jYCg2}GUg`RK27dhf?C+|G60 zx6gyv=g-w!joZWG&SsJCHGN-g(bMv5G&=swH#$AsEZmv0wfob-NEZItVl_ZDvsSOy z!_nKj%iH=!?EYY6{S*Cm_v%)sWVL|RE3w#-LE8QFJiGOGipckw{LAPI$Dc6I*FM)@ z3_PKX_MXNvTwn2*+Q-SfE@$7_C&Nts`Dzv2^Od9r+Lv|&MHqj-mflQK$@BZ70}X8B zcH>$#;e$Iwwr@$Tq0brHyGnfn-^7o8T;jc+zEZh6;=~=xGrLE)OC))t<Eb|I?uL{X zsVrj1tW)cS1JdtN|DtHQ?CP`TzfX`0X)6{f?ES>OI%4-N=)G13)~f!yE$H+?$8uOT zdP%@dx9EzQVyi8ALcdHk-w4TVN&0SnvhH*Yyw{*poP+1mEXXmn2h?^UAu#@@QM0Hy z@xQ7Wm;<kq+LI3VJ@`9smJE*^ZxrH7eJiDp9b)(KVzavkmg)`u89n<O(!#eOh&k+e zyCf4=R8VF=KD``yx;`!Gq;u!mP?#LZik*3EBg<QPqKxZa^sLSI-x$O&$&^Mw^uIhp z{&e)z2!)oUE?Tk}`X1kVD$xgW2vXJXx8KtIFNt?w?e$W$#IIqBjh09=(#_cPFehjB zL|@h@&J%XtWL5OG<k<Sw{NmQOC;Q2e%-5u9PENxmT3)CmT4%d&`?YMcEudA*COvtl zvB6mcJ&Ov|_OS~4`)y(Sx>+fGJX^C3ac;3Y9R9Vs9+CX34pbx5`i~4NUqLuM$2!`G zo*=ko5REQws5Iz27bJOi0JU7tbwpY;eF?WQ__DGH$6MqNe&KOoZAb?_GMWg@H+oI8 z(xPd>mvkDX+@jzg`GseOx1+f}a%j-`|A(r3jIkx^+J)V=-Mekuwr$(CZQHhObGL1q zyKU?1=Xt-J^PWFzjbv6<rIK1n%~|uh$BD#6+yHkE5c4;0WYF%MrpG=r44PE7IpWz* zcp*SPeg)BRA_<zKKO_0ad1ErbM|c0{HQbp)llk!~9o<ze9o^{R!Tkd604?2S8i!v0 zamn)Lv58Mf-uv*esKdEB@UTWlRvPr)kn>wl$pgwYO%Crh&3MS)wW;jCE@?*DnAbD` zpN3miupKi@xTiTKHkrb@{8+OiZmHT%yFxn}jO~#Rpn4jH&dK2zw$!N6U9smeB@f}Y z)L5Uz!~wjvR1U5{;1W5+HJP<S4@2;6DVIqjy`xDdh&XgFE=m@U9!h8BTgr(SOw@(* z!L*WO)241IN6w$#b(9xn851%j67S42PP`nHtAla}r3(r@70$TRGA2IrVNnzJg$tOp zl)uI73<#gLG8}r!Uy);_wejCidj-gZ;n1iFF;9hYX)z(xKIwzp^gzwAlu0m00->H| zo3LVXHcZ)z=q@n<+0WGCo^T&M`CGO0PGnbys4GHH+}kusxUbUA^~OxVhYl=K)ejw= zQBS^+6srNGf6xm%NgcVhzwfCq<%1?D635fpU5#yd30d=u(Tl>GN%e2^Xc-shzBxtB zcv-D<z@k`qQk}REHZE49+}oZnm*n~kzjEQjR%kC|f8J*F-W$*@`EX45%I-FP-a94` z%H}z9-=K)*;3RC~;{+~eor;ygCUDgxmsD!Vo;>s)_d`8N@gq)d3B*@))$@RLfv*5^ z+y)wXf|T&AQ2z<1o4p(Eytoyc)|gqaUOUu(zS-D+?aZ>oSAWEsT%E`AG+Ork;_>tv z7p+|v?9tk`?~Ek}3zphA@m;@58cV)7*M==t!=CQ-<ge>C-i6Xr2&(}R1j7CNXM~2c zjTb*}bnpjOC_mF5ZzNHQ%%O2qPT8iiG;@pl(M365K@6GaOFbgkua~@u#U_BObj>K8 z%@)|vKXIhjW7!y?V6P;23DLr=ZoJvGXXS5WwO<bOvXj^E7_edBEK>~(4bIIgsZ5P5 zU#Qnvet2E9p0<U0&R$3DXa`NP46UT*)!xz8lI0Oud^l&wUcr7Az3?thmB3iYOJn6M znfaLcv2PF7gb?_g3}_%NcvC+pSwyfGA6I?#`GS+eNQ1<UQZc6S>A^MUzS&^rus!Q4 zy!|(QKX+m)|H_8q;6J6P6|VFMB9_Tm$dX+D;;pQ@_kTuccu4e!^+vNhVWB~EzshpK z2s*FyEm=Jnu`*c7u#3P!$^H;p=}sZ-##|~fK}Id~WccauF7)}r8R3@pT*PXZ@v;#- z)N5Pa155$4u}r;Zfv+&s$BGSe!a!cI=jQh0Tw8cFoPn*H^KM51W9Xf3Ggc4+zrzh2 z*ZgJ9(~ObfZ@o|JKI`1l*@A`H<iWC?wqe~~bqVym*cQ2X1i*8Gq@_qF8lQXofgm|* zBDWkHb>B}gbV8=Cv<z3?vV(WN^cv?R{lK?aTm|Qoo!CF)8xe1#`!`zG7uqsOmSf>g zBG&5coyN03ilO1X4a)$Vh`^yll%=^78fm3lEx@M5!osSe?UIJFO<zw`XqE6-g+IJ( zsiy)Td6D1FY9i;e+Jck57oq+*<^$2t#3Q!<_EI~;oV#|%HkO^&H&xM>e+I28z}Zzf z?YIkV_S!kJDtpW1IDg9v_185_#$^GPcp<=p8};NaWO61**!u>lK|^v#rmupA#1I=! zfW%M<d^x#QxFsGu;uVniV5<Fojo8pExE=jg-3fb06Zc5ns_zY&cMYt9-IGz#A^K>0 zgP26nVg1`-YzX+{^>S?#AKi@z9es%LcT!{Vrv{_S2kC=Npjp=5dCmdzMfhic@4M)` zvHHz9M|6D3ioV_N69$1m8PsuPabri$Xow$)@6o{=xeCzKodbTV<i)u)Hi_I6?lta< zJo0n^siA!^ur7|dXAPK->Cflhmp|HmSYY}1Ev8@X7BGtP&wSV2Z<K^*A8TCYUU0hU znZu|$$JQP&FNNvwq2x=OIyR|MUTrsK;*UBJb<eVfGGss%&*LJBi<B%k2p}Be<VG~c z<brjPP)qTwR#u~=jb!EkNTo~yp>J(K3q{!LSd78O(jLakSThB3Kh%v*7Gw2x1n83u z!<5dVaPcbu5TaAAUcE3gx$^v>Qn_`6Aj=b-r0tfybp;<2$n4Zf(}TvFvK_pZ-`1aw zZ+5It26Ibbt9NdV#r$fQ%4#0}z^7sp=Q0RghAa!cjrC#w0V*PGD2q`+#!iO8GcY&j zc=-691o*jcw%zPp-;mxMZ}xE!wPG$HY%NP41TtuGSP#w2hLx5vTg96|ExZHrtL7EY zKchQ1UBH>&E-AHVe3y_3DqMGlH<=^U2`zPUR4>_|e`HyvrARQAjYon4?IUk6&!S5l z<e(ra#fYV0lxBlPqdV&7%3MtjB*S$=1E`bb5aeB(vp@3c%Y1?lp~l&+LiwwFSj0L- zni24^SVkTC*qKuGC)oXlIeA1hCq|$fle7w=NFr#JVDYa0MA#HTAF59q>(;mcUjJjL zrK-JPA5SyDBDM-8(3DeP6j`Ru|Cnbno%+tsnQRINnW7gIlcrsrd_XA>1i;(TVn0XP z-%rv{ee3_9{h7-3IP#2VY*N)<*ELCtPm#n_h-`en*&1<)i%U{pZf)YLWLDE>z%q!( z&S~Ar!JB5@6wgc)mlu30jiSqEbawrb@-{Mkjd06nU7u&@Ji-++x3U)g`?J6j)U*V- zo@J~SOBLj?wQ3ec@C^#tgl8Z*@_(i&NTe{(YP0A}M_(9~dKi5{?-H8IQ`*m|7b15j z`c<1Ua2<@+`Bx+O{gr4iLj`y@^U3!bB*6@YixZdnMJB4OZYVW(az=aE#HxmGLY8tA zx!r#OZ)7VI5`Vez?d222{B^u@g%8XERU^+3P7H8m15vsg95cKW@`hTIdBhMdUe*$e zGXz1SWL=<p?X;7g=Rk!shPP(P;t@Rple__A9qrgS`Ekh1Sj3Qo7CTF(fkDM$BPJvO z#$ceNcn1)J$E3)=JUpBq<~gOGM`dj~bx|gc`_jkYM|#37gup)ufo)*Xg(HM+H0k+D zWF;!BRGH<j`9(B}tl7gmj01{m0dmG!(aHCE61gLn3aN8~wNOD%m_F8VQQhc=5t2L5 z0ld<sQVxb6Tr##`gOWrsxqWb7ui5nVN1us9cti<YYQ!KA7W77ilyk+XhYkN!>*f%x z2e!4NFn8Y!Ft(wT>D7^XrWsHUwXT5Zrj>K0q3CbNjSq=)I|Ee6H%*K0tPf4LWPQ5! z30wr35dbs2hBl&iVscMEtNC;KP3MkAOJg0_Fn<vMghwra2MP`$QUA$5^V4n+<D+V` zgXU3MGDI^bKr+iQ@&0w$Zpe(3es9IB6#vM3pirC{Nn_spCPsnwMvBS}(M1_j68su# z#qQ?4DT$Vj7t$o89JKXn>l6)^GlRbx5)s=t<71TQHs8m8rapCduM3jAU58sNP@0FP zNOpXuA*f1dnG)24mSk296j1kJqB#V}B9$@cgmGAT+vyDVhmMoG^$ms_jYUeGnx)sw z_X$KTMp}z`rC7n09N?<;*or-{#2*5C6!Lw#NygjOIWK5BZCv;z6RXEq6b&s@T2_9) zHV0eDN}eSfPV^~f47#>&7_SG~ts`Sb(2#7{vo@knWCEB)%y$?()`u^WT%4=8&IXd9 zSr#->yo?L&TF_-Ml*m}Y`ztq)OVe9uo-(Rw=G~jB{_b|~4~`%4j$#L)&-7ae=<Ofn za|tRrrF?fHqKIVLi25ng|EpeeF=EY5ajq+DqY#h8Im5fUn&)OIQFQ4zx;%uT_K$d> z1oSn`^tt3S8bY#T-`drmFoIoR;86L~xmgoRkmOF^h>ya;aCJ>SL2p8d=!=v7b#Zw) zI2YoAg0=!!P1Wl8BH%w0uCiGtprrc4%#wfuI5Y>K!(%4J;W?Q6jUjwsO(Uii?LB(g zhH2_s-vA0WpoMvp!@ea+OHIh)eq%f~8_3DPO`&UZO)7M1I6dszUf9iFu%<hY(Xd2+ zeZ6X6*=k}x^q%{OBu4&6RlpxZ4m*nCpBtqJRFN+PJOfR;d_xgeQce3<IsyEBcz*~s zV20_$oMWrzSp%%93d~DNtC0pM(Sq0%l!<lhT+8;9p*mIuv_+=1O6*_ScjfHS!)J%h zVug;{q>DG4KOHs|XR2+YaL$G}kuI&Yi|0`h5;v5Lz_w!dC*qzA@fGw4Mr}4}mQ__z z-UyA0{pa!yF2Xyin6a>HE<moh7jUDoa}wRG3<!y2pofkC<gA_D>xqic9(b?zjP}RL z*}C}kYunrR?L-;(y48{W&+`3-wq-qC2S)g16S_-oX&O#RHpjs0wlqmf4DDS+V>shW zZj8|EB#DzCk`W`~mJX8=4Ov$5Q3buM>GYgS1FpqaOCu4$WngGO3JVPBf>;+eNeBA# zWRmEf)IH5nS{R_m;Wl>%5`r%-CQJr95{;l<sgRjuYfR}TW?jC7yH8+Ch{KJX+y`U} zIMO@di8s_uLT|Q%^?MGaVEZ&7GegWTEdU08XjwspX+4eo{bMh%5yBx%7-CYf1__=# z2tWXc4T^-o3H+~(2jvKIk24?z)XGybWp5RqfdtqB`-PQRX~O_$m#xpdm<_ZOnD<9* z33$Sbk#Vf2*XMsTfNl+V8Hg3dTNj8(^-h4Rn89;gf(C#w&m$5gDmEifuo4>yOvp-s zxEfkfEHPUFM^shouPeK?+&NT|P&8PRTJwifwK;Wq8n&PTTz6xEYr2f?-oqQzvapf< z<;8adJ3D(u7B(?Dx}lEspfo=s9w8WRl(Ok~`4@w_2{3NaEGx9@;JJd<IKo#m%B8O! zq)(42&p`PUH)RKQoDxO(tA}Gctx1xdW=+{Na30@b6f+pTbmNl2AVOhB86|9<_}irN z*alnED^gX{na6SahBR|MrLjYkyeE$eXT7&)Y8M20{lPcoTm8d<PbotwlAu$~#<7ON zMA)(Kks~Q4m9_1UXROZbar4vpob)(N<|mq{?jsqOs^*Jb3=vi6i)W7GAPQ|x8wg2{ zE+Bz8#SOw<`;U7_qq?yfSb&5gvXpQ2-{{Y`&rO`$>Nla>X2w@EKrby*yJgH4ZQVC9 z?)I41=f~xQ92d?;we05!_qn5W752w8o<o~aT-8HvQAA&QnNF;o+Nhp2hof*~ZS(&a zGmoJ|yqw-r{7jGU++iK;uLhpn^E!q$%_GY{@Dr!W?^Z6Ua}y$WG)1@Gz0<p*%o)hN ztoC=qsHVZ{6Z2xJo7`=Yy6j1`RH>cQ({ZWG@<TmNgQ${la1oX`Tt(F7%eXOn3^hRW zos;^Loc_xgJ4lk^(UcU5g;_@EX_;idpe!4R=)OlZhgI#JloAmjf|+E}n!~hpDiu1C zu?4jBoVQ4tWUr4Sj%p9uk}FlCZHsZnwU}yXoza%}4+g^V@p%fs%&CH=p@95snE*(U zcbyiPHN3b`3|=tiWe%O>KhU?fi@D7rZ|F77Z~);6&Jf*x!p`7cl8!9!4Y!82&OyjM z7D6Y_6aeSoWC=BiaoEIz0m6oJv~?b|$@mS?T&g|1{%*5KL7y5rwR*A||G^%PbK3cI zdEBL@?y&zFveE|P<WPS?G{%QYI+hAtddj~?1JcvWXug)_@<{%cJRXAbIdg^oGEeaS zmco@X1qMgWxfFWDMCBN<JzOp6YHni|KWD`56Ab&yjKo&Tv2S8>VWZoKj0m8Y4s+xC z_YE{Av(`*1x-vPSqT3Hb-%1q5S#%1M?=9eKw#qMaxjwIq`(ApbFz5e6Pvk6n<q%V3 zx-f?Jzg$UA5C{vCb0p+o<xQz~o}i?h7A+%A70k}8h*h3qK}r=?vr661DMj#kejiLK z{+?`qGQie3wbQTvphd4_HdvPdEssiJj4(n}thZ@Awh{G#dsdX#^6wogVVo$jv~<9s zPKgNd#l|#|9V<=Lh>S`}On1sVkz{GYKb2Y@3yn^#tgvHDleEJO7m;GYHE}&)m?k2< z(4<Z|s^mAQxNjb22ge2i7+;=MqGsaJBLOTU18Vtl0!HVHPm0L7ZeB^3MOJI(uNz6B zHpbb>^Whe`IH2(+G~)G&aT=NARIyy!!!xhcgJS-k0eb|+Qe*+CpLHe$g4oH!hg#G2 zmjNC><p<XPcHGme<3nX+`$}v|D*Y-A;dOB}M8wLAiiNh4hO;nTLW{~1*S31@UZ-p6 zc19QXcr7u)U7Gi37(P%IE-%%o2wEnP0J`h2j(1MDb<#-0JS#xhUR3ap4G`=7^5O)7 z`0z8#2iD+|TXE<159*k3)0I!Q%g=L4U0_~ejaP*V33fA5<#mmijh*5sX|5G->`izR zkD(`q=NrKW`^OyP&;vv0*0=N<jv=#WF~Im_6f91o8-^{dx+Yt8nBz%N`*ql-g<BvC z&FAZOIGSeQJlT?M)9IOlTwtMkLX&qDKLtyB@H8Yn(y4Jooo8(D@BYp0TkT}kFQu7B zH_W0QDrgJN<Fdrz_N=P!$7Q?K0j_FR<4aM_Ex%Nu(L+K6wbP@6f_tNiuHhRtORd$r zrm9fX=EaeP<XKmN(SB!ea}A%HVXn5UBPPStccfD)n%3@sJrdqbDtjG=0QS%#t(bkZ z<e%H(XOeNIuQyKdF1YXIFq5Oh^Nw7hy-eBn3GxZDz`HHxPQ)n3-;*i}Mwy}u{pUqS zagOJ-^M)GVIF$=OPjzZ~L&K*hloynpz=YIGsq78>lqhWA(_@B)QHTnq%S`O~zD^gA zG>(?gd*~ca#aOsrcr-P<`N7du-A`yFhK|9OBVJ>jbrd?i#%GbMX%&~yBhdM~X-*2l z;lE%>tK*xL+OEG#{iFk;0x}PaV{A2{VXDWFV1&lffl+LPc=}GA7U4r&q$lizf;Bb; zM-CQ(plVlz#+nLTRk6%DBm~Q*t|v5<-qKWID~dxz<`OW|hI$yc^|J}J?rW<$f~{{z z_JvO#Yo}LJlAERjjZWH4Fkth(%`*q*{PGkj^j1%%$&A3#N(F@)>uE*wt$S%_lPz#4 zeV4#h^U5MF)h=7YKE%NG&St|kZlQ5kCQrB$RDPE9)TlEy>%s#=)mdZZMyNZ}h)Spe zR?123Re*mx%@GF$;|SEgunnR0T3T^(g|5a3ucrX4bB8cZveS?)m(GO<869n><ub|` z4hog?<FBUC+COphBn{UV$)bD%ZZ9c4Nwb@Q2tOebv23Gq3I7Q}LIt6x(F6|efl<4F zgY9+O(uERYWFuHIU`&%2+`HuqzTx6H39my{-ot<Y2dFjCMg&O@G+`G~YKp5AyA)a1 zNAMfAj{2b=pXc>F3l=6%Hve^N4!3Q=N3Rv_jUj~-)V9!aB8H<PIhkUB1RO~_IXVi| zQX{q{_rV|Ndo=RXQ0@4*)#ZXs?Mv1V%H}gZ`CHk==c+z@t;|`mY?H3<M`_9!K=}gu zpYXIv%Yvc@i?j@d-p=D97w!k9w_8%UpeS_A&v;+u-5-RZvkhno&<*?^;749fQVPX) zU_(7mEDvist%VTQoP>jYLz^x^WbNq|W-gF#nv@z)B$r`sN1T%H@02!e2+$W%@J}T9 zhrj*sr{kmS;!4($uRHKT8qI>%25hm4hU;tpuUn(}Uv3Q#%wyoM-s%o^4^`x>-CfYb z(^S;r_GY`zM?C`^+5!`MiTNkO)Ym_JI@z&W|7~ns^z2D1ri03DAfb6^#G2bzz*Ff! z3D4=IMKql6Y2-z;;%5D6C{C4#0M0y0y4xHMmD=={ZDo`1f^}t&4qB_2$z))WP!{N~ zA}nu-X3)}cx#m{bbjIBY7-`*JI@a_<#%VnAF>dg<oCZ&<TVuG04CRVuHjw#$o6;(- ze@vB*m!-;CXqD_!qy{Q!CIV*-N~5-Mc_V`4;qd4VA^j@1=|ZM-N?Tt{V(BrLA@1R9 znN%baBj1$^T-vqS^&HzhmtF10u@N2n`8NslfCV~gWlkiAkuwe{mVoLE%ghS`(qhV1 z+7lX%QcO{|08=lZ!t9;BU{vJEZ#RQ85xDpXnukPV1!cbwc&|H+s!6VgZ2N33CH%Lr zz2w1+VwXrjWIGRQFk$6^kT7#Jr5lV818SLfb9x~YrBQeFeQ;8mX3m2oZga3UA>zjr zvxxWw_gFxjdlo%xYiw>w3Rh0{fM?fphZu3l(;{e@G@Ve7vbHR1`3IyWwos4YHYKUT z#x-N1bk|)VJ)BI|*STV@>eM4aCHRs9KVYM@f8y+`vl&X&!m2sPY@Fpl)+6|`_I$r~ z0zWj)S~#I^)TS`!MphT2uj{}%lJrL$f5Z!8GkqCtUAGGn&c62uzNfapVu|z1;Mm7) z_yN?$Y;NDeUbzwxLI{TXcrX8k{MP2d1VcXoX_YWI_9O+sLg9Y9RG@HoZUqj2Lg7CM z2YkV=@C4tz^h3L#CenWdKdY{;>Hbqo{MKOzegJzy;e9ZVbOb}YDeTU01mAJ^lIeH{ zH<FCrums<7c288EoJ-7{!LNQ`1mCpG0gDI+dRS%<cYcEe-?dD^ucz)9f}f~DpOAOX zC<pN2T{wcDUj##b5O;O-)n!NraRHdW!-AiXrz+8zrCaY&5O=fuD$sXi!msIqpB2)L z1C)HV2tN~s<bih_!LMC&*tx$~Ks2-)QabBgO*pjs^(pj8hJPCO-`})z{XJQhxZlC= zxg{~0Hr40>tt<1}!{821awPa19_k+fXvvcX&>S96y03#;3<Ml#$v*^aDz}lbsei9| z_y(2ApnP;%PV|c!l$y>TdSXsK%ko7E5c+QRnU^|s&Swtc$GVbdXu6BXL_HuRhl6sy z+IAFE^<P3AE-T%g)*620Jg7*s3j*s+dmNE<@5dA{CX^RUR$03jjKRY;8O~V!s?l2a zqS6jxMhXEqLUKBx8FSCksejnCRB*1$%BnKQxhOmi>#om^KMY`fy+@l7B&C+0{hIfS z2C#O@BeShug|mM~nliC?TV1_JzIJJ1Z2wghD3A$FNyl^YG02~Ty27~*Ne$Uf=)1gk zbmCXZv$}=cjcyQ|O~s6zKh#Q<wg%AWYa<12tY{Y4I?3Gm>M&)~=94K1oagA%tS)bq z18ZB`RT#i0=PC?Rwz<vx<HJ?VZ!U@F{q1GS;F<{+dtF`ZlBV+$qpDXP_1Z@?>J(7T zqOpN$2UFmg3bW<*-yidLa(>otf#L1QEqm#wb^QQecZRu@J*Kht={@?M-yc~#EgG%p z-kaL6^f$fto#jQ^u*10KUXKmLtQl;(KsCc2(r1-}XzQ^))UDu7=SEw26166tvln}Z z)o7=<<CYG-n0r}re!4;dfYbf5_WB!`aQz&R#+HjgCGH5GTu4*?iZN9kLP9;*DJ-Z3 zZbVxu*hkCa@kG%e!5++#&2f>=h4$;vPsYlsq5HVeED%sPB0^9hji-hbSOPt0R5yzE z>X#&qag1cxkMY?>$Qqub9~r@&fM3Ytw1J{>0zSwFl)M<pp?ro$1D5&Z0zkLY)_A2z zaBBmY^Jm+S!ivV_HkZmB$0gja1a!?6xA~6XYSJB6LFmB=<vV6}`X3Vj!C60~g_#mB z4mmQz*vl-J78CVWS5S$lrPa=58x{K}-levk6gmK8GH2dYo3IRPzmg3VQBUeWl8sC> zD;<3ESF&xV2VI%gZ*#kB#xSheMi03DZP>;Lx(c=HV(4tx7PnRZJxaf;!qwBV73=Wq zzeg;pGRElIu#E(5+QO)8#@sF0u!UA$jkud{#uQj~G2m{w8kKL@Mte1FHxDAc0AUxE z;2;fj8K=ptLy{{q4&x*uOb%LR{>BnSAJa1?wMOjPB8yABUxg1jV7ZAr<RS5mj9x<8 z#@)6iV~E^8&&F5!y|tO4KU~N;JwBOye{c-{#?~mt_+^t(S<f`+F4@yuNY_v%(hklw zAFOeB#(m_K-g$-s@Ie?_8+1e;SY7=SFW$Ts`#vVgflU-w{ibg3CW7oc2|yQxR#@%X z6Jxex1Sm{hbSpdko$8mzv2nsQD1XmKrHNx8vG8p8J!_Vy;$0OLsce|W+5jG~u8BJ# ziTwtW)?0pi@<FYxP6|ID*|;9lq=f@p>FJD=H@NPTd}pWV*99Yl;T%MpIncj!yiGo= z{3jL)BqT#RT+b0}*oo#bE$R_!HUJ|*Kge5{XE!mHJELm*l>XUN1g}(w=qBk^ygh@> zEXp)|WgxCW8}br1&$I;DJ9mj(HLs8@t42bA;Evcr?e){#>vd_2`J72>cplqEGX{?2 zN;@ZO9L2zLx=M*DWD~$9xk3}3`@s!HTMDxE5+bbhvIt~h9BjMx>w>&@Gu+o)js0ux zxl-#^y#Za~GDaN>^o%~5I17Jrm0a;-GRgWR<Qtq$`-8hlj^UCLwl-+@Qxl%Si#p4+ zN`WIEBE>?TVX0RWLc>upT2Tm7ik;@8So|*;SrDO3Qf#$OKx*t-u0Bz`8rAK1VH^-m z3X_Vrf|pRl?jzc`xG_b^l5j}=^bz6)TbGz;&&y$f{UPd^)4XeCO;R?z+Q%TKdP`a` z`rQMfb3TA_t#MZAaSaQAqnHp2fD@2I8QT?W3lAx5|DXRO)_%R3YMcP@o-+<Jz)Ago z#aa;9?c5)JjVD7wn(~^;|7F&=^tnl4^|}9l*!JIJt8s(C`p-CjgFXzv|HrZA`@!a; z_P5-GFimxNUlEI&iI=O-w7e)_q;~Q*0pUuaBdkAajk`#1P9$AK%ZU4@?n8YBgaXj8 zYU0xKPj<cl&=BXm8i);OWUp2Dl`%U{{H;4@<*kYa(9!|T>M8h>DPqq+qQD~LuS&!p z<>4<em^|j$Ow@cyhFL%Y$KA+5a_|34K<mp2$DOGEPZv1OT9%?a@hb=@j`$3Ttx6yd z6gTFfp9ozuSU0uMW3!(~2WmJC&0TnX8cNEj5l*g&+<U|>0pWdY|AzbD#0koy(bd1{ zpxQM++AL5VmGBm@5haNBzyaLV6q1m16DTf7&0n@wer!v$V688#iOXRWWr=BvTu)-u zZ}X+RWu2r?qovpr9}=T$$tj-h@Uc@Xr`?}eyD0OTpJ3HmY)#}e!J}daBwD+kh!itL zK~=(bLwhmj>)Zq7uw1tkb)yMr9Xq9OGC)_SGnFBOCH594p3s9Rq-|pd6q>6cIi+w( z7rySp2i1Uv_3<#!{e+p(Hu7S-bH4OEB*EL<a3=8y)ReIuUW}{g_17;#&tO{*sAPIq zo?#C0`gpZtRlmFn>pWdW)F8Aol<|ODf(d6)P-9Wp{>j+fV;i=KY@AY_Tm6|>HIpLK zACPRb@=%=OZ*mfH81zc3KxbyL!VkOV@b|O_3!WOR1gUZk*~+GZsQ7=)8WPg4S-bT4 zS+O^(4}GZFmt|YAmk`MPk5~)+KVofvB|fyuz_0um;uGk>o+B?uqP@eAMLjoAr(LV5 ztjPS?xs%O{vUG(o@mN&px;K%r+L#3Oku}rt#bhLaRG84!hS{X_;a~-FikMn``LaEN zU`>G~lB>srK1k)Z6shol@Yw`BG$pzkU&CPH#R#1DHUgB!i{~pbkH$6(Q40C8<R1pR z*#HPQ9S1A9S-|}B7Wp4U@>pQ&5>zY^iy_F&hlV!KXU}PS0G<lMeEUY!m~eoH!7p=; zS$u1_PJ(-?J3|=(Kj_O%;kyj{qs_HF+YJ1zI1t=I_<)7;k^B0N8|wb*$IDe)dAs9s zHc=T+XRN_CooEN?7q}H}9fb4Iz=^cD%u6rbB8Lvqh4<o0tKtjOUUBgl&>BUp1mEnc zU<Zc6ALRb!;XoB>uJttUo?;e>wHddmr-cSmqYU>Dm%%yfP|8JJIxYKjfEy5KCpoQ9 z8(pa$t@$%ucNr1$ruG9NY{7OReS#<5-nc=Jh#fel=s%<^8(l+94$`fmGq*O@7o5lf z^Jy!nS2=M)Y;QOifaA6LfQTy%G^TiBN*>U9-Dj2qLlUl=uRyR2QC~}b3Ib1g^qD5W z^HhtHbTQk|C|c6jHfd)Pm%G1{trq&}5;h?-^O(_ZxFBjSI6Je10^J3JFppYBPU6tv zXgFA%p?*nDWd~G@fAKO3aZzwu-<0AOp(%`Pq6<^d)>3Ryq&V7UgF`51vIqhjXyJ66 zK)vlTqoQoR=+8YLx}PsMUVc+{GepCd67qe}+}wY9{uWH1&;9tiUD0*JiM3T0QH5v* z<WP$PB;kpzhSv;bfw%-5*0fe$sJNW<V|^O%u)D^uv<gw94cRgn>RH(A5A0hjZd%@a zl5*yWS&Z*y&KI|!uN;{=PRA}|JMQxum~%XhpP0Hu<W&81Im0+Z+Am@$K+xa){oUwJ zilT2i-!L+82hmOcJOfEZiMZIj7J+Dl9&V6=picxQ@B4w+uKS<0%3^*VR|v&lo`#|X zP6R5ydM=<%qbZ1-A8j7MhI15Ja6+sfEfGRn-KfQGxeXFFC1K0E!Psf+WP84)6=v-O zzPrIrPqwR>20JvO=|^I=t0`A7C!r|_DkmmzTP<UNzze?LWVY{g?N!j)0wGzRN)eh! zX06aHdOiU++_FQM(7Ymlt*&h~V^4eXj$0Ag^d5etqn*XS7@>S_pdF@qX`*daWlx*r zd)b5;8Sw`#-M3kgS^O&|!+h^`k#%P%%^eR$&*dx)0ZwWSxlsDtcS;n~E(*Y8A6#g? zP}YDNQ!bdcgNPAJ$3KQNG4Tdghw#)mk|DKC2O6#+h!K5&pUi|cay?U{re;n<15*vZ z%p{Uo)!=wzia&PJXs>kg5$XDFOyQ?o$#}oN+6g;-ea#FD#?od#cIt`3lO2_k(;QJf z>h#WoImn>k004F%xDna8hHVY8^G=q;%zPv55Met|?*v8Xf`2u5=+iins5mXs$oV%J zXlC9RKz1g6n*J|ere^v818*LgVY2$4si5q8=G5hu0810PdriNHCly3y)xwyUr%x>q z+WxoFONAMbs6!Q9tIbn|U4HS9!HbLP!YKa5IC{jvXbkh7i|=9kRyt}d5P(@S-UelL z^!A~Zclow8>EykRVMTiPB$WUl{~ah4K{9s+4DFl_WO{&1F&745xCul0c8+pRK;V2t zWi_FrKeS*$FNIhA^6}J~`M~VN{ik_Rlu~;yvqGq=FMU+f0>m+Bg#ewi&*4CqWt1`w zLU664$?Tv0(4pjyA<&`Qd>EIP(c1LF#}^&?*1~Po<xuZj%qtuZM-z)@D68m4tEMU9 zLTSPzwn%T6(qk%pciK*)L$<&%lPM(A$(*#Snm_TY)%{%ZSXZ2>)bF?bdZHclu}+%T z(XKHKFt<}L8Rf}urhc_oW1WyXc@mSdYFp%L+KH3~hp7JnY7R<iCcreR+DI6^$B|i~ zmx4JhN3BFMrW@-AK4PDO4<eI&$5PAA4JZ4%BNPTQ*2FEaiJ3T=R{i?mqP7fgP*w&R zd+klDcURmQJ+?x1|6pCCiPuyL>=p6x9xS8+v(CQhm!897aW)&=x{MB<Fa-#bMLr;f zAS`7XTwOhn_q*I0W&M4^_C9y*dI6b-LQvsm0FwBj=vmwJKl4f<x~Bs6N>Y8sCVcUI zTOI{}mtK+V!j<TB4x{OBQpL&_2jg~4LS))y9kLL`Ldr>U?Xr}>T^~r63^3-lsW@o8 z%3|$$-*y8yS5{M+R1QenAzcu1#ofbfDDL1yX?i$4!A>0Ljto+d2pm$kvbpIW@Q(n^ zaIrUc`*}Rc;$C(fadphp2vrW<uj`$AqXUQN#=*{IEtA4YsAcAF73=GYf>C09;9-BT zGIj4$-n7k94l0{VcRbffZuK(HZrC@drnjbf*}K5LZ}DUTz3@iA@Kq%JXs3&pGRVIV zH?&Fz?7CUrTD-GsqNuIZ8)%UaK;w$sNS6`-J86-wAd-VxSBQcVUfm2DW9_<so5IwZ z#E5>w5q;_c`uzx(6F!t06jEc8x;Ip=;_MZR9|DCKO`P=Gb~g@<=gh-fY0){}^pB*1 zol+5NZ7@I3*aW%|MXY|FXl?Xst%-PP>@J^`iXH{|CD<&9HIz+)zPZFSf4}>NR&E;e zVZC<R2yQ<QnAK9>X^UZHQctT^@;EW2jak_lmpAg!+KaI^0$m%AdvX%}S?O_^8I<%d z;Fx<vRJoBxnhoI_EaK)o{dtj>E5c7iQrR<Sh@@PdRxpV*t_I5VQpQoqGkSvsPJK8d zhAPiP<5e^MpzB-M+nLxBYUOM;+3To==_#`|$ftG@A6Lq#+?EsMk$2?;PL;MJvc!A= zMlXj7CFriRl3DiX-*OZOP|c{^gjW^dIEL9)E<^)0ba)4pGR2+l2SS`A)$jO1NEId@ z>;JP(8C;V5CbvJAIM(&1oznhMj%S%rvORNJIkY48MU0oSaoyNKY3x6BvZ1r0V1E8N zI17}Ew6xcCWW%Ah)=@!449xN_2|~$YZS16S0PHi3>WXm=mEj26Q?{YsIEDN+P$LY? zBT>wG8P3E{=El343*v+0YI{Zrl%P4H30ea3TSJYP-w|?)r?iL``&6VzL04x$fv#jT z#3H)h16hgtfUBrCfk?oH8JcgR3w=aei8bgX5zm)KZzzP%^^I*PfY`Qlil4U>;Yz`3 zLAtuP6p_c~oBqgHiAe-cfJ^BUM{~1=Hi}~!Vjzx)vY8|p<8r11sdrE>kc%<Bzl%>0 zW(a8%7cva*r|F<Y+^3f*phfgECW}~7=FT;Whj^&40i+l^#+(;Kk(&^vMk2k=i6k>d zm=#gDnT;y%`BtiFoufuLLZD8?eW?%w>Dp7M5>K#S1?f8fr!eq_VNF{2+Vw{v2O@o5 z86`ScG(C(*KM*tax0IxJT=*RwFcq{Wol*id<uoTQq~9X5U_rd-zRrKRchPOb%29J1 zinMyTrT;W{(f!ZkeCdO#baR~cwu%S<8wDgZ;F|Ks@8i7owi_RpOP)vG9xtp69+=mc z<bX=MqQ7aWXLB0VcBY_q3Do@huS6U9m1vc%@iNS|YAT1WT&wK@Q|ilOjX1Q#L2C8} zk4K+Ck65lM)9|)_C*b+RLn<tM?QtWY@?Z#93s60m#LdzP>w~`<Bs9PUGcA?qH*6U! zEoR`epOr72dX*#ojX<g|Rhj(jSgOhF19(w$p($D=tS8Z<7SMCn7fbpy6C9y|`1SYi z6k!#?FEjJIm0W35;df-}Qji9l$9<n7dqE%3Yro)TmhShp7L2ff5tG5$^JX|u3ayvF zp|YXTZn2yZUW6|3tMfp@dEEFK+u6t(xIR<H5+PA*YQrq^ee+v)CG(5nWmWOSkC(mg zm5#_{*QuZ0ab9}D7`IUY$?#yBDK)X$kdmX&=U9vh4<>Zh)>ni<Ko&qpY)B;b?HJ-* z$Fy^yH51M$8rxq$tu0QsghH=Yu#q%<CL7z;cTPd85?fo2l%X~5boE_+B@@0?29RlI z5r!iaW+3!)62g8T$fxa%)QHAv!>vs2_ET&HN4CuSAdeZu9H-wq1`iO1c?s#t?zcpT zfJr)1zUs_U-yo}OgG<V_#o<@ffhIx{>$;)`>h{7PRmUSwh;XN|79VtO`x|QPrP45u zj0GzCEURp1Ncy!s)DPrMrLLNO|Ft!QopwU_OU`7bN;Aq$`sE=~SR8zR$(bk#@~Pl2 zIa@8;9<hzkFsNKnv>r#QgQB%(tT@?@oOvF!nqbDtZ+OhL!F<$mH$Lq($y|5VcG8cg z<AupYUoaIPx8dfrA>2TTyAmok;%=n{yK^^V;G}Q%fluR{`*+y)`L_6o`bLFSIpqF; z8xZ19-q$FwF!^W5U_CP)q=~wtiw02^q<K?v%JnqNz`5&*(8j5TtT#VsCDRSna+(d& zY?1T9?mK)LYM?I=E#v2f60#LLU8#yEtA&+_c>9dYvT64pXbR9(_jH>|hpTIaYlzey z&Pzw=Pn{f0CToI*wON#uzA2>kddX7OgJe9*XCWLDDzKh;7ID=ZM&{Su{^89{_a>6= zt<R=$w$2{1y9|AIe%3fR{X@4|G5<*M+?cPmpiBU<NOi1JR5VVaFsf&ospJ%QRvDkG zD_N_}8`pbyDZl6@?FZuy&U&d#?_<htwn~`CgZ7xQ$%e(WjCrSOVnU|&z&sS`UZqfJ zu<s3z6vu!tRapZ?#fgF@(G&M=f8!DY!QwrqmbXI%DY9(_Zqh#}Yqt^?vV3f-DlD*- z%gIVA(k;vAj!WXa9?%&c9@7ln)>;zdfNpq{$$;pw+$k#yf&?7NNJgT6@^DAFRm1A} z3(=NG0&X;<ad+Y|+_;@c>-@M!MJkEl<*|ogTYstB!yrlFFABzu%2`BsH%L6hlWSu- z!ZhsR**#!N#&9FK)&F2Fs9-^5fY$C9%o8$a2%5_F!w5Qhs8p)IUynJ+_=&k@&FRHp zMCY|?8VjVTYL=JDN9_%(XQZN4Xf7$$phpL%iW&>32o)k`goqaV1FsLe>Z$04Ly6M_ zleEi&&XpvbvLgk#7Z1X6!0++y0ASNOBioj9itn*Px9@{hGmM#hGC|)l3!GK4QIr`x zrJQ1bq?H_K8b2lH;++&3RcwW1@tAamzMZ5~iojEU5nNQH=VyXrC6CqPGLxi~9Qc_& zCEr4)+UzLaaW#2D!G(4dt6M%PE4Sy*&yxDT)u>a3piq|>-#~#QQZw{asDeowKu&?v z^cEgXnm?(G0k~RHc0^|KpcVk3=`p03chz+a&d5lWh=-RPRkb(lVkiX_R!R~mZw9V? zEsTZ|0~PZcc3vUiVX2~?wz?0gpA{-hj+!EV^y2gDxL<)hXcvOwH|^i1-EaI&@LUA^ zUDM?1S0QuGcAO^$C8th@PVaY!ntF0Ro(-Jze^<{gWl#;!Lx<xoZZ~O+nitYUu79CJ z&&V44=8XL^>BOU<3j%FD2kH12b(;Q3)}=ex-e^+d`-*(>;>FhNs^<DS<?@SgZjt{u zBmdxtS^Zv}RS9K}S-G21!w7H{w+!-zG4#tNDq)m=ZbwoSvF1WAh-1*s0~f`!EjRmS zDCF>lNc^1#p8BuybA{LT=&$DvRK)3Gf%UyTNJ~t8eCOt?HZf!UwyOL7WNr7o@iMTv z#F^Y!#_=*<_T_ozWzf24?Y&@+)v^0xx)Zeh-vB}E75?IQy7bbm?+N|eF}5B}8^j=f zXBk&CEv@C|=am-j#0KSi>idm2T9G*-iHdF<{Sk>q=G*;!Tn?gWJon40xZvko$-@&Z zA4kcm!K$luU;S`?2qy#i?;Jqi5z%k5)yYiQA`1=+-g*lk+=#`x4qnmzZN9i28)<6n z%7&w8YiZx0&%=$;s>rO&W0Y+i_Nt)w3d6_>NK8sxf(#^!!$TR7k73*`-SkU=t*nc_ zQQ#lU7Exqo;3WpXTp18RVX~3H{O6#zJVU2q1E0RHRlUJSR9GwG;I}jp%`y>hV#7XB zK3U-A(49+4yuFv*pI0KQN2P;N@NW`J&fngGsZx1E;-puheARV#{%^=l_lcfy-k1$7 zh+)iLcR8*Y!4-J_mmuhRf|mIuu+W)C+~9_X{bMvy=wy4Sn-qIroi&*H+w8WTaIths zYK)s|C4=klu~#athoL^&&xuQSK~G#=l;Bx0z>+D~b^tK4>d_`$Ip*IhWbbi7KV7D3 zgdAV<Nn+PY>xS+I{MU6hRLdz#=EWr^f5+2Je1NBaR6FqRz9TVa<~LqJus50r>>CCh zx1zOepoj`=LgdF)K&%g)#;7qKvCaGY-lzlz_tz-K*)!<Z>(gqz>sv7sY~9gVYV7uJ zgcS%;R9zQAsX*-=6H8;ou}yh<s&8m4w>P9FZ327r!ju>BDiYOT-aaeU*e4%(ZO}pH zc<y_x6&L*ga>Kub4+KLquh_wd8=V{r?uJ9Vcn&_l3?)B>@ha`C<KJko751wN*T6iB z9mm?9xWW2u1Em~i;0R}ZT)7Yr@BPLHe8k-@VeL?I_WN5$l8Chyr-(IUlP^Q@p+fU- z0YYDZ2zI7gZq|r3OoD4r?iFnChE#Bll?}V^K=@Vx%Glg!<!ET@B~l8+$jRq8AyVA6 zQL|BAu#R@Dj&}Ui3_cmTMe||xtE9C)$ikn|oi4Yw7$Tp+AHF<6yOT?&Qa8h}7b!Qn z8Hoeqjco}|WV821rrB3|BpWL+v~84>wX>_6Z=gL?Vp`D1WD?A#k7APufB?Y)d6n|_ zWzUcRp`E2$vNylmw7xkyD%{bz?kbBVB>TQkD0u>9RL7CJrJY$tVt&;-!jW>aYVi7g zDii&R9<xQ4PDw@6u)c2bMCZ_bZz{|;xyAJKW!%@4yZ+68G@8L}s7guK&~IDq;N|V# zr~j0^6N*>q${m<d$%vWzq!!-LiP@>n7PUD(`{iDX(^dJ{GW$l(>CZkcNizw*;+Fq1 zcD}{yFULI@Wt+6O4|hRK0~pPs%wj~FSnwGM))arWmYzrJ_T@CLZ)Orkm=%*ppCw^% zs6KIrvXlTHx=v*_0v6g|tRx>}hruzo4mZZxU^N`@kPA;a@ao5iV=0ecV=Ctk<$I#} zRhKwW)rWjfBYm2-`Eli~^kr__p5<}zEb^h}+ys`CiY)p@lG;?mT2^ld1-Q&{cIsXH zvnh^_jfESgW2Mi$P6)b-f>n%I1Q`bK=rQ!y{XC{KGxHPm>-jj-spur!L_}B<Y!OJb zmW`LYUlORa0CkjP8<6W0B(+RdkmHkD{1>|o0Q=K9zWV03225BbYH5GWAyo!@xnZbo za&)9-Uu&U9InZ8ekE<N5^rh1%i^X3&$*KQ%F^6wqnC>;mZA9%~!t3I6X%2zSot$^t zbSVje?Aw_=+{V%V1XZ+~-$$A^W=-aoOR!1Ufr5a=!z;#$JoAML!%^qz7FwOW1HDk; z{7dnSk-eMc#BH@&=xvmfW(EP;nxhivrGcbv5dmlx8}V6OYVxx*VTVL3alI0>jmD!L zL_}K5Hc75mCLgS4%I#HV>lF5`Rp}*D2Ax%?L=`w4I&|zsIO!$b*s&#FP^wr$^d%1k zVLvJ%31pb`-vFq%T9`gZIGIClFh2LyXo5|!9nK6r|J+&UMkHB5KFq~*Rtq>OWNPmk z*RT#rID{@CI}6J=c3WVIFBxw8GH|t}K~_$`q7jRWgIZ1Hk}+sJ209+Mfw=d*R>YGB zFb|{Bo+rfqQ>7TNEl)(EmPZ|Pe}K`egT@0Tgs!^W^bn@}%+`xvq9%@}jD#>O(}L^~ zjy!?vp@o(&r{d)a*j4Q41wc?K=Zm19)6#jSMhKp3mZWp9l{u%&KLo{OMi^|T3_+iB zjKD~Q9czYdlyMrpdy|ofk8}kJ^N{I^&mI~J{fqxr91O~NFHqL#@7c}iAT$>QD2*>B zWH~^bP76<30GpuSPAwis%ME0#4s_LsjRubz#8X|Xf6i1*JE35v&K*qjT)**f$yQA( zso<qvFj}FyGHee?O&UJgHapM2(sN+RNQhB*Ed^s;3MO5h&RXCNrw(uEJ`$e)*H{3- zCG4!pV!#LXP-H<clSKqu3@lIst?~YCk0bjnXp{;VY$8lQG*U?4XESac6M_%h7M+`1 zfI83-v1`lbl%(|3dP<BD05>wBm^=f8$YG-2ZbCeN!3~sXAgq49l}&@)1^aG@)KHAu z0pJPD*uBEN4Q9{4{9XFCBlqw;@_ohvVmI8>+_n|f012n7oqBAL5ISNy9g7kFg8QGp zyMz5p=plvZ(*c~^9sWY6aEraglpU%2syks&qT!$ciini&pLTBVsaSHuTK8Fp2txfx zrO2?FQB_p%KWWPQZSBj+n9#GltNB?2hG=^h)4Y59E4HohG$BF#hLt8cDvqMN&A+W7 z_Xbv4#V%mSFBXCT`rue={UhAg?X&}&;SXv+TcWI^bO10W99We`&vJuG`x<J^rTj@Q zzO2#$vwTRQbSFG%v_y_CsiIyaL-kJ%=I&8dh6|cfR7T|6`Tqjtco^wyq!wng9i`X_ zPLJ6;VaW#kWR%pYGx@)P2F|Ati&hlQVA8t0C?j(*e%Uht0<GA`0gXkdr0c?{ZJJ(C zFWFN-B6u@#IA%+NWq|$7nn(f@;tIxyC!bPjwrR~7L`F5z3>_?94iqSv(6$(51kCV? zmGZsSl;^9MMQP_5B~kN@a)_XGWZO;zj*&XQrcH4SFFf#Q;XteZ?Oi=3Lt6Bl9jPtW zBKWF2D9QTjAA#|^eeP8FNV0}NrPZpzfJ2~%+`r<;?16q2IF_6|SQB~RyZmWy+L{;q z0N@VQn&P!;9ke`ymN5Nhc8@&huY|j3PZJ#aePm^Qdpvug6Rq(IziHDxf0`LU8iY6P zifOJ_n#RA#acJuCqQdS;N(B`<XsQky$;ko*IB(hcTG$vk4~vpeN^tBtI&w3H?(u=z z*2$%G4PU9;k*WB^Ae&c!`uzd)d*Dj)+D{mUVoFJgVL%`5!hRG_ZG-~F3_>y9{x}>) zxr$u1SAei?P`;u`4}fM;Vk@w0uztb-Fx#~$Abp-uP<F4q7aY=2<gx62{@@hw^I*k} zIXj@g+26SRBLNqSSYQ?If;WC0bnGU6tXxUluNlUUTkLztTS-eGR4EVwHd!($5ORta zQJM7IwgFCTzq>gfjg8Jcf>J=pvAD7*8hYpQ3#vZ~*4M(eP4$=Kj|25DS>cf3+MEY1 zd4^RQ9%0Cz)&OUv^{!Ly3n=rZA7h@e)3gn>psIB*R7(Nby*>fu{Pg~`MYut(-NUeM zHtzxV8&VW-OTzXJ7zAX~)*az}hTozJ66;u$ye>Q|Ff*%wVfzab*YL|HHQx{{(^9WS zzMCG^*6^LsOklj4En4HS1n%N={r1$r_e{|}m`AbWRy0F2WVMHojy8!00S;RXck*4@ zOvox$<+<nmw!x`uOl!MK_6OcFEt{-j&oT2@ceCy4X5=Pffyq2LPVYyl%S28;(_tss z_YRl`jI^%xAX;}0B-bsbP1`;C5kc;$MQk9g(O$Rvu3EGbM8f0R{{DD5_4{<k(Gv}F zwM&ute%hy;3BB61h5K6cU^G9K-F}<oTL|EC%Oc7vDB#O53F_^)>fKYUxe(<vAVEp? zOrPs2PeOg6DS|NVVA3V?(B*iR1b>wU;o`X)xBMeJhjynz1#><uE>%+^m8gCC<_8le zsm7j5o3$=*LmBZ8xG^9eEl710&gOtx(0iz}`#QXbC?Jr*_&`bRauiR(bD#bvIoYuo zau$u7XMThtqBWqYiW^I;A;|GL7*0uj<YAIoW<gDf86pwUyFr{6FR54>hRQQLB@d)2 zeDT8Ld7E3d$k{Ul@pfml%D7?1?D_uLlp$}X2`?>*%NGxCfqf#kCf8*A$@@L-m>aoF zj|w-CSwmMP`~IH=v{}k-q?dPMS-w~~i*_pWEymZ&gCDHJmO@UP$A$`U-f<2U9;Qr( z@At>#sUJCuSvukr_P<)|veasVT^ei?^FwWIAYzO)nC8&hXft|Du{k0q#Ygf)<=ttz zI$u#P_MX^<pIbvelCr-K4<JqoG;h7%ojDQGJ*k4`1EZM{vk-yj_zn6XW}r{lx7}l_ z^-iYzCtFiPwz6B6Wq+W}Y`uo3G+HXsnbJ-<8=S($$Yv$HdwOXqm<ar2$OoGRd^rD} zlwCSm{4-Jm;6;!CX&mm2HC0e>^veP+qUTpg7GD4r%TPwZWwzPiSXt8N6;6vebW?oc z9G_!wizQhxBy=!ibA}5&=`X6ojK9)A%0PY}D6Biu?Td+bj1^EkVscNYhUQChMw3*h zP?iGIjWjlgil^}4TC#e%Skc~1#2Me5hzWE0!>SK&47=m^`UaB&H*X^C94aQq5SUS| z0IY!Om$1kP?mXnzMD`xcqICQG=C3kpvgGfTxuiG$Q5N&QRA@Rp2N(O(gzdcpLd*>8 zxkrx#i)#A+0jfY%zaoXGAhS@KM1E)nYNw_|>J4x#bUn^&a!NK7c0A{L1jqH<qD^^s z%gIBbo+d8HLhSOrkgSP7XD2y*>)Bbn@C)I9*;xsF1`HD&o%u;r5CZO5IHhHa(V&IR z36bH@f_cl-pA>v_4c>Tp_hFpzS|bfuvZp%)h7Xt%Xv!XN+xwn>2XMzwdL#M6tb}3+ zKzI`2+fk|v)?i%XhYxHFd*nmF{7gd>>kRXuRLZ2_GP4l7Io#i)ryrxP&}FI(OqD@+ z|C|r_c2WZUh@ORN3ca-imWBYIrx0NxpXc2n%u^VTo6qyhuFkWk3@8giJ1zv}O-TmW zhFQu0+kup9Fbz>)%l^s$TncK(xMkqoPs(2H@e~0Y|JSGsv$vN!-mZ4Mv;w^9j(3de z)OSEd;7uWZ%l_{8=gI7Df>DIgLd>)7jm!S*48Z0mlf65H$pXXxne3Ncoor8$;8Y?( zS^`&9B$!^M1Xu=031GO44@M;5N|3wCJ7Y)%QV#wQCJdDfchTovoo-Lr;8wChTF^~Z zHh4}Y8@vD}8xGSzDAWZ~EjG>zm+TnxjH5Cf$b{i)!wyflUr5)>vlo-{o5Gg}Q6Yfg zSPlVb!B?p`EXy@JL3s=r!GQQt6%jfXYkRR+_SR#uMha>E>ErqD@x_H&pi?tWs@_Tu zC=7}LZ^e>3oFG}pI>-PhVT2EwvfYk&ZOwVR5k8WDm~BS*VA=>T_dyXpQmBlIzUmP^ zZWZAp%OMg5L^Pi36XDaSg7oe>x_$iadcJ)8(?|KdtGFOj#|5=CJS6{P&ii^Oc2uL? z4GF><uAQjRBIE!eK}^iSo*_Z`GBqdgfTDpo2&45r%3~NTU^q|_!a$_%urU|XE!CZx zgvdQ&W%7B!V`Z$-Vr7`HrR)Lo!0tH%wgr_BHX5-+E9j6IK4K0c27AQ4qh&gl?%&er z6E0)i%|DX*#SE~)YZG4>21s*o6;(g*02XhkE#7^yc%2a~US7KG%U9=$iJ2ES>3o@8 z6#bUWU;g?KEK}z5YPOpF_19LgOSYN><zN_F?Qf(GUqzGrPl_mZJJyIhQ&K9WG}>*b z#>FVeF}SUX*H)<df^1D`!1V^UW{+$V2~g68w&vyIYi(j~U}C;Je|7o53{1Ss+QG>! zGHz~QG71s(H!$%cHHZHI%u5M(cE!x#rWz5(3Z|MpnyCg$Ng-#Tg58tPZyZYvOkf^b zK5xJRe7x}!M{16M4_E*}IG|;Difon3v?=+T-xRSH?Ht|>E>V4~JK6XjAM1^_5RO%V zkX{QEWSY&R1v0v3<vU1Px^bR7o{&#w^~tI}+2=_IQe{(eRS7I^Tgq-gFVn)X-VTOE z%qvwpLL6QJn74>xx96YY#d-40<gWbiCI2uuk?IJ4DNu?kk!-6XlFb4|>k>%-=f@xt z4wu8}a+o|Ml&t*YF8Z8*9GqHpbhH3~N10k4_U5=DL2@^-i-%Qrs_WPh;9WCWim(%5 zrQr!v$B4Eq+KmZgdu~Y>n*}=GAq)c-P{u|T3l;3srBI^}>`$66*U36p_@8B2I{&!F zS;SBOnfpL)uIBlN(w$O6uoU0itcoXktwhKD`1)fEghP@Z9jb6hP8gPONWKAaND84Y zwL_9gmV0zay7vHwv^j#__OX!u{Ze_<jqsk=8U~5wWo4?{QW&I9NiFW=h&P+Y0LegX z?g<3Rk$aan20@a-;_e~{k|XypZ`JM2bVm>Fc89sG9hpN7<hGX9cHJrn64QUTq1#%6 zAh91VeSN9aseE9bXe?Bqv8Me!(VRlKJw4GWeN0NiMmKjw%VI%y4fn`_qRaFGK61wM zfx^7Zj-u1H8t~A-M_h5C>W%JkHIPpVel<Wg%6)pS9mTr=BAD(I@~EaTe88M?5d*v0 z)x9W#08&dmhituwC5k<)4tb$dIPU`!6cDyKsDk#tY|sDVZQuW*9uKw){+H*QkD603 z;@{8v*DZK`{`>Qn+OgAi>@bsJC2kHXcEW$KjvZe+cG!*`UpscVjvapx$Bwj8Vx_<^ z1q{rw!>T>crtb)jokl#ON;IM+o$y2R0X^USXhhYSv#n3Y%y)g_Lp#6xy>os&Z>tiA z;QW$Lnwql>Es>GWnP?G#k{V&{NRf;|y@I|X=Cps`em-B(&*zWj=i?p;Tk!Mwihe$S zct4-`bWn8%ZbSnKeQO%z#d`0{b?7VlI{oo{ov;*JU(wg;-=DAZO@fc`7C4g>@)aH& z<`7#cAUJLW@f{RbEC^}Tu1Pjo?$I^rZ{0Q74@L><olFL=Ia>|<U(w>`O0n;T7qPip zA5@xcpE`Ig5D)VpQK0B4e{RlJ405!&cTnbc*-h`DDYtkYEHaiUGvGnqL5Whg<*=`j zk+DuM9)F+4zdin8_V@?%@2AJ_)%=AzW{kFrKA+E$?1A~s@U|0{oE*Y$HYh$8S*7Oq z#U(QbahypE;Vt50!IEK3HGC{{Jfjr|=w&LxEL9^O+CjvZ0o|z$59pOo3+^H^$E#cj zMD!vmjpD+MHDVZ|S50I1h?QJW!#POaH%%_J7%yL*1nGjo@I#zxYz0^=H64O;4Z^}_ zT$gB9%I>;Sf~~t!`gkO^=}4ivwug-JqI!1fp8xgZ(8G3zOljoCz0LB0Kbd8NzM&ER zHbbLV?!Mu^df#zh=}@@R#pSYMt)%{*h8~Vi8yVQx0I_hA(4XzOxbo>f)Bw14s%sU- zK*-XGEf<o-FS&qKU57~)nCDMoCT)W(<N%@=M#U#;83n^w7MNiq8hcKe@l9EHZgfr- zl@MCXDaqo2$pY{RN^gU=>?+Q8k_1++zpL1BOIL9K1^H)&KHZC}IH!$J_<~%;fZbA9 zNit6BxQflPh=OH<=_@ftH*^&fKk@gsw~xQSyL<fomoLO;eD(N;>@gxm7M*{1eEm2* zPo|I4t6TJccj*7VDEN|HDUBYQFS(Had*D%4B>*@C^;2?yvu7WljM=~1@re(6kwAoU zr$Bp)imi(Tw~Xer{EebH`^TbITa?mA)M8TmTqoRvcG{VHzB{Sq8#@+Ph68(V7EL!Y zo1%+S{g~XO3Dj&FKvK&#Y#M0HuPknWc-jk}0NB%B=yfB7Da)J(jUmGWl^a7I?jEWh zvcv&U583HOWwtEcXvi|-yg_BqZC?*mi^c?5XZ5BNgaqgpW^JD}VaA$m6zVNjLm4xa z$Y14K&2o0oTg~DS9w+c!pp!C4F?0?<lN6Bn_x$)7hZ1c4ltF}{lK`4Tko4Uk!bsTS zmIX-zDBLk>8`@Qhs#h5@<YvA}Ww;DdN)qaS&pl0U;!@cv{wR=p+b*xJy9-#R$|ZJ1 z_;_MtRm?U;?W)j!QJE?{%(I(#I=`6b7ddBHimWhfeH9m_EBwgn_{01<CQp+Yzqq(8 zE}&kl(==XYFOucO{BoUF*e>s!;@j-{GCih#JBzbFv%W98OVaYnD*w;l;$@shi^)Gu zi?6eE9e?#$rHiv<olawg9`Xh&s*|7RX*?^50`2Ih`Dz_4=#DTUCnw2uG+#ElDTf-T z^Jp>u63+^qw`}|S3OzN=%Aoc6^4Hh%>-TZAp!z;Cj)TCnZR*Q6(Jk{~|2Xu$kbd@8 zBKJCv(*5Nxe-m9&UmM2;{vYer?MGQ}ejQ)N%NZir{NsF4mAoo`OfD{{zkm5#I-hl^ z_bdDBcZ(!LLwI);txCqYK&w*z{OmSfy+{^GTKx7;V}kzQ|1^I6Fh?9uJ#p*>9<uLU zBMb~Xw5$o>o3cmJ6WN<(cjm-Ij~gEKKOa-HZf?4$JKU*dyH@C!rtdkv;Z4kMaNF{4 zHwe)0Hu}c&3_oye)AlXb2~l5VAH|T+BSHDAVTPW8ziGb@HS?PtTOoSLq8<v-2vEcF z_hKMuLixa0GoZe(|EJm)*@E7;|LeaO**Ccth_K~<UuHBXV&RSBKjJi-qcx1CS7isk z|Nh4x#Y6vC#py|WfgYW`xQdp`n7EWy-3Q;UuW^UvFHYknbc_5$T{iq{lNwdy2aETE z&HKU0zo`a=1Bytv%`#&#b~KHz>z~Z8%4UW1D2Q{1<{zyWSvdtQOAc3-3@J3YatS6B zdP<y4WXV^;<M>08v<_puoJbY=G{0;rE{*m6aXF2jWoKD(!&vQiY5ZxPtXJ5@y_!ZX z@%78EMXZh5klw`6YMqj8z3PtVr#M~J1I_<q8K(D9)(5rcvlI!ARlJCCWDV;9EcA-+ zt*?qsS40x8vZ(6wpNQUHDGlshq081MpMzF6w2VoJSC6l#BH?_B<G%`pxvk9iRM4wB zHeTDu-&aHT^WcWCzzwuKh=%TV{YzRyA523pkHq?pi3FB@T##d(9tS2Le$WJL-K{J4 zj^WwIZV-k(=uEa9-$HWP^Jpz(gJXFzQ8<`6qZOXbKhpB!z>a3E<|q57<~Q@hTZ%sQ zlg0nZ=Kr)q>b{mP`z>9x;=g^xABU&Ese|l`A0wL29)y)(mUcikU8k!gWp?<>izG>B zIK-wBvxse7H?V`y4qPNsoB;ED^BdQxj*ed$&EH0E(K5cRwgq{4aR5{gAwDV}_&NF% zUnJ@E3u=^2B@Id7?~-)>1xevbh&9(9KkySiil)`ijpnbh>P`ASyNRYq*JSmujBY+8 zSj}Yp7-t!3wnAJKFK~`T@r=P(wDvRRSNm>{8I?gM1xx}a`I(`O!-5U_F`Ac;KRP}n z%g+!2CTW{Y+hn=cWb##(&cm!{x8o#bz4-yFO4<-hcFzzqC5G7hWKryqzSa`Z5W2@L ztzrS8H9a;$KcH<=y{q-E-ltvt4wr`BWLsN$TkCDDxAl%~>tCbKn`~;kk7pCIK_Bow zdf@&+nx9@rcgZ?CL6+eXdr2x!kv%d0M~4t_`q;j6&^q?riRo$w;LbY$+j0MW9e{O2 zMmt||GY6pQRSrPQ0672|=!n_@c&`pX8z2m|15i5vwM}u5HpTN~b~j0r#bWX)M#8k> zSnUqP|IvN}y~ht^kKbUQ;2@h^I|ub9*PDDNH~C%kd5|rxU4`0Js9lBk<0{;9Uz1h% znk;mn4wU|5nxXM{;&{&EiD_YQ7bo-p&L-Q|89+PcY_b5`Y3t4=``Gi$u$6_tQB$pB z!*-m(qVpBBRMsdTa!RgNQg={EwIxbw6Ij0#$xoi2ziQ<GaUZi_j}<=cT}S}Z!et+Y z%LCWdht|LkPRX_=jx`D00R5k{{e%vyy3TD^v+Jv22Vt3DA6oDP`!4vGR<E^s-97;W z|JZPB%L5&Oo);cFzVEyDa0s&B{g97Atz##<r(?@<>rauMdzoUu^_EuM_`%}+VDo<1 zp`3axQ1(`!XubL&d$##~^bUfxML1f;Ppa{;F1`)6Ju@&u!*MNph*(*BQk^F{R+eV+ z-Ab0XE8D7FYHYJmS;q*<P+7!Npio(jFs#k1oer|mp|aYrIv~Re6k&6#<764nS|)zj zG-#VlZ*aZA_ilsVZ8t`?*kslJ9MD#8wX%nU3)GulZ~BL~>A&cxS-qzYV^8To+lLWo z>r{@ab}iP;995oE<#c-iET>z8I_{XG$^mR9?Wod@Dt-JOu1b45iKf$d5jQ2~0XwTy z3|G@|!eh&`1HH@jF5mB6emB@IhkC5q4y%41E5o9j>8-D~zTWzZKC7X&zV=(`eRc2q zO8c!IhTqC9{8pyn4pkn~v`IA*k{@n+_#-SoTt`^#n&WCG!3dFf^TH4oZtfljhG)~y zZpU%Odh<gLHP;8Q;sLx3#a5OdUMHNG+~gILo4sQ0QsTFk8v7_Ubb`u5)~xw`Y>v`C zV1h~x;9l(u4dC8dvx7@Y@v6IiZ_vAb*Q%0ITpyB@;)mK|+AWJoU-j#&er+%vtidF^ z3AmlyP)F4P-|%ZhXT7%{)ZV@uWN-J)MCo&_e?NIBdbjJ{zW=-Z%OJa5U*&6`;J`jX znxFK&{DI!f`<0K$ALv@%GmOU*&kpfF_>&I-l?=6qX~#TFCSWJsgNMmQLXQSk;~Jv& zv2V4&jkn}sV!Zhw->zxJbO#kv*`55~QglRTcaur$M!x>u;(WhDxA9tD?4!JR;F|a0 z!?5%F7zYt@&+mbQN=FZd0)EGE?;Zwz4_y2S1pICqy0FrYDe1cjP3RoEp=JB9Q<wGd zmX2N4s~_^YtM&9`|Mc_;`+qI1o%fUldTN(6dM#Y`Q@CiQei)@*>*)<D?UtS%R(g6k zREnErxkZI0({f#Ci6+yqw5GmWn)*(rxE*M~=7FE2T1`*(Pfh0(ElsZD%jkTTWUx}G z_2ZzDsP*H!q`_;Uvxh=QtM3mv#$^OUKxfG16ww)SV2kU=b#{ZAmo`^%zLiFoZ}N?< z+Mo&?Y(?2P0WQD^a2BX4lP9Qodpb>)#ku(CDW2YBxxW4wrvuC|UN7SGJX&5Z;#D<G z3p`ERx65hTAWYv-FikwOM^6QI<%o26e*P(`<}WCI+?u~r&))&f-xWX_=ksqz-EC+7 zFVE9@{(=H!t@*oQ#pa#~Ve>#bf9KxTAFHty4FuTNEgJY{MFZak6<{+2Yn&6oy(c1E zR`VC+1Gnez*Ygiy^B1gfK7Rpz(gyR#x`AwL0<Ts&McnCFe@fQKmJ-cizRW#vh%UxA z6XWsZ$TJvpd7ehg=@tDYV@O?r$a)!mi{p0R(s=e{g}0X*{%O8sjsFR2JkUXQIlA*= z$ArK5+b8X{0xh0sW0B?a-2l9NxLiG2J{)Ge!Rndat;}1#5VCyUD9gtHEbB6kH}?8j zBA+tZeP|5O<-@-0P1el-FC0?vzCoMM^s4P{It*Q)O;F5>h@cEvxY1Ht!mZe1xNjzo z>oDoWeIe_W-8popi?nAp|L`WPGy>LQ@utlZ#*Fd0mfCnXTs9vdLC4>LqKX^&`6u0h z1@!{fSo@92mdXXk0glQaa8$Cx2EPp|tvvQF1RuYw9mwW>7jnut<0uJ2ky=OzXKWs~ zMc|w{H^JA<+Hl>x?uO$nT)>vnE%ku8?KV~q454(Yh8bAZ5olWgJ}Ztu#zq=$wMA)P z&D9pjn1VBz(pPO%_}@oQ>->AUvE&F$L2^w|um_6?Tk{NI^Yq9(+mH2`=dH>-1-r7> zJf&xWH`sc9QJH6VCv7%Q!70?7XE&KseV*^;+4KtF;~H#=t^s6Ob10U5pDY%edGUJ9 zP|mDO<+;xce~mr^CMb}ay(TE<QgbLSB{d9gFsoLzHv#T<LE?epge@S?T0`+HnQ)32 zS7p8ej_WmFIR`V%sowLwi$1GNSFjwtrYq-XYfyf^Q<<z_aEg;PfxPSt%FDMZlNI=q zdrel($V>~R_hi4QOm;A3u$Zizjh%tnxLH~TFyX<pLe~bevO6#<D^7Sg-N^>BvpX<5 zD^7SgRmujkw7WS=SEH9&m#z!;CD@z!5*!om1cLYya2=H~oC%Hz_E3i#I;L4SjqH~l z*}fsXt?SaKa9%KdS{pmGeU{&uHE`eKxbFpTW4(`c%h;VWcC>Pw;`~`Fj)cV>?78E$ z^3j?(hRG#@@a2rx+YAXT9)Zh!bBB5^_X>nO%%z{|Bz*RD2xCOP-ETx(4hLV2^u6Mh z-363ayn^SN%jY5fvHZ;hFT;1md7I_A-=J5r-=`uUECVVaRBpVu%rL+W9V4}$F$ABf zjqr!C;ZfuWkIaH9oFNUz)Q<GlO(AT-;wVetdq|k8-($Z<g(Yl;6M}lMU<t*0ShXQY zxDs%6)@2xu+B6OiyWsdB*T8WKcEApdP$C=ir984(7Bd<`O)YTQnjA+#;S6sO1;ynZ zuAJFBe9fdabmqm2c<7sN0he`nF;!$g@GBKL<Sl7yN<ME&V=D?)Aid_brPsX0BnI$Y z*2a(g_E~DU*Y~Y#<sWW|v7{eQ&xYJSGs7!3KBbMWmCfO_QBP?`C|~=SmWH9!;c3BU z$8-o@I?FV0cp8pWFT>LePz(t3Qf<@4v_j!|)wHaKe>L+=X0p3!g7}@IFb~LdQfVRe zT37ROY7Yl1QW&go090m$ARhRO!B!S85E^_YI*h0b{@Xm5TIeaNg(?F!W#(XWUu~wD z_TyvMmf1L^-7fRrT7Ce!3;*^>o~&Gc(@F^FCPTbPma8mUR@o5GvJ5A1&x(`?%ki6K zr5mi!z@^6NUN{cevq=t^Lo-H)DuK=Z{Z*32mua$I&PbZ<qo>!=WxUKH_R~21FZaMF z7Z;63q%(fLUY!-GlvN7IdiCFbx_$Od{e3a{&|^=&02_Hc;mx&~FX9GhznBir7jXkZ zD_=$-S8dLXM{sh>I?L1b(HK9SCy#%`*?f;v^y$M@+#x5L3&l{)NxmgHCXB4Y@}Yb% z7$5+>2m=G~9(@1d=QBiDw4g5*(FzR==iu@lZUBJbFWw}x7=x(bDdE5A2|S@^0Gm+f zrmH(4LbW}bQs-)?JEe55)~KxnFeXI!c?YH>l{shYkGWhfCC-a0G@N;ve2OGOC=xUl z5*h$OV`E*%#C~1VHL;*^Y>A-pIfCYW{M$NSWiM~zDM7Qi%}$qBaXLpQ#Z)AH2wo35 zOuA3}`0@WD(K^8h7x|-aqSb%$FCR_v|B@8E@X>@URUz<7<Rtv`BlfBlS#f!@zdo8? zMQCC;!S8&5Z&Hi2_JqjAGC#Y>y8hSe==$R<qB613WUtZ6(-;&*UiMf2)#-P>>~{O_ z-=F{S^H7~yRYH3-gZJ5D)||kNZ)h!nBIxTRN3X)pj{x7A;+m$UvZ>(&ZJn<^cW&Zk zciEdPmn7G(B67MuH9MIr-7RyvY$j>`T<w&=0OV-eI1dUNo5b%2s>OP=rBrl!UU*gO zsX;RBLt@<G1Z?c{W_lTw=C;-R^Nt*RHk(ao8VJ(xb76=SO<+}Cn<!o`R?{#Vv*kDt zS_xEfMX^Y=<%&k~6i__622eawuLg=pmMFVE|K0dwXi@h4ke!wQQR(^b$rN`ySkF#P zgV%#~>ee(Eu2Zi;1EpTO-7?R~>rDnq^;ogMU_DanuP}Fpo2GqAl5e{wCAGJdPD`pK z@5H2~QsdNQUna{=nCo++7OriK59(bF$%)Z1ZFI)C1nooO=n<SU)N{atBwvfpVFH=! z_szMs@jOIx#j1kK(G=Kom0kt1Pt`3G1X+C3CQaJ-9wM3q#rjJxy#yyGgC>%P#;3{k z`JyIB8}LI!5Ys5Q#I(R{B8|jjgTHK<B;Pkl(ymu0BuObGIJy5Ul1QD*Y$%v5lLYOY z22I-aL4-6Zg^3B5CeqtzHayJeG~w#&lPsD1eI3oxq~R_#gEl^MXBK<~o<~yRG4-&e zgOzzd9BAjgo_|cE^sYc>Lni65WlPSlmuZ@$ucqkXvn<Nui$(JJ_(K{kR}1vlaaMkk z%q&i?=h=7j7`=UZg|X}2$E#$q&S(4b_GU4k&a)qvi*8~B)z61Cj<RQ~XIXMRpZ;Sx z$A(2W@SJMW!+N3GpS`L$<I&SM&py0<_I&bcy__;b-l>*C+lM^K*0Sgot2Hgt!#*wx z8Fm3SheMmgPe5&pdXVx{aKiVRL^(bAZhm?7Gg|ocI!cihW-=50Nh1|iE&TdxyY1@e zyuB%U@b<tV!Ndt@a`p*5RS^zO>sbZqLfWw<41@~bx2e$fib$zodj%C-hQZIL0w@HU zuh!iYx!NiordZpDBBhvL@=c(`H!K(jCdGKs?e{`4N&!UVvRGQNh+LLYFqma2F&Ho4 z9H<c96S=-`lZ&M@3(4h_<nolr1=waHW$~WKMJtY&UMz)LNUxySjaI0%8v&b4q)2X! zUMKPO`nDw3g#0z3C}!F$+r2Z9;tHNoxI;)`pRgo$aOA}1#IZ1G%!pa<Je%LZGq8Aj z5$o)zRIw_Got59TsmAi|P(%9=T{e{0N!|A(LyF-!c9tzBtgu54^}S92gpB$oamgF_ zLen-FH<V)P15W62M)@W2>f(HLv1V(hof*AI)<u**XjauSoWwVa<PHNt=U2vjC9`Qv zEOA{E9E-BPA>xClzPH{vU7oJU3jX+c8K;C%WN&O;wsYst3yxqm$mx3xc@%O9&upl2 zAy0Migg<9>a`44!haBHO0CMnklMXqsYPx3>QIgFcur0rg8i8b!`m45ZR#7q?j{t09 z@rvc8<*VpT4o`q9&8-EJd`%k|(vzk=ncOlB)J;>sX*8y;(jvq6G#LPDN{bA3xu$Bi zsm1d{?3!)bq8F9`G|7~=L2jD{%EqY$wzjrwoOZ*8xl;hlfCLej-Xcy+e5X+!QCupG z;#6qfa8>33;K}AZc(MI}d2sXj2bl+eQJVAMK|}%O!9@cYWF7$bLSr5l56c5E4{rM6 zAoBp&{mpssFnj^?;CgfinFqigZ_b04zz3KI?@gP{LuLzfCJeCSBq%r{0^zx`u@FQQ z8dDI;tb-1L0B(i>2n3L4O#%r(P=+Cp&|c`!2%s4bKqG*xY|@Ae<ghu7>Z~WliSW`h zMH4Z%G7~igr(6<{VkgFh5Kp}qqqj4!>hFPf?Ocm1WL*O?U7OfxjPs0$kJAH3AF!p( zsDTAsyDDVe_Hid0mXkGEb(q+*Wy=ka8MRH4P^MGJy3ylO#jJS1gfjt0tblB#A?d=| zT`=3IBQ|&lGStJ>=I5zM>^%=1s)Uy+2`4y{+d~Zn=rEfMRr2<7s3HxNO;t8t+$KYn z#P^g#6)FAfp)$ddHX5oVn2lxt3AdCCASf%d$xtORX5~;tCLx=uO!UKzhRQY~Izts{ zKkT8hfm=2is^oyB82~oaP>@%@$xtPyV>wijCdQ^Jbf_#ns$XsqL1ulGqR$hO-TiEN zxn4x+<fj68IR7?FCNFV0(8+sT&bB^r1?4cSq)f)uGwV<e^PDZ56kwVLzIX;DZHX|R zyU~l50Ai<a<YGOU{!xqd<ufQ^vAz`AAlFJMQn6|!&d`GAfxw~@>v#dxJP>wNVm<k8 zL?WZW6>A64fh;5e{``4kM<Ck>s)mAs5gAJ8_SJ5B(j=pto-#Q08x(rjo%60{k_f|e z2xXX&O&vMO57A*#k%Z^iMj4*NM&M#;E)sn}7?uMMhzEt^<kS)7mViQWICogAqey1w zbz^W!I-63QQ~@qM^&C9*hMGYYcVkIsp&WBlAA!(#o5s78Vr{sQ6x3X0F*Yra=q$<3 zyPz$M$5lcoYW=K7_{6u&&<XJV0ftQE8we_S^Kc2LyeGC?=y}7gL)X(`Q>_&>3uwk2 zG)kg-evF?MG^k64EG@)(s4GefoVXpcD3`qB*hVl%POdblm~!=)hci7P@<Y}A1Gr9M z5~H|z1$s8{rWt4bU@oIVwNYL`0m|I?&Z8!sRR+z$58aAsjxFyf&8{Xdk|dqsBOso< zxQdpSaV<gH5muX8;htR@;mqtzZG_X0Ya^Uuip`AhKIjd%O#|F{cm}wm4RDSDjwxe; z@~yXIfHSIRQqOJG04LNDG7iiD2k^!g4RA&UR_ZxzfDdhe-=4pGXr?#bIu<nKq`&FS zJPmuA-e{Gm@oS^IZ5}wI8r`|Hy;q~#Q8l{jF%NBY^JK<0%<W=U3g)(R-{y9%$fz!z zHPZbz(A;j&S%u%Wa}$mZ*%#Q(>jIotUzftNEh#&ijRUr?P1hi1HNiP2nD8u2D2V!9 zQ=5x-PCa(I%oR(4tzHP@A8+!(evG=JxX~RkabKm$b=h-ARe`Pp6lvZJ+qXq5H6Dn2 zO0wG#$Kmrh$6weG_Y}AeE$sR0^Vg5RNB@_eC$AZeSh@^LQxldi$w!5;z|q?nNZ{1N zP))73md4W1;1d;=h^Z&~{oYShSP8eDDCV0Toas<o->mn3`yQRO_eI{yrb<hYEt~@K zIJ}>o|LXDI$KUX;c91tl*zSMd!D)iF0Oh_a{wNu~?U~u&u=BAE=Z23bzDJ-rMcPWm z@q&8uN*upp2{X9T(UXo1$<cNIZc0eAqNMc@C~1|Hv<yL60aZ$xCKkd$h&>8!4ncqT zq_k^N3d$JtBc<gyB`s|ObfoPQE#K6Xd{YZa%aB$=u)(%jfT@W0cR={jV%1>m-UW$@ zcB)xso6vAz)#1~*@NnGK)0Acsv*r?MoVp^Hm=&8?51CC!^z;5RO5=c&hEl*8#U%Gu zArU1ufxLdeoRS`bKxv%bQkS4ApXBZ+!YDSY2Jb^*6kZ_S&a+A<eCuueIZKvB-qgw6 zGP<5mS2YJoU70@Eo#A4x!PkpE2}ZCP7jz8v=|&>dG`{x|PUe<MI86}M>Uwmq%5Pbv zaVARDh9*|C<G&BsvEA(W)A{eo9|LyoG&}!SUfy%K-rcgn^?;pvWrObr?9?wCP!*G4 zJxgja(JVJ3EBIuVZ8muN4HWOq@?}(g1w$?#Wa+0@wMd2*bs?d#9-adZq6^^Y5#r~@ zj~o1ZJy&SFAen1e&Q$?H1dx@r1GS$%)fAD03DOiXt%@Yhuq3(n(oaNMRAe!sK~6bY z+=?vlx;`MX+<W<_>zX9c_~M)-K}izJ7?vdWUjFI(nj}!@9YT^k%b$?M9+o8cQ2nV} zXr!hJw31*>6{n(#0w58DDw3q%t<=QIt)Zg=MPhzApG`=9OUE!WB_#<(#u1mkL0Rb- zmmIU;qDi?vmMuBaba^a=d>5+a!zzzu@X$Zu>a5AhgrQzNOl>TV7^0rtUU8Yf(<ESN zx<VTCtBl3TkZHYX2hhiP3NRrSO9>Vdt6xzpP8C!Jv39B`R!cQT1hZ7Di1jRs#W{%> z1ly^ySl1M>998b>Srp3xU|x$<=zAj8_Y|>Q)w+f~D`GLSaXG}=sRD?!qK)aLde+%y z!Cbbj#9ZJCh=2$0tAbcA>^pZ5%!zDLK}?<@$)vFZV6}UwAXZRKTAc%yH3>Wd3u^~b z0*s$MY4Nfr+2jX^#UV<F`Jh?p5@L^@&OSk&-JuduedwW3Lu|&2JlSQMj8HbKkVq=U zGoi_-RC{T0!A<HP&1f4$z4%ejvROwEX#FkLftoSQ3l*hiqvBad@Jh1VwO_|51(k0b zwTchr;lD$bpbGy+|9R|4C8)yn(0?8~QVFW?2=t%Fj#PpwjP?HW*pW(5g&p009^+Jk zQYi4$oW}<8ihpWvUXMtins#P9TE(VnvPvbba=MOPut}n;c8D}u$tH?O;IdYQ9<oa% zn@aCRuMNQk^BZs`ii(J#SUj+r{|;1OYAWwgL>U`j$C^ffgH}n@Gx$FC{wof(m2@F~ zb$ia1X%}<0Sk(=B&3RjaR6|1TSSAQ(r{eZ;isOJlb1YM&&#{L(e03yH$sxpD%0p#o z23r8Mu?z+1*kY*n1Y=_v3J5mEP=_y$11dRW843tN#Zd35<d9{G)N=Mvhp#yWDmjGT zt}xV*aH2pZhsvRXP_59}wH2VH7s+y!;mDoh?aKsvF&F2J>rMf*M}4D_hh&hL0}^il z%BB;b9sLw7){KI)8_lV4-z`9IsL_^*!!A!Y=0IHbnNqvR@J3UjFIojq3Uss`StN_7 zI>tcLVpP5b&FplU#g}Q*m40(R#}h3k)xmKDUVpOY?vuG=?|NY6ND&*Ndz~&(*U<v4 z&a8OHP1jDUp2jhG^W{2O=XY1nvMil{T;q~mPxHKvoBTfmk@0Fy6B2@H0L_Zb8OS!t z<{<C}BarfHz7a96=7W-R)gq@9+d!3^wo#GOW?hwRO3u}0<XjC(&fjQaN+AGLH+fKP za#p;}hNS#$6GHwrBpFkhjM4;oMKW5JSCG+i8242hk}=(cjOmbM%y3>aO-gAFxw5qM zyh>UI!xNKCVH1Lq4u&M^nkFa&9a4!mOV%8LGuN9Cay=vwKhZ>l!0f3I(JP5K0!Mz@ zgovMpB;se9h!E&DrNhRk4x16q?a!N#@$-;myrszq0d7;0kbWf~!{NE{b`vt*4oSv4 zij4Mv_DxPk)2#GJ(;A*1?=~Ui-H?R*LKAXu`^I!ChBR3r?i&*F%O-^U(w~s6JCoPZ z^~YI#XJQNNng&odN!2q5P<E~;f=W?|=mWb1=`+LU=bw`ESyHiz??7By0mf}PvMnUq zF_`3$$pAzET(C&5f`*^~!y%|JveG@t^ZGZYP?lB**>~G5C#D%#EQfp7fhn2*{#Syg z47fak-p;p(Vul{)LY_U<_Dw+FsqzrA0e4Ru&Qw4;YNqY$nZ7gSft~}dt~Q*hfYGU$ zwqL9^Q~q^Udsu-5V>K&}Eok55^c$84ri>bvlrM^5ZMFmW*HoNgNf)sg)@JO=zmn<< zi+6L@=B<z!>e6=?u_3kr_f)<2kgvoQLmdHZ#PsfACs3{WO%%#!n=PmyMyWF{UN}K# zT+HaOp5qc#Iw@|sO`sIBtO3U*!vCknC1+TRc}LuHT!KT39+!L_*-?Hy$0a?DEN-N9 zR~vL8x}e1l2Jbn3>9K{E5x75?!S+4JB|W$BGD7J}t|*~|9f&dHCtS!2xaf?FS>LMX zxCAFxxseQ@;IRkXNQ{cOoN>tok3As0EV;R705uiMVwU{sIWGADVk>QsBhU_E22=H% zf&8ekp_Db4@n}8AB|mB`UI1Eu(Zh`W>p21WnPfms)Nn|am77Rm2-SIpq?g=AD#iuS zdF%nl1vo;aj989qNRcQ%LM-XgMu{E^vP10QM2{^$Y%H)<U=JsHZ24hhNkw9lvcjqj z)C7iM4F)b8NAy4@5U|zZ=V`Q@UeRAN#u6}La@j{8OGI}l<vX0Dns1-5h6Ej_&x(2N z$YD-JUDm66E}ir^#)AM#XXa>oj!SwRm*WCR=K)+r)wtw-$dDIO-x=3{9uFH}(Lu*$ zSOdyjfJFztH-V~E16-R_6ObOqcpVicV1p+x5NAlwZ8L=0`t|_h%AJwyN*LWs3xItn z9ehQ7PC;|1$aaJkJ}4%&jBoJWCw|{I6MWW$?4ySLX4bo<iE_o;k8o6a@lw-ezLjy# z2oifZ#DR}olHOGgfvHgOhp^e{>oC)8IxcRDlYz|ECmiv!<wQAP2%Dej`Oab$BkImy zaEw*6w;>LGY{M$;Kf;=(Fl~aO)Mn>UP7`*LdY3AKLsaeB1FP3is`xckSVsepqg__I z7n4spYzp7dl58z%L$edGHkBzZJDZ+u40%WtI}K56+8ngM&MEBi6Z1w8Nz8234*Quh zkwk4ChH^ZRm|+!B?5-2QjS9afA&7q)oZqgn-f};o&lF_5)fn1_bcJQqsk43XR|^kN z>R9x#E<|dP=NmADP^{Q|45M=})7O<dOu6t=jI+&A3F#U}wRh!49~XFvvArD7MPxC9 zVa!7p5U2vY;KgA{0Lr#AeOuvxfMO3XlI!dBa-L)DPs-m&Xrvo7qdyxYPAhpq)3@<R z1HP9eU|9s%6o-ZeoHms!$zcDkSk9no$1O$xE^uc73*6O92rF*KDK&N$XE%h4Rce6I zVKCkLUyO<i^;w}(_p55ftFTZnXrr=%-Knh5WzAP<a{Y6X{%3U)p#?2E!C(IOpKhOh z)A)rjr|pVzF6p>kD?rMBXpwrI3@jHVHzHxDkBd0h8*a~6#cJhH!GirCUEeI?4|C!! z_>KP@4s1_v5?onCQoZs2#A)&(O)yX@11Gm$C&FdVE>O3xaF%$Hq5WO5n9Y}$lMDRa z<P-j~BWnP`)xbqF>s1pZchalo80D%tECe1UCo8>bU-YVhR?VtcO^{1UubS;td(8u_ znm})%SMBbhuNqz9xLzA+8lVGCbqR4Ozl{rpgdy32kc=UrQyEs>SX#OmR@XO+Z%PW~ zp9?((B6B<p#A{={*Eb0fAW#^hyTVsV8egW#dO3TMEbt+i#xwrY&*Ka9JXWi|nH2wD z@P5K#)x)OvVc~Y@Mc9To7bNo5f&r(@IKGSPH{t4DprYBLyOv`5B6oUY&K=dGN7hg& zdR7%rK_sGS;B+V(s~@I`UD<XBk%<CBXxy|Q+4U(_y5KfsP};~s{2yZPU@117B`LdY zC2xb6VQ7_y8<otw#iuOXytPW=+F;@ibA>3gaj}ZmgGY|!VIJi?hB4M<H=$Uz!M)y2 zHIG1gBU;WwmP#~)alg#cWYIF~eOqMKca;U^Y3UHX+`$eoTw&SuBxb!AvVZTKl6Uc9 zk$h%9%-1G%z)fI}<R+ksop0zRkd#udijn_|+-RTwelcI5lQy0yRaKY0#V%XS%GX@p zrOJiXWp8on!s;*oNY9fE`{p=n-l=svLrY$CNbk+P@b$DUAEv9PTSQY<AFQKW`5@iO zBi1IF0I@b9Ip>3^>q91})6|G@+1>MKdAW#J=jHyZC?fzOqABAVC1qStHohRPMvXFK zX10S!mqr*Fp(Gf@KFJA2v~)r+kdiLS%IiZhf$lvX#ir{tjhET^O-YQBY#^9VV%FIu z*&GK#Hb(tfKG`nQI2O2DcvUn<AzT}Dv;LcqECk_gS~ful%Ijp3k03XLC$Jq<iB|Ze zKD6;Uc@BeKIG#LB6z$J~UZ!WuVg4`#JIrxqyTla24G5AI%wsG{lj%`DTdqu!r=SX@ z15_xfS8t?L=Bm=~w~xysc~HI2YQ5%eoY&Z`*L)f0HI;t(FAN6y`zY^l>8acf*|$gc zeK%y^KHc}1A^Q$$x|f))!*m>09XG%ahv^zSlxt=gwC8H?&M-X&wxLX`?wt^2=>8j~ zAR^4>y>qOz_4$WEJGSbMpAFivU3dI)(2kwD<M(PEcTHAwh%0r$h<a+9tmIoxwVPh1 zE7g)0sz56RLK~JmDp98EV1Qc3X<M??E8o@n3r0{ovMeMx1M<n_l-q^q)6{cg)Y+k@ zeaDzKw7d|Rwu7UC$g~}gxsWUuzoZ}tLo1H%#7(wUokv2>FAQ=*D;E)R`c_F!-vE<S zQnZ9;qHdWschP4Cbyy{JdDOwt379r6w5F43NM_xe(<Ie*#;4|O+w4cQY@^}wXlYtG z3ZjMM{K-e~*7c;}?wC4~{k;vb)}>C{#1~V?aVqLK?XX8abtLjUr;cR1ZbM3SsN=M; zYq``RSel;aV<c7b(S@FN9;m{aq^!~S)WJ$pO&3;SXlC$D&NU{YOPF(w0j7(jJW@^< z$wTAQ<z}8uuWG`y131NmF+Hm!jLBB`<kyZI!bl$4%E4BXrR^6JlEoxZl9(!{2|v>$ z(lw_Fr^@G+_Yv{u*TjJ;)TU$PS&Uf9IJj`rksU&}lMfQYoZ6w=-cKz8K~?X9K&ER| z1Tt;tw(>!8m{X^I%L*e+9;hm9+Bg(4z~&`Mw=)fB<x^jxFc!4A2W7hBm4CL#=Gl4{ zPio74a*7=^HN7Otb?&Ig*&Pz<G)PNsK9HG$Z*2+RdF&)A*8OcLVX2NbejQ!LOGa`& z)k++tN<G@+T7YU_Uk!BcXvl-m+W}YMc7PfI`-Y(5=K1%_FW5OBr)iR^xwF|bVtRYX zFKmwwHCkn_57k=a`Jo<cdVegY_lG<#)rtwx^7!<653!6Y>g|oqK}v{NBw!SOvN>lu zJ@{&O0P1op2o}<gEnHyKC~X9qAVDW~Rz?uZDG6fn40jGe0JYOaexI#Tt|OXX#qsQ8 zH2qJ_MJ(g9GZC>g=Fzw){^;RUDVI~;i%;Z$tv*u^%Ox!Jcuy%y^&z~3<vm>-gpZys zlFMhyXmPiiuRbJ~my7tXe-&&lsL=Klg*G)rso*YoW^<WM-piHS<X67zrUu<hep5Zj zWH|M(+>2i|=_SiumXo71il!cEltvnHdvJ}k?o5QG&pVGR3MbN*FQ8xqVv2VpOIUWj zoJL+y(kKv!FD8xnQoi*{v83NRL0d^C1<TdU#_}AA2x)sp!ED5OQD-(rO`hE$PRrwn z7>(sAk<$k=T23EjMq~Tz8LzxwMq?K$=gx}l$LKsx(ju@36x3MnG$I)fn3Z|>IrW@G zqgI^~koE;CgUicm;!g>4-zHOH)o8DO+eCBxGHFQ>o;dC(jz&Ml(afuul4{x<L!N41 zD~<qj<q#A{K97JEM}Jhs@!u~=oZL_rKY97SYmXKOmaAy8DH4Ji8a%fEHKeARRBDm| z0cBKHBpGn~%m!_+g!0@4id0eXFsF?)5uZIVVNyP`N$&)Gsy9_l2FMy-EwWV=8^Rhv z&KZuXQe!ddLoge(8H30R%@sv&Lo5G0CmA(#>Ouz}!`RTonf4;bAx*EUTFoBm{z!WA z++jlUm?SI8Cq7p7ZL%k3=D6BFFS(o9sMP*BsC~^j-Iw-{4`THxA^zJ5?O!HDShvB{ zbQ(K^TnLl92XY;(cK0Cg9Q3=KqgsyXdY8(YAW*r$Aygz67KDnb7Z!XE!vJKwkE@Pn z%Vm-k=z;}PvhLui*XIfbF7f#Po&5OX!>{jNPQLr_=Jn*=Kc2rneKGm(-_}X?&C!!5 zKie;!JURJrlK<))8&96Re4GDTJam<1H(x(_^7-@U<InbSl3qUf@czmBmoJX4vg?Io zJXvMwe3~84vRVE-t|<9m_{I2l{0I3QN3-(tb(}?$B_3to;5XF%3fq~*Yp2-iTxP|u zX7TNlviT~zTf~zLGhY4^Zu(@pS~XsO^LVnDPkx_#zM5z85m61lp4_DI(dRU}`DXG5 z8Q&AqQ`zm4<`6$7v%3lTxp>Fq0uAcuBD$V0?!L|~w`WL`TjU>$pI7rQ@z<ttb6foV zIi6o$WnUw9E+4=>e!Wc6>uB*!i&{7I`>vz(a=tvulAEtdhsEC?lPpWFsjn9CMMiy* zlDCp?j(*FIK4QK)nlERFreC9xU~*M|;)jqK93NffV>J!qe>Fx%=zS9{WwiJ%UVMtP z`849tqwdlCYVvG0o8<IIJ(q8ZCRb^EQM}<g$`;W_#B|YY_Gz`6UM2HsJeysfPe1<o za=Ln)zol~96qfYx!_H|ni>FCSw%^wiBr)O?6AZH{k{n<E$w2?RxM<7}4QrJTt3Agj z(Ks}nB<UaoeS_~H-p3bl8ZW2uZc&wtZF>|Yn`SkMR@i8n&(OcbMK#GOw>s{Q<mRF6 zWb3QRugQ8cjqvG&h4vD=;Yz|~lk94~nk?c^@#1*$ESs#b!;P%><MQG8r+IcaK~F_% zM2ZN%b+NeXvhu^D?JP!y^fh|p?D6Ddw2EgFboOUg@g%}jiz{}Fmb1wX(Jjz%ie{Eg zuaLRT<4*DkA8qxSR~*rDb>>5K`RM6SXJ<%wzaV?y10s-;qZ>ma1{mW2|HA-9>}pWh zd9jQZZ^(j`r55u44`}{sejCreBMS!fLz5Oi&u7^cu)%jpI{$*!Fj_oY%rBSMF?M-l zP6JL3X(R-N4=X?lb^_02`u0h!DRzJ78BE~V$G=7MWvSxlpG$2Nnm%M2773Egqpn?k z9UPX8Eh{rYhV;}7j3+m9Ng!pEM%O1%7U6lFWvKJwhU4o=@nQ059!=&2|4q{Mg6+0y zy1xeP?<~sJIOz7rCFYaMIQ{WcoL(%F&)gi$zKdwqs|Ze9a*35o;tX73=6cXYv}9$A z^dk0IM5|szaDJ6RGD2)}5n_;(5ZeXE5F2_K2Uy0=z4Plx7EJC*GQ@fXllufb67OW2 z<dvCVp=<?`M6rhxOdgCFOilo09&9i<KL}Btp34eA^ms90++cDNS7*xN>KMC&on%Tq zyuD!ZTV61^2MBLz1(TNqu~?Xae1aTMFgb*1y@Sc|*=%888Y?8^hL}q=*RfL*sfQ0C zCTM_Q@=ynp?@KT_N0uvxc^qsoIY+!(rl%YRL1^Sx!Q|ls4JN;BT?H!>@{ohcJJ2VH z(Rf$oV*2=1Fu5|L>0oj!0(*p$csm?Uf+bduU~-RBQWG|%@q)>b=2A-#Krl(~Kyu<$ z#W;yXX*3;<5l^+R*2iZfn@|t$q!ze&WVmOH9~nNJ`A%Lwv?>_7Hn~?p64)oIpzxsD zTovpVGo+gI4gan8881GD8c}oe7)A82+avnd<ba)Y8ni1P>geBQZzIKoH_`=E^*5_j z-*QL+^>|>QBHZQ+oi5PoZD>WFbz#{VdXo`I9HL!R;613o@GgX5XsGJ(gghiLoX|%- zFx>RDCXY|8KAJqU>Ki?$dkhR$*W@w(?Sv*T6C!FM&E-9UBhAl0+`#aztO>Z98kdUX z@_|rM_445X1crN3h?`u;(1GDPFnqT{9(7>24h+|U;fJu3bzry-4A+6-4=6Ca8^@R| zFC~GD{%C=Wq<UQ*$mqZ$S~&=e4=<3>Gsg{Ne88x<{R0{An87c;av-B$q2dNgIn@E+ zc5r)vjCZ_1MrNG|5kV}kLdEq5hY8-3Kt_MeKt__uPf&4vLmd^D9b8U5tOFT|(6)3S z<Gutka%8y<WR!?^%VbtAk<-YpXe2uHm^3<&K*qb))rGGE83k3!5To@BWUT0;%xL=h z6N|te*Ps4Q2QoT+0vVm%xc=;Dj(06oTz|}9Mv`KjE9UqU&yc6u*TIYrq@2P4v5)rn zv5&)9{N&~Pu08T=<B%o;gt@5(KW>VOYw*1TR0BH9?M{cewR;;W0@AKUb}!cGjf!jV z4S1?Sn=y1;Y_qqam4DUX#{)*i?N%rbjb7y02o=}ht1GRS9<uh|C-~9d?cm2AQ$qZ= z6WYH_h^PcV+ST2Iqki{rFu{*qSrahJHw&pqE-air7Zw6r;ZTAfeI5L$gCF-YtVahw z>flEm{CEgESqDGr;71+&sDmF_!H=bj)-o(spwfoXkDf=OAF&U@C)l12uasc-n%iX) z?*T?XIwM9uetOW+kNj$Y@_-O@Tr#3&&^}T{E<BhBNKBCyEqD<`I{1+n{D_Fgi-Z|0 z_>rJE=E09@D2_V#5h}A?9sIaI!H--~t{QW7$N`WY>25m8H@6kyfGI^BV3OxxVjnAx zt9eb8n1>zz_^HWfs@I=6X}k)<QJK$l=pz<>>T!aIi+A_(6AP?9p^v+9`6&r~v<#b- zy+}=H<IqQ=41H9@anzxYP_@w;IrMQ*bDz9?-*rd63xG7)H1rYeOI`vXHKZK~eMCpD zj&Cb^8#(F`aRtvyL`~-2qaG_gRdYts+X$+^t(<3f$kC4t&EK$<v+H!=BYR$Iy1#Ap z(EV+Dhjo8+4ELGRMwwjW1wJxl2q5vPwvYWP_|bUC!H<-vQ2~7<1kB?e4ITH`jeA7o z<oRrL+@p?r-06rO9rvi?9(CN~A?#!w_o(9@b=;$ldt}8uT9x9@%+MJm?$N@vTJpF@ zGk}(_wq16C-Uk@>=#LxssLNM_tmbw_PhPN00JwiV#JI;>M%-hdK_AuQ9)nS<S685q zp$2^%G43(YagSS!dsMu;28(hH{3wv_rl)*&tBY5+Ij-h4jr-UlP|atm+fdi8X3k3O z?lVw_e8gP5!*`!ZVD+h8z0q~<_TnA`0PIWu`qf0%xP{ti^0F7H_B!sd?ggqghU3RQ z?s&QDgNu6%c*r-@knTP1@m9w@HhLR9?lI(fiKxlkbKK*tj(hC%HiGIODn~{iZrmfK z`5U3Kg{k8n+4EA<{X?UN?jM>vtox&5xX+ZVozVRuGDHPoK!ZLqL=6CKK;u1v;~qn4 z9B!^+=(tB6_qbaTJv#1D$35z}$3xi3I_^=&J?gl}haC6#ZjShkU+9|Yn%ywu(KIX) z^JtPAlYj(0`p}?9D`4Mn?{oN~Z;Tec_%9@IvgrKx2OGc0uU93D=eWT;gIVpA>zU@p zFA^XtQwC(kV0LzdFZJ;D;umv@M9a%XOj9JZq&a-;C`Px6V)WD^IsrGOdlAKm*a#5% z**l8SE~6N2qem2@`!KGfH;-cUO&!I!FX)W|f!;4n?+~LHc{1KIJ>~mY9n09}yPD(r z1?(MWEMtS`YHm}#@zoKH%vq_Gu?yA1|1dA_@U157y;X2sJrE{nj2U8PhM1X|W5>+Q z%*@Qpj4|8S%y#UUnVFfHIflK-KU=%AwKEU<yf5dpTCGpFRMk4V>eeR|Egupbj$dW? z3<U}2$*ROw!%f;(W#a9$#xnEY7laqz=v?G2_YW0fI@tg?T#cCi9X?wrl3v+Tiw~X3 zArO>b`#F6lF1~h|z6!!f4ArnXClTCOb)7u3aT?8&Ps*qq#Mz6F;Fuz9f}FC`ZW38$ z9L5y1FiC@&Sikkf*qm#EnYY|W*;hgvKmMG~RnOg91v@RfOwVvz!srfck&v`<q9n!3 zNE97_yGl1X03S+F;pbe3mMG~~h;Sk^CTqbCjs~<~gS7g;$2y5>Q%(FDTR^}+D%-<z zqY0E4;yUG&z(4vs;rtH~Sh1Cp%W8;k6_a-WFcI5HhgFE}f3Y{lCUzA^Q-~!%Tb)S| z<wC^#HSC4r>12R}+a6Bd&&B<@C+6VBG;~vTa1pGbE5FZy^CFWz>oW+vkU_smSCF<3 zK`$P8%E%11;SF8R^tdA;L4jM(RElBOrqav;XM=6=LMOT4v*35TCo2`Zgi`__k5EST z@H=%S@}B~}o36GM3rHhYb^o|A<tXF(-9@RP1}?qF#ww9tCrBLeq2Ulq92zwxZBFU7 z7I1;P{cZ+2kvBD=g9XbS0t13F8fd7&OXVohSEPhd`VAit;A|#erR@_cr5JsQ=M$g@ zpCm?((dlff1*<Z6U1@vWRf=(@RM>D9_$xh==(=pOwt+;4{ixcr5#Pg{IlKpJ=bOXQ z@#QNLs6zsz9n-7|Pc+Dwx>atwz;E}i$Qgc?gpBGy<cEX=;lj|-D%g{XsBIGJ?~URK zl~~A7Gt%O3f$b<P5{tR>%}<kqYUfvpYCvZhJYXYSGDvirC9Frv@q<(?5-zPsCX1!} znqlK88XS1@QSnRjPZW-HFm_U&Xd(lqp_PUgEs_TW=<5u;uuBDeBj<p*c^cpNl`($Z z{zx5*;k1mrID+YWYm9e+HUUw}0KKhUp6-1Zx_(b44+j`Bg6I!*{LA#aq%_u#SIZoV zukHGKbW*rpLQZa4$~UsM;TR@Ke)@8F<}La2{=`x2+-O{3_U=~9x8aUHMqpxZiXn}Y z-t-G1>mP$J3*e*)r}r1AE9p?XV{WCiUEz@5&|9&MG<|#0OG?QytU+r1(wJ<%^MORN zsfCokK`5DZYEzyqpsq#~4Q97ias7Zuw2P8nRd--z{0>)XolCYfgO|{-pHm257NEFe zK=eCp*o+L2bT5;wLvC(blX&lxJW0W@L^7-7I}6E;_sStRYbBcfEe1J5bURKZ%CB<w zEhllBb&z^KH#6IWfR9d&Jw5@%#Wq{m<`p#oW~<SvC`02Ru;7A_ZaUda6!AX8tR1OQ zlr0ZLV*I#Jn^pc#TFZ<3)=&l3Ny?Zp%qnPU+89}k-c-#I3WuN4KBx#jt|5|3o&-;z z-fdh~7AM_3iD;~0@Ev*C&DlOn;my~^2XAbNleZsl)(;#cYW^a=q5C&ecL&x!K{Z-C zR@Z$J4n*2?XS3$7c`vujR|KAyX5E`x3}))zh!YyW2iGlSl~*Yv4R?P`t*~l#m)^yO z7jd|2e85BwGT?}|SR#bZ-eh^nxEz-PL<I1yjwyjJ1^m|$brHV`?)w&ih#$}5wBK_X z_hUVz_qA9QlXxCg9KRBQ5BuWrR{ouo*y#2Uy79QbZm?;~a|cfOnVSVOZt0m4n_?ay z;nlfFC{E&Z?&iBsf%qvZP#4X53@k7cly3oRt8mJ<V*e`MU3nEhuN7hzU+$>Q_P_5< zq7CIx#q!`v3aSiN73`O+QiWfewtqcL!d<m=Dqrh9QfR_9Kr}nEYJx#S*e;yHjb^!5 zQu4U=KrP-$q9B#&R?Gu(>492xz$~Al)-F)$$FYNoEtFX2v%V#u;mzMQoH+A^VvDr; zj!#wrDd;55-;5hOX}StYBor^up6gd)`3SvxVj7sf>zA)aXl*g)m?&TfjMY1TIOGge zNXXsQPQB?h$x5o(EmoZSbVy<3?IMk=yrImrLLY{_f}J65`8{XcdxY{!q%pxzdEVcz zaR1moy7gz7;K4Ib^)SntxHk3`y3}akDp@>%^X8Lyt8T#4#&jJLd@3-Pa$TifPPu3f zg4Boi%9t44ANaVrW6u25Ij9;j=BQIx_O_dN>KLTvi_O^kJ>GSb0K16ZBZ2JdN8-Mf z>_|_2rC>7Alw7PDHot%M!8Kp;&K^<NP1w{>k~z{=Vm>{qJH`!X?C)+Y9pIUq#4yC| z1(Zd7xQZ`=4D|A=$VgOjYt*GaMf`RI0thU2(B8H^RofnE>(mg-+X#M@-hij?o3}lC zeN5eZIxKP(B=*kg!h{(Fc)YpzpGq~O1c5^p82vVQ_bAJ)+#)BS;KO&MT7m{MqNE1; zh<`$v!@cE&OS1BDhKDZ$hEW02$hWzXiQ>Bh@36wUk`g>b&>mY@=)wd^izLXm5T$w| z!*O85gk`FqKSRri_YaVe;EAU&fiWyy+5@_xx(5;k`M_bVL6I*BHC#1^TnJ=SM2Zu3 zw5X!8xj%yw)Q&h1NaG;$xhF|>_cuaf`vWVWqC0ReA)Lu@#R;yGB!8qw!;;J0>cj}= z?BiT0|G|+WNNjZiIo&^$zwK#7j~Kj$iT}#WI-rQnw!SCAeXUHXsCRP{yl%97TDIfe z1-jrLfD>y1C*NT?ew~|buwbawH0!USio@usg0r3Vs0@y%cWeo+Y-h9riKCKhg+ZhN zunt9$_Gsu$Zka#n>k6>>eIJhyM38<Pp5nH|*gfQkB<&&R{z9EKTb6!Ht5Fb3LzwJ; zZ0Uv`7D6Kzg_r9T|3lQVC!uhZM%NyXAJAcEuIv#*-IeA(f}^5aIBKQ*0$e-&6DwM~ z*#O>Vj!*&Aas@<O)3@|A<5B22g<y178W6Jl{nNLd68v8F<{r&|Y=gT85%Lef7YbSv zwcv>wy}{Fbc->zHe}sqG<AuNIQ7lP@Di>Nf`ousS`1X!Ly+Ma*vR?^wbU0W;*F&HM zR0ds$++J~Xd)NAie*6JRmykAvR~sZ+=BEB6_8*7R3OigPx_inL(r*JdL7tZ)Cp!P5 zA8<%j^Q&T4#c!GMj$STKu~ytYd4ch6gWnC&bn}bElMTKpK|JAFTdkB)CysKI7lQ1T zjStrLJpoaGY|vZ<W9gUDrS1EwFF4t{L341c=JuYhJP5KiJtt!LR`#A2;0Uq;`4B;0 zN}-yjx9`PTaI$k>TECPs6jy#JEp1=izIXnsdg}O6YQ`zV%K7^r+CMB{YXn(2j{#Or zzAmMIh)9IlACK7(hIyC)%MbX?QbbDuBy%D{y$-c$B+S1r&QX|uTTvVOcn#7M&lS#C zLuG8DgY_V=*qC!c^onQ+mrNb~rWw9BXN_F9yo6?cr`DZHENmHZ6tcCWeCE&I&q018 zEB2GRr(0_h^w4g`N&Rhv`sUepV;}uBbb#kp1aaKa?dX>^-kB%yj{YNqgZoVd6%N`A z?e)OLO&F_YHDl!LzvOv%N^8@ti9J@SQZ>$$6my<4?`8%&JB+&%-aig)t*B3T#4&~E zE2kQ%+Eb;U>XVRIFAE_Lp<GsGHPo@d`Dvm7sV0vvuS1ie)ctrj_12oB>8CTC2;&N; zCQtYDTEIjMZ-pijf|cIagZusVmxG0=uao^Tv!D7{;<~sR+m8z!I;l{0<uzTZGk&yz zW@fwTywL*?l0P>l7+n)zhf2bVQKn>}4ZR?Rw9&m?QSC3UL>YNx+S-p<Wa!b2NrdUU z_VWZo{G<iVO=ampbcV>5{$np=1G1NyN5)`5*zVARL<x3iLUchV7U?En{mk4CFrx8A zOVZ5kSD@OZ3H+PN9!?>XL$nRDu)<Z|o@;!pJt{O!Nl*0HkuND|7+ZdhK|(l2F6al4 zCuD4NlxmZ$`^BlJQ~4s~Hy^D_b|%dBWdfiXn)Ga%ux_9X>hV*nYCQh?-qG2@%4;Yz zl7hA2Ue4Ts#pTrta5k2W!m_%-Rk%`2gY-S7TiG@=Z+rDjo^J6l&Xr4IjVa9_+RHD8 zH~5riSdvc`t4SIgd$~pNOGx5%Q{L%<>_p`!p0^+aJGYw&=l}kcDkY_O1|A?rywhJi z59qRtptDWn6Y=KcJm_(}zQIBc(mC<o=W<~0oi@4zu?!tW9e)@S)CqvdmemTz+-Ktd z{YH(R;&_T|!Ysc;0eYGIXPN>XkCb9QPHmY^YBE7F3Tvwda^?(ou6CXmFyRq>RvLIr zI^j{aKx;D@BvCtYICBPnRgBs-$jC^}iUwQ~$kVyqfO2*THGQope&n6sDV_Og41V57 z(eMCRD{r;<se3VtcHUsoEKi4NXydjd;z01bIyCf2wMz~I&K6Q-3#%{?5b#bY5i5Z_ z5iz$?$EEetYYn}ABh)8*vRzS#4O+b7=PQFZ81MROx$4zwxjP4=)p-WMM2RlCIXw;L zK{;N|y(zFftmWv13?d>mEy{IcUT`2J7RFG^WJ6g?`5-_jzOOvXGFF3wjY0Bk#}B$~ z;j~0}@*4b`Gn?Rs@<Q*@JhID%@=IUeg3LjblMb^A$qwDzi5km7h53HP?6II_$)dK} zT^4=X=x%G~((A&H2kO^vcbU~`k;VFP_1_O=mwvds&i`<6ZPcaS{8pt{ewbdY2qQ~M zB_K_UB@bk=ET7L&hT*93!NDm61ovs)?Qi_4#<;DMkxY`Q$khz>wE5u(?}2qWPrmlO zsk7K5vSi+TT8OMedJjvTC$Tz4gRox^yJF1n(U`UrWBWH2P1*CP@*z#ol|ViY{J7e$ zb<2j9uhOs!QWfm{n<AA=Nd*Oi#3`B=nP{Po<eI{SiATw(-;<B}$>L4G7AE`HsbA+c z+1y$esa3zs$G{pj+}0T_Xqv#F6f;+dd$jB<kGkPPDVa8r+K$I-jRgG=b0iinD|07C z0jth_`aKCKKdU_DuJF<jl3&tTa8Y&1Spa@WeoX?Z8vwfkOD?KBNo#l96=YJ0N(Ku- zgWmzl>TK`4;<G&_g2J~esZBLwE46!Z642i3wY`?+n?FKSyyKV+ZB%CYm|%y>0o;8I z-6>jQSP$=&6*#vdc9t3)pDrpFJEuCKYc-<nTPiAj7isyw;{X6Kj(F;xX5G+7WNJXD zR*gsn4PetsH-Jx2SEyLvl^PooN?AH(hvzBfY?Oc562K2qCZVRpw{HpXKY#TCl)w(- zs75oDhy1QCT?KwG9+Z7_kDv76tIo=swN5+%jd_YoN(&FlAwI{R0B3L=IhAGEe+n@K zXFe5RaY+fiY5GAq%GQNX<#6v;t|gTTQ2J%1BbRcix}<c#S94a*oK5sA7f@XaI4eK( z1pJ?(qAnBAXsi66p1_w+#XBT)WAB1Q(-f;r)QRso640rM503Xx{{vmc$6j)_K)jd% z0&C4xOobJgPNMu!l>;a{wW%nu<iFA>FFUP3U+b>74r4ssB6S#p0&on00NkAHJ;7S` z4`DPg@XB&!T09jVk;?e*CBOj;PMHLZ>c4-IP!lC)nv>E78=3CtTO!kWKjO76C4)Y> za``@ioWUrVx4z1wS8qB>IjUFVaF2b6rjKo(Rx$0I(gh}(7laan;;K+ZmF%4E^lCMY zLbHh?s4@7ttG9Y~3NFPz2xHq3|E|Ied5aVt4flhBP}jTDnQ*{q?EF!fx#k{Ln9l7h zhHqj!7yqCR`zV-(rq(@v<m?y!P(7YCpM!GPnIo8HEWEg9GaFbHmgaW_swKxNnOKXF zNUOoN>?!C{o}-Ka<zGeEk~nkS%;)hbqVyF#|7?O$9+ICu1`m__*u^wRA+8;3M_nF7 ztXLfSY6R1kE+{48C?YlSE`&vs3!Gic{MjAQl7QxIA{h`cBZ)6T*oQ%g6X-3{C1IEh z6-7rTi-p#IqEIFz57+rHDWZD)r+X->Li@<+7Xu_A;qa-F@OcX=EWdpGH<96_wJ#Ey z6t!yieVc;AO1Gg=QA5SVZ3V*y&*(MZ2tfQhib40;{NHqifk{Ii2t+lY`$z_q|B1UJ ziy*f-Bluwcyf6m)KZjZBax`|>sK4FjiUnfmM3Y>3k)_WB77jOvSc!*Ats{#OM5KEK zB-Ge14+SOG=nCNl?RAfQa<|Dc7h%XGomr8QJ)uf(vOc$5H|cNsv3l$+Blkbi?5buB zJ`z7a;mU8aHY4@;5r*G}PekvWVx$i)Iy@tRs&1mq6A(sN<EVY;DuFyNoG*}wTUDVT z+d7pk-!>}g6jPt|iKiZ^Hpu^5dJW$KmtII31ojc7z*F{3bHld-N$pXzcG%j*K8&G@ z!?zczI2yUG`j*BXF|-WlBBWz;2(0xTwK?LcOT)JXUvM;ZNyn^=Jrv+#X!V>c5)Lxr ztc+h2M}hXgtYT>8+<+>NDWE|ps^~w%7}}bI1Gf5(f9;diq)Er_cov3laWp=z6ArE> zC0QRmzQ*Wm8B~Zm^0{lj$bTV_Z;%Y2VHmI9Vz2f-E<@O24DL2v8%UunTtTe%ZVj;n zfo;A0XtqDN^SFYo_J$suV`y7wBh-G`J-ktnfCAjm2r}NjeIrg~WCxGF{VupKk{yR` zkMXMktb{Tko^pthU_R^kaAuC}4`&I(P?VMp93?^&A?4D}0XgT@3#hr?PRa{AT(gVP zZWu)07MZ_)z6`(DG-NI9BL+_;WbG-W{((F~14yiuGTcvj(H=uW?yx2h*WVzO-jxOz z-7Tk(*TT<WwL$t%j-VwYGBQ4I5+e8h^>!*{mx-<NxMrKbAP$!9ezG0~w=E6P6Z~0` z;my$-ze7Veo*hq1i_2A&O!>=gg#|^GSPFx!tF4WZ@snYZsyRCT#*?XwwzXFJCfcsy zZ0tV$^@4WtWBj%AoL+Jae&$WUFDlI;^1RG18$-|Rg!|*PP72fGdyX)YM-ckL$kZKc zZi=Xdv+`T?Ma$C20eOKAs(1W<Oha^zx?)Dp7M+?BaGvn)2oxT*7H$w`OyYwXei3FN zY%0y~J|Vf8rea;g#vkYxK~D}51xl;}_12%u4cc3Uo#Lv@cQ@CZ_ZQRooqrzKCXp|B zrJmBdK4hFFefWAb0+0PF-CFWYknUZ)v4PQK%e%O{0p9k)|2y54<nuqeD~OSzF*mgt zfc7+8BkRG`l<gk+2+}v-Kc!4UpI3f3UB2ms_#%JVu5u3wlW6}ZwyW*GY*+md_hp|i zTR&?~55Gr35M0jJ>(Dq$&pqL7T~i!#wA#G1;6fa`;rbYPh7xkJ*Nf8rf1$g=1JYgD zeZmFV?9(&!W<dA_?P43_ZTH`DP8^ye6rQN8^jvj)-bma`3#dAHqUh->$78C^IASwg z59+!Qdbf8D;-_|{$D~cu!S;l@)@Arr{^~vuiv)4Sz!jf+{`E2P2C!DOem10bGjE*n zOh{pvU;FHC`HcUQO(UiMr?oVG+4zqiIj^_?ndBMrz*t0Mp4{D7Nj1p=%rE@k5rqrf z<UEcG2bm;8p{6>0_xu=UpK9Gl{ja!*Tq&y^hC>>51@r8UnyFLnELEu>qss*BLg7g- z!-or2r@vT)*?T(|t*%sRn#yW$Wg>P$J|};t^e$zK<r!uhp_wS#kul^geZpuSpB<tc zd@_+wB?*Z{w77(<^ESty!wVfTB@Tw}t%>9e!45H5B_q8sF8*?__xr^u%g#GQ(DXK? zGd=Whxiz#=qjJ-yGB75D$!$${jW1e&Jj2pY)~e?7+u^eptb9dOuf@8c0C#gQ;vnIN z=~jSezR9FVRn=Blvu-wKd+|L9m3avL@jOdHcO$~<`O0GXlFyw8|3l+s)_LBfmz%Fh zj&b|X`_qlCuy(z(j=tlL0dN8O(wl~J+8?%96*BrUi4U+tIyLrhtP|>8V6pc(^SN|J zP>o08*YI#H_M~<#0S-iQ=OA9~GD+Tt`8O>0N1F<G3?H{?4GjW?U7PRs)yg!5a$v>N zR9xYfeUDohvo<5vfq5A14r>U({OgN-#>6o9!if1UtNy%pFdH?ODdjjA*l@58q*3ro zUw9owtP@`L3!$2ZrA5GoYv`EqF_q7ZtHI&n7;j+krkCi~6i0vA`3_5Eu#Y6Zvy1?f zlq5@9J~wUrY?6R1SRd<`YsLsk(JEdpEJ@?N5xhd-6^z@-)NtBUqxH)tg_=H{Y7Z+A z=Z#+ByE_Di(RU4h&YLHvE(?)f-sVr8>itgdbndx6YvDW_HlO~qUNvo2KA65ZwbyX) zG;P8M5z8Y&0CxSm6$G;bjWsPcA&cAAl!wlrW*=qd5WJ_$<pS}?dmNAFNwByJy@yLX z7ax<}=N|3crZuWtKKX6^s_u~h_g24sd4F$K+<QWW+7~Cr|L9GW#@n&`Mb->~w-eVY zd-ljvv38XjX{|LB8xV|i9N&0u1V<{f(ML6ccO=43(Uh8fo|o#)GF76+le!8Z@6MG1 zsrn{he8t&?WV!a=Jtl{C|L!qi*CTOI{`inPTXsw6)o|RXiI&(DxBE)Gr5Y`%D<3{` zO5B)u04^Yrw;M(F+gB*2sJxG8=Se4VvWo~*eI%aZ;Ram5Ab_vR*OqliMdYq?%C>+? zaX_7qwlE7xvQI<uKe94U%zW%Ochodi4lGt%0VCgsg`H&<1DmOC5Tg`D`s;^a3lFjb zFh9he$LPWfY?~=TaATdm{De67U(rtItG@PxocNU-0>(1pYs@1bE6jcsk5}~SOrBd; zJDp1y<08%akE(XMdTN??ufM(=I16HZrlJh`g*TZ(6^@gBy>s8~*?C`4(X~v$j<9@- z&~uBXhH-I4C)V1r$gE6b5!?V_o%wu9Bkc}qMcWvG>L&U^eYZfLg!$P@X0o??KP2bi z38YBB8=Ot!i_R1fEQX$c?sLxWfQFLIwdcKE`I43oLoUY2nq(azi6aaVd|ok3MjQd( zpALml*MV=JkH?an4C4_pKL4YBci-Lb{+>Bzuh_IgN52B+q8oH)iYkgg`+bxs5bFIb zXo^At!xQjgMDwOlddEc+j4rl7K1ALRMmg@|x4kPG%b(^ND0JHD0tJyaE8)L=D_0E7 z#SG3E^?j0jf@IC$Ym4buc`19siI9EH{Y<!5%weKxGAeZ%`t~tpT@}0)uz`hgCiL=b z?|uDviYZ3NGnirJW>zb4r(spj{+a>AZ-s!k<(sNe{ab`@VXXnC@jCkPKT(KxpnuuW z3)7B$6N6SX>?RTQI&=*bIn{@93l^am_i=dMiuae{MqEE4p^~lSGNwg*iGRy3`qbDE zoug(v6k)dTR&yMm-eDpRh;IDOw}O{F5BBF(Mz5EFwBpyq_XOZ3G4hg1_Qtm8!rhrM z21EbFmS~HM;aOqnUGct;iziSp+jn%&83a;Gt}H-=r4Hk2QN9#&qYO$=CP9}D$bLk# zkD}e6#X4t+Mj3l>jZ`0=STl?0(BC{H?}wf&yggEQHG8s2pe4<u`WNli@q2nU&Zr~@ z>shtb!&L}WdEe;2q#NnvWd|T;8-?+JW3Pvq1RV-~gYtd0kw&bn>00lhalkFQ<pOS2 zjo?!)$2Q<e4hUyfToz0n<rNHYFOK))i3DYo7%?k}<Ra*RG<45&Kb5&Ee4va=U)sNF zMqL4lEGOK@nXIF3PP16uuBBxAVJ>&(<|+8?r-E5F?Vre4_k3oeTX3Vz)NJ9M%=dq; zhwT`)9ewpngL^U<j-5gv+bng@cWK$s@4S7TVvcc0k6Ui%y6c(H@e;(OnecAOd~pqZ z!J)jIUeKfME0b2Esre`{{3UgXzDCO?Q(aSdAnk<e1h2&`a`qk5?f4giflo9EQ@Lxb zW_>S%*28*2{g~$KMc{n}xZQeBz@lWOeNSx&BD9&hQ|q5A`a6rRjY;Tn?#dy2ygF6^ zU!8V-UllBQMeiyb+2cJosMhkqk=xM05$aYd#`VZ7Z$i9DBgx6FW;Ic#IYhizm-9Fd zPAMVm#K<Y}xH9K$+>knN2Vh#V591~L9VFWwf={vLYVkr_S+_T{e>6h69NcdmPT@0i za=T-%`L|P=O54uv5rb5gTuRw30c)|<oGO9bjjH-q*yukdx0m<EfkJq-Vxg*S`tADB zL|i;^p7p&$Nnn?(_uXp9C_nE1FXonjqSlE>^9FM+NS1wORNj}pp-)`72AI&QZ!h)_ zd2eG9NpD@j&R-P$^k@qf0O}nmiO>R*KP`;lAsNMI-fH4X)V^lEA{0ElfbFTEdA!_- zw;e>hxGNUj%k8pO{ltxA_=<lWTF_N#DeiZtx7%6u>k5|}x6AHngxe_YT`4-<Id?-w zs!8HRY#dS~n4BCLheq5|bx0$-nm{HJVMaUW^hhEp$q};<@_nn4XPe>&D`wt-oi!bc zuai~G-U{!YbfBeFKl#Re818ow(V(-eO0~H>dot;YVux`UD+;>2eTV?mn1g$qH1oR; zQDC$cbplA~ZT~(z=(rI5gWXk-Dct&JiF7@J1XGerS&UR&8AngSzyx|3Th;<tbM<1J zHEp|>a=nlGLx~pff?YNqkcV{c)NI!+e&Qnp5tnWDSN5gBV9lO0vLQ}U*m(tiAH6sx zc*Kt-d$8u$dGnY$ninY<r8%j@GqoAkz9re}o;7Eklw0QrxfjK}4n9iF?^WWr>R~6b zJqgz(`1(OuevWjT_gFY2EcL%0Xl3KRrBs%xhvm>NEfMY|b7(YcA{2tpN?TIbdP50Q ztB2~y_b~fFQeWTiFOE$M=G7NswTRb<yG}N&R8pXitzSgzT6<l8JBvSdnd)W4cvdo} zQNZZc7ZXRI%rE&<Nn0Lj$s})xuu$sgh+t7wKYg_q#Tk><ln3rG&njm57;NCKS%R=k z6EY=|0s6h493>aa2(EpDw))MO8D#C?2j83L2UE;!JJ{~|jM7~?g0^4{sE{o=nb-Y2 zMAbee*|orcTzYVzs|4bH>07B>8jT^YQEXyvBIGD3XiAhom$u>3g!Fh*%%Z^f&sRON z+4N2yAQ_dQ_seDS!B>M#6NSR9WG1>Ued#%+MCoS1r9GAsI>oOUm2K3~2bAgDe@|f6 z<W66bvK{u@OlXkAdutib4n`IR2x;o0vkb9`w>NM9joP{?^7F+v|JY|iS&)3Cn5;%& zZBUbZ<&rW>O0)WULY21%hL8B3MR~$TBAYB8E^SR|Q!xNsW`D?5Cp9em)D2lxOKO03 zy+5SH9cK0S<dDtBc#jxHvC(8Pw{uu918)8`z86Af-bN1x@ZVWK1*Dc8qHc#{`y@ww zvHZMcC%pROj!yd9F@si!XZzkUqlk&h8FsVilTtPb)1qEe=q1AWlk|rBe-7SuScN{q zB~3*SN=z@_ncx)zQ*Rp<w!*bR5nr$qhXkh58XhLHj4}F_w!`AA?dK<h2>%!1Ta@^3 zr^U^ReA~<@W>{F5>$~`0CGD>3-;(@z-EjZ^=<WX|ddnA~ii)BRaNS*Okv7vv9{BH| zui4G%%$#W(`~M?&D@m}X192<t6W|hdCGaNw$}5srIF=59!si(|X4^A$0BV-$#yL%U zH_4v0Gx8R=-eBq^T{VaK>>2y4V@3u7=KlW@xs9pe#MzNxr8e^ksX~c4NYrHLe0LX~ z9h?v(M?5iapAmcBgy3Xm&xLw8*5LNJN0YF5r_wOf1Ml^fRprbbZLAWQNLxSZ^6AAb z9=!&2rVF#9Mj(XZj27?~gqC6QX2sdQ9uxiPx7$y#mjx4hzO&C-S8}nsCzq8|vy{WW zLwsPNb<h|$e>AaIYH&yw?rP^$Q8ij+nrHIo5r${iH3=S&H@c2)N}Xa7Oo}#l1GCv` z0;Gb-Pe_{uEmdqwJfGQ+EbbMIeoB;5DJG4{P*UkM&dvt-nW#BnTzK)PjKD$JRz864 zE8$}gfsK@A*YpUF;is8DCCaf84Y<>C5e!_Croh%^5X%##ln(};;-*+WrOJ|rA1hI= zEjo$1aI5h3dVMdg=QQb8e>LHWffh+-R|3RykBp_7oJ2sSD2A9TC<UawjTZNU%aqqk zgJ-w?R01Hf6vJ*mwwEST3%VwQeWPBGEj47)BowAj9gtYTiq3bTR&7s_9WdPZI8ml; z)5uq<bEa0URH`GpaHdX`9YA55E?4J9|50ifp?R!aS)i2@IpD2bYM7#^T533>bEZuD z>#xd77l@io^v@88lM`9|7YEqBpu><GJ!-35c3`$#9f=ivY<G!Qe?yYcoEoFFmGr?n z7sDtx-;!Rn<{r7}M#QPkemr;g8o|%av2NJBIUy=UWMMFmy|jeRYLlHa#J0h>(s8#v zAzDnlaJah1mdxmVl*Y`Y0qhO8VyP=T1(nl;i)JXLDRls5VX3w~DF}W22jXH4X^HMT zw<A}D9#TnmO4~b%$REAQ(N)is{Ge}UCN{rEr#sUc>MNm={Md}SXsph-in%`l1UtG1 zdK*on8Y>;q5~;rKf^BMU%3L%O8L&vKPp}EF+2uc-Y7m*9Mpri0Y5WBQk8~AuPS<Hz zYJodiIbOxR+1yW3N4iZo$LlmXUgYM5PBqIH&X*~ZzfoK&oob2@oG%xGQQ*0sVCRL8 zbkR3}O%M0Dp8(1A+)t60nn$`be^r}zz|s!HOq<$2w3EMB#ZEQOm*@xRb8TvGvMzrS zx!=}lyh9eN0!_dT9TE8+U^U~Rp}eRL139&ZI|9=Z>K8)e_HYLY`N^;-2s<HV@z!c# zQyW5pS-$@i%k|&4rn&)SKea}vT_-vra?Vs^b#7R#49ayd)BN<MP<1kTVIS^bt{A7` z0Ws6%@=EeB;o`mnxE(I!QfO<eF^D=dz^H+R$g^b`or#4%{$5ULdUzFiQaZQnj<j6= zxis_L6)QtkOO9|ML-hgrig<4HFw`4hqDkCz6QJ5=X{t#~eN3&^O|2GMUZL%v#TzY6 z!w7yXO_O7x!rRuKq58exgj$Vz4zMC@rYWffteB~ADM^`Zv_w)f(>(cWw~*Y<Jtws& zXr|fZwV0vWJLFQLLe=D4g1*r-*;vpH?05XH$|V$NeR;<{2YZ|_lc5^_g?ldYuLT$f zu(XluQi5LLlw(o6D*F#soRE9Y5;tw7O1h%`PR@aHVU$@~=KwbQJ)rQnvQkyEJUxu= z{-`{yqe*(Z@;+>wDUDb)yb~}fWa5gHw=oAtZJ@)gXb_zshNR`vJcgzsv6-F*th&zo zU8zc%gBJK03o6lUJD*V7>b;Z(q}Z(g04y+&mT0~+I|7A2xt1n&U7ORnrJ5_LvQ3Ib z%Zon{E_?tf7stvK{KjjZyJfOX010<Ou`16}&5dToDs91tOcCj(U&TOib7!!)H%O+* z(W5jou&Sr9Qnu;zvCXMmm7R!Ap;Yt0s#K{elG2T9VHB6oO}<pKN$W(JX7M6dwka_S zje9|=RC56MoRuxr1nL#Qb1aLMs+<8SWg)Un)V~(W{|+ZW1sLc707qE12{^*#svSqb zQXfpgKSSB3*>cr?IKcL!G$l$^&pD^cG&z<o&*iEu=gKs4<dJ8BN>$yEq3}zJ(oOY! zI#NxJJr4<y`{;IXToTvHG&K^F3N^|!O9Xza#LlbfVa>^wDN|l*idEC*Xl+euFl|hV zRld}Y+L~NyDf3MlFx4?8=ShwSUPZrBu6T2Uzq}m#S7^1Jv(?xcxltaBwwIo&nyk*2 znN)iohzB^;e7HEV<t5{Ecb4ecbivO2F4DtC%D`=SU>5bt^KW{96@5zdH^IXNJ5We5 zUzfru{CcseSPL=ZeF_|U;d0p?fJE!kLNyT#dRTg(m|A<F^7RarI#)T!CP7Z1%P^I? zwo3a12sh-9Qhju}OGnsLaDUi2Ds}4da-~{lSk;OE*`8S{^+0xR$fyn3QvDM&T7@B? z^{Qa0zRb6tpGviYbU?G2D%l=G{%WOKDXI#k+T&^$Sd0yzYL~A@sTNBXIVZ6AFIwt9 ztbcte=rZL54qPe!MXc<T>*-Z9-+-r;AP+wiWU1XAsNQx78-=HJOJlCxZsQe`jhd_Q zj$ggr!B$6XRb2uS>B`n96Es=$Md=U|tSWv{1qRkex*e78Aait2Vo8nl#qw}(7?R$k z#~`auyebumW6&$Xh`2!OY1^!EVx#(k<G-`Z+}BKL+*Kb#lP^?HRwqt9qY{l-w$jo) z((!Xjj@5<A%x31>eQF;vRvjL7B{3cgu*(^&wlCj&9Pj}DMSI*obCt{%Y$EuFPiww+ z!(SF)qa5_9MG&<FdLc$!CXxa<n+-GZ0*1yI_7eIWVI9?TQMfq&bUpxbpvmoEmed@0 z|6s{{DmBEHBC8-0D{|;=^`C-&7>7}dJ`zV3D|ai#J)zYr6V5uTFU}2kJRYBrw0Vcp zX0$JOKM=Qx(!MQq!Oo&|Gq0&8ugqf=JGL8V63@ztIcB|$rftms^ct}PKxM#}64;J9 zNHQAgX-vw+9+cB@qC%VX5#eK=(Stc9=0?rm<`bwT%N5b-i3>^2r(C6;+@AGEd`E+T zjGz@E>P{!y9eY`%8L0O?ySL_Ipw6vmi^)?Rr!XOqi)))ejNxCWu-88a^MLMJ$R1>< zq9j2&WCb1&k=>(gYSi`U${yrU$!I_s05r>}(t?pw&@6<fSEVP3nOgBv&XlQ?LKOMz z_}JqgP#FL>H>G%^ct34W558UiGq<AsD+00K8zo43A|B1TLlXzU?7i^<AHStjsCzk! zFA#(^y^gd$=>+YYB_vVg<UCW$RQt)!epcERaJM1)z5K`K`VggYIX1oD$5qRbrILGT zJf|@VC>jXsFTg>L{b&upvr)tE5X@K|zuqPNDsOY$WaybhTOgg8I-QNlNK-NbPey*Y z0_nL?!L<s^A@BX10^aA$VM}___c>L%{g^!=>AK2(m3EoIKV;!1=Urk~dO?<yvGR~l zzIuo&sZ0j2ar1q-WB}Qe^#3MbWGn8<o<I&piv}AaoPS!bCLo&Rz}c>1d+j!g`DT)r z3NO!`t!>1UL)Iq)(TCP#>70}ERl{OB8Loh_NW19wgD;5v@-TVy#WEQ^-Z{4@A-n=Y zKGz?kPty052%gN-lJgnoofN}H8yL9*i0y0JaGID|RR1~8t@LOMElQ9M^e7~lkuBM5 zkY`O%%<ER%{^%hN<S%v1!PP`WH%JKK5#@fk<GUDdK{C(V9;1UM07DAYk>8L81;+!B zAUuUUm@N(m4%}H{Om%xs8T+Z!a?#Ot6gOj^+<%^5Z`0)Lk_qXzx|I0epWoZ>mPR?c zstTSDW=2M)2G5d`8pay-)$Y{!xIFHNU)X$(>0^%=WMwa}uHvp@_RJl;9A94c@3NL8 z+-{r=0hD9zUt@Ro9C&4OKM&b`Unt)U-*`TPyb<3V9zAgSJDK~GDG+=`F0QT>SbQ$N z2^oL)TbQ+zt3Mojc0l>Yl-j;exqfflsGX`S;8!gzeBgHQK_4ANYDmy2e;BoW?7K6i zN9~9FD*IhdqlMB0rKa$vP}o;?D}SA+AlCNHg44r00dG?_fsI3wzeIqcucil1CP$#i zZwqSYLg%eldEp#%eJ@I*G5s|ujm>tV;wtMkYR%piP2vu-sPF#j>|1Q1#X*InJ*rx# zdi=iwl~Hlkb=vqL4NSWyaH24#Y9Exo(D=bYh3&zrGAf_#qS!l6>v=csHzJHLDE&Lb zX4i$s3V&p|@Z(Z~Kg*8J={g--plxS4q~G0l^+@yYhV~f74vy(zC3@Vwz1V(zJi0b| z=XQ`kZ4`x_e2mDtvmuHrpwzqy3*nHe>xUXJiDm8$<f+_GO~_aThgX^itNKJ!elYT? z6o@gv4_Le=;cc6?v`U$;;Yo}XXzU^zJ6ppH9dGsjC??C+BH*CP5NJxN^ecTssY*_W zbEB+mG+RbZW1?5xZMQF%4rJ)rSLcdB2Ll&9{NwRx{|vc@URe5uZWt1`#ht;+F7|SA z;~GtDU2+_=cQo461wRP8`e(0Q@P=tAP#f=kMLh#`4a}z0-1z1g5x-SqR+4|Gs%rUe zmM+t7Qv0=KO84E_At3q5s{RZ8*PvkUjo3$RA&Q)c3vN^ta);bd(Jo5VRPN=uPteRR z1j4`@B;#KHYV+CMBl~D3F+l|1aEu)_*07I#XOzv!63|CaBS~;X+fE|=xtdx~GJ9$L zAqI?8!@DPg0<3b7+u_Yp{7my5b}*3J%+RlRGSNvTdvM=}f_sNpx^bbPrL{5nHyfM5 z2;;68zCgrMZX|*4Fm~S<y#*#YbX;xUP|(O%Rfazi^6CoM!g!&EmTvNHf8+)Yu@F;* z?JcWz?|JPn5AHm+gyL;|xuP0nx7zdngTm$8KJ&S_I`bI<IpX3#@XghG&TSGF#wJ3- zFY);%Tt)xcK7!CM{`rPtyIyv8h|-DjW^azt4O2kZX`=^Hb9ZP-OY-d*kf*pi^yBS$ zk)O=hyD6YQ&dvsCNAByb1s*}j@Sg-1L73-CbF)_-2Q-u(lX`o$TtX4(T&?PlGvfo= zP{|_y58ICZxU}aR6an4cA+-)e6yT<1`9Doq9O38jmeG|vzOb&7PJ((hB_eU$-fsxv zeHkA&qJ4+$T;vzdegmKg!<OYAKU8Pg4nb_^isgz4{bIe|4oWOn_BC162v{#bYBM&N zP&ycsT2hA^+YvIehnj8!54P9quzx~qG2nep9NSTh5K5X?%*tm#>)|R0M--ZgMZyYi z_&wa7{?az|u)w0%oc<Rabnm*kHrI}12yU*t10jm0Ee;ij^N)VUIh}6ZM$-HPUS1C~ zL0*rI;p=?_6+F4kkYz3?f9O?kpu1>-7YP^kCmji_)8z7M<^7O;VMnjA!r&=yjS-R! z{T3&>KSDB!si-!bC7NPaTNckYGmy?WG{Sf=U?O8UYJ|QFso>bcbZ|kRemf~kBsI%; za6?_bGs*+LJ9;)USyG}}WGei|BAim|I!k*F`fU@Zd0hT;$n*BYhXZNFWbb>@L(i_v zB7$g0QDos++b*^RF_#1CjB)!P8U&p5ZFL0@HWRM2Gmh;^*X8hS!8&^<{PReX0aOlo zO?f#ys!npK)>(gQ^qiU9Vr%~xFEx@u7Hh8};Sic6gH3lX?GB1g?PdDDRUV|}R=4)< zfp#7QOuJj#a4Heu-4@hAKIxcn!NDv|)y75EkcveD6k~6dwQ%h@WQ@ctm|o$TtO)vH zJg+ZUQ*qsr)(9|I44`{%aIhL+gFm|6VX*w5Y5o(xQZ_?G+reLgfb2<*li;&$vY20D zYRbnzTXw|wxMGM)I57qm!b!v&iPByoS^~#>Bh|?OR5WJFU@1%_c1lm^Euin`kWqQI zI8%Lu_>6NT>wa#*Pz#zfL*wm7;ZViUuO*Zp-{2L0dyK#H4aM2P++sx<dBqai+2A>R zGG6a-AhvgzytzNh<n+g3h9lFROMVr2GcXud%RUKZO#M(2i+_R#S?&~#7chqK=+;bt zz8zVYgm}3h!55Ezk`_F%i6CMi$wm><B^h4A`3~U`L9{h1PBJ{VCizcZtP_ntVvmQu zl@enD*2=?05CL82>pswhAYOnj1n~lNAt9g(iN*t6=<EJp7a{__$pbq?<I|vT{{jDX zAs_=``9F;un9xULu%TXY{_+4_^Y?E{N@2jC$OP{SOdAscCdz|;A)V?5)x1GuhbN9J zUx5zpFl#g<vBnc7pmnwq9xmP6{0i+M9rLr%mD+vUk9)BT%R{~T2V4jJgl-xyEjW|_ z0oSjHq&nLBnMe1ks9}y*Wz45qo}>tq3ayd;*Cl@{^-sma6I#S1--nu@@16B4!wO=I zy&sf%_~k=@BY=&<W`PC)`&d10tkc@}?%r%AovNX6wyYQnPPDz|gs>3oBP`XZ7xHmV z_QVyzXr6FqTCcsAVlCMr9GBgVogyRb9JpHVDhk6k0ywiIQz`;^lEoz&<5Dzj5YgQ+ z*2-WN5Vtt#KJIN++MpEX4P=mvQ1ZFjSxPrfgt3Qi`%h+ssHJ@AzC;W4`7g`}KS~Um z8WSwk?_K|sU1;ZOTM>+LQWX{8nGxXTg-Z;IH%3`$PxqJ+Xy)pf5h_-jr27D_G;_7; zQ)8^Ok*K021|zJr|2hFS`v;6(lP=w7=tezPYmBqFQ)=L2LS|4-VxSF`84NiQ*0ZA< zD5)OWE+VO3Jw(H+MNTNec`lEFQDRC8)GSeDNmwsWj|-59WJ&f)4gCfx({bv^XjL|( zP*i2+C?0mI#WmJ@Tg!;0;S@_xG<3*Mlw(Ww+!a_Ps|-aOg&wRi@z+uy<K}1P3@1(s zm+H1NDX@Qw@i*+gWd6!l+Nq!uc1@!7{8=Ba+8W+NLW^b&PC-kOhc6zio+Nfpu5R>I zht5tp^397n$-F7@SX%L`k#$hNcA*?%pQZ(Kcy*Q){4TU661?GY1$Ucsh}v99vqh8n z+#zBhI&xv}u3ncO5zRv^zzE3LLGS~gL$@6FrNo3Wif7TeGe`Yf^n-VAfwDDpW!dl{ zGV%q6Q&&~OWjfuOia=3=bj26)SWeWFH7aFOt|-bBjlR%fYj)_8s$T@<cs3actENS4 zkORh;jOZEqm%F3xdx)J<%8OKyhB>Yp$IaaL$m$qeE*V+Yy(=|EHxuC5e)_K=cb54< z40{KzKV~*c=CP|vhng+Un6X^XJ(HN*(Q%7&>KC^ljtK0X<?vvJ;cW#nnJ~MFPPOK^ z4h<p;^I>rCJ>^uP?%=;~Jcq6avK=PREG{J=G!s-}5Do|?O)^EXh%{U*%Vym9x(dqx zcYHI~3_cygI9PW`yK#|~6|Jq@iH|ggS3DayY|Jg4QOoHY!zI8{DNr*lWi%0{Veg{Z z8Jv~W*K?Dp3*EVYq;To0n7YZE7&e}1(`6?Xw4~F5!;}f>Jw8abta?99U|(nJQs_Y0 z6%THgYQzL!H+6z&K9-o})M>HFrr2;A-;3yeT1u8$Jq>mu6*OHx-Zx%p*<VF3?yR4f z2VMQ)UKgX-*Ru>lIUnijhd?clDyh5i*@Ccn%iVA-<y?me$-mdg#&t#sS<jL{bU#q1 zbK3&<K<9em&H!HCmiOuyl4bv=Gm2(i0cuH^Vkv+9CU~~z6s0KJs@+t0t!JXOWV#n` z9OJu!2_Vm6x>Ay698%wZoj)Vg$X3bf_2MK;Nd&u5XkF2J={=q9OHdMRRYl!WV)|IZ zNgOa;73pW_w<9jZR6D&7B{=`0Bp7VUda-#QYW6jZCuEh}bBq{<L4t(x!AT$YqWHcj zt23KO&=%5+!^7<yyG0RO&>Do0H(6<ck<3Og{Pv$~%e|o|G=YN0^GN&zD>~y!3bSoT zh14yx;e53NM~&ZBb6GK$8?0<rZR`DWb*2ZrOBU0)jVI>Hz9>Rfle)VVSpBYK!u8fO zMfh!co_{%Zp6ZFx2VI8ni?m6GX~<UYOW9!SMBym~-I5HQ0TSE8DtXCwdF9|s(${)` zwIGO-X+mRVDt`<aF7glE6;eoRkHUjnd-uMTFYP1T&-{zp8$>m&;Oz)Cc-gO8zIf9L z%K;(bs@8F!=8!Mf*Ct`%i{~R45B`W(teQ5<JZ{8Ybn`Y@VmLOAh0cPw#o#=C%Drq~ zkmcfu!@#4q8|xb?7mLu1iFs<X4kDA<{4{ms(b~c97FDV*zx+i1Rs%+$m4zSCd^i%c z0}0p)@-VcOm$^9F--&D!(s@3Z+g5|6pJ!)c_r2A(MsNYOsTxru4B?sfz3NRyqdlZ5 zOtEmUk)Sd9V>eA*Aioh%ZONN1ydYMcvYwxe22RlCtL%z0=*X&>Ic~`ayp;k4?nkR5 zL=h2rv)?2Rqb5S#xA5G0HP%Co%-u(SW7Z`O6|?K?uQC^BQrhP@aSpH6%tC4l7!uNX zy3jEm>Q}p=$kHFvn%+ccdq10oEqRpsEm)S_)bTk*>KHUPq_e3AmII9J)!fNp^$Wim zQqxw?V9e~D_uc*K@3rNzPQXvZKdZmAfjaj$h7)bstw;!{HWh3u!>(hT<Q}&Va)}5T zK!|E3T+i1g$04N)7NU)AIA_gvVOiBrO{CFh*t>5r;2aw^(?^EewU#;u$u>Fndw@KI zHV2RMDbY<+PiMD>XcYQakql88B}8MZn6upD$|#<~_XXGmVslUr7=9fG+N6fpH$JQ0 zbv^*J*+u?6EiEnTAKRVmhfvrxeTYk@@DPVZqeJ1!lMASfFR}WWu`^SWc@7mr-1SJF z4u{ZUM!gJ^^N1eJR-=^XhvOjwMwpX64W*KpQr6std7fw4rh4c1lw`Ht9MLMxFB)OX z-$V(-Og9vw^zCZmR>Jfy)X&d6VEZx_mHm>C?lg^)x)f?4zfYi!{`_M$I1BnHhgrXp z^wbw&5|&%@gVwlVDk8-C5xY(VPfh3uO^wk?d&z4QCk%=|O4Omi7i#H^yKinWTg&cF zWAA4LB}#9D%)}K!(M!$_u{v+r;Zw7}F&Nk3*U|0KdF)f^Q=zwo{darA-vQNmF4GTA zvb557UgK6RY<AAr;h8QINKVSBwO=cJNj%|wExp)^pa^;dcy%ej{YxdI>KyLrf)ZfW zFcpP}Mmw+JMeo?R1GIw*)v&kk(<Z_OaiZ~-LT52~&Q5gY8t6@rV2Ey=!!uBeauNg< ziw4d|CJR9)lz!%AwJzs@D>@jX84oYl6r$5p-A?2Y%IbCMK=jNUEm&hr+A2j`FWp%p zuN0rC8#m;$9TnWG2NcBQH}FBd|7e-%VpS=YHVkS<J3O4~h{5Q&07Ec%<Idd9yl*jw zo>;wjxx4B;3+Zxyqf)1ZkzB14g0ZJn6>Zdv2J7uKt4ZB)W`i;7$|c*Pms4DPFCS;u z)pN(l{Vk<MeL=To*}A{6d&=KKI~ZcuyZtdS-Zcnv6ph2{QGrx(@<g1=XDM#|q26&{ zdS_NcFCnv=j&3Sw=#C++hLi!FC=d;wys_Yt+fRJf3n7KakA?+^Ade-wXqL1DEt^&r z8(`fOdwNFA85r=C+g=rzL=~=n=T`TUVAp`mf(Oa^#`z)5o)Mc?KT@x6Z8;kIEsIh5 zGje$6P{RVVvJ!JnJuKx*0t>Cf7Xtu-p^4LvWlB|UNSd=0u0@k#6O+nD7c3gB!7iuD z4s{($T#v!Yr_!`5*)FxsYE#nnx>TFK7%6m_PD6|yEGzYW=24;DlbsDMwpCLysB;T~ zL8<m>=SWxL`nyK!E<21U^BdP-b0W4aTZ)<Y8**mPRMh(=hio59Y|+~E&>JKJf7hEC z9nM?IqAwfN*vnaAFJyQjH$yA?2^&KPB-cQGJPSOTzL~fNM%z-Zj6Ar;ud;z-$YYZS zcITx6P+h=~&)Xp}Rzl7Tv1~=lPE{hQE2f>(i2Eae0{UE4;3aB0k7@MsovnPN)LT>Z zPPzN-pvEGfpZtYEqm_L&wCGV+O3LyKZ*K^fP4P5}$mX@htdNHg2A00Vk?p1?Xrx8b zLP#-}=_S1AqAk(;t!r!Rt*-U;edmQa{AjuHlhljsg~4!>6$fg8p-|&?>q_^d{GHA7 zf-SDEW3cS^;TdBMQv=3l218%P7L-Sr3jU}_p3mAsC*hy-werXJrm4=2z$-U{JbW*Y zp&K3KKR&K83e#`~CrwA*7qLtNvV#sazt6<3f~kC-?2^m$9%X$xMg3miPJ$eL7p;y| ziRnL1EgMa@zSh~{z<Rj2tXK_s&fHkk;Nyx7*?C?p({g{TTMfOu`EUy;5u}(mRiCT0 zw~TG<;h62(VHH;KUi@jg<)%q#Mm`PRCI2oRz1k8@6491Kf%CHR6{Ii?=Zj)rb?ldu zS@?ze9eyNJ?X97%0`u2J!hx?WTD7&qlT*IXc2~aQ>?ek&4DsZmF}yab4@V7-4_u8p zdVFZ9Z&8>yt><{EN6Q-l0_K%)3%`ne`)@W773^!cc86}mab<HBiE&-IjiYvt@)0xA zDC(OuV`MtLtFDVL2P_Vvk|F}(&>?ljM;BpP754|aYV5!0?x3leNRx{%^`L-L>u`CS zh$EVbSBR;&vGUSZc{8zeF6(#tQ>!|rw_tZFv%z<4QyGS3Rg-Oi*O1B9YWHFy-m&+k z0YU?oIK{N8Qb(f<{0~A<r4p}0`Z^}AA#*gSvmL}Zjfzo>mh~fcMAgW$cWUievWbtX zVC_zqe5?Ksw%!58(kAK_ZriqPPusR_Thq2}+qP}nn6{@q?VfhuGw;1$^56V7spQ#v zSDiXZCF?wOYSr4i$4RA<S*>E_EQcvG<Od#vy`*&-dL^?e@LY!17&ht*_McIn-*BWf z&JVB`*1AS<5oR`<=SeL1XGw?Tv}H3JU7y+Yl{ns_HHOPFX5&i(O`uId*d5o|2I}m; zBQl245~t$Kg3KUIVIB}rhFMRijrqG_s%wxphUs~daWUzB6!7J^r(xx>rx&wm$ReAW zSWtrD`Uvj>@0RFp1X1gD2C7XMNSporeWmm&M|YB!KPeinDfD7sI{#Nw$N-)-VtDMM zEtMb^)^u`I$xSWo;e_P9YzVh@wW;&bK_)#}da)V>a{2|vyPpE)_$)(jlG_o%hT-mh zUj-VP#BdPq2iFWUL=!Wa#@=*x^~r3NXYnsAkVs|eu|a(Cxyxol{z!s5vs>>G+BDWW zA4*x_v_1oRM)jXfYgX-zt?serr!p*3gf|w0B(d|x{m@UFA6*>35KWbubVW<UQ7Qa- zal~LZaq4*AU++(&IkjKffjfzOpD$d{CAJlX1fKWA+S?DVF#Ho6?nruaUr|4Pkh&%C zOExzCyem&?6gX@o{I$^evNyRvh~Tu@=}B|m^8PoR)5|`?kLAsiv(Kw1O8qVnK0n(? z365|N>KYhwfMS>&fg<bmg@lR~JF33w8Es{W&F+wR$O5$|6L&wD{z(>s0Ggvv+T6K` zD-{yx2^;k-8JAMyYRU>$-O+BvRHrH@tKbLJWW{7@GOf#HN$?+}HplI{#@~g+NMRYG zoSmWp4tXvMd_x%WTds{#?X58G1@6!xJd-DY;qN1~n?0>t<v8y5cJ)I96-T^A@tMt# zKG35TCOw}rR50F6c8x>C74N(U3EA|FFRp0C1i!}WiwE`x6I7Rv0}$ko<mMkh2k{^3 zs9>U8IbS>@kAd$!g$9DHwuLa0tTw&$l8A4Etpo)D4vh=I*=Ro3^94B8b^xa`|D4?m z;CPt>oK>YI+&>It%N+ZzQei}&r5f{kl4YLf>*UxVz$v>>?!=j8PXH%KFHwKhZBx2} zIM8MZZub)`N+rdL!0`J>3yVC9=h{Dp^u~)V_=jNeGK6F=zHYktEdrI|LA&e&kPZ=4 z_>bO_OVOYH-bCvL3fTA-?LOh4jms<UyZCaGb)h1CWc=BF*V=hEc|#C$2t63MoFJ+V zgJ+$ZNb89TMqm~O2GPiPTC~i@Sb>%g7b=>AjhJi3;1aviHD{d*$Rnc)2Y}pgTG5zz ziL`e`7H}d3{rN)(ak0%9Je<ZF#^Z{AfRF^eaD0i|PT;{ar9{vT6X<{vbK#W&j^`}d zXCGgn3}*LjfBJLin^%CAO@UVyj(08aI^#eOGs)o_KqEmxu7~a;DB|h9ioj=N{i8OF z^LIcZR28SX<8KyV?Qed~*Cl7^lVz%~EDm!0miOoSUFy<WC2PxNbUiW3=_2XEi~p^| zPTizpy`eFLLurqo(;vbo1*Fnv&t^&29DR_*#!G^?T!PKb+29C!a1CF3#{o6A{&lu) zyq)vD&2Z<0bC4MNfG+njc@ip%&U^T3sO>6rvWQ^Qv($$!8}w|NMg4ZQO4h}f`<gs% z*3lCKP>T=leU1HM8oU@nSHwi$98nE(ZjLB}LEy}&Dd&ZPR|OaLE2K??IT(s6S?ZF@ zR3$j3MZ5RVC>4fvuJ7sZu~r2EvoI_bc7ZclRXv|qNBC9({uJI^bcM^sPpN<%iVs3< ziEzW9j3Ij*A}VYx%HiCkqdkM5N^MHh4nk)|o0f})*S1OspeA{4L#Hj-nsYH}G3zN3 zw_<+HIZNia9oZ}vgX2Iz7<-8nPr{xX7_enPvwwZ&+cCz1#JI&cvNMlPe3yQ`8;kOa z=Gf0K9<875GyqCIWQ3-%`ifSoq1S#?4oz7q;v&I~e$XX8<)#S`^~KxX1a+nE%>$df z&pfo6=LjMf{M&jI#V!Slv3MyKQcQzwbl>Y>+@eW^QO|DsW;}xsYe}6*AEUQ!mH*t( z2Ky}?Y>Q|E3`XFHcr?$=b~LlH@@Q#^VhVG+m|)Zt@h(eK>&2;%H)pOSyJ9vMv*yum zdf?9*Y4EkaF}|MO@8ebc;rRNMdw)KDvzObi-uG&UKFSy`FYm{ppP!SXmq*^8HGVNU znT<GEe=g$g#Ov?m?CkIF@8f_c5xtc>Jx`gx*TdfxU5={4r!^Msh(;KH<aGb>qy27L z-~jVz?~d^J=YD+i{4&vVDs~x*)h({Ie|Y=VV{0)OFXyM4Oh4ab7UR*lRKbX*aZ<kH za`K|Hme=P;Cku4yUg~={6GB`>o?qb%=HTMzP=3Ga7tv#GLSB=-!W5al#F0ekM^2we zr;sTA&dajn{R_zkszPFz+`Reu{PeBOt+2`|;`!cRArEiNekL_`Z=k;~#u)TvU&m&# zIu94`WnYIJIryWCAK>RqpYPmJN0!>J)+pN}sf-xMwa3}Tdxym~bP5s&wlN-WAWA_S zso#-=!ee5NF6j$V924IRO5!hke=T_RKagbmz??Ymu|KH1R{B)r$4$r&1TMI|qwBZn zgR&ptRRr>0)+NtA?p~&yxw@i<l$Z$i^keJ#d-3V>DIF%|c2~sD^RGfQjttT0CziYm z3qlF$n1&lNNWgCo=V{(ff0wZdi>|Q{SM!gd`eWtMOq5*)7mjQtm^9vCXrL-gjB!e1 z%qridPht9_#4YwmuGas*cq<A3Z}sAm{Qu*vR2BX=Z$%zMi2j(;FI;nbr$d=MUPdLr zw;LCnar^=HKfKl4Q!gwU;ZORBQDh#N(~&&EEovMs-Y!^+cDi%2{M$A4E6;O`9s9n7 z$D@1(hJ-^ux#MpXX2>go0WF*nq~Y&F@TB}B7_c+W&pcUWH^%Ib_~l2t7o-?}B2+NW zvE*`pgz-E4{R6@xu^05&Q~|Eskakv|&QOFe$s(X&A$5rudKueeAUnl3cylA*XV>`i zaoUo=hi1FCA5!X+9Aze}3R;)jhE<$0fFudg5qMsDQ!yMFMjWI{(jU3?#<G*%{$E$C zRi*qx@eiI29+>jXHP7Xh-?svbbeeuP{Of%t?VgxB>6;;}=D1kR5{o_iF831F6WOjJ zeUoNH(Q>+16GN>I3yGNiEkfj|R9xVr$SBEP%!uL#av2>q3<<pg!yaIn2G)^;S_CHU zz@Aw#Z%?y!5Zj&FMBX4gGxkGUssk*Hs7s{FTcb`V?a@SEY0tiE_}qb|v&r8dd>P=d z{zV@id4Bke>Vxj{VqKC|1yGL(7&?_M_dh$J#;{eS@k<5Lm8GWVGHLKLd|!n4*!wmu zU#NBKKBQ71cp;~-H)V#kl7pgw@--LiS>@-8w6^vZk?q-|SP6|d-@zk4Pl<STN@m&B z+V!3^*V$I9KW=yZ3pf@Qxz}S%M4oip?}r)5&dTn5T9-qj{(jXWAwQjFvh~0&bo$14 zVCjdWnue+RiQ)>M-1vX_BFAOJeTIHLl}m-NEnS!Mv^bUb?-oQ(`SJTgrHyzdd_6m; z34Q<VFEwBkY4M{`z}u>;<&pICs<Za!ssrkq^djR+EX{K*r^fNpZKeI@WL(q``#CGT zb0F^uN{yznjJM^Ys<Wtn*tW5kc3HFs{}^jt9cP1+b#Rt;Uf9>fubi|%YX4ka<=Gb1 zU)hhy{&NcdlE6!{p7)p-MsfJ+ZweAyK?u_(6paDacQ#|Hhq9jUcdT3yS!XsBRbvtj zOE4VERWBljQ^fBD!W}dGkFR$^{}RN{4mb>pLHM>E{XOC>PNK}i>EFSG>MGkt&(T_5 zQmx?h1;?T4sb3fIUR&|vTk+=icJgF>K~m9Ni(os1;LC@U*WEQ*Rffvud?bD^)lxa| zQdQZMrS@+tw6d$<%eeTdOWYT~yVvACSfZ?TIP>I9y?vn_rqfW?Nvzx+`ES#!!L{<I z%T`K80SWM{t)E@3J$)d(8A!R=g`@GuR&LGmsys5lZ68pm2e+fj1MFO*$7NkQ?g{Yk zn!vo+tawSczzEIof;zHB0Eskv;FXyZk~$Iun&ZhMo?9ytitT$U7T(zD&eTHI7>$G& zaa;VrVZCw-`d~GW;l9Y$?5IhKYG^~a&jqC2Pp706mmNKUJtCtYty9o1u`qF7pi?qD zOyP8EiiE?ZQHiiNYDKR28-9_hMih$-LL-6QtqHj$xBQ?9&a>W$#8BJ_VHOFTLTOP! zS&aDF=26@b-FgP1fnA`jyqke-d{rG!87<|9PIpa3{<Cg+JCM;t;f|&Nul$U9(-=IY zCaW5SR99sGn@MX;-4R_N)k*+NQp}K~vP`(a14RsKj#TdHH&bPO7EIuw)b%I>+244* zpcJ+YQ_fxK$m6d<88&o~(PV8kJ;^_aoh5Rk%44hUG~OH(R6vqNMiAP#J+-}THn+0R zs`-dwEM&>OGp3xA*;A&BK4mW^C{Kg&5(|TM%GsjZN4k((!})Xx<t>#Ifm}kVc4vok z<A20ZYG<KIgo5Av{a;~E3t=Dcu96;%TewV)ARhjbh?_|H7BQwg2H%rErZUAkD`Qkk zMXUUPU3ldjP84k)JUmJ_42*TffybxNowmq{RwZIO;(Xj4f!=UaW&~k7n$;7ZdjVpt zJ5AJkGI`i!{bR;zZ&iTpV87%%2ASbRnt%6JX}*Kqp5rsdw-D1Vm^guL;4o%`S&;4? zO%+Eegg_xEo&}C~f#4ooP6@OuIyltn8fHhLM0A&11s_yurS%y+xMYiOJ+=rDm{mFd zoL1i$29do;kM&E|M9pwK#rgajry#x5Mra)mp~5dc!~=eOmz(Q%6wJ8pL5?mW_4Ljn z<g~Lxg+NfLa^BZd8dRbAp7Ne+;EFrj^)wc&^rpg*{9hUx3?zEWcHz--996J3G*@ST ziRf%A1d?empkv1GV+D0f;)-#KY9CcIQU<fmc+Ht}W;=Z5=(Of(<2BTA{lOygl=ird zZroqAS5HOf3}-{ij>AqXa3|A>-eRwtmG~BNXAI-NZsQ(Q7rVnYtnp;PhHON5;6u0Z zw>=WpkPmhO?RkNQCdPun<lq>=o!lw!lwB}&nXhi|lo!+i4w?Q`A2G0G4_ah8$(=HS z5xLAi6Qpqz&=Gf7sw)o9xiBp`+0W|StaI`kM;MsTC3m|{OKTMp)MdF!C2BEJKTQcp z)S&rR<U#!A6VgZSjT%OZ)0NXk2Kccb%%RZ?^N7kN2dPgRY---fr+h!z$y?-;4jRMn zd5V);<zsZnU$sw6+xeJO2J5r`P@!mpUcEB9kwtuG))B=<hJXg;#?z<E2e<8%w+*B? zD5T=gjYmN@_r*EEO0|ZMY&+C3EPt6!!7rL-Ps8eWHiFG<>|BUfNkUUT$|x?$ARJK$ zXfSwd>yS4h!goSba?f(M882CmpBZggv!(D+SuELu&9O#n5f?0q;ys<K7~+aUWJ5+I zWuf?S7zFv}iaxMN{XrG(0UR9CSEiq{@;X%7hXlr>=ILYkR0IA;qZ<?rBmT!3EBn`F zTTr5Y*%t~E7T|pD<a^5AWc~D#RK)q<=G&P*wF37$9Avd@I2jUt(&*?xow#b;<SIqd zX_t*4Db=Q(bt3e;8;Nxsl3>E=<8V3lb8S`y8-9`Wd!)^B-s%v_lm%OYbgiKSqPB8a z!HqtT6tNg51Z90$nvIXDO&9NSKbmCY`zN%pc~qO;62+sH%lo7;7|tOuB&G{#^KUS} zY+cql>sBfoD}OYv9_ZA(+qXO^?SlBTw>o;6gwQbPFW_vY4ozl*n7XYx+EIf>N;XPQ zsIW!0udQgQU#_ISx*sdwkYE0lsbU@B)lt9XEl)0INjiAT=H2>j2bwnAs)b^$m+OVP zp30D?s5JwX3Zb{+HK=!fm|2lF%$~&3Rk0e?wKUqyM<3n|#oAS2WsZOD+!3{7M!~oS z)f~%@El$laL{xJ!2xIh#h0wO_+*E_Ic5fKk;3o^YbwEFv(}1zP|E~{`<L@s?mw<?v zCzGtrZBQe5EY-0Km4#HMJoF4yh}6b6G#9cM?+8+B6;qnafAIhU){wF$esDc#&@*Nc zOB&pb0X=F^DwciyOr^EtKkhncs;MkzrW}goUCLvu<IYn9%^UI0?o^g+>{GX}LSN`_ znI*J(x^ZSMcfVPlz@No1-P>o*4rfg-jxVDb{+MSjj&6;r+~^s&IQ^Bz$L}m0mkjoU zmO&rM>nXQ8*;NrhOaE%J2pwO4)3csEMSx0GIO<J3-l8MLZ|uZt&_1Mxtxk3OYiI&_ zn`pid`vm3`wMwNRTjNRg0Ey!i6F+E*va?KRZqWEU9%^hgz0MWu?(vq&0~HJ00BVGL zp&V0)mlD<(325b8cNe_T|LI+hGcs6=>B|I(bH(X7YinHWaeR{V&jURd=f(Hu*YEgI zwH6zo%2n`9zU;!xQNc<52{U;r8)ApiDRrtfPi%zNM2V?j3tjUjT}$c-^tQ00A8^TV zfgwKy83c9ULc<t@gXaCbVz-nLc!E~RG<9E_x1<_+rqm4waU`KYjbcm9YZ_gkY_y*_ znb#Twm41xzz=0~FP)HUC4l%D!aQ;?uX2roP212hLZNji|;!KN8;uh9;h{5LC)2>og zdo{<w-jhWg`XOzKo$UbF7+ON(8xvO`40U?hO5eGUHK!r9l7vUCRH#EI)#REsi4-|( zZvQUQl^NEg(ozm>T}_i)g%>z-#b9ox!Wv^-3N?)eX_qmnF-imh=?IJ#Qgw-7!tsi} zeGIm1#Hi_Ob<+GCF$Nq7d$uwEwf;J9UFSu3z$t#tsvqv5_`&+kY7nN;k9dzz&7Bg? z|K3*ZEAYJ0u5$fulkeLNzIQXk&+~jAXX3+o-fWWtrwJuf&v$C$9`m~Rpd`H<y$h}K z_NU*4L^MXL-+j!;?$eogHO{*RQ~A1MJP2TRYrt9M=~C)2UM*6RptKJNmu<jKm!gAz zsZc{;dr!OITZyFmELA*77@9kubjqddSi)@`?c1t`+jV(y+b)L%EwVD1Z`$hhYxz}* zugRyJzepQVqM_wBEHARUaU0tDCxgcIim-EMZ3nI~Hcn8p9mIl*SuLv0Rq)7cV!(K< zJgxTl<@_xub#58yjn`lh(&bqikXip7AV;~4O>mJ{y$1LsMvzp8Nfwv8EdC6B9KS-x zuvT66g0kEn!AnBRU#(82Tb9kFd4;4~L4VvhB={(|5B6!`=kaY{(R>0y0zD8S^Vf4~ z+71#cgRqB%7-g}BJuN-PW`;dnG#ty&(MtxgXV-qtS<-!!P*`wId_r4rBHEeS(7p(Z zR24sr4y{**(2htzg~lDM-AHx}Rl_!9ri$u5f&VO^Xf@9geL7T@kfPX5JP=w(CAUo- z%df@VGZj+9I<8VY;xS7wKj#W&1MRAzI%sBtu-nNQqcBP3Q#8?LjkR^nY+JY}61`pW zXa@h;6*<ilIqbncw(q$S*bAZ=`!dR0|MSB+5Xbab928%*2951*;<><V*Tn&8rTTg1 zW2*RbkcCA$A+Y!B*)SvO`|odBw=T#Iwx*2iEdCM^aitpEu@EaM=ze45#W}Uq_H=bf z{(S2Wg4#0VTWDl3!5tIiUAg82HxkQ;8WZ7M;+A4nToD&mlZZL)ZdNQ|jpkPOMm+)C zBVCan{qR9|tpabYhB((Dt5}lV+~#+hlr^KHGEX5pF&CvS6x}ZGo%c)zqv`}V73Q?Q zj>wKy3em;;N%{lYTgWS$=s2BOJg8YusT`h+Do)7;8&loFE|lQ<=Yi!Tw1^Lv_NQ`P z)IT=^`-H?cl4KDqGy@YW;y7g2FC;t8DpSY7TT!j1*A$r`8XtLJGy8HS+OqE^>=q4F z2^v>@u2Zk8{Ep!4fF@BAX|X1SYb}_S!2~m=CNPi=u35|fxVori@dV5h(pf_Lhk(ca zX)o__?hYD*uqca*g747v<gG*qP$hya?OdX&L<$h?gs<enR>55@5&^mA$3>~%2X>X5 zv2INuZWOFY-dkhF@263tFIw~wP6bYlB6MlQi+rO<D>i3|yH9-%J%Qq^#|t|71!9TN zhPNX`KmP44LbCtH{g9k~)BP%0@1FX@if*Jm+Hw=9YQ(_r;WT_X{gqL>k;!Uz0z%4+ zhnkgKN*SHrBbC1bFAt>xy&5ZJbPRT-GJyuRl>-{YifwRCdrmhM5`(U2J=(I<^lceO zjz7t<d>Qw#tDRW8%qr&ranTfS&OR0Q13yezpFNOCrZ+N+MR2hJcF{03wgRq<0mq&M zyR1U3SOqDg0{$XM=rJ@Us--=z)<5>-M@@o$XUo7l6Tel`;e64BkcsXk8_reOU43Iu zMD5k0<Xo~yPtD=9slr@laMm|Yy`)U3k~OW3>SNwTMw`W#4c$uj8nIGhX@SVa?8hlJ za==zcg?Mq*`E{_=R3`Kezu*NT^v=ARHp00N<QY!ddi<oAvzbr_m6zF|8}sA9n4PZM z3M~k+o3o4t1w>d43|TeEwR$hC7P_Q5c#>KmU{g3<B?zgHUSX^-KnuD$Ltc0xs0J(D zA*@)+RUxg|3|_9RSQ@C=TJU?n13j2Vj#J7;TIQtSc%41k?P~|oA~Q1IXRb!ca-_8^ zX+bP$zpxT(_Ao*nBZAv{_E<C%HA&y9&Wi<+t1;zkDF4t|z(W_4`GU9i(4(+~Fom(O zKBV%4I(jwaPa92lzt{E6P`n1`pXVdE=}EhWmltx)ZP_Akb2qbfDLSs@!NLQKJJ3Wy z&}hye+cUC@6cT=Cl=VDOzI;)9yuP}m8l+&|5KA)Jk%j@Ik*b_Ag0e=ZyN|ik(d5gV zmv{NQV^I{BD{JD?%{aCO<+aLIf-Y|DXP&%mT&BDn!%^N14`(+l5&@}njG&6>loa=e z3GP@-EeS1xN7d!2;p}Kif5TDSiz49Xu1sdpawCu?Y-ho{V{Rg-{-3;DZ3(V1T*clY zI|&cU#IBEzBU8iSNa!mfyq(ok9{0YHlonJ!*FJSaqbQLT=GJa@jQ`~F=52cy-5n#g zP8;g6F?}Z-O#=S4*X`2p?oJ*}hJwqDC0|}~6Rn6_J%-Lz%%~GAKZ8g=G7#UtX%pWM zk0z5YmueE%#6<HOPevM`n-HN?D;1-o+O^D|hAZ1w-rdS)1@eJ~cW>STl8fN)PfowL zf%8ohY0yf7qe9{1%&?V)&$Sg0Tf%~n20VnCHzaY;prvZWXF&kz05YDjLmW#L3$X*e z2tfd8c;Qmf^>iFFiLydG&iKhVf{%y<1*SRbF_?}C*0$%-dy23L1iXwpnU=@Ntp!KH zmt)<BS)TD4Ax6Seejvxguj5%w9qCmE@7O5HKx&M)@Tu&cq2S6hs>9+hDK;L!lamAu z8~^5dqxd25?PxM=)g?|h#NX{lq>I+;=K<1q0P$mmzmeJ0wj&09ueL%08<)Xk*v$5Y zxW@E<Ow=fNhcFiLW*vFD;z3}h8-i&`>t*uB7z*BsRN&zkFcWM&-(Q+zlrgbed}()y zIA6vM_S>0_G4gS-moO)4-2v}|v!g8hO~!g~1K>97X^V4>PPw~-L4V287Qsk!TqDfL zHa@^`*Of*aoz8)Or-qx+nH06cV^4Q5HpaM^*~1)V;@i@Zs`O_M4d`3<U1Im>#ZMK3 zMw<E5=;>z^Y50WWP5-LV_?=aBt7%1NGDm16l#E%R3GUWG&*qMUH+>cK*X$1jr~0r9 zAj#NK)_xTX{vkGWmb!7~kwQ(ePpL2R{EKK6%_H)cB?95suf5EFl`>`}++y*TOg|-m zsBoT|$l2<qUK3WZRfu=-O-Z(UIe>x-;e=X3rKfAc;%b-?9?$}QnTSP9rhA|4KBLVq z@R&FlW?wMrV;cE6>ZaN>tQq-CANpnRp?{Xkm}KZFXU^<U#SSWwU<}yl;>AB~L8^Q_ z9~d4IQg@9Rdwyo<l4)R=r_)BK4G$HL2x#lN#E%Rl+{LqeIkl5`n|>6>_@~^(hc_gd z{U4L%D-q*cv%`{p6aFd-IH64rga}ZvWKjx;th&hXA#baQ^@bWkP#Y9N(9d%TIN_=& z;3EO4#X$MUoGy`fCKx7Y1h4W=m@Hd)OrT5_G=)-|@hj1gi{dWcSTm003%RDn4*R=9 z;4WTPkHLq_bAUMk?TNw1A$=IZQuh}yjW+_t2XlHyP-YQ;-ogiYEhV#Pqw-N7!r_r{ zMoVMG{)|X92=5lQsqG#rtQVkfA5O4!rK}U^T#V<~zp$S@lVFebLlga(vKVjJy@<{E z*0>J(uh1H9ye%b=Rg>Ri@lNH(J4O-VVjiu?_R=l{qEAaG?2rTbE%Oi6Qqz)Nc*FOt zqH{h-d>}36&rn*LiC+?L9V0RRTW7}9^{JF>Eq4y?Qoc>KxlCWg+@d8_y$8p4@fRv_ z{xuai_W1AIpvemoYGM3K!i07VSdzxZ6AKd9Zyh>9d@PSjVf<4I<06`q|HlM$NW%Kk zU8HQ~7(eWY5W4C%l0*Bh=vw023>RTu_(m1R|7j?UZ;E3-`=widH3^gMB&y7WNcDIZ zh=O|*L8c6tEyXIp_-tod^K>CTFT@Xz<#92&Fdi4q7p<ok;?nuxaxxg+x1`Gb0GCH= zw2Q$BoK=kR6@lyVuF#qKAcDkVl4NZ~DRRe;ThCq~x3vx?yzkRxhC!ss{qQ*%_w5X* z?oStH6GhjU^tE_w>X4=tqX=QNet}zYIRfEZ$B}D2BE#b%@*L8J^x07`oG;xIhsRkl zDV$|{=)yQ8_S>&BJD{yS^x12!{e|(W^BWjU!-T^4M<-~UZ+%Fa4Lw>ZOUI*rncd{- z>ySIdMPi`##t=VS6?Qrc!sI}dC+6=;?6)&#VnGyCk^h!%2j(KNF#f;QBN&oS`#&cC z$-=k-ancXBQJZwP^Dgt1;<8Q7HKp~5(waaKB6diezZKn&w10Zz3?EwtNwB_y+2pSb zKEF&wur|!9J&^H#_OMkLG1f_9lx7!eS@E*bMzt&#`_LjfFoZB4L<n@}g1G{+_lu#d z2c$x>Y#IyY26Qj+L7Tb&r!Me7vfyYD6&JcenYQGOg}NXH#^f=8V*dpnZWJqqHQ*qy zB_h?C^d4$=WXWk{aR0aZe-OBG8p(cw2a5tXnktgIsv7^zvQPJxbEuUWD7<0kYn@Jb z%<WjW#Y!|ST>-)68yM9+9S|q2wv@Y)T#Q<~B6n4EGbId+9V>7%-SY#wfA(#sh&7Vd z#)MU2`wkXGK0@NC7J<tC4Wy>a9#U(X;{s*$E*I7?2wn{3`6QaG6=7;xROp%jU*IH? z3~!t+wIS(^dq_u=)&FzgAa<oVz%djY<v4>?@^YY%kIM_e3+uM41k}@}6cpYMtDy^S zawBpWNHiHpcj}dfxwQr;$m$-32+ux&RPCT)J5ZJ*=^buJeDNI)$b29#oZE{A^PZIX zhiOGIoa=Ti5droEl?c9B#nHd_!T&Y^9Um@!>M-s;Y1tJmmzvsmaTG{rl8VG}E~~=~ z5o`;KVIaI&IfCO~MVML&LG=tXe#4lJQ60h%fD&JfjKX-yS$YbV8}MSzrHR|2(0Z01 zm7m~V*WkyN9lv2o4!vyQjB<JoO=CE6fO4gWwdfv6)~2}i=sw1mMttuv&-yLz81kvl zFQ^ohzaCgm=tQlJB9Ad=FTa^!S<91@(tz7Ux)rC+W?L%}#)x&^SLVZ4%f2&2a7YMb zPo2ukBE35{mn@-UZ2IAg8)B}X@T1I(+|vTHmNeH;OeklV+Xy|V;$pjh!mXr?HKuKu z8pSmhszDrLZBdV!WC&#L1!}95UUk4<t7X_-ISvH=a_hXBX+NHm8%(#?>s)tMTOZ>w z9XyB)Gw<OWr3)O&KnuiKn24<l3@c9t1D2V9MU+h0llBuFghgHf8iK_i=S0yzvty1! zi}v(qihB@&<}SdfIV1tOohPQ7%PJwMkHyg@i<@Q*;e<tIwG|;f{Bj2K!8otoze4eF z`|OCC|M)fj(H(&-b*^<9n&hY07t)7PCgEt-Xbr7N1x`Cs9ZCpEXz}9VjZ4Sx2aWL~ z`K(XPH$v9sPwq?^uG9)tei8Z`af+4WI=CPzMgST2+OiWpi;qlc`-r*{7*K=pZs<C! z|J@5Jw^@RQ^>_kc^;@yPL(Jy&a|<&+4o%V*p;MIr1xwaGqCOvAZKdQVHH$jlPcD!B zPM1kuP$2#~m~(QQ!y){5AIGwWezR*^Hc;?j`%9LdKUWz9E$N}7z~oAaE<1~{Bnts_ z)K8rOQNkuD#+H8W`3m-vGN-m^^}ggn8U<B;TOC&dpl1sf*3NPg#VP^k;FvF}BqVV& zZ~BP_O1~hTfHm=l{0+PE!t#zk;)aB+seSQq*B~bKM>WTqMo%ef3zv%n0ex8n*VmAQ zt+hztjLt^~T#~yp$O=`nVuuY%qUSTs)`nm>SViy=o>z^44bN!$Jo`3St+DXp{a;GU z36mnou9)Us$gCn^`2aMPw+RaPm9JS5;hR%KY@%*wj9Ee2{SP+``XKiMwqwrsX&OYV zTTNx}ig&W#$RA0Brw@jSn_?08)S(A(D=&I33RXT~cKCB3{>Xmt^6CDRUf`1V)Jx+6 z;mvo}ag2HgKX2nNpB+1d*XchN>kqCt&I!71#s_u<=EpRtiBs7kwMiS+S#@an3P7Lh zF-iSF2<Iq^l6H@*UVl(g2-xilM6jPtk1^J>D=p27NeK`}J+cBUQ7Hl3s7J)25`QG} z&tb)q?<4J$=Nj;wmzGhamGPnfnuyXj^tA?wHiQ5}fr-~6NlN$V`>LRxzqaU+Q5Qd^ z$x|m*^*khr7pHnY;`jwCvwD7H<C`r}QMk#|hGWea(bxr|am^PK(&BLA+b|$7-ilS9 zd@A-l5qK5{e*UjPDl5Jos4M=|*o3aQb?ycpOU7#%9aC-zj3;$q9l&BxS7`(;f!|-D zgbySB)J3J>w;~bcw_;fUa=8OOI|N+_#|<Fn2NLlC8Z!h%VzX<)5I#mU-7m;fkSJb7 z8pk4e5^<|T+~{OBJhcdZ%6-QNCvRGk7i5^eK06x3+~%YV7EO=3?ii(C7P}fBw8CQ? zx>UoX%kPyo7D)Dwc9rh(>en924>n_aMbQ<<JfJ^x!dZfS0>{Aj>-zxIDhcF&ZwCg{ zD*5k<)~#>ncp?S<Guu>2^OLv-#%_Z58t2G1w|{K?X~dpuPQlgCAFQfgC<1a^JMg*G zr?y^j!$<E-x#?3tt&(cGlCF+13?b@PI(B+slSG!Ez3Bnx%tICAuRZeEL`jrVsee`V zeV2umC9`_U+txVD$|s@|5ch4w`xvDCXdQ(Fj+>RpagMhX?*)vo#~U#@hedrW6Kq`q zYRrc@!U;LZkf`uE5c30BZ254X6JI*C?pNkJh?%<1J3JL};qP^rsWp!gQ`MfZ&vhuG zddioI7GzL2pv88Zl8>v%>X1pNY&h`5@(8|FW~ROhCrIVt!bl8`srih^Jl!l|sTi^{ z$k48g6wrZji3bnu!*c69jWtQT!zmOxluyFP#9%8;CV9BhdJ+=d1U2vT#)42W6r1S? zF0p#F)}hmQfv?gv?}H5|FRLu^6JTOdWb(cp=QZzTbL%35Gzk9{{GM$_3EtE?Hn+U* zdP`Y6hMlCvqKV@0zKyugkOKD>CDuTF?!eCL>FAN-^{jy!y~6<1c3}!3Q`XfBTe-kJ zg10i{_3V*P$zlPv_;49ap~SAYwpL(?zfOGyFXJV1Jq5a&d}2OH9K%`3!yBR%r1G#% zE2Z-3D2E0mNzNr04nIN+<MiR&`l)Co7>GDN1zur5?%^RZxd1z92<q1&DNcihZ+Nm1 z{w@s~raRFDnz|dtjRl4IgU8Y1b*fVkv(8$4;G`8#S0D2f5%;0<c}avHyF+ir(xF@d zLOz`M{6anlE}%;k@+H#-=)pcLhQUq8NfYQnEtNC~F=b$yhpVS&AAKA(Abq_PNhETE z7?5GP=ffVDQpUp*nvwC~1Q9?u{bwG6rr+Mj4&sCL@Ir@}8qQp{z-nvz#6gYqTqEgv zBAU!}<Gk7qGygvS(+zBlyFQY!uC{pJkz)f#H0A?c;LDlwx+D`3?TA(L>QA#wCEm73 zl_j58wyluknH!m?y*BqA&stAVO<xHT<haI-s^P*}cKu_iXAZ0fFV193FiXO?>{(+` z(BiiS{8+1qVD@_DIdX85T+yrpd$M4=*Ay9*tPGIz;~>eLhVNy-0D0t({05i=1lqgb zh*%E#kgCzUD7(BwN^MSdtx&(h6bt{5OZzrI85OKt28eP;D*w|Kmg*O+0JMcEUXjWG zZDG+0KwJ2q4bT==0<?uxPye)qDP90=p)x>QsB{6)7N)!bw1p{e0BvFEKW$+pKwGGE z@lRW*40w`D_lj1gQ$77R@jq>0=|64Zzesqz^0%W{QDgm*<<$qm780<4?>*8JHx?P6 zOq;tqbdf$}aIVF1`w*cmP7#4pGj@bmFX~$7uZ9D_AjFO!mMeRtr^ya?@FM-wLY<Y# zAKHoZ9FR)iTv@We_8%eO7mL_Ja|h1V@HD+lH^HbOY|crS4NK11pTZ^f9HU=<NjQ2r zFgd<`&)f`A!pYRThn0>`2S(}JM(igiAX(>(Wf3)OkqjQ!aKojB|G<=!$2y$1r*y3` z4vuD0Hi;;-NO%;-^}z@Q=w_rG8kC>FQfQ;cr8@d-j{K3`qJ@?~1)UIpg<Bvcz2sUd zBtylarRM!R1SGxM_%TEK_;uO5+M+BheA@0N<~)xh?#~4G&tNNQJ*Z(6yeA|dLr2g* zkio6wUQA9ukki<q#o}8HAzj3aSDzAMth@t~A?Clu@Rh3(V}6tz6r9}&R~9bd?#JXI zP(4Zk)3dV^yC#^3LxuWL+6@sHp0pZGqdj@&QQqvjcPHdB$!FCdQaQi`6D9jjjBy=f zXh{?;9GsZ~+bl>v^yq;BBc*l2@aSKS2$ItxkMqE!X+dGYGIp?JbQyMb>RJssmp1WH zr9$vcr;0W){$2ad973zDFyH^&8Kz(zw9!C>9?f$uV-lOLME**cJ_-@COCMK-Am$Ow zqe%$5Gz`jqW5}nG1?=Kuayiw2(4YtC^#(F3Hm<|0p!V$X;DY$%b|QcfkQtI_k%z<v zX^{~fk9uy9o+&U}shHWxLV80Q_UIkWp^X@cugF6_0UPE2OfkGOl%YQ64!-aP%D^PJ zTd!oda+&C3WZ-&AcP5E4yF(e5U>^>TYuFe;FS#XPW5RXt`gPIETW1EDfc>Wz5;MVH zUQ2vj=m?;i0%ME=1uxS;x#It}!#Hb6o4lsIW6v|_n;zf9m$3waBdxQ=A2(cvy=|Tm z-*!N2?HxfOTy0Jf-@!oD4%B@7NLyr@pXv{=F$DLpFtjKEoW2p9Pi%<XL~T+atElQ) z0VSHys{R9lPZ$Lkk7)rHz^}<ci4>tt>55OYYvI6Z4!|r|WU9Rpj?xug&}s%YM1>dR zs=hL~&}s?}l>gZ}<0w^mTY|!?wCJONULkriRo~6pkg9TihQbS0dfLK^YCV~XH|uu5 zu%{kCoKpxeVMrC=8&InBg;!<%oA@qDs=~{y{J#hxzbap!@bDkNdlI3$V-zD$%=g~# zi2{p(Pp-1PMGvI<$6&)L_G>K>WHv;##ELCM&F)2r7Xybar)KYHaCre-H?F2H%O5@9 z>UIw-48ZH|j+O&X{TsVdhr_s6Y&wo=)`W7zi&m(TvOvZyDXnxE`SRR{mck4X`I6n8 zY2=Nr`5d}<t$A3RsBmQjuaFpDhophb9$~-w4#+2)q~CkuDTJEc&Cy5<NAL@q$3+IN z#LQoK#<SxIgLYU<aJ0#z<`RrfNd%q`gd1iuJFVkMjM4C#UfbcHV!jrjm}j)-(<zQN zHY4P4<CB|gMv2_yIzGlj5&z;LI(`%W<LtLtq}dT3ryuXB>L`J>z<v;y{8K`6lgy28 zEeM|o`&wN=l%?#tP*$7Q9m`d+mVtRUA#Aj6e7Ypez#(|qhkJh=RVAqez=tZR!}Sv= zT3A!s4HMj6J{j5IJo$G~-uPQ{6fuSM(nkf<R6+~3Y*{Ts3={qs9BM2Bx{!uO-&JC$ z5oY*h$YR^Mur10kGkAfsFe-dF0XVOm7{aUz4?|v(l9GTt!X(5=@mU?fWC#h%JnE$W z$*pR;5U|Z<3A@M9oiV(|p!3qUXeRkAulXV<2I7dWp|mjR8$1cPDMAfo?9gyr{U#2E zLN$6c??L4ybqAJkY{yWeXzVCS<{3%WuY)y-BBf6<DMR)OID+}ljP7V6Px3Kw3=bev zD8j;ayhpfBO2sfF1)+4<BC}r{a=fn-Kg4$B%;DwhFb^0QaXmP8U3}}#>4qiB@rfJf z$1Cyqf;q&(gHZp%G{YI4pu-VcrdCe!hM}o%o;JdW^86M$Sv6@TA2C4d*52bq`OX`j zy3B?=+=Hm$MPY3nzXyLC8+<_o(bnJNB<T-H+p|Ui>aOY4oUk-f192=uMAz>-RCNam zlt9ttH$o?hR12CWWa{VvrGla#JW1|M-oHOj?uKKy0ZQ5@>*xUh%Fz>=0RX7M6Y>rp z0H7EEfcnn{07@4CsG#Y8fEqjj0II`hvlc8J0I0ze0H6j>0Dy9Q1prDH04P8l0H_YY zGkyOaMOQy)TIRor0f2J!1OVz^gpj}E;|Nf#txvkRF`CB~`FM#Ek^UxNaCVu_dwiSR z(i0L+IWKW9%DchJ(o=NSyx=5P9_z$-I80=khj#>Ks-atGn(}BD-O@80(q@sUAAQM~ z)AIH4_np=-1WgMae18#}T@Mv;7RwrM%#5JpF<(yn2@6G6<sVywDBg`QW~H0Y*Jcgc zH#gm0JOzhV*BrL(FV0Scd4@r)`M(42AoVkazy>w5J|IW+$fAPt<oR}IU}xOEk@#z1 zXQN;X1uSowK*^e9lVDIQN(<-Nb4GFji3$O*(jeDtz;XJr0oQ|+0ezp>Ctxu}o`ZnG z5rtm5+IgbMcO;eVVA~T+Qj%1ITup_%79pLOTMT8N#so1#*-TPOLK0byZtquWd8(Zw z@pSP{2_&9b4F`a0ms!wnUabR^q%I!4&<-lpGs?Wd;T~SyoOK^=$Rm48ee+$>7+PVL z_xb&h&4z(<N&<Q12IJ9cw>v)*8IlsX0|}BKrllzb!lMmym`hib-dOqjd!y|gkZ-2; zgVng1-fx4|vmQ3ZhZPQ-PZX-y_PG?343{auF@eR$p!*??9@$b`KYb(fa7L~A&n7-# zwITC^;lwEI{7P`=8f$gp^j>jtlPcrA$0yVuW~SWxdxo)xVkN3S$?N@Z_SE~-9n*;3 z!k_=VHM<D!fwvFZ#&lrlhbJ@n)qG&>Yy*<MpYCBEbW9EzoEi9MiAqxL_;o#`Z-nd? zR8IbP|B_6A=<|B7D(LIRU#4F_%yLvUkF!lr$9+LQtfk`MybI)o;xh436vJaJx6Cpl z(Cviql>DvAvQDdlXS>o~v&+Id%OpF_ns!rWo8x`US?{qMK$dEcJIRT#;_a~Tt!S)C zNTYa-%=)P%vR55CT-=Dv<~Wacg%d2%B6>!EtT4Uvk%Pfg5yx-@O<|6G|BfcjQ(fQk zH))6+IT0gE-gi(ng}_H}H1=$W5CLSTIb*oo|GW47Lh5@qZq~pFYtKY8amnM)0ZZXw z#F&lfrzz(YzQL${PQHp!X)IE$DZ~F;Zy$uz3W!Gz?o)}0-fyXII;#|xAAgFpXw5+G z@G8{#mGI^M=4URe8ni9GyDG{h-S>@l`{FcJm0ghscjD6nc@O;-jc#_q#^U>cK^=yv z7(=#l^6y`&Vj8Pgmo7Ko2rs(bpJ6WY_8g4o`m?Svn@MUiGG2PqRjp73F-AwE5hscB zHBoYM?qL$)ztY{V)vvXC?_DdYxjYW~Q60=KZ5Tcnf#;a-kEH)qj#&N1&N{R5j7s{p z%sGW#RQzqXO|%~8TEfG(;1|=<Xw5Bd@ZLD!CR=<@?J%~45&t}oF+Lfl@vAuPqZ9VI zL-+H&<E@n1ucORE+{Jnr17=T@?jA{iZziaA^K$evT1G@)Yg~W*uJtXkaC07gha!C@ z4*E&>A?IO9doQdt?+<3T*`qQ287GG2)^eQO{8E+pS6N%{@9g~hHp<vt%kP-o@oG;q z+AZ*E4Tf)D-LIvK>+uUY!WT|l@bWt`yjkjIxq#TBRTK$*Mkg>=wFW<6+Y25mfy)bo zU-PB6*f@?m+F$nc%msQ^H)|2#b`7^L)EF+OoN?>^uhXNW?Pv800=`plGT$=MT9)Q0 zs#YR@_scfz#O;Fe?cI;pa9g~bY!H(p$@XEPBi1~jAA8DN`nReSQ|C<Ct~y%hOgp&u z6Hg9UGe!6}7g#gPoQYmfGG)afPQ){#YVb3Z!k&K)Gi}pjnYH{7Fe{eLn=Ja|N%q~D zWX;t5dT;*#jLn;TnZN$ZtZ^YLF0HL|B~yV8>A5^W)dC?#sI@G;Y-7uJpZ8e<qP2r{ z;+>I;Ib62o@21W-e^@N<@t1z!+7x(rUF=ujzY5x+TmR&*^S1gS)1CPZs75hsZuDa~ z04hWz@LrP05f7=DER!wEebCaLBUR}gzs480(r&!YT)4r_cbK~kPUL4>!?lXRXUbn+ zs~d@TiyMKff^J=!fKOGRrQ4g;+w`_i$F^R*U(ZZAw1q9YAhw}LAMDeljsp7`C~{*d zS9QMqI_6D<gxOUHJ!)&QCio(Ib|%>+i?1mF)h8ujLdto-Et7T==sIQ4t4fH3uzQu~ zgy#1Ox_6HjZMtIcr*{9oxS~<c9Aej$&o771UyTWanNmB9DH8lIgh-?U$3as1300FH z#B9kMpaSm(LD`nfzIufvw!=gxe??lL`boeuE)!V({wo|2$~WcDz&_q8lHAAm`wJ@5 zxP`#{>w|@ci;h+R!YL+;Uf|UdjPO)w>}TrG(HrZg`yT$B=NRoAE7LE{#1>e5$T1sk z{&`C*uGb0Bd<$96yu?#%%Y>TJET-~&Ph0G`Zul02&FuUpa?*L0#jjkmue|y_J<iby z*Z%NJ{XE0GduVfq>))$v?O7VjAX&?x#GjYOlHW8O*>ZRU^@n6CxN-LijL*uyW+XL^ z6t3<~Ql}I#-TArcdbCBWH?S1>fnp!OKTn`;iRvWX-Jpqz%B>BatUU+Eu`3BM|L3$d zPfSMRRS^~#Sd9z`4QW}%+G*blEKQsrci)<gpd2F{EeRf4N-8=4$PYY}ED;%VG9oVm zszX2Sw^LPUkJ#yo4$G0LzyI@v8!{LxwR$&^I{0xQWKbch8lPr?Br*}KhPcy!ck*Pk zK<a%X@++0|8!ysKRK;~r>0yLr&PW{B(tui&Y$xk=NCeu!B>@zBX*A5BYXJ+nb4jNm z^1+p?vM2{Bi8?V!!OT8G8?2P8q%G#7LqULM&bFad*HxV&dZ8-;m7Tb3MNNrip@{s- z`71P)D#Q;@ap?(hvJq-BFf^YHv1?8*KT~JbiV)2@v;;jQq;@2v1v@uP^r9n_oJbfU zaX8IT$-QlPNlA<w!-@-{zO9+{pm_l@jb*k2KTP>tV`|dj$q85GRNmwif13Qcc{HEK z$jjt{jmZ*m+<{$osDP3>?|F0?nYoz-nr4Xk`g^VyJ9N6EABcm1bW8jr)DNE<P$ZIM z6s8#Mysvj}->~A1LG{kb6gQtI^^@uIDaZYy<d>Fz{rK+Er(IZ@neab2L(9o=mZlF| zUib21|M;*yaveUcg6$oYxvLpLhp7UX#&h;`6grGoSMxXW!{Pt5&Ohl^)BUY)bQs_A zG#o0r+z4xpxvvdC$V!YpD(Hee;#2}d^+j`;Ml_RfbhDU)PH+lbJABGYV2gNpUgzgi znjLXwZfAG)@~pl^9uQK*ig;hyylXjTUuIjm5XOvVutZC#7o+|!u0r57S?#m*g4raW zl3oENY#>v-*(l6R`&X`2L77WgWz{n27To3-Ki$^ZJ8gtrL78gX(**M-{Ye4d0}ty= z{>+VF?RnAfB?ar9U*g^ExG8q&({nyD1zqTPksGPr>BaIr@0ZXU4pe2J&5H)8HZ`j> z9+>1#{SyJ)&WVd5UxZo<4A9w*=f71pIC3Fb+muw=TK=~b`j?g^a~1WXth6aju^xXj zC1G6zx^hM$8=}TZ?}-ZdbB0Y=^e4*koPh;=yfHDs;=v{D{Nb{&xoPhZM-7XPTzxRO zO@m7_&KRU=CYr9H7Pu_KSyiGl;JP?4L&Mea<}^}a{aJWJ>|M2sE+2k8ta_s@a9}fJ zbTh@^VT-FzbF_eG7?K4sNE!hX_UZKR<{nn_QZa?o8R`5X3%Mn2(;@-LAA=+V<qd}! ztlC7ZI)wzhu4!t^NI-I$KycZz-EqTnP#Cl-{>tD1ehxaGFM1xmx0vx(zxJ9nHkm&u z>bW7wvI85gHmX_Kk_{4uzEN@%vB9t7Y$xh}Ddf+m9oxo`M|I1TCC-yAuypvd4sW0y zxmD7)egR01?^ipF|1Zfg$wJ_bD!U^EuF@RJmb_?u*$BRD$%<TA)G3QNO_{-SV2fUx zMyd8UF~jk&ZIjb_(FYf8X(@(uh={%+GV}PYKrMS}P6@7s2bC4w9k|sk(oejKTe}DG zup27&%C4p3FQy4VlpOn1%CH;uf3qA}g4+La97R?Id;IG-Xw8Z**8jtENPt$j19*-i z0M8Mbroh^93x78GfUW)Y1qSaa`zV<1wDvBjqB;ScU@T3zQ4+Y>?<slqiAM)&sxeoD zZ3&*UH&-Mk2m~}3{b(>q;?*0GCR4$i_(uSxp7e!WVD5B~q%|6eM;T@qyW+0<EN|%r zYLhz${EOrRCx_u%{t+hOSfwQ1AHm{i^~0A9VIM$t*mw;I9t}>13cRuB>`?58{QboG z^?tg6MN3|iM4<$xES5X7CXLA1`UXN79iZbwLUYcSm*(HxergW-EmR|9z~Sdv8=2(C zApQ2LSdtI0D5T#u6#pYSf~n34!$>{}*Na*#==Vp;>B9>6G0Ofmf~YqI%YKwamKP^r z{N-ZI!fpE9dWeg+WfC03<^PC|QB7a||ELTf0N(*1I%H#3EkKd^@T%v-Or9W_)%}r7 zp27no2;x==0Re%!QIA|+#wG~_QFl7Ye~mXGXbQ1CD61R5K!m1m!87F@7tnL06~X)9 zd1eETIW}fR!4ug5mGfIM!JVIGG2Ka_65mTD2SOA?BMM>?2JmkK!QBC49fC4J;06>} zCAT7x_!EIbKKXFt)P`}6AypDK{q&ufiv{Kpz^%F2zM-N@Omzcs*0Pr%MC{vF|0op( zkr{Q{K1@3&c|O`_i^Dv4qCrTT*H0ym8Q~_^>ouT1njd7z@_}Y31`DNuKL!+Kk46wM z_>z6=5zPPG3IJsG_YN(z+<$kDCza#AvPzM%xQxA}>mmMI;}p^9`h{aKkKBKm0VW7^ z^Z(#E0Ga)z4<w+meqzYz=^8bIyjr?1VFU^|#+<@TLN4hha+Va&0w@-5R3ftgs=VmY zvkh9j)~8cT^nM^VPMxuiz`8H49OnG*OXz56<a=PB*$H>i$@MTwLL}kjr1%Qpr2G_w zVI?$4+0}HIxGSS$lEtuE&tXJd6tENo9dyFBJotA>pKUtN3yW>~#XqiAPokx2H!ODk ze1#I*b;&|cDrwzAlBG+KKow3`VE!ZCbsl75DnAD+RWTr)J=~Qm;Y?&IRXw?v61dbh zWWpvZ-xPc>N51+_Rj}D^^EPz}1^HJKy|#;9Lmt>Q;RxcabSBF$5=~lc*NwQ^VpVC# z%&nt=sb|>LoyQGzx3sy{WJL2hw>a`hX_hNtVA>PpM`@(xni(&xL?<LGN>$Hm=o8H; z2~?%g55)$-%a8{Thmz$gm$b682e3m%wKA1guYUejt^$(E(2=eL;S>iexT3i>rNJnD z3M?@OzPB=?NsDltQl-m`QnMjaX*8u#m%+`95_6#Z&(;}dL66=NEHkDCoF}L>3ep4m zH)~}_i})E-8d>ORRT``Grd4aK+X2I#dH``wAyb+(+0mp*O%`;SGULhrCccXTJl)Fw zi}3BJ(gDpi%8pJo8`CXbAz7p=H@c{#`1~*8-Z47T;BEJfZQHh;$;8IQw#|uc+nU(6 zZCev#Vw<OD{^#s>ziaJ%*8XtTI{DCjcU5&gPwsW4J5_bnuUtzM>w3fOt%?m#9_5M* z{ZWsXWrw7OyJ*YQ!*B#GE|LUSd})>$E8*xYi<0KgT^LPG+D%m_#~a<M+<yoSk)K~0 z>$_`>^}d?)4p!(vFql3}^r1DdaO&xse?@Af<JK@cBMnu`V6gSsTW{PMs#4Hbxhcfp zi!jqV?PC|Qyp{j5uc@yguu4~(ymerEyY^$LA)p<qOk3JX({`&*SA&oih0Wqu&q_{L zoBHO;a2ElsH;d#KZKezS4$N{_K3_E1DFgy9(E+F@>8EC`F+NhM@}KNXNLQn`F+M`? z%KjJI;7?4_+JdIL7b&9!PIiJc#igrRw6NSoytYnujyG0Lc9#F7XRRsU9G|3Jz5|r+ zfyJk*vD`_S>W)p)rn{5>>v)Kkg0*Hf8_*`*-Q_u5?HQ&j-EAo7wM0i!;AN0j7;_Sw zc~VEJlciU*kma`OUu0otMWKs5%s{S-z2n^Gf?AW{a3!^eo-d}L$$K~fpX*kHzMcZX zuba`$&QjCJcQ<a|m#%iSWvrW?GTC{W<=#{St(FPcQJEZ6ff1;{mT9yP*xT2&nA~=A zD!f7MvSh^1o*2Bugf)RcvM|2x_F6jGNJI5os5rR~?gb4%&PRK814&mU!D5!@U5H38 zXRu$^cThFeWPkhJCPQnw?kx;tT%0`FD3$yBP==O*NXQO^p0(<<%D5Q)!cpE-^ClLJ zWkJeR6P#rsVnNPSb4;e98RB2b-w1<cf#w3x+YiFjbk+2f<aE`gYLjA>CarXfArD<Z zc^1+C-Ig}pf}9o5E8tS)ZbN|HJCy#FAP6j+-keH*muxa5SzNd*G$~J}O#3jf<W05& zXFy4guenkzPllFr)?!^6S9Yad8V92st;)1aj`|ClM`90{U#AwfeO9LJnr&vQyqUju zk#Cx(W0Y>1cgD@IG?~NHbAat&EmKWtPFAk)MM$%JnDJMt`fR%@Q^la|tY+(ASt{?Z zi(bK9e^REk+Aj)u{I)c1NWa^s{u8TA6;~cFxl9#2c!SDviF@fZFU8UXgvJBUuzX3F zd?_N`ed?fpLAJ@TNE<eb9iY%MRe(Ynmtf+usFkV`+7ioDPZD{vEx|_{0962SDpeVm z1H>uQlu)J$5NA0+od05gIF<j3)AFx4WtsruEK>!Da|s|$nI?cZWtsruRH_1q6L18; z9iSW_&N5Y&C8=V~F=g6xOY(mm1H`FR1rX=olD`mt#Cv60ie;V)x!180&GcsT$IuSx zGF6IJI%To$7Ns)P9l*hDN>y3eQcWO$lxABVo-3CplTuZwmcX?U1IYbSPTH2-YQf7z z{xPY=b<*R>Mv14YF)!LT%C~c1YAyB0PP)H`FXhIQ8;VX<HP+{UnN;)q2i(uv1DiYv zvbu6#F{MVlF7>+PklV(L3()WtwEE*PEs_m6ur$A_R+P9waUG2X+;C%6k$#iNU3i1d zK6DWacm?1Sp+bk*Dc<677r01Y1rXmwrUO0<sMRM24gdXP323zTXSztAd7%&&gh;8@ z7)JH=fT2X68FkeY)jT~w#g1I5*1W}s1w7KXFpgTC1)LV}nDvtdT)J4liTz*6->3-? z0Wu993CMKc-%R)Y&2%jw(`a;nOoK-PGX3}6fVN|3bm;+rUICZ-o9S9WrvH|>JX5Pb z!$c?egZqi5V5@5=hM9y>1gm!>`J4Dxh?*R1{EP0kmnVDcCw0bq>wDdu&P?^m_qUSa z=tTZvO{KDMi9jcM7>9bO#&S|<wKZWREg<fIB*gsaWEri>OZJ$E3lrEUJgT{(xb4aj zVwEmV_ZZqoa)C5dKTIs<>~8ubHJj(`5|**N-)vF_8sTbuC=F(PD|7oBUF-HYCtUen zpCs>}(U0Z})!~8Q?)u+*L2UDoQT7Lr!--Zl=|e?0*LDF5lY-IslaquPyw0p9p|-Gf zfpwQwHS6IDw;7J!xM2HMzV}vrtg3sleu^e_T+u5lwJ&}G*f~&%__(zz4(Qg0H!)Jp z^N^hQDUZ(Wx%{5&;kNQ~l1C2M42%U@Wc|KxTGE;z>Smb%JRL%$YIbHq3*ze*nOhV+ z^)9Z#$8xV7^PuvfY6J{t4suL};yPOiQo}4-_7q6dA#-r=W%RhkJQ$Z_CAY1=d`N88 zcwoj!%6-f*Nv)0I&x+~hmoUJ^Opvu^R&>{@&p4-NGVVxH+X9l$X@Z?qDQ@o7*Wu(Z zNNng4qIC2T<68pw&m)3t&ifL?R!JEw&OvQ1k~fms9)BeBlsBs{9mOvlajVlr&l^>2 zp4vzZFN!rC$N6>6gbX^l{|H??ecXc&cOjAY(He0RITI->L$-&AU7zwG!^u*Q%_xJ( zRwuF@1Fa>{3W07Ws1mFi@sa;H*nG1UtZx{VOdOW->If?q5RcSLb?T9*9{8X3XfS9z zp`a&7Mas_nbge&jHc(Q0(uWTd(UT7_UOU8PR47Sd?Oc@rOXhgibYPC9@R^jAriz74 zLs!CpNI-G&2-JPz5Q${-mv?&*X2T8z>|urQE%EBpd$bq>A|Ie83ykhtAi=gJ!TP&5 z<Lo?YR4TAo8!4FhkmRE33ls=fEvybdb1*niC-gXwxSW{HEce_uG@5v^A79o*>CwFX zT8eqSIf&8;WT%f@702Yrk#^RErI<bk$W0=wk(j&6Jgk%W;U~zBB{Jj=Kg0Cs{~K!m zWn2slI*cj)w-ypbgswKw<y4201FjlDNrMI&D(^QlN=!v6W|r>sLB_AM^Zm04y>DGV zd|JJ}<X-OgpRT6$Xt&>+Blc3oDJcbTYvkpo8D<jnri>mA4yHm6R_^mUxN>^9xZ8Sq z1iCq63WhGm4*w+1*y$2(4lRV2<<RYmaz(_B+;F*nW^Ozm=3YnMTs<S+a$k?E{jorL z8;4U$XM2Wk>KPE9`im@yC;soqlFR=Mvc&yaD4j8&;4N6dx9nZ;n3tH}WHTp8vNL8l z7UqT9JJc~SjHmsk1mI;Bb#&tuUH(n>lJ?mN*8{=G=JFZ$=}j2a;(7zCq|yLsAIoSu zXLu^FyWGlN(`|RkXgjd>18+(%4q>6ErhqG^IJt(RPgeWIP;g7CoBNgiTl=u13)=K> zSP3H%d792k?lZA75<<)+iYB|t#}$f6(6*EB@cs~D-+?qzC~0nAY`*vf@1ZlFD#~X; zPD9J{_$EoK<Tlg8ez<RR&@^Fe4_#_O2NfRp{>{bG@$1IM+^zd<%5T?1g5ozy-rXfG zEK$kMQ&@0|D1CqIkRddS7))Q)IRQ@2B4m>K6ljeH=A7q&Yvpi^E+({+6M09!%*{QT zJR2uG@<`Kg;kdava=ZdxRL0~4dt3M4g~p$Ys`UUCjdY`;*tf0h+W8y<dF|m=_3*3y zA{OXwutcLnHdQD%r1YylYXiHOQEE{+w`yVN-+a!DZ&%R{OGY-BLu%9WIb(8ZS3X&= zXw3n~D}W4*Xu~=>+?yGh$XUZSX6MHb74SOmm`YN<1hq69&PcbIcXK<PY=857SQr9V z+^QMFX%&G(xpm=PcLGm$rf5Eskw_YJ$3X#5OVm&G<-Z`!KREzruM5OMgSO{OM&=GM z52FFIKND*P>CNH2CN4<2@n%A-o<)<xbG5z%_{sM4L&Wtm`{Vbht4B<2hlU#(1C8=F zcBpB#Mg#eEiXkxrIQynM6}JDKv)|nEzvb-HtKkHbZ24ZheYBFF%VOnt-1)t|ArSPq zw|-RljXaIiVW_=)$J@Yh^up~dVcOt8Xl0DwZ^8YrtHS@#Q;!28I}RL-v3s2c29`h( z_`A@lrm{Ce$mG*GP!9q4{`^PF2Yi3-kMR24a{`d~029w&6h6Sj^X?W-2r%*NjQ~tM z|KjDk!B~Ka=lSNZiRax7VB-1zjIoa@w1o~r?|q7Ni-0xAH&F<1@Ca=I2gU;&JchW| zI6{9NJW%c>s2KkoJhupl$^RTYw|^ZxLR-6nYKvp8S_ZTnu*6^37FrxJozk#946;U) zc<!)9tm=|vg%QY!y<E4>8gxfShz<w%-b{EebVVo7Mq>@2nn28pgGhM>NF9Kg$^U}w z&vxTR(^B%4IRwIzDei~-7i%A~zUf@VoEuSo%LEt}mP!pH)`fH+kyF`$&mGh74;~PS zIilNbj5+*Yube!<D_7%oYwgVdW8^)XcFTr7BSmOw7MDmoPKxYaA9fqOh<=V1oXu~q z>^_+vz@0x@0qv9pr=+XBOjgXN>W{yJxvBaj46qLnOSSV6{<RPIFm1&_3?+?J6o$}V z1+aP!IvhS2n<**LDzXxPV&_Sz^IBj$0-;^OX_=OO8S%S+b!Ud2*E<xBz3SiOFs(9c za^%EgB%pF4%X0Kf772o);?ctVDyIA6_yO^I4FMM!j|#(<7{fXUrdi$GLXh8~@Hqu< zM+&rD*;y<ywH}z`l7AP(1Tq>+ukM0>cicFQQx^fVCY%wod7}1l8Wd1n6-a)5(qaAE z(=wG9o7dp?z#>$yp!QCLxyGF40$R1Er$pS1iVZ2qm$15oEd>;;s2xQ+k<&T0e&@&# zlGOh(e;<^6t6;NgKEP5$Vc*7U$lSo04b$^Vo6C}q($K+GVIP0)v^fhFmdMfzq2n8# z<6koYA|3=kf%G9;M7%6pM6psK@e>+<PB^O8^7vaUK@Gu~t~6a9lf=Uj^V1WaKu&la z58lWlzJSku*c+rj;fxF}Zj_DIaID$(BH-`AA8M{Y2ke(1AytUiQaS<@djiyLn#%Dn z2IK<``W%pe&SH>pegHV%_>wHZ>-7MEbkvH5XjhhGG!m-h9~{34;vX=-r4hjCzyJB4 z*o6-HpbefZpcBA+M-e1g6e1Zd*^~lvKix+W{I*d4m%iU55?Aw=%C9ja4dxDDzLSgs zp8p$%AH60GK<Ia+`Ag=1Py8O&Lz1_uW<mASA(9?M`SpPKfS)PMJwd0YY@I=H)Kj17 zHtJoqGZ0>Q)X0(pgt(?GyLNOa1U@8ggryN1>c#mtF9-n6kDRouN)<UJIQkVCA6it# z_8tM44;UL@vA^DrFUaJ=o&apgiCt+A^D2;caX{=~O;@jOPL`?kg-;83U^K~@-eWpZ z`{D^ZprxqvvWP$=dO4Ng7wc$P$2g?VI_w)x#)<f!5&RTzANEljVgwkbSw`ygN2yHv zt8u%a%$H2_bsRZ*?T5~lKPb2G<#<x&+JGijEJ;#|BYwH#{}25BPJsOwTV<3=Wu>*h z5>#XZfR(@Y=d#EESdr5NN0r4D0MPe#ELo`i|Bu0M0c3BS9+dnics1Xh_!5EKz@nU7 z3NSR2RNp~sbxEuR49)sMN~Wu_g8)M_loY_wOta*7TT^1KWd=tXqAUCO9)?tVN{F!B zLPNV{;v|ji$W4BZlwt)IvW)`&hUmyolRi?H`$lJ+;bRAubPI|C%3O^bujo16EEqi- z<oZnGInZR$#!hUWNQqPYbw3BJI;n5GQBZXhk;l@t!zAsRTcv0(Ps$VyEZEXA{YMee z163;4)m(5^MPo#`{X{Xp9(svFx&zV~Rcy*Ts;H}`@WCKUS!w7#AKt+06|YKpFf23K z^h$AGQcRenc~#lFFUgP4jo5Q*kI}G!CU`6mfKthfFPmKYH!(VD3Hvo3MYB<6P|S$E zX@kdU#XrbyPu*<F{zMBht+fG&`=W92mQeKci8`Ii#sL}@q3~O)!ZpaMi%dfd7qz20 zI=CJ{Iin<;Ye5Zql1dxDymI!sG9a1{;(d0r^fl8+IiPw^=<B9c7OVxdnJ68R$O|2s zuZ%4`tAMbaRn~hj42`ik7Zo<#!|Mm03PRYPPgi~;RBT_=3P8tvw|)_Ra#O?gid{(` z%W@gB*6<vtWW+a3wzTPv4pB7nC|E8`cEXz^iu!&=TeM_Av%_uyt|6ae8!^ih_fWW? zBCKQAW@F3W&dv%{<xD<1TSufBDJ(0%v%FJ%Cp7YtTTBCgF>nVet#~x!Pbo%HZ4T8R z0t42ubN%9K$_9uL@x)UQB@sJ!nZ;H>#{@;|4C)YfiderJ7CmfXjIL4PSa+RdamDN$ z%AQ2HS6-!N5N)6w0CxznC$t$dCz#VDW03y$Wr(1WclhinbMje6qtH3M2<<2bovNuo zdvB2EJDa>ZCRRCn>%{y)`)9c=crA`odb65cVPLjqrWyp3(XtgNOi`?%A2<YysZN?x z!4>#015{56^|2*=9n6PB2{@-Abj>`hTdk!%Bqu6eEwh#NyDE_J<emn`sx>5wDSg=8 ztO9<#aO;RjoKB+Zue(}$wy?cXz;+C)zA06m2{q+N$nIiP6r>YDwWPSa+2E@t89hh6 zqz!$Y**-&!yLI@VwdhQytQ}T<v_h+*Am=f)^~iAFX(!#O+@P*T=xR?8K*r-6!B@IV zl7U?zcWP0tKW$lNd;;mo;^rc1AbW9>CzfTb=3!Vg`B%kM!Vyn$RU!AVi5OtHs)oNu zZUMVP@a4I|S`jgZfZoEnG0l7*g23`qU8Oh-8}(zIg~w#fr!QJUUsYhYp>hYuu1r$_ zX+$6gW%@YnJw%7}M-ZWv>EXHF0KtpohO1(jyt5>0bW9R!f5VYUoy%zKw{3?9?k;Xb z=vDjm2i+L)9)I?zpTFkUd&sMpexotxJsK3{fxAsxFmgnnBQQ03y0!xf-zyBPlg2P# zAbQ3)TRye8kz5u2+;^5f?vPD2lNQQMJ`T^`H=5QWv(okNHy8vmR>h6|Y@NeV&Vcl) zd&QC0P8e<PFnI;57jaiHb@NPK#{tCCCii=J-O43W1V5sNXhl+tHmrua3iKM?_+me> zvscoC$Z8u@;|;qCsoV7L&4x9}ce>j1@4%x`9t&1}WT~bRT&FD$WZX=_IUl^v6|y5Y zGl0E*kNB=+@QH?AZNO?6x<faaXBfuiJLxZ?s$@Wb4$9B~fVtaa96hxJfjB_&JX+99 z-sGad?pLzTx@#&KOw*_riaHpdQ*H=?i<K6ZOcB>mv#C%WBl^hC1>d{;!E4sR7TUEE zKB0#HN#N)1bxZBINRlymCa9QRrjdlp_lT~mR9l6RN1R_6n5f3v>b#uowS!;&eb!}s zo|p{%CrYgdLrImt90(5G6g?@1X}u;WJ~*4$y4HRcy(5PH%BOCkx&jNvO)ixAihp%E z8$O1%NyJO(+j4ajUu9EM#RYt|j*EVwD9;e?QZ>){En-TDiopp|0!;hIz*XoOkauYn zP|8jUGVDS%&jOlyqPkeWmJa0cwKwgAKfYhXFE+Zp3)C=e^mQ0>Bvmv8?C(PzD|0Y` z=>LH;*kKCV-@CJC1~+Vgc$ertHWgk07O~}&Hj)Wwfjr;}vH2lWg@(f9Gs+ch2XWqu zMYNA*fFjwBW(F*G&;ci`c&B=G@JYHqm9T8Pd6S!5&8J9tPH?!5c53A%xc(Q$z1ip= z#@)#h-Gsx9TmoSx;N+CJrakP72`0QEb=5{9>rtE8A0_n3(3n?0oK%6pCShIGy(Mk9 z<CwrVzoAuq85(7A#9e5#NpHmebd;h(U#Y8;AzBtKjEN#sW<+|;Sc8d!-9$V|mQYfs znH>J7g}v%JfYu&txnfWxcmOAzC75OzsJ^!N{x&F8qHoeAa@t<mSQ(Yvj9_Fk@$4Ft zj9GDJOgXdq@_B!|dGa*Av1A>@yX-i8>hgPw!iYImKZ~7ik8p6vlpiJ9pix#*x?a}; zH$!fYL!>z;<>LvSf%@w&!rg7YReSq}oJWn0^0;Q7>ur%GOrIHkpRgauX1}1rUc^#P zEK!A}mJ{(#k_%=(wqcC4BX&Y`XQX6efh!}VfY7Y)*%)?e3{0iG>2uiU)#-YJMt#_h zAOLwSgK!TG8|Nw+udTx^Gjg~=ja^c|<#kLi=raoV<YNWwO6#RD?5Hg0WkOF0$sWLN z$6(qNwMyIZC@Cx)o@Vyx^zTvE1GiY{;m6&4kx*bN-Cr8)L7>>Cs67OG<^Nx@+n=xB z#UCYZ^#(gF*bvI~#2OBIw!7Yy-mLD|tq4Nhqkni#tr+MUnbLp$AMtzkJBS|N&T&A! z(fjAEW?t6ujeN4A_H{j1{zLHDruxxyp8e_-{(1kh0D1UcxiVcPr2W3MWIokRYPiFO zc6)kSzY_D1zrUc%%MlT?eZO9(;r!mV5_9)5fPO{zU+8wDcjFt*s5#Y~#}7^Fh+0?| zAqP}43b6|<2q4ePqHr;vpAfyzydnOJwG{<|?QFtL)@?JOreo**InntiTD~IV1q;IQ zFp=l)=b_h+muAL^3;=Aa8pNg4Lajh<a(va?Pwxi>mP5TxKhgms?-+anu=YTg#2=hX zv0S<%#Iv25!akL78ln4rMmjbnM$J^!1gB}(Pus~(^Qv(>nNcsACUAJ*1ZqZOL4Cn6 zpop)|R?k;x;Wt+mmHtLOMvG6%rq1|utVHJTyYbuHmDp7n>>qh6o3~X_%&fz!`on%i zH{8EB;EXIai!b?YO`<XxC^kVEDW-!>`mqq6I0n)(Qp(;UH?WM%%LcI^)D5{(3!sg- z{=Q>&u4p`?{i`LJU6qD41U?0OTE)5_2jPoj0LSsNoTcP)&c-Arb3D3C=rF|JLfZ%- zG!Qo-(?rD<PLrM;!%BwVC>q)no^utvA;h1y=Y`#cz1mTHaG3qVStT98S>;9{OX<>j z6J<J8C0l^xvG$~B-pE4#1bA(rb9Fhos*=Z5B+76?qG*JrZyuB-!rd%lx9!e^Iaeo` zeJjlRFeO_u1~vt6R&|<J6>cVT;zuxG|7Cw&!$1K1H##P!sx#}gfFIgz@qh8{E~tOb zm0y<V4)=1$L_^hu0r>W_C-oByc&D&|k@weR0tE1bzxZ~S6xJgEzI{AvINK#SL;9=P zS*r|flg6Pos-~9LI{zBUcEYu>v)q^*!^#$9HNvj<hN4#}+onFv2-Vm~f?*()Q*9zs z<u0O*84RT*DJqaRDr?QG&kKcrZ)5i<3;;PF7$RqeHhlGI>QtW^b1c!BS>9sL$fitA z6xf;x5XGq*@<BaqdU3I-B^<2>OJb8wdw#G)qfZOAx;rz_mc&*UX=^okF#6JQ_QajG zy}^XWO>~@owtK~rKMq90<>f3Q!{)92ax)kHQ(Q<U?8`N1@n^WbWI+ywgW&gZ+wSey z@t@u2(;FJY<;LxmT_;q6$lZO~eEuDvRnykNIZ;;aKm08KYP%%{`r;~p+D_XKiPo8k zyK_hXV7%PaY+28%A_nw8ln6}bs!+X3zKB6*AZ4(3S_*$0EyQB&2!9B(DSSi2aiJ)> zmmz^=$g+FD0^A*GctB$F#Sozx**Z;dya{3;?}!g*D1I}a*Zh-E#Yn#UN#zCfp@8z8 z+3C}-rpQfFR;wc=|C(|GuYxYXV*xOIvIY~Vr*NZK#^E9eK2^Mzb)KM2<0ymqJy<H{ z0aPUhRH-r&NCTbhDOV3tT3y-@nI~SxvoC{Oc86@>?tGkVL6^xZ`|SL&8+EJ^6Hf1n zr$g;ZgyjO<s(-y-5<{?=UZS{5UlvW3YmB6~4;;{@5}Fc%QUfftjVS#wz=heQmkqXe zT=@~jvT`S*6~#WE*Va$?AY~x@vKgFZy8Eoi=5GkCxLxaCez;bo&zb+W4JjDLy_T#4 z2sfbHrr(aPxiXJ<@rtr3hVL$|#*eCikc9VoPF6Y(-ET9!cFqUSZu}cGrM;LuhTV5w zA2PFctgp`;0t!IJv#`X-);r&2b?xawAKd!p=uC9)qm1BhUN~bT@Dh#rP3`X$(y{qd zhk&<$*k1a6+@IY97Q~LfV~w*D?cgG@3$B^eE*E0kVnQz(PC~XpD`&zA=+eJ)K{iQ# zQRESpT~#4Rso#Xw1?rhsbIUeKutPf12V^@@R88tF6wE0f1oyyGz8Oeuy#dZtQKf$- z{cFG31K1oj&T@-C2fjoa^k1r8wBKSjk93^%EK#S^Z1jH<h~5P(jS*s}o)JgOGJtAS zrY}1U&GUP02LT7t;etsD{b&s)GE!tb>Z9s}PJFMAbo0-P(LEfylztz*#WH(IEEy}+ z+x~6p?ocsAk~UORuqNx4DW#qQgUL7e-_XQ5jiW3l3I9tpu|f!#heTf#P4+t;Lx96@ zlA`#@Oi`pp0KYvyG*f7Wv;N~Q<O3ULZFER(|KWJ9vPG}cuPjj|fh>0FR;XDk%H0+H zES|E4<{rj5r2?*tC-498iF<REUze3Pe=Zs6EGXC94tRd~uYVUmd;c=K(&^aXNNAdy zq3i(}Y51AKPpUB(jJYbgTyNsJHyFV<&y|=sHUS<V7lfZM3n3^Tvwgnp^BSN98r=;- zrcde_OBa7Erse|pQE}lf{+K0bYrwu4Vl*Eq=ac^#A?|RbBMqPb?sb8s`?B(B3hjoa z4N*b#DdB~!tAp(O^_Kgiwvy!@^L4~dm3UTS#m=_VhNnwSKYzX^_xFpIvMcS&<w`v8 z=T%F83ns9-z#u9jWkWbS`1nG0wDn3ooWJ}$!4G-!vXag85NHBI*|4wT*gkQ0Cnvae zz>tbVfeK-k64i_+1MA3WmE*&cFVp|Z<~p1kTh<Ig!BolWy!BU2W2~{nPQ1qJ#i%nS z>9gdE_pi0a)w;ugP`W*0%qSo>nI3rv5U768f*;?#^uJQ*liftCyT4vN&;^FeP$a(h zbjL`h2W2wSLGOt>03FS0{Vv4!dc9xK8x#Iof1P9fg5hiD>$>5<B|Oxzu0Z^3)EYoo zu*>R~9>oav3uVd#QH{Fcn7ANKO!B#vj(jMZdY$jfH4O}E@=Y+bU=w`8_~iK-_lo0? zMw98UjP)bjvPCZ;gFiirROFOBP1al@FXlu`PKarD@BKZ<*k9WiJa7Wmyb`+8Zcgn$ zpI|9&*4?rxYVK`Yp_qu~L{{W#EXRO4vG2d?bn*+8lx^Dpua{&62b;lIu*)4fN#Arx z$#G?A+}{A-HVfR<CnrL&4M(Z29)GuC5^d8MZ`U&Gm?KC+Qm*4PbS&q@D7<D1<09jt z%RJR58p|V@;RA*FzFzwk-SF6@HG=^uk@-1VyCt}uUettmNm2z!prf9Cagb;0qaK&g z8D$33f;r1X5Zo7-T>IPd4+gbbk-UV++0Ds7J?*ZF!&v1a+~5EPAx=+39~X4Um}9(G z#j|!MJ4=%3Mi(X2O(GFa_9`A@s+031@2y1<nil`e3=k_y<~;hf$c)-w42BKt87>F; z#RElq(j6r)Ay2DjKQ*AK(aR>JQW8zFV-X!SPT-lJXLfTG3&yS`P^Cl+>yG%0S@<|` zl0&>ojoqwAsNr7}#;#Xu6>%J$B>m{fwelhxuF>WNQ4$7OPvSx>%xuEQSBwhe9hcXo zAdsc28JRQ;M?J^E*AAzZo~_#BlMwOH17}bk)8+Jq0-}kiwVyZCM@=-7L$az2Ytifp zd3tVs<su6bILu1|{rGw!{MzAjM)2|e**7xa_Xux%?G9%ynN<)Qb%41qyn_ua!WQsZ zV%}ot=DMJry^@*wtFMW$>vKnZR<|Tt&|uhUFlyXHHJdt=T^%o|)*rSGN|qax(J1Zq zsQCAINfs<VIq#t@&!Lf$`M8F@;Xo26$04_-dJ#s(Wm0U(T2hCQ(zIU*Zn3uAxb)m? zWF}SAesV5_J671dHd-r_?w&%hQJSy0JRT7Y)tVDo5Wi>}RGg>dxI(bi)%x~ePV@aS z7~>ri8M!JoUa)g!q!32G#^KsGdx<l*pT@mk>DA!AF?i*X^8AG+(PhN+pXGj+)cgH! zn~;nXD}dQIAS?bPf~o8*ByxKgP)~$$%pDcKi3v%^%MmIGrnww!nG*i=UajA6w&=P7 zz~vYF9ILuPD=V~L8+KN5Z26IW_>y!GhSu}2{jCxGO+T`Hy2t~>gmoy6abFdQCE|1$ zM68w*hzZD2;Mq~42x{o?nJ$nT8ozb(A~t{@%<eG_Qbhn`m~(wsniKNp(?pO>4qI#y z#^l;td)l&u#OOcHQ&LNhUJZkla8Wr}KCoynNSNl7qNgVF<8CnjJmfK5Ta~veNXVn= z(F@QTanbc*_oa_TcW!}pF$P&kYn8`KX$dutYn9K^v_mBDjdlv%6Ec{ktzBSRfu%gE zYTT9iu?{3fE(q*+gCDv-db${+gbIST<uJ*A#l_Uxgwvd{x9_0^PoEuvHT2nnGw#;W zb~lS6dFsY_&R2<rH%GMTZh5u5f78-<cU_{xMP;2Io+G#lpA<DL9l9ga^6rphzVw~y zWy}<HSmMECQa^=!kO0h$`1s5F@%4T$m2)Qgig8*O+wSw>erZB!|Lkim_-21UF){aI zAu-VmbLP5bdH`_V`d#jI%a|~ygV)>f!9lFRr`vPr2UAqFJi}IYr>BpH7ix{#^szCn zcpr&RYgFp9yW80@?X%%Ce|rF!?^Bn_>)U!PzY(Z-IPN>5xi2W^{y`J0mk#C2vdlMr z$xOTbSbeLAyuqCs{e{G#pIUAo7x8s4QS!rtoPy_sc6MFCU!$$j@B0EISC4f!m^j<e zr_>jZg<OLZ_Ahha^(e2Hs(XLM)O5PkzCKg6xq~p0?&&4gwDjeEk~%qiroMkb&KJjK z%~5#+JwBVGidoq`v<_Bj-FjOwwj*$iIJmt*xum^&LvtM2%X&55))?*uLUo~gJH89t z+>j@g?CUpx@p*%ZfvhEeKof$P2Kq*^3t)X5_rQ<}zjr@y@acM8)qHz)sJ*s)j(;-$ z#*{;s3UMTG%<Ua%_FLpr<u;@Vv!+v;$a%~0#h^pycTiuy9z)Ha$ceX=NE?qPT6Ser z&w>{NBVGCr(Xg6wK9=78C(=<Ss^ag!e6Jf&@2)N?zmVXpB12V*Zw9SGOT@6)`xT6L zyY6b<M<E~WTUsNkX1W~E=rgKzZK4skXw(C8M{_ut{xl<2khXoytJXjCK9m2(hDE%T zQLwPvX(Kn$wjSi{TULJ|d|wjYm$bIt1qPpb`tfRiO&lhGvqNnMslMCSQmsl@k^g>p z^Ydhcs$@ow06TSSSr3OP`(c=qZ<JjCRosoML-Y}BRSwwXW{+Z3dqtA+72ek7B`4K- z&iW4AWVKsB05akYZR`tNKjzwjfTEpL818e2{7;umzMPqP!aNz#`&U*mV*s!33x5WY zKPZpKD}Wrc4aN8FjRo!-&~~dTuiEzjK`{|P${$AsZ0NUyEIfgN!yUju#ji!t0yII4 zFqD;kYw%Eglr<h!bLh|NHjJZHYYfR}6djykM0L%52zr8lMprI!ID$hn5ud0@^8*~P zr$8S#?bJD??0uCld5}B`BzwO;up?!9j4FF7Twx2Ae5hN<%tDzaX_*2(7Q4v@2Ho@* z>JYYYY&`hTQo3SH2+4@h+5mnumlO!zSCSt0=1S24`Z3~l6OaUxwDCe`7c)J0i^n-8 zwm_i6$@5vnc6qGt{O@OMq3kGM?LRAOgkOzqH>~CICKlP9Hzfo4!=#HLL#>iIa1)iZ zDLMqI2?m-J$~M}S&azw#Ry-B7t(w`kBM=K8SnCWU2-1NGK}i|~Vo<cu%;~N_AV7gF zWbib?9mi@<X<`;aRdjPL2Mo!b$Orc1c$q6r3*#O48(6B_X^B-F8tK~~-ErJAhh&F# zD&aybQ&LI^R|e_&F2&s=uPe${1Zltmg2fs}sho_%V-+2az|g`=x7f?rWzk257GU+Y z^I>NTQ!rKVFy)#39F{g6%A%~+cUs*tfTN_9W9J!-s54Y5BSOa@XgFg1{2>0sE1ou) zYQqi0VW|n5Qf(v14i71`4Yp>ixlx&@TMZ8}9fUcsH{2=M*VFFrtzQ6Yn60R&tl0Na zl56VoRRNdTHv1p(HUiraU8b|PiD(rULpO0+l(aL!M1-b;wwE*$cIq*oYV|8^jxadd zw-w~?2$k5;^8VsA*lEWys+Igh{?MiGJhT28{_F*JHaXMcSEzh83aspCfZyt6t<{Y+ zy*&;G2UGr!+5Voa@hOg_xi$#Lr;PcPoX$7+Xz87E#!IJ$lRV6JB92B!@J_J&P+%{- zKg`W|!qnVW;0eaL**G%+Hl2|S1`K8XRvws^b6V4l$GHsGZPks4Q{McdWpy#22<^u$ zYlX$KM-YxD+iJII)udOXA3w$l*8*mGC^S+M{-m=fj9*P^E*-iYo$GJ4?y59;baA_9 z>(m3Ij#0VhLgFZF7GdLY!{9^*^~1rrFGH~^k9xLm<n$}1yTfB&kFEH2c;0fotd55t zs^X*fm|F~FiY&wF)Zym6iDcwq&PAq-JxDG$2Xnu@Vjw=uR~#Low+rumk-)52%p`j{ zTXN#d4?I+1zL--m2<?B}6)@#O*;0c-Q^8_FQ<hhS*tSLvGRI<X=&+_DyIAJ8r;OW( zD0e4M2Ff4xN<7cpQ@n17qUpyI^GfP{nZxV$cqiSvBli>hF`H4(?*8qk5kLh=P_#X< zbahR=ueI;t@bX+y6F_T(D<1i9@nI#96X@!8_O_FmNtPGcd7Me+OunrXvOE4Xul-T; znOj9zKt+F?dE2{R^S-n!ZdA?ZhW?v=|84f=mB`br;r+D2hNDm~(Sfq&o8%$hNAmJ! z%)5$PrZ)Na9ztwH!f)@VUuBesRJhU}Pe8X%Y%nbrUFM{3ejd2QYGj|Mr*zs7YEaAh zgU*)j4fRLAHjAIp6a7aFqfi_xh6<%M2{0J8QeFqR3y@v|mR=V-9u(Xkdl_A8bp(Ih zr@~(Sj1&ptiK0Yi0)>gZfY17t)&tTm?X2oxV4}ATIy|$!-7B=Qy~X+^M~{|Kd9asJ zwC$%~HNA2D(^VRq+vUENfBAUrTK;1x0_*(Xsws7Kr{Q3u=i@OG^|{PG@GIE{sG%M$ zL!#$Mvr5)G(M}HODg7=SFsY%`D0F(ny3y7v=ZV{(LdOJ5YTh<E)0+Hg&m!fLzgm^! z3p9naj#h^EoEpyX6E{P(Oq!>nhfq{Q@ZOWjQ%5jm5{71K9RZKUEWuIzlw_?KCsoFA zz(Pdi$J%0}lBl38*D|~YJ)2iOOy_OR9Ze?!2Kcvryh{k<oS)EP^mmcCzBg|sZX=`t zBoOJqb3tG`^JTRY;O8u>+5(^*lr#h7R0!-vYKXM3C0mv*C-gowX+&cm^8!jahCYSO zIQ3Eo4AF`!%|EANq09Mfc&~?xU<Hp$Tj<-iAoqx?SRR!ZonsaZ)wsA}FsnG{fbl6L z0=}TP(|Ny-y}EwumfoqFkM3~}VNhgr7SFyME;T_b4`%Ua;JS{qhj!h1=#NU{2_*Ba zR~{&{hg#UR;*RC|;x#Lwf&;o&h@pfsgn*N740&U&QJ`J;Bg_XAgm9X=a2<$v#&ZX& z0$5}_P?x9A1%JqOfQ6$*93XNaqrGkMx$l!-^A^0LmXtN7mVGsH01>sD%Llo=UJr?8 z4iGV`{Q!A`$50(6q1RqQqfPoLg%+u-GJL9S&^o0Sjb2uo)v0IMs_5d5+wpO0_(`Wn z8ikWz7`mMigNoS0k8*3uD&!yj2n?FXCrpd2_q%`I@p+O=wvy9=k?PeE9Cr5)D`0Bp zD^m*CD-RkJ;?c2Xl+mZqx7cY}A6Wsdpw{%4KRi9jM&S<DkI7#UQbIp_LiUNG9{SCX z=2!K-74eu^SuLC)EXdZ`siN)PsG|?N&TSkRQQNxHFZG$$zX_>KXRb|{zvEF<8fIg% zh~K)Sw#7x9{$4F;oQ}46cw-@D`#L~LyuK(8A8x|ftsoz1?%hN&51mDX^x)Jl-61*T zRH}iW-~K&qB9w+pni2>@smZ%rr3<bsHZ4JX&>O8xg(l-EUt9nUb3z$_5*&37rvWp> z&{&wiB{NU*q?^Es-oXgY{zq3dGQN^(!mUrnYZT_fSQ>iHP(7g@4Q5MHiprYLroozu z|IWzHAu&%`bJ|)&etxnK<X610p#1`LP(a=Iak0ux?eR9ON&;%_s>ZZ5gTQp>)U;Oi z7xG{vZUnPo;dbHgGD(A}wm=v<o&{2)i0^V{9I?E`M6RcIO7gBhz_45|N0@8Z$*>h9 z`#jM-q%|KeCoQQwS6CL#b*v_*wz4gp{y0r+vAZ<5nneXIzmG=Sn^AHI$p#Bhkqe9N z>C3Jz-L7@C;TjIh;xq+sB4L?3fcRrjmLk!UACtQ*$4zdT=v*FqJzhpdN|EPuMdmXv zyJanoG@A;AKG>RF$%UM65_`IiZe6H6+O7>v>17K)UdDCt8ebjJmY!!Y_IQkL;n%wg zw4CeU2w`g-h5l{+Gy%A;=$?afo$nuUT^rhu4Elcn&wtK!nEZtw8ITnNNa*ABV9>{j z8(i~v)UYn|>RspFib6co&Nm5<YHr#4N5RO|Lb-9tCk9Yx{d;HJKma0K&>u#<02kG> z6=%)iTI*<lxFfew-`m8K&qD_D&HUj9Ol>+F$4Jc>bv7f31#7^{P}o_?HmzvUI4Ot| z{xi_BP})d0z+!k5OeH~VVzMwEB7;YQR0of&h&dy)3vHy{qKP3*wHnF;E~FGcHsJtT z35s02w=v&_W58B5n~BQpB`W;aULl2j#*ZB~HlsyyCc64lU_#UELnYNmx4B|#xROcd zz8jyY;>mN*BY~c%Z}fM$DTzHTlfJK>2Q%v+SNV8NR`nmz8JQ3)`-iQ5^T-NkcPp{q zuOLL&19MqOS}t&rekb(A5LH5=JcrCLo_q_PAH{}#OpyE?07P8o$0lenC8kJH*CykY z8d)wZp^Zv5UzLdxJY}-ip}oi=G{Y8D+)rzW$f^oHa;W%`e*ujN{wd)O42^LbIyozb z6R&`bmPT%ZB5Ef&g;R>lQ0J!}rddxGv9+8It>co|Jt5T5;cv^B#9)J@!eLQN*52sv z1#&ze!hWQ?jy2b_y-^e`3Y935u-5CVk2G61L|1RSgrv&XnV;6Xn%%oTN&%DAhWB%o z{9r*_VP|&Q?nBfbedj*tj!Wpk)ICk>dGv8twDxgsA#8l1;*4yC!~m6RR|kBB*NdE7 zw)OgI@4@9h?iu0w?%Ty(V+WJ$24H{ajc97}O-<_9h(qHYA>Np?1Hol}FykDkZ7n&^ z3wPMN$#{~G_}EIYF!nfSkM>L4zyTN0+fJZd2K5xyz?(koG6FXQ7vyk*{RMdDDb(}_ zRWEku7&f)dn+0r+=AdMcS>I8rTHkB-RaIDbY*lD8YmUZXsM!|&!|t50mF3!?cn{I0 zvU|cgLeJY|2g3tLz}MWCwoekrsM=>!j|PYjI2HQ~>5Yk-i|G5um9JP|{dlL|F=3BJ zFf&$vCaztk+#z~e()}5w>nFxZ{6UAFIK*?$Hq5pzn0^(KJYUu%#quI{?C-VFpY#(* z&tw<K4?!u;>)94*J2!Jd&vr1}8JwIWzj#;6z>{Ln(vF<>WW-Siyx=y9ePhj7ue;#C zF;f<tO#1r~F0VQW>RAwu#r2Xl+;7C6$cbGi-oAZru&6VdVE;9XM(EfF^?l&}&6voK zh>r;ed=T={Zmm8{?Lg{{F|8p=heU!7IfIXwRo^I3qtpjXX-$3?e!{uQ>-DVWAkWw4 z<2c<HocU7Tu5)Tw{4?3+p)dER)vCd3w2m9}8p+sV=vVezrVW-&pWRXT$0(VYxO?v& ze_Z9Twan~EboIEkVTQIRtZ%lj$u}+(6_jFLC(3*&L%yGzpytr15p*wmf|77j`7=@h zC8TaNLTbY5i1Vi5F7Zr9q`x*ds`i|pgK&^FF7$5utsTLa864}-i(9>1FpfYKf9bjt z_8G8uJjKH-)}$DG4mTzN<{OPE2f`sCvk?1SZnzYaqDH@vf;#BonyfK(C7IvfFyCtq zv}U~QIwEKD*Hrahwql!K)UO4WN3*mkt~`hywWYp0;!Ub_8udq>lMV!D6%juAK?pHl z9#mRL;+s#Xh5JI3bPq+x`-I8grsy~&jD%|a87<{)?V&FG7OTGovk<ZpJ@;dU#r@Al znebQl%RETHO7O*;#C5y<WklZAT@Z2W3rzW($R!9@VA)!V6euyS-=s?`nJCZX<t__v zW5USS-ME$>LsxOT>{I*K-N}ibz>EO@TSZw+wlgYpSCL5WlAN%!OZnh(u1kpIecJ7V zOsBZwISr?rhZ<n8P)&-3P6#6fWFpbOjwpdE)2_S~PzYC(oW++n-dQR(Lq$Hr;xZP9 z#=N_~Uhws&GpWENl8j^Knw|((cipe2Z3=1TI<tlACAbl4!n6<yGwuRt%BU5OK5d($ zSSL{NS5ExtJlVsaj!6)=dOC$^S#g&jR3OUP5*y9ScxDH4sC;LLIuQZt{9D9py_$uu z#fWY{cNPieLsKg`nh?!R<2-9R$mHMHd1vZLR_aS*r;bIKp2p?M9&=3F%Xjhx!!r4c zi_dvua!Q~K8NM)>wfn>LT)ly6(JnmG?z7q@i6DrD9_Wo6E74k+0&L5q%wK?0=jOB6 zYUJ+VHS<lB)JnKjdp*95H&!UgeW%z`QOL%ii3NA2=!BJJ_8(;?xMpCJJVO-K6ut5$ zl{O2p$cEXzJNT_u+2H;(8E1~*Z0Jv!wXp*xZ#wqAAfwMC-x{9btmHPsr!k|(Ei7{7 zR8V1GAR;BBnP<-<&DHkH<?$v*<5oDHoK0a;Go?_fA8iGtQF#$YnhWv5<Pgn`#LEiL z9YT>Ad4)oyAh92HTG-~ga9N*oZ`Q5jF6BqqxO|}(4PhOv@}kzY3!SJwOCp%nW)_TE z<_=xCTA#^*C?RSp$Er4=CWqOV2Z5-;y&*8cx7fZqsGJ}IU6C!*4iI1dsD*8=q?b9K zupUIO>&GG4+H2LTcbnFA1Iyg)&FTPAq@JzHZ}o3&enV2Z*13bbJnFsW?(Z;&Fe8}x zA1{$IESKJ{j|Y28i6z64o2Gq?H@$rCzbH>sF}RJ|icI8+6<{-KU!me)R;uGE1+608 z;_MvaWy;VhnQhu{6WEq0VhPsRoTA-4e?0UaG7E+3U}cqRP?D8dXj1AlAk9dbV=l&2 z8;G=C3#Y?2kuRUN0-Z(fYdNzAs~u~X9z82<DcddMhv}H0B05Hy9x-!s$Q~9~XCP)9 zxeTp>MR$WbL@@yYchK>WIr4W@{vgr+)dkma{01AWbKiCL{roj=l3|@<#yB;xKJv)F z!Ys9y#RxkR(h$>vOUP%Awu|MNU0Su^P^wDIUv!v->}j~h?9;<FwSMBeFE-f7q!d<+ zl!W)D9YyF5Ne`^wbye-J+f95w!Pp2GT-vHCddbEr@Ael5$GLvy_$VIXTrf$)UG#S_ zVAY6iwIG8I*dt_{(Dvdob4$s%$CK;8F;B&18wz3}u^~4V<3@jgXgN!vyq|5kZdANH zTB@m0)r-tov<`4eQVJ=X++9!h=mZlQIKp>dYulM%$fK5i?k{XUdbvj4i+l4+?`20$ zP0(lbulQQOLrKD1MJM6zE59ye?mtAd%mUrH(%+UIv)@VyubmxeKqgxq@|>5hRG|NS zzXq=@(B)TN1-4npaS)N>*6SU3FIM+o7!{zgGQ*}t%?nnq^(zdlpDbnxNff3{r;*hv z8}85GGq7*TU}1hX=SdXETt;r7G%6YlA(Y^NTBRoESUt%a$Cs<(5f@oOC?WR|g#TVI z<AJ?1a3b^SYza-+^61G^q?T5gK=d8BTQ0LT603<KT<qD>#*%$GIcqRz5ne3>0XUs* zzK`Z+EU(~Fc50TGh)R@4y-9%Ed9kYun+J^U9Ry!h#|9gi=X7fk4j%;aiv-^#nG@`| z)a8UjD74qVQ$l=m$^CD2p*Z9fodU7?4&F!^Wv?MpA-bc)_X{+x#bT0!Yy=uOlxtSD zULs&`Rb!+k6yZcT!yHT+K9pKG+?{y8YP#FfX1|7Su~;tpt3iwC!3M~Nm%%99pp@At z!~+b}Fs9Jce1h!>zZS|J_GgyHmoeqE*$`QlT29DB&*Br6I?efYHX1WD6nv}m`*@a6 z&WZ;!8c}?lEl)gzkFlEMQ{u!aajxa*)h1;iWE_Y~f6xk<6;Zs*lXd$a)>^Ne?$xly zKl<4KZR_?>s)a~ZWfco36KjJ`7+g>}S1ZCIS;8kL?j$0pfNYUq(^MIC<vG@`NdWIi zNb@LLx_tl0b4-|=&y(uaB-1XEOxaR62@M-pAO{jo$m58$?O)TE1V+N6X{!JAsleS~ z#G{;26F$AP{6lv1O%I#EpWQTRQ?&!=s2H=ChUi{71p%}7SjqTMX|S|`UaQbIVrOjl zSD!Ntf_{Hy{!Glv&uK5QA#07J4k~+-KnRBNNUj%<G`rcr(#4&!?>`<}D#hD1<Fk|K zDO0N)e<`Rn_xe-B(=Xr~ORF~P-s?3Fw^=hsuuItC*jLoj&FY7Y6Grs_t)Uox0wj*6 z%RZ`v*GsAQb#Xbif4=X`gEd5MTrz+cJqHtd;$6U;fg^RSW+`MG_p`Z?)sx|Iwa34% z@5<ZtM5PNi_;MDnJFMSj-HCh(FyS`+k=*l3M-2Q^9xQ)8X%jK#}<Vt6zc409N3 zO@-m?mVck(*E!z~om8bvZ<yX>L7O|6ujX+{w9h<@G+QaX0rIzdLv^1TqYR}GWeR0T z$?_#9#WGz8p0b}al11%h$AvujWKGmnYFvMuelVFV<z$xgTRCDiJz<n}wMblaiCSJ= z_$+R1Fp6JveK`I<!Q_%|pX+dyooEl4u#zW2<+JGk>^Xw6-=j<^kovym)!uMy*JCoC z$CMczDL5xwOC?4e^0GE2<3T|I%YDr>5>Ts4DQX{UE%vvK5$GKaNRz_k=-S92jwUR} zp1B}gM3!KyNe!qg(}VoTpxR+P>AB_>tmQj3aRI-tCPZu)aPZEmz<~Mwi08bgAQ+qw z1zR48GR+@j3sk>tqv0_5bROVCuqf@9c&|N{7e%mLg{CFNvKJAQQyP_Nr1LeIj5Q<! z-ehjBTOz4?<&-rsTUudBJ6ZMwga*1<qY)(%?clFA^!OL9=>{5nd07~GJ|5=T80h!s zKQDIG2&3)bXIfbq`g)%D&*nK|`ixSS1ACt#pL-!<0}v;r-}-zD5M^eOy!3T45Pi(x zpFDkCv~d2wKOYP4d^vmxH+HYvU`V?6W8yxai@M>`C1?hULwp_zv*~?bN10EsORuOd z{`rR{>gtQf1Bw{mv`4TJ0xCfN<8kLkZK>wk?tG=UlV4rbT+3sQB5E0{EwWyl{fs=r zeuK?S3CjssfP(Z?_S0)(L%wUUQ}a=zQIjA_y5Dh!iAItZLN2D3bqR&hNlJ8LCl9JJ zG0rk3*y6&nX|O#h47vo0z-pj$KO6qefq2_`kS{S*nO;*h-iBFK-OXpe?^OrNJmJnc zBg2{Q8jp5Sl5g{SYa*E*Lly%uo=7&zz4)bbx;+g@J;G9vxD&9T3g_<HfT>PmH4GFb z>SI~Ub2bo0m$tt=4r+Pj7Br(nG9gEDTGnLeK(>IMfe4k`UI)FFkB|!VAqFcF5R+PM z1T<Z`T}Ed>Nd6L|z)F+yw`|XlSTpNPdDK5Cur)h~HW@NpvZd2-lc)B<DhxG?rZ6h^ zPPI{XFF(q9M@9~g2d&$P@Y(QgyITEQzzmWzi70l~3_i?#5mAF(Csiimx=KC;v# zhix5&llXt;V{U(^tMa%X$+$goh3|%D^0V1NWDImo>7J<0jd)Fq)Sz+O>p9xE?TM<y z1y^-H)+DogsF{;ERhZ1rgX7h82qo5ys>Gk8kbyN}^K-;aO{aGz@zK<Fesec`ilh)~ zX{I{BpO{;DzYo`u${5wYPg~R-+#D$?44;(Em6Uc>9AqGuHLmuM)od3a|49wqsUy}q zM{Y{D6I1F(cu%nqq>>*Xnme^|0DVhVeD!x-ar7?f(pQNB3*y_mxf=-~`$c%=T9yse z9E5avCIU^<`0n<^0h|4i=t>_&)A;q5Q${z`<@@22kG=Om`GG87wz~T7&>qBsof&&n z&kD+l9S_jx3D51SciIe4jm6Z*DamhtOlFF1;Tsf7ciS+BIBPLJ7XS-?T<`<t(2+ea z5QAFXkE~i&>-yIQQ4=Y0iL~a;tL#t^5V%EXpGn9S3iN@w3;DVr0*HK2$vt*t-6SfH zx=b{ryJVO&F59h%e5Bo)Te@QvKAgU~>Tt0H>HQCILF4PLvmG%BkrElfv|3Q;byu;e z*&5f_j>Cr%fe~*&EAGwW7TJHwO5gPVFXrAlsII14AH)gn76^K9cPF?@aCaxTySu}| z-6goYySuvu2oN+l$($tbcjta{@2&dXnyRV!gJSL7tM~3L&t6aWv%1eDb9DNT?4fKL zVV7()r!*rnwRuf2C(5;8!0VC}^>NbFSJAYAEagOZIP<{3O7DiDV&QgYr|y@C6dQ(4 znJ*?zHbQ!VYI@~g6F+!y`i*;iDuJ=HjiFuKc?;F@Qg`2bx4bC^?*@o;3p=~uvCLQe zOxHdWeY#|{=<Q^X5`L|%G=Ni9OM7|pJuM136WMW^L>#*IrX0OuLxktPHk){FWHfAZ zQ!}@U)x^gWg8k7#$KD)$$^OcUyGRBllQ|Is7ITrr#|xT6=3Qpef%a3`n*!q~9oZ|d zQuKYRqhlWRAl!I^zuFk4ra#+45zPq4!93&p0k^MGO{11SeHm|-V|0(c-#1<P6?g|) z2PXE+cSR|F0<;j$u|qUE^r5zkAzUiPx*SoXzrWD*eHH8}IXJ{FtsSzP&U2(>;A?Dq z$EW_zIxDa<MImD|#6?`5oAXw9>gfl?>p<K-m423gAt^Z?)Mfgvbm*0EV$cjO<_u>@ z;nK5ejC;WQ@%pBR=$)S>mgo1sI&YR!WokU4uXB%cN$CZhX{I07%#q#+6sxHoa+Pc! zR;XewFN?}JKtu?NiCL~dj48SfBZUpIQ>FtEQYa7FaI@hphz<qNXIzd5Wsy_PwB~nM z4W#L8quo&ZS0sC+p8!eG<f*Kwc^<1wOZXm#gPP;i(q&QB6C<TqYFDwrft15}`G@35 zIx|V$F^~}@sdJo;O#MdB=@wNmWI6|aN1tmNyoKgFdk68OXl<e={6#Q2s=?T}wVH28 zbGC?*%rxB=3ZUq)Tj3C_J_pg>=3#u2u@1>u5le^bl{9zxB*vw>N#W4M)+!?`zEW(r z$fO0<C#2Yf;RA{-o?041apbCe%-BfmJ+BI__cdKW)6Ldyi4UAh71?}0{RH^m&IVqU z%S@MWcwON?{5ozrjE8nB!>J+=*&hF)MO!2opCg*^P)A%mdUiPC+t_6e@XV)5SX+6B zHtz$87?^Q(m+5{r3&lglpD>?!W{(ryl^KG!#rJrM4ukAZ0{M$UzhGck`qN64v=A9z z;0(K&WaReXb^oxdWjz3`k1;)nN2n0JfS}Ea#%^CRyIiHWXrp!U=RU={jWOg&7yT!< zI~^)%{qWXrp9IqVn7zt4E9xn!92H@0b>Ay99`3(%jSW3$IbOeAM=@zVBEbzmT)Y#{ z?$QDkLK(Ml_T}l16*ZQ?4^K>8XC}8?$3!tfm??`u)LTmkYVdyQfdXXgoJ$GzW;Q|{ zX15@^Y9GLRhbgP+3!e45e}G;Q;(vB8H_u4&4`?DKH``h(W-B3-9Aovv^73lnPi#58 zVC{bB<J^AP9mN|YiWwy6(?j}TC^fts+god1q5yHLVAr*s+Y7M!+;0%_v?^%rJOsc~ z<TVnmxDdiqw;MFkZ~lD4LC^g3z!;GpXoo#uvc$?58_4TpX*rU{ezyBv=HOdQBk}Q= z9yv^x;*6`*r5*bhz1h}vwD(#_c;l;{#B3iY3;E#?+<__ae7|yaullr~GFQ0}47E5r z8y_4GBpit8eAo=Z59YDZDa==6K0EbGh1%0_tG(YnCk?hIzTv`TyIhZYGt~=LEy|WP z<DUCO-a+6ZIK`yEn`&z6lT_M2-txY(s82w3-6bmd$DG>!mNc4r0j%C)vU^&1XY5&B z{nNFCor@PRjL4jBNJ`E?q&UDDe_JrHhnxKgSrz^<L2}<?jF`+yo5%ul4>1zwD9aFU zL1j8`o}o}vOJK}M^g|QZK-2<ZS`3jRc0JvsCw43=w)}=E3I9kBB%QaMH0i|GFZzWI z)-mliRf?11&$@v@wF&9`@vKQHq>|*wTTON8a8Sh@CZ>bwPA1Wc6hgX4LDD!`5bnvx z6*ybec)u1?zPN3lCRObCmEM;okP6+Axy)s+2Yo7lw(8^f5H4TLIH2r>#!M0p^D1+* zXtsoK%b+bHY1e!p5!Wigl~IDxE~#K10+MFesmhoZbE<|#S5@oR!8)v6Q3LuIzmt1Y z^iZ|%;@W-HrV$MqV19(`(}}vkH)e9nfG4Z+_OxNN&brCKxs}5$=-YFDX|G?VZ^kdr z=~<>i)0<F2*UK3Pve|~igc)DO-68~bVVMxXBmlg!le#dl?s;6O`xZGx?xoqd0A4+m zt1|T8v_t@7+nNO*=+wn{qsi5H&1!<H1pr>D054THjt$wOR8Pga=2ThFVmA&?T|TRz zfjZ8No%nNA_QrDu(yn_^G0zWhwublf6E}+Z1hHLGo4F>;yr>ff*K`R6=0$)$bb<l8 z6ecd@k$r%fe7(k!uv2ByP%L^>u^by-=D{o<!-W&wN2v&<#1WvVGM93(kNm!5%2g{) zSgWvo%3;G7_Vd;Vx;Qy3O|xM%8ar|C??am3!#qT9QnQcsXLjncN3T~E6OG|)$zLx{ zJYqG^k?U8JYuDUEF0C@8aQX`GfyrzsO!sL+*WuVSomjLPu<3jl0?QFtv%p3-Wpl2T zk5aiDDw;D>CGs}Qfa$1x=m#t6>B!6UX3VAe<j1nEcj`wKctI*50`(~3JVHle1(wjs zq3%W+YuL#Y_2m%B$STS(^|83+kWUjTYa=T^vF__w=xF3Tdj-g`Xfy=SY*c7U_2;A` z7kyc_hIoI`B<Ou<ehj>W{4!7T$u&XhtZq$lMKVIyPO7Gnr{|NbX$hf9g21)&0BWiF zcVi$;UC3UfFBR7))ro{nCg#I{nX<0K$3z`MW|~E5S>*sNuOc~y%b|;SS_g0H_|J7r z@`IyCU9BG+$pb~i95v%*jSg@0Hj&%Vhus1;nJfIuaN9a@T12V`uge4(Fv!KDb+)56 zNYsr+7!oULzC5}r;vY)4jz=ASvlIQ}7rfCf$$&s5^N-)~sa}z~ALV{`8+qW;ISmC> zHgR8AU8RZ6oLJxwPW|th+N2s&tw#MfaOj=-XVQy|Do63b{1l&hv)8M8*U~4bzRKI^ z>{`?RB$=y)?!NgTuG%e)>pOL=D!hr{-Gtn$k-Rtx(N!G_ca#BJq&{VmbxQDVQ_CJ4 z&(jj?b?lOyk+4Y2(yBpNgGAD*aZsFir%aTYrfXVLRuv~}_YK^eStYMAltY1r8m5ws z$7***R8w*kCo0iY>nmIjouCLGbum=!7g@z87IAQPL@qGMWp?{7Q#T=QPhBM2n9HaQ zokTWBauQ=$RG)(Z=8WE!E=X9)_-V{;?>~OhRSxDgAcG2Qc7cD{?%-gIv}~KKMP9N& zDTauI(c-X?f$8AVgUlLLkD&FkTasOYHImw3>0=;T1EajrF;c&OrpAWG{P_ja&N2n7 zvfus2jR=RNvMm85qM%GhSlZMbqEjXkpgc{)0-49fd08mzAu}TGiLo)pZ6qZZpQ?J^ zRYQ3DeCLY|M3Qxpsu-}{BijhW>06gjAp4o6r%UN#4N?{l?Tm=o)%(~*QQ+rq8YM#g zaB6A_!v@`seZ6z<J=S$`6NYSmo!Y&QYUBO#O!p>`;QiH?Ad7Rnhn&)fc?r(BiVjK$ z7p;YdG?UIRJUkP|CEBv>{J%9AGo_wX_Rxnu*W;>D=3Z{5oRH6qt11%q--A}F13$i* zqNmGl_^t<*Vmr)VYSum-ffkxR_M$DgG(OHh;9}ixV7-ieK0n!W|Hfs!-=IIs+;l^= zM&$dD?xy?A7V1}FSNkiKX?)G=XTJuhb9jazRa8HK47vV)Byit+|C7LNh$w#bb$FwM z)dTt~;O%)VyN4f1-7v}f;cOJ_*Ms)nMidww)_z17aBVPy=OBR>f34aS4<fgSzaVG! zS-yi634>1{1NE02iOB8Ouei>zyiMnIM?59m*<1^AgG@vN&8IsDYlz-<K?;*&7CcVY z3prZGBhWs@J^&GjxXF1ti4tDCK85j1$f=T{Sb7{j6Eu`I1E@U1XCD?+K~zHA7>Iqy zmlkW)L0ZTBx0RKON9O5#A*H7uF0$~XeB=G=G_~6(X(AwX+4bslLEn!Y<?ZvC#LO%0 z73e2R8tuH3;v1?29v5tpcx8L)5Ex0ccl9H2P89U`SRxXVyBjt1*B=+G2~gn>x6Zc* z*);F}BXfIEtUoT!-^8vZazPPg{J=?-P|hksOAJr~jj0+Pd*j}_>GL~t`=S37N_^pW z=Jr13G4IVss6AT*46qi2nxe#?Z&AHD`aWmrmo{!_S}hyjXo2upq6nWs$=pCUepD|8 za$;ry<tKZ}ls%15-kgA6+&y)(Fp&(`TknOCC`uR`CX>I<6}h9#B-5V;DgfR+K=Z<A z3)I$sW|6rq;E<Waq8m!gWfP~i+88v;Z(d?85D5WVHK6Hgx?SV8fsyddyNB9ZG!LbS z;N<Q<{!mp&v2+$DE>Mq^ZpF|O4g3%jPcCKe43O%F&PMll@ES(i@wsKY@ede59FUZV z{z3*m?`@s2`N_yqt%Nmz3oV`<8BUtbaiL`#0)Se7h}5KshCvsd5}76`EykWQGGT0; z0_eM7B$oo9gv+BxxlJVw#*U{-If^N@odD|e7U`tUi<Q&Ku_t*m0cOYw4QzF)dLa}E zcXRJE?pt8%oN#H`BA{MBTNtJA*d$T778rpF8)<mtDsk9l&?#~13P=~RxMhgnmq<+) zIW4hsf8OJe1!l<|M*>I|ERCpFLoE~8NEcg5-^%&r0}Vqcet4|!+z(29uNcjdtk;_2 zE6)(Gw622bGp%}k)J;uSiAbgioXC)mWcVD@1LmyhB$)bP*0hK1k9G7Z7JZ&KhT(G) zcs^_1gd<hyxLC`qsWw_PxNeFFw<=S61j9z8KjKL}!8kR<yruIRN73N>SySk;Qb}o| z-;QbEx@!KOk-g41y3JV3c)yEkuz<*g6V0UbknQKkF`)Xhf9v<pn>uUCk({!$SE2@f z^JmcB0c*Iaf}w?VUVA27oHI?YwRhw)t-h1HXN1;WPVSlz$eY;bG~=?lm%M*|@n^^^ z3oQVwld(gcfa@-o7EY{_^&vch&f(9%n>X=%Q8*EZ#ho`1scjRk3)ya+?-O)VAKnJC zw!00TH79q#bvf*IsM_g_E<vZZ_;<?;v@f&84pSGq!A&rAYJ)SDAxe`kZ{q6(zC`K} z9pS7g!XJz8kEJb?I^_L#pIGY9E9iD2Tx5!;iv9Lej9Q*GMFWC1li5aLoHgf~A=@h@ zMfjNiG*pIf?tMGmc3C&7v*tN00qAa>wHemjff{7JgXXMBK%fFyBsEz=m_I>L$8Y24 z708e&y3sgx0oQJg{yI<5LU~dz#U!1%nUgm`(MR&v0qXNV4t#Te9f(CTH@iU&iqJm1 zg^VZl5mEZNyT5mIyZQvafDXyk^8*glRLd+?Q1jL1{262#D{fTZ>vC`pJizI4L}Xi3 z&idw0U>~a|Z0i+(?z3i5#|)9~GU1r8wKv{L{k<f%!@-1LYLmqLyQy6E_DcRlG4r3^ zbEX#w=lshvSRhX+V<x|nllo?AueZjXlX^rp+Kr?x;pg-M&9#!<B?a_mxO`2L)sh*E zsc{a|sRi(<Ncj}ZJ8-Vq(L&9Dwr@-ss?v!nKRjw_9%K?RuLAg$z~KD7PZ&JWxzuTZ zi;8yug9oZV|7%Y{+p2c}`xEuj^1>6TU4t+3$`W(H^8^SQ1z~0NIiNpQrR?wjy(ALp zCDjF#0Rx>Za@k@Ej!P}2(*=}m-)?``_bT%Lo;s~O0;>7is($Q28LRvLM5-(vM_9pV z`?f3x{v{&E1nEQy(sMpF^p8a_uGlYD3i9WW7DYLcA{Z}soTI-hQiC!URM`I{j}>iO zK-ok}4C#p;<{0Vk{GPuYiFyxH;2fBQcp_!`+tEx=0X;8=6f{Rz!AeXP<_-Y<?ekF4 zz=>3q<b;3Dokt<4KHJ~=wa$3_Qp%F;(K&;NW|+7Fd6Y|Ry_Mb-edFN#<=wC@cL1{` zkv5*!k~_H=MkxL<4%163&}klHxRC>>y}Ce6l2(DFj<9-X4(XYwACxmV*jfWX1$hW3 zf!Yq~sZ>|BX?BKuBE_PX$(u)sc9AKn5IFf^7I<?nS4c_n6I9~yVm1dP_JX}D68?7! z_4mF`pN12u@Gj7iw!1y<0E7GB{M2?ke4gk=*Zw&w7Qe0izZNpcy8W|{4rE>avA8_Z zO+cl=T8&{jQ0bd&o{2?GOnH<M&7c;DzTc0)n+1Yy&wj-HEO1u*M{yn{$;Vy)9DvTp z-%XUh=m^XS4h)KfPOV#8q`U(VY%EZ;FrG+pt(VBz>dyl0uVj8Bf^yFwiKER&NTL5X zbY4Jpg4ov&@1gnOU==_RLhwXKHn9M1;DZjJI@`kP8I%*O`}z#^0K*UWvi<|^JCY~5 ztM3^GUmoQgS4DJAaAg5Fe}n~y=7X+HVBi6sA8tgRP0eCv76^Y^A!+w<4oIg72xA1} zA4?2zeiWVsZ3c&d9!^AhlANwcE~h6tYedFy+zc*%#A$nJ`^86f&{I^D`9|}kGY3pF zC9uqT^adFr2<5`p=>?R`2zPV1*QR-t%#6ULdQ(A##AsVJ1rhiYDUJsyXURK&GBkPb zzPJSn=tceF50$pbwM8-ql*Nh$1L9lq13VLpAq<Tj2cp7673!1XM;`^gi4;(3(!ArK z_&941s-FKE@;;+IGRLGm?<Q?Cd`Ae>eiyNA%{zdMF3=5|e@sazhPAC6<9B_z9~b2n zCsNJj0tz4`p-WGHNiU5pq~v~bsF}W%C+J|C1)gh0<{Y-_gLx+M=TU-yqyPSo<v=9? zhm$R?;J8kO1}bp)8*zYIpoqgC@i*e+EdGu-AVB?&ICn*$hy!~3P=6y1$T1C^U+Qnf z;V=IkaX>|XA`S>F^dNK|$AIdCBF^vnpont^_#JUTx7ww+_X>oS5^%F4Z6r0&`}~8y ztdNq~5asaO6)QMrIVXEJ<{f~d6_Csdf}E#utVnOLR;Br#e~##ON&OP)H0TBFf#Hw9 zd#Ly?z~Ke8!lbf!4CLErht3bj;wGptzQGxj6Z{AQ)6qqym_pz==uL(HcT4#9zMK20 z0!otmKLGnW2Sknf1EyOLn1(=L%J=zgjr_5ALDtM4>o?ST{#XYmQt==^bgMZ+5QH2T zPNWjG*FeZvcLjZ0EW;^5pP2Wvz;McS5d~rVrBu*6|LPC=0@%ORf*Px0wS#pBz$8$i zYmJ^N5y+?9Tg~|kkU5Tj0HXg7Knni>2(l$`0|x|<N>Hr%jWG9uzX<ysbGAVUD+}z- zo&zE1e1C<qmGeYub){Ot-fk9Hd#jzh3wpxCnxH3Qf(3dXL_28okLG|^c-`ut<G2>o z344X+sHEwOd4j&QgLKqlF)7|ZPoyTTq!)X4QUgG{NJWn({ur4ef8o<WgBU}U%j}8X za0j<!^Q#SnkqOUF>SM=|IfIp|LI;D#Q8|aBdY~VqodXhRTGuf`@{c93E5P0Xcr+bn zVedu3`Nz^-@%YEogy8Hcbj20wRRtl=rBdgB)*#f#DuIFq0oFVGKZZ3HfJIix{C5#l zX7KMg!c8M70w<>{2CDVRgXvF1S;X=Hc@VhB{YH%hG&}ObBFND8@%l#RnOOA)D~>9& zZ;2i}T%PkF@ssT)%42pHSo6#E;n3mU!E?9bwhIH65qBh$`SSGBOz3C=8@PmsyQH&5 z2$M-{$dl|=u-~pm3F@c$38d~$<(mH6(?N3y9oxHYw^Y5ivAS7)8ksv#%KT}jRgLAS zJOu-}PWII6tuxP=Fii3(Tk&4)tjh<Dwb{U&JnF&}4Hu3x_26&T`yCpZ0b}&fL*C)v z4ko7x@9b3cEcALJwdn<(f6(}5A)cI_J=RGM*e>;2H)K(n$g}YBo5(NFu1<o+TNv7x z7STCAaB2>eOi+ot)rwh@N3HTm{~9*xUq`#I53eE|Ki$T5AWC1jBW=DBqeGM_Z$}w0 z3a~)ipeUTY>cg(frZak>dc%)`JNx0KIp~UV<ZKt!8aHX_iMH`XT0KE-VTHEQ;7sXy z&hULuzCJt~)IK_jAKL-^^hTv&j_oaCn-X8yy273OPaJgL%PL2?XJ{^{wJcwSdAJWw zPkr`j3M9Gvg!@pd#N6%lOJm`V=fm+?BZE{$opDVjgG!WYkdH=LmiULnVZ;3IHu>^5 zAzG=ztBb-e=aV!!NC++(Wk%6>*fc-AGZ+`!F;|9TYs}g|U5wR!3JakbPGdC6PeHHr zW7u5ATPfC17C9-C-(MAAp}@X><{%JBolG)g4oFxLlm^EK)@8Kz`KeshJCNIjq#h`y zC4%Aj2Zw7Fj=;Fj)REtmu+@1COE-R*fkQK=5jDr0t#~!D)h)?DrcCV`U(}pd8UBIJ zqi}}am9cw@z?}on_hm#GPl*0%F$sIIU8TGPN>z~S@##E6wrR6GG*5cM^1}zYv2rMx zGmO3WM&<rl=$+--TyhbagJ#OPoa?h@WMsBqC9klcIL~f2GWJV)&u?m=PNdhZ8!2s< zyYkCjX#3;>2F3Vo$Ilt9HY>e?2sxiP@yDa)_O=A5QT!%5tyhAX!YL5cE)Je2P}+GW z_H_AZ>fqq#30DD$92%y|UdQjk)WIUBOE^@c!VwC_3-0BijklX%d7{=E5eKu-R4JOw zzf#I3CKqzZ$;_RP&}3?{ZeG+~*(TSHZAIN+j|ElMm$Mu5nF3qc3^`mBXq(J|aUnBH zP*Lq=$y%&U$`oVcbH0t}yvB9oCCk<pUUcWOva-?(Yq@HPra*u4su2o9OX<}`?kbZe zbC)=eV%8J7Z+U9<>kVxqor%=W6c-Y-b;?W?)>d=hzv@oWH;kDrquHp@j@6foO>874 zQB0P6w=Bl4velb|;`wvV#<me@$HiE+@e?ejJPe6lmDN4qh$t6<=kGa7NN+Oh2I)&w z<9ghgx;T587|R>QVZ(Gk6%7$5xlM;a9g#dFp;~vDaiWrl2rVY=A{J5YTI?vOT&PeX z{C6!}>5lH2B`W)X2$EfV@F=_y`Eqxi->1J(Xy?Ohxl%$!Cp%>ENwb4;{!9A)8OR zYoHN@BVst%{7Ow9GuE^03$fg_z>ry`>mzI*JE2^-W%kedxenk#<D2OIP!>|T4t>5E z^X6(eKQwhe<Yt_6!(-lkM}LSnee!fTmms<Y2y11hLMRtTmpaE{6O#K+%dH6Cf&q~~ zS0}4eytEEuCGtN`|H{qoiOJo0idwM8cyV)3qJ_OmPT0+C^1BoRuQb>Bb$B-M>mH}> zngSj)O2KOP!u#_I)Y%X54myfMN|MYtNAL4&f#>M?7#yeEz~bZ~;|OrLwY#LZ<rCzY zyw0lGRowfzvTf7qLr}nH^7@kC5$xyj@t5<H`VHPs*eft$JB-{A{MSoJo(Re`#Bt8( z48=7|3LW<`I-;3a#K(_J3s=XZ<yD07O};*7b{Zb5ZKA<@&mm#;3q7nOF0Oh0tv$EP zE$NjC!3YJ56JDnd^_@*XwU(Sn6PKgeW(ac|u{p};-N=ugTJCVNfK)JMY%cv`cCcgV z(ZTEAxer)PqlEL!d|E-w)<k{CpqWFW&)#j|7^hW%ANi$QQY&`$l!se}f9&5}t80JE z+3`$h>HhWk8A;Ec(z4I__1I2g?D%rdCz7*vY}q@dQuSs4mUJrvl<`3L(n6yf$#l1= zubUk*u}kA0e@h<9qIm3);fOW-;MWwJRk&s+VUQmio3(S2QN6fT?sldNL(4Stvw88@ z6&iY2pP_T(!iQ;ua}qiCw?tMefNJbrTM=lB!LFi%@GphTI>6t@Yvz>~Lxxy0c<5-D zrfgbI<0nhF*c8bj3at}m=Mi|_F%2{PN(-}>Zq5Mc0_{X!2C?487*cN^2(+tgGbeKL zuF^t?78&A<8PRPS2aQ+vpyN5^1f0B?q;<^l(VE7O{G1ZlOf|C3@g9fMC^C0uv<;kX zz+312siO5ZAER~{2Y8XpfF0ru(Xi`x95)C3w4gPQA@qv4(I%@REZ$xrExr#WBjYx! zreAg-**G0K_hN+D$<M;5y1g@HH_HMG55SQJS9YItD(Srs8LqkDl5L4S5%PCW<3fy1 zJDOrWJ2+~%3_8oq?Yk5G%=nxgR3sVD9nez}7Je9aj(IIfNO3mmKZg_z1weuTX!U5H zl+eyWrD=SEP#8cF=zKrcFzE~)eADBkH{NeeatzVA`Y|-D3hp3H+`NQ}EfUk5Mq123 zWCmw|Av9H%WMbNwY4FhCVN}wWSpX`>;S_v%8zOU|LtMs=Xu$;gSn53#q6mLq)Yex? z%Mz%G{IhAy5vr4Ew(Lum7MN!4$OW=++0ZR~?1e5xD<!ZH*}jWilot9|255GeOTye8 z_ZHN9+D#h`VvE6aBAk_<J-;3$fD2G`X-BpR^d;vr-qld~3(jB1gEx={aU1gV$4zza zDLhBNN;eMrY-r2RK{jjVJY7$9UFuc#*D9j2p1?|#BK*pkNv3PZ?=-WM$5?4Gp19Fv zi!2@&btg?)&&tsenhEhoAx?#}^Xa&`j#|}V`}U0TmZ6YHyqq;1=!k(a&9-FCr6^m- z&p@SH<*|8qnDR}>|0CR)2=?k)Xy3yrVvc0qPv9^*X7J~4_<Y2C9aMP<z2wWL;ezhb z@g%fSSiI*+tk{hAVVq>J2*JapY(occiR593P;xr#^=T_1nUpff1n&qdlK^g&fVN3| z)Tvux<Sf*Pym?Fn03{)EF6#RPX=TJN@mBG0GS6iidNb7&HW(t+^`)I-?RKzAq3(3D zophu}uo%X+aaGb4(g*E!>4NvF6het`w;070I8&7P{2xE^`#yhLD|f&iHZ&>HFJTdM zdXq{!Qz3$Ge3`6E#`RUxRe~R4lr&d|b&4A{n`o2hE6MP@6X&})p*0Ij(PCIoU(ze5 zRx%gyRJnII4G3(|7Q*itQ!fy-^qL<qEFJT49Cxp2PZRn1@?<&<7Lc(A1)295iP?Zc z=~5*WoX`Ea%U+t`-hotSF#W<UpLsn1*<5AR1H!kJw59ak|C!2>yu!FF?!1kTODh=R zjYgiL9V5VOAxS2IphVf7$LYK_LNGw1>QuB3nk{?TByGA<v2Y>1P*N@!%~iE@L9TRx z5M?2q-O8EAi7!8bslS>GC5=yLB#)YlLt*b*lF0pMJ058CEnfEQnb#lR8M4O?QTTjf zX@m6oMk5Qv?e^Aw;D(^(=i1R3n?$u@9a1Q`ix+9gIAP;%n^|HKz_gjNV8Q&TJ0y8m z`yEmXMeDwLRA~aqGvJwHtD~K{*}2-*!X3@lYhO&`C+rdyx8^VpBt^TtM6}oPof3d` zepU_&m`o`<L2Gsthy@jrsP2uR;*9HLhmiyq#BcZpRCN7Tqh`vJHUP2J&vEGPoAvRd zkcYueRxe1PH#%BMp^{i{x}hLkO1CXI68yL^L=>|S7nN-HiYb0}_a!mlO|U?BK`Ezi z6r|Bd+}rQzDwRQwXMV{4G_G$>-t<Fe+V;4Re{7BZm;zj3n!$DMEAFT&gB?#jwD^MJ zni2Wl54q;$?XB%1giaZm?&(h6TFNSf8`I5)=HY&A=+p$97n$W)31@{=PNwcyX#(2h zT7C3~gV&2~*QplIb-HN(Ynvjx3(t*1ZJR#fkqm56nKxUD2hp>)ZP6&7pd?Byg|4B? zk(n7iHh|70FRjkERHF_GoxbhLTEPYQ7ivCV(4?*dXB@Ha91CcqGy|K6lxMl!>WJmI z+oSC}Y+mI|N-aiC&{{Ox!<_H8@Kbe@>(&bxkAz(GhqtFzyb_tODEP^U+U$0oHVmRV zvp|<MJg>QCq+pb5g0NlQ6KfFs4N(3W?5>}s*9})Yg+pgR({4Z(#-?*1J+!5pv68&p z6znRVht|DPd*Kbelj!SQPSSgKV2KiB(y+L@Y3Jr6T0F-GaL6D_@z$T$^4f#WG~$gB zzS;h15o{-@oel8HfcP4W(fXgvV%^Q*?(p<;L7ol?)D5xpl(}p@9DG=vyV(+Xid9e; zdg=uEU*P5+u%Itf8twHJNhe%sywZ90U=E{VZlAUH5g1QhFJ&v2ZKfJX9et&@ymF{P zfBB7aX(9W<lSZGH)z-q)XWxi?ye}oR@62vVN>e<RZ#*zV=Axi2oCv+@{F>l@xx1rz zWM06({$P^#!vJi>EepN+><0DG*#?HRK$NE0Hw~P-`?__&V+*}{Hat@;??B7Gc-H%% zhn*Q*Ga3|0WAc5P!6$j<_Dg`nuEopI>GZr=bg$c><N6`>4pN->1**w_)}vq{uz-`Y z%qY;qWbzYy>{NLsart=!%>GhQxY<&q600qiO^y{E-J!%}hSH$qcvHMMQxBplg}sLk za3x+8A9^Tky&*aGT}AwyNbQ8tF$~kAsRFuhOnTF})#Fg_XmMwHPX#Ix^2n~+EqmYg z`l16oNR%%v=bBa-oHN|1qVK}1Pxax=v9Ra5|H<ViQ=5A5SZ!XzE?u-zuTqq%E#K3x zcmG}Pw`?z^JAVDdvU*l@o?TYElAwlsZUqj?6R6`%i<7+n@?CYAP7yh!qKE)+Pcy0K z3Jy`wM^fx2RiApXSz%sdLoxq(LwX*>m<{ixsm=!K9za@ped>o9vs$+-$r^seM7^9Y z4Z|AIAfNiwR!qaZ9>l-_R=5L_4$?mE%#;i)9m-GHy)p$H-Eos*zWK6KqQdbGr$h8L zH;JTnGjR(*&EehKJ0Lo6?bIar_OacbjpIfgmzhg%+VI=c_^y8y+6Qbtc!Dt5ay-o( z)U58r@&+^M28#SG<-|G^7ccf5y$ko`92v~q&<?25Pm$lOpL3pCDz3;7NeujGeoboK zIpj&tDY$LiZqX~*z6vi5;$ml}Y6Bo@eyu*Dp>xflF?p{g<3v0+(jp-s`=y)J6MmP5 z{gU&&k}PzD*GE_gNk@=zvBW)Q7L+=F3Z8s{xU=T6>&qd6Do2CA9()F-NYbUk@-70( z!&M11iACD%eRZNO!O_~%mokx5rYvBF$S67ar{+kD%p{`z4GbcMsoljRrD8Rs4ERMY z(jP~whmL)m+9c}zkV?dEq)O!R|A_N@2~_dCU-!^%$Nq}*d{9GcN6Cl>zzHu0-b3kC zXEDbgs#t$@{41(NTBVDmf64j<^obLYJ4e6?PSp&6`fx_om1MsdZ8*KYrTXrLb$?%a z4I9Ii8W?0dy;Nev0Or`z`j6IP6K#-s9-JAGL|9dvs(q&!tf$7T`05kXhE}#X{w8OU zSL+9cyn%8v5M+SnaK4#lpN-#iir$PgaS-$AsJ`5JJkqf{*ce_dk`SF@^$igYV+baO zT((swQ-sgZhyx%SK5}c$bM4*b4EN;j%jr$Wa{Zbv&Zp0+D=d(+19XOSEUy^3{V`8| zc<|IEnM%C>#G38iZPp&_%-4f+iZ06MSAsUPB9|H;d+f%h8~DK<hQKw%IR672mjXH0 zR)jyRNxl897~L*i+ar(_Z)LW4Mho4(dETEDB|YYZGLs$d$AU?(2dUT(RC{d8$0wL9 z7md*tWLi4W^0iz%1nrnL5!Ek_?>_^~J|4Zi;m55(29};jCLjj71l=FR61q#%(dyc# zofdKDVZ6vbjr!6ZSbd*Q_xb37#v0T4&P4174Wm&BkSac5BeOF+UA{n2+}7@f)Ql$r z0<W!WEGq330B>@5Pw|ga$4=+Fs?oOK8cj~e*tJ4jZV8yVpDo~cUb>V{h1}cH7FQ5< zD6Iq1tp`zyG_a?0ng#k&xKHOa^Ba;zmM>CpsMDmJCz{v!k(r+>Rmw@gR~=)c>!O(S zDMX4xNv`vnhj5bInGV*O_KSTsNv;Jux8o`>@K$8_;^U&-1|s@m=mjWOD+usbsuqYp z;9ZsxRX5H?B{-;4vQ($L6JG?LiS2_6n-k+z65y}M^2f)<xUv24|9}rmkR!#F$cu)b zD{0@3QRgsfvS$Tan#w`yR2CTtNq4w8$xKcdoE;CJ2qm@dOs@zJ|2W?mRj&IkubNgl zJ|9FYy@{%PgKzjPmuYu+R*+8Cx5^^xa}5eB(5yu_lxhNFs^#zK$yzx3#MLREQ$V*8 zRD|I(F?u0aJGT_kZF=~fbCs(7`b?D4rBEb|Ju-o_(dmOcCC%o&I3?EyW*&nN$RQis zp!<}#A$e7Eeex-`Ix$0eNCCaWYB<<1<zun(j3=2h6A_t+HJy@Y#kVkQ#QX64NesF1 zQC6c_CQT<?FF1}4`!EG{g?%n~2De=upUVy?72dFIvpXvO4(dScs{P&QBcY<HS<ET; z=p(tgh`gr2Gu-6hpvZ!$sDc5{VaNM9cSBywYY%)9!05ym0>)L`Eu<^b9(FEc)4_Rn z=74Uz1!(KEJl4XcdY#$?b^Kj1-#in~nX*nn0;aw=ICvM{stM=`3M+q{rx50nj+8Hq zwVVX6y%|BrPD{to2pTe(I73krvT^XL4B}LI&`15l=<^JWt4tm@+yFnQ>;2Htf?PY` zj8e)wVc$c1flruB1kiXv24<MpQDYp3H*cKqMjzojy>>3>4*Yu9p;|6dGdFa-f3NLD z0;Js=;tj|7=@}$T{n7KSFD_3Z8{w^xwqWS2Ve(s)3YtsZ4a@|Vwh?`W0|#mq2jg<> zw{bq&W)}V5s|L-ik)=JT)GCxx9omud0a}k0xaEa)VYb|fUOghB@3GmN&1It2vDjWG zqC6Ant-RRitoVf(#DD5)W`58v{p6U9w%mL%es0qdm4Ud>QLo0k9{~3w3sSM8^;*=& z)_;#<4CSi}hx)QTr;T;gDpe_*<u6MaiSItdKxW43w)zzB{w&MsEKTi6Znk0kks|;O zJq_=)8L0yhf;LbtgN@148m!rAD!$afPG^%T+o~Qd@0)$z-t-T+)Ggod;Y2^cod)oF z-~%>iWh{$Yb8@yN*Q#YSNib9zBjVdg=e~^J*&E0I*89^`mSaYbhT)|)CwPBvSF3oR zum+q+x?BhyMY;6VQG1I5QiwluvrVA75`f@1-|mpbI+$YePVe-^I6RL&7rtwehk_&O zs~enN4u|eCm$9ALmXjT?B4?wq6N|4kLE)k#oxFD~P}-!z2_LppT#&uG6yPvgwH7$( z5I|7IYI!5foD_laj-v%oSwB3cvP-y^V=6n%lO7p7R>6GmW_whU<-vm0h9_Mb0Y|+< zC+B!SCJUeqm0$SDp`tuJXfKAIdBRo~+-aC`SP7->lcOQL%_L`in@{Q`eam)4@{Uag zNPc1@XPG#UwiX&HJVt+Bh0XaC+TJ3M^{_0G^+IoW8xT({?{eSuy(-0^{1H)FP;OWY zo!J(hY6~?Ln;8u(I7Ku%^HGz~3UZ_%R7`fBu69Y(dVU)86PeiKg+yqFGp?*YTX~YC zIGAByhPl+9d`)E?UvQ-8i$~LzVhIn7syVz6momA;&_k-gg@?IHi@L_sEF6F;!;76U zw!Bu8*shSMq+e;iFn4(<0~A-^6N^SS@Ls470)nuWa**fqw*tc*?1<*YWEG=Mr!q++ z`iH?tj0lJVL&NJBsF?O=15GPBr{<{)tTa8`dl<Nr-_?`N(BE?K&|~zDkE^dS@Sw7c zt1H&0e?tm5H;kc?3rWHVc$VJj?0&WLL&LW#xWeY-y>0F}K)J+w)F1uiWwgUO>vL-2 z0eiMZv-<iIRX{IOGGRh1G1tH2@qT-M7_!oT4DS}J)5L{n$N8NB1@_M$qkR26n-qQr zeqgi)Tj2W*paoTYuCN+JXgyxvUKft^(X-XOkQAxI=DAXT2|bZhPH33-imsf7|59#6 zB%P<9c)JBecE*LA`W}ew?ySZ&KSY~kW0i8eJm*}~X}sWTh+k}Yech2WBQzjY5xX{2 z&mM(>Uc#W2lESPOkuPS4H>@pPX|W$NOUiz(0IeRpy=A`|N-z_5drV1{eFj?Lh1}^A zrG<)c(m?J5jUD=S4H(e&K<UN2<FU};*`e+xCb!?B3;w5Q(;T8sxoqR-tadfLHOe!_ zIYQ910eBZdA196vbRQiZhZ#r~D7ibb<L&|G=LB*E?5h8@@1;I<l4@Pm)zKw|!+V@; zp^#j|dWn24br$H2_s~^UccoU_X@1VA$xArLue;s*$V1~`eH9}hwHbHY;<dr9*#aK1 z>}-QA-uuWgFYDB0b5qr9kRK$6P%u;-xxhH**~2-vkCkN*wXAG+{c?TVfP)0L@-hvN z(~)SE8%(>Ji8b8)Qyi3^y`r#pT`{ZuzO;kNNFR~xxgbJq)*o&;(L!!b)#L@B^>I4Y zYeBm*YF6~~7mKb<f*wr|{2dEtI~`ZG;Z@)oC7u_j{-xCLD$XRRJ!C}O_WzH*m^#{b zp!JbUfc*H9y;dqmf)THGRVb(jCX(ppd-l?=l}O<{_PYmWtur71w~caZp&%Wj>kw|C zTexVjr3adKrDyy4PBJsrKcJ6|Oy`$-DZP<wcRfBUEhNTVTO%nG>v47(KjH|xIYp8= zGshTDuLqM%-Oo$T==Po)S+oK)R_M<qge)P->kK|_;CDms2kfi8Ow!6cBe>r)Us{;! zh7)%m=Ia<X;y5&7Q!wzczl(wAPGi+jg#2md6d9!qF=sS$c~IiZ&xC;Cmo}Ulj33X) zK{K|Dt&i*@m77bfC>cHaM6Ch+?pS;>iH37}*pi+PXL-o7hG7@%Qq`8H*9-2>QP7>y zmXK9}9UJ=w>~hFNwR{u7Ae9`^XP&M%74hCA4y-%!2a0ZRw-2#DV}#ZcKg1(Vih+yy z`zz-RF#Ve==Ps~E8Z{TO`3iW2QiMzLDgqw(OR@SE4G;7>b-Wzg6e`#WRVC#4D`#{t z@UWz9@-e+;?Y5k*=5)y#n@iX%d0|bW*sh`alkhGYT;cGp15wY5h{QYTU37zcS4c-m z<QEjjG)?+eVRM|?UjV2!gjK)rvHn(lqg6k2SCziPS=4)?Uq5L;S-*{5z*WBn@RyqJ zVi~J`qX&!&=LjReL_7uY&=v51#hrm!g8iydfyT+nMurA=pRC$x%0=>E#PuH~FAfh6 zZYdQo1T%_D1Szh4V1tB&zZF;TaDIm0iYp|lmtf=A79&g^M3H`ij*sdPY{LZ%8__+g z1#qHEYa7i%z}skrBGv8-8;S+B*_4_)V6R{as!4XW5XLGZ>D%7DdpehFf=-q0r9W;? z)_6<PU8KrsMX`DwGG6ZXup+%?8`|F)moJ&Kqk=AkhheZnD#ZVZ(L0cf&o=DI7AvbI z-I5c?UvH5Z8cC*cne+!wG;t4NP;8PI3iIV$ejEIUu5Vq{jSk-G#{8k{-h4fjr|5@D z>T$<s#WJHKw_XVhLZH%rC-XZ?;m2nsGLj>=ycrCA$Xt-ftQg;Eon47{`I2{?DIuog z$NB?s>iipmztClkwT3eIEGPOmB*SEVNcXMR1b+G`2a`pqq=Eu&o)DUA*Q*&8;(b=z zFPxO|mR?u8l*X@8OjBAXZgj8Qz0-4@#!sB)WSA~gYdh<^IR}Y?KeN0f<s?XXpMI0@ zrZK#<S<L$4dqb-8FCyQ+B!xK&BAt4{75^~$cj}ai#2{kofmZ!5YOj+m8W6qt_EpS6 zY?|DAsy)GJl5l90n<f0d2WfQmj3*s`>RL@W2*=&4_k&vh2mK;7ZppZ5^f&4LQFBmk zl{mW0hJv(zICi<vWpo<({e*3Gol-FjrAR&QKw7OSOFUh;K&Uj5$Ub<(LN_JhWGhFs zg(XpKeApo5oae`I&2I?~U4xKMqwbtpxSOl{PJvzH2@YF4Nb?ETvCn(b2>fx;#`iQ5 z!|WI+MY{G~l6-<!h=8DE<AaQH*!jBa*b>58ql0izH(kP!(&zvKPTq}}BQ~8*Cq|Nv zgP||5KR-WzVl`#HQi>{%!ua4|kHvK>ip}_d&mFN~EcL_U5RV`!T>0LA&*<X}$OLS@ zJdG#XluPstAGVgs*(wCaj9trtlGmW{fd`;W9DX<siZFZ|#|M0C%&kY40-)zyeiFNM zLW{{UPnLXA_eFNruJhoDzYAB9ofi)1hHZ)m`o&0uIl3n=X3_X2uB+0S1N*77J(uzG zgPw5ljEocJwN*bh8q^-YQoNGEaYqe*9G_)1TK%6$y(;g>KcqewyLdm3)rh;*f|X6I z0m9fr*_qU$YL_RJe6P2_;x^D;qoH2Vva>e3@v$=o75&guH5SJ@{yU8OHODdZgt6$s z5Y)4oEKaRq;B>UwgkxW*o{c|F2qgK0nA8#UzCWBVu?gy|$VR8ZnkdqhQTnYgHm^x! z*WNDdG67$1g#e?*sMdNXm5z?9c)dFb5Dnf!sI9gxxN!o3Lq5kFd5lP?vz4U&<apz- zA&ERNp6DqQ1rr)kLTH#c4KHNKs2-`!`&UfhY8=Gnwj1xn<BlCtpUunBS67_eApKn3 z(L-tXYh;Mfo^4{~@i;xdE3y;iW8q&Xkrtm2(czad$HW$g#_{RYts|N$hu0(<*E=-^ zzR=!Qu8w;<V89@JG>)VGKOps(|Ao}c{dc53^S>qa%Pt%vN$i_)_#31g<Cenfxe>;t z4u{*YEO=-88OGyUH*iiR+)idT%*V61b_A(FoyM|rE><xJIA}GfOg2k{yHzmj;|vmo zzU|glL!KoQGQp)i!GY{E42F(3S>S)>^=m@h3q;f#F4VLpfsq_oED2X~rk<^YYi3eL z60$VN<_Yr!Sc$EMOTV|(r2%Wzw5T7-tNF{k>lnB=LgK;)(M{;X%<%eS3m2J0wK!v) zLRS+J`)Gaq5YZZsl=D-yMh4C1UK#o(7D^`Go1a&ed40E`{1)nJEk7I=W1RFpVkiQ| zRjFXjmAA#g-U>?Pz*8DMY%_y?lmKTmfCosyh$)iJ^<dCXW0?hDDdAiUHI*IbsSB}H zR5Koa*&3Ilz8!QGvtpdJG!h=<lmRCB>_=Ohf)b1KGn6PojU!E-K_ze=18ifOa3#-t ze+d5SR}ry$%&*jQ(R5$g|6kF1thz&7w|BQw`xL$@Ve7qhWrk=#HU!c6pH!qAmdD`+ z4hTncaqn)-dDZnfsS-z_hw{HL$EtSg;{i8+im_NyvzRp%j#!h21>P{L*zIFVVK&3O z!#l`Iyr(fP7?M-MQ@-VBzbIp7sASX~)DdGZ;k1hcz-vPWhda2IzD1^)%nFY$2=O#( zqcVTL5NQvmw)%(r<AS*VfygW>^D;EFIDuBJb#ja5duUmDUX;rf@=|mm*TXi`ZShi5 zh`c1X&xZtf9MTDyO#dr#|84XCr{sQZEivK~)=-%4IvED0ib5rTT(K3IJ9(KZxGzU< zryncxA4SF8ZNL!Uk?-SlZf>4)wVnKK>ZDM1o+6wgvfp+^r<8jSglv0^%th|Se%$cs z$j~^aFMQz-nn#Q!aaQ|cmbq$&Z(61%x#vBiUaeOQ)QjLhrq-NmUq{FAI_iaT56@i% z)`3}dPHYj&D%>5bVwuLo>TR8;qu97|5~fi|A+wBYT3&8mKnB-o+PNGWebBmEtH5RG zCzkJC+QxfT1|Bo3`t`1S1zzo)0oN`n`>Vw=&j5#y(>vd7R!p{F09p%8nz-Nx8<MP3 zKbpr{)&oP3Iq1W&J6275{;DhL_JQ>Orml3*=&-t$&j`S&*K*QE`@F?i$YE9I_8+L{ zx3I~(DGqkyir<N0RONwVRMLY;tzoX{*~pWlooAE_S_a6qDmC+flh*D4KjwSP#Pm3B z$NcA9lk+X_E=oLOeI`n+g&6O{UY}#TAo?4}Z=lPRF$Y~H;|k^4_!&fYQpH{)gAM7B z>!TJD(z<&X;PQ3(A*2Z)calirqIR|F;`ah@|2<)nn%#AXq`)OcDageu=4#x%?V60( zh6e%$W+B@C?I623ocU?ocCr#tR`hs2vUf7e&FG$qU?nTvJ9}sqa0YhVM>q7`v%~c5 z=QwLfI-3H^|AO2rH~XW~lo)3GcicXTT3d|jj}{|c-!zmeqCbC3DT#?r=I9Hr2HxL> z##%fc)8L?mFcae9uwH?{)$5g<iF~C8(M5o|9hEsUsT>m$!q@A?tf@-#0I_NcCz8vC za77-(zeeU?WArA1k#9%zZday2&E+@MC)bcuhs=@3*p(s7sm1}*ANo=)>8ZMR>b%!g zlq@2#*Clz6O{+k9PcyJEg??nvCOt0nK1UvccsG8&1F$xMthv~*!hvzxbn)iDAoW|B zXwks_P^S(p@~-Y*$^@Ja#N@WEAo7^uFCpX^Ky;X`!7r(Ijv#uE3Jh`R83fUM71RGr z>_ayJ_dC|TKP$WvDDH`F9w*pd`mcY*6MhOETp0d!z$5s+_ZO{dUx<0Bh!7Z|)0x|a zxyUvG46&mWH7V)dMY#g5|7u|oC^M1?tS(FflzVIdBKlGP5Peh-<B0+<13Og*sOzg< z_gQy<PlfSAtsgqpq_{z4pyaMLjU8puOhIZzYBpdIO0`<B3(;fTmj!5%7JIhx>ro&p z1JpmS@DhhomfqOVcagI5TAgOQqAw*T<6r;S`JThq-2)ecsB$di>Rt<_7*OkE-0xz$ zSR%8^F_?@iG!x32EU&3JoodfD<Q5hjL1MTc4~N09@)cD+tyWy5KiHm+h((4!rzVww zglOh6G){~(2W72-U}i-&H9qe60iYYG^X=Qe#_$>E$s@152lbBr(=h#zyMR%R6`ww* zt}su|&YUxxSudXBDpqWWE8q{a$AOpzb*TO@`y$i$|24CpO5<1hPt5)_jUV7X-c3D2 ztifsV@%u?YScG|0Y|=P^$iH!Wy&KZ_W2w2)*s3ytBQb-O1klqMi|VZ=0Cl?(aRPK{ zLESELMu-j`P@=1h9+WG;1@NB%`oRb#R>z!L33|s^q=Gj)NS6C{`LE(moyoJi(A$Le zVafI*IOVEH^9K#0HHl2{4WQI-vWVgfN^(KbsLecck5$^gv>sN~iYc4SI69tA7A6sT zZsb$Bp(LMy>-xiB5Z+2C8pDNgy2yTjeHYOv-H*{$z5M`hlTLhjL|f}??moSv(N^1R znA1^ri8uS=5WVQ=Or8XXsX<6f934h<6jVOQF@vMkR<myb&eolU<*?_gT)S7Y{Rx{9 ztB<0A3)$f@A`}SfWav>bGAZzq|I<Ky-#-KO)c@^3{rJi7HY~nei~-qtiYJyen@fQm zNY;Sk$l#f4iQe3X!k5cF(FQ3VfiWe&NATTx`o!mA^eK7D@jvueDn@taXP?>gDE@5b z6zDq*p94R$AKkfUn5-ski-G#}J`VZlil&@f^%c-mq0x;RqRjK7l2aJ=mYHR6n6$X% zi?2nW!OWA~qXfDmc8p(AzWHFSVf|O8dvt5pJ>=Z#oIwXno$tME&)aTrUtD9mrcM++ zU6tR_YYhoSB|k}K=2K^2;Z9^0U<iGNUSXz#gT)rh#0ehAI3mx#?suKvzvU2?j89eN z)~gk22aU$>EfY`BOZ-oy{_IfpKS=$Ar7nX8hax11yyF6gkkgIqxE=%8VP}rN%phRb zr*JTaM@{^HO6jkkE9o_q0XT{{w05;Rb>z$S@6E~PtZt2vDyk<NjA(C%<Z$U;v-kr& z6rf+6BZYrb^os;~{Y*LlESk>7JoM$Jj#}6$8hbT2me~jm^mLX{t`#&(3=}M592y<& zq%^J7xxkaJ;2GL%R8MX<ca)7Wb<uxrA|p)uG{cSB6os#_cnpJU3w$-uGjA|Oa$6W~ z4v%rnh`%@AU$rD?dkByn?rb%i`0ojQgBai0{{f-5j{0{(fBG#h>7qRei$zE*6Fyy% zuaJdb2iCa(P)A0A71kixStpFXGPVhtmUki@Qj{R*T-1J_cQe$!yNW45iY^lmC%r)> zvg(lZK2-8-*kKw~JCVe__%e<pu-SVYwcJJ48hh#zy_3(Tz0zTLJF@+F+qJ;fV&tpI z>nfLcd4fjPqXDI9#?-V8LDqZlrPiFpL6R0T1eOtK$GqvHF@&K{cfBVdI{!J#0B-@` zYJi2pJUfll1^&yw2I-9=RRl^G1_zVuQYfTeL;>9jrIvp9U#QKER-0Mm=t%6+D7b0+ z)N(0P;yGn8HoVJ5bH@1$r$&wR8rU=g8J3eMs6QmwSWqQx_HSD`0PV`W&Qu)i_y^l| z&^d_S!R@P<@0@L0!KFmb<UuW(RFb0|Pz1~)Ie4Ib?xj!yB>dY5J?fZaQTS?6Hd){h zeUijSQpwzl+V=|!NRa?XA%`-nXyfEd^<hAZUxF|#CSJq(oN;rah|m-67fy%2JU!Y$ zUdk((d2XMge68}Ujq`@0adR!cKPt1jV$9z$_+`)-eAbp_4=Dv+WBiSCJn{v$XtdW$ zJcCiBmaN@2s7t^B^A7Fc5tU6e+C?Y;EexAZ`^Y9m99(%~Y~aOZtXwqygNJQ;%baC8 z7}e31V>a19X!|T7>;H<(b99^Mz08l@ATM{Q);_(Fcz1Fnkft^PK7zYlUvv${z-oX4 zS-;Y{kA3^Uczeen+k$<|x6ECx+GX3eZQHhO+q-I)ZQIyoYn5$VyX>xWy3dQg{qF7V z8}G*Zkg+1>njbQAWz03^Z;bpWU-v0uuMExm`9H#_?XsW4UqEWT9iW5eyAWS*JKuRQ zwZG4AFQpSbBwW>xSOrS(#g24e!GERYQtAN#ku~#3U!@M1B1PIMZ^x3Tp7^lyAH&hT zJ@xpu*O+5m)N;0u54`)Db&u?IF>9?)lRcS}CUYWXQF{a3jycdU736A(i4;2FSyI-h z{RZ;2_PbG26x<K$l}xyQI(O^fICJoir{xv6mf6W~q>u9CX39b+!uhXNw@Ciz1CwnI z7e7wB-HPwu?;9Or^M}rQp}j|16=Jq2rCTg>xK=YY$OH5Xcy&BdQO^Qik8HR!{0<Ic zbZffho!q$bFC_shoEhJcJ4^SXV2bfqrOuX%32aPBVZ#s|$?Sht&7(oT{h!qQRCLNj z&G5?q2Gx82d?WcsR*K>Af&JS;X!C=K*ALyA<Jc5MdNab9MVD;~f{>|e5sB6fZImx~ z*!O8??;7fWl5Hx9TKZSj6|tvbQ*+Z8IN+uKBdJf-zx=-<^%r~NzW>Tfb?za~c8Hbt zb#(o^aj7&PQ+6{o2(kiaOHl(e05_vIMw~T3Mg?GGljs_7XOLp_v2Bmx>VKHtFOxx@ z9>l7Qkls&eo7&w8^lB7q$g#}JB%{(bh!dOU-qc7Zf~fyjp@v~CnnNp^R$BlHZJuEY zv#Jc(zmaojh%(Tk{`kpJxd$(8D5aVx$pQ55kQnLe+TKJy{plSF2}~psCO>W;l>i63 zQHe^sBb%J{ZhIY_oVP15q(`mOJn)uuUMgt6x8q%!XGMM8FGvr1vdU2>`d_+}1vxT) zr@%gA2J(+kJCzz=GlD1UkRZ>AWvZM1(D%@4=0(8rrO-E|2=dFY-xpNXNxCX-Tsm&_ z=En02Z}dpKqm#*zypwlN%_5!ZbVv^g;N;1H5gjB>brUa4!-vjRturI<*B<?PPf3y< zc2~4%qT^O7g9t-bxaEqLb0{QhNjfr6e+in`eG!CnMrI~`AAV8)zkvG06u~`33#hkv zfB$4QYvi>q$%~%VfDiR2BH0W6gWFWg$I$&RLf*U|k)^R;Bd!4~0bk;3eWL%r=y{w$ zmjAt;FAo0?^t_)3q6m0DAQpPLT``l+a2-+I2#gmSpu%M;%BkPKi@J@AOcoXrDNOc1 z5;y%g$Yg{2FC}t3`t<)y*uddO%kXS3L>ya}{FBNj(h1VJK6rHNb%cB)`+p{EwihD* z@$EO1|L@FR_M7P2{WE}5c#3=xz`RpOjRSir(d$XocPa;#Mff`ulwJtfTyrzyKP}|{ z9YpUjUen+EzZde~kY48hf%FUig7oG8g7nJ&g7hW-g7h-~MUcK-aM}r2eM85%SPBll zV!?n*d>CUmg!Xr!iQqk>iWLSjLR$7C@2$abvtfwz8^_Ww4+5QQ$nRGvrkYd_0({Kt zFqB|yZ6CQhbxx)l?NUK5rY%K&9m{-l;{6mk6CLJTfi>{u=s{4hX#pk;PPUqKF9KZb zYl|~rZZ>!hp5G26?nG>S3E#$u(f+qFvKTRFw4XS^&&k5#g1N4g!3qt&U}EFLqcdFN zonU5@1sN~M@-i3Pks>1)HcW4H=iBs(H2zeiS?hDI!=7jDUPv|W7ZjT!R)=IO-37y@ z^)C@m`!5ln@~;?<^gm)ao!bV5C&RTU*$c7ohD#J;TQdMxj_fjrb?of_!RS%#ypO-% zee8()dWH*yIsZsm$)WK}UQ($gX8l(&`sO`?31)%+Sj<Ni{0CzGyh-9e67$r!8RM{n zz$otmqXa4Q9XfS31rQ#JZ46}5xJ*M^4mY6I@Hx|}x#%<|w6=PP=&7c+LS)3KGeJ&< z#?Y3j=r&nAFF1+(K^~66CbQG6W9HD(!~cbV{`U1kqpn1Pu7FN$%b?vzy2_LlAXcz= zG=!z5n{Ga&b`+h-pz+M<4R)6U^LUCH`Ysz14)*j;IU-p$k%xU9%uk;%yHzm!Xyd5} zi}iUZ$~*S6nHTG4a}EJI@t5(x$LHfstK9}cQO-Ca3)~#{BVRXw25b}YC(mt+H3v4E z>S>J%v&f1*(mC9){uR54HKlzC;hfLnY-~w$wuoVmn~<c_QgO?Q71f#gzfkkTZ2V`S zM`6r<XdvzRsedKJUx`gS=}bdq6lP0=%qE~TrC6T)g#NplPZR-h_@?uG5C5d|RD3SV z1YAnG-U=^9x(+rl_(+kYqgwD&Od+`9<%SVWb~wjB>P<13*64-7Y+sTHmCn;vXfn1* zJv`T3H1}h=&|IgxE=4wH;-<!)>m6g1i0e6S`{bw+s{dmxPX^#gs~g86*BHJJTdRv1 z(<E<^NWQU}^ytxUr!>!5Av#rX$w*84J2gjQnHy2WJY%`G9cDG2j$xdT1<v&^HE&qO zC;v}j-}0i6z+3Ezb&Cj=Q9Oq1QeVO%c^Y9OES!Jv^HD82(?@tyyEMxCoDlGlQuiVt zfmq7*ruU>KU8mv$LHg~<(MDphLnqlqNJp=<0e`1WMC|s=H3zXcezMXSC7K0FApMAn zkX_>>(%2C4yeAHNUj-~I|G&k&lG*=fF@KEaP{e~<B-{y(w7<ny6rEP^b3T*(JGv7K zEHuc$2L^{^tgB!!nBPA8-pG@vpBgSDYsIYS*5Yd-qcGeu5wSZlc&$2cOY@T<P0Nw) z1~N>&h<7);kD46zh_>jpJQcGWNPm9!Zi8q}oEt#(8>U$K0dgH`kIrdP!ov~jkF1jD zJQV($34{_Fzqc2~cI1s&Ld*gxklK;865wfWj_3q;m}TXiX!HWfsXJN6N=Dqw@<167 zYqd0bpM>$AuJ?sJBMo9$d!gBfU1mzkdAP|%%WU7D^+>i7TnjZ?SE@I~I*7MR%U~$a zt!<FN3xYz1m_2Wb(0XJU$~#F?c=R*%hxb{syYNMVhR&pKKIbXY3^@p+u<T>6u7Z+R znx^}dWc>FX>^Wg8#Du&uZ>8UND71nk$ml+<@U)tT^3vwWMa>cS;fX0U5k5*tOjq%q zB0&|Z$=Ua7OS@S(G?=hB4{}JTLb*RVSS53`z*rB(IB*khq?B|XLZd4bQ*QEn;am5| z%c|id$$4&a*+w`4v;I<|s~V$V_M4QlE<w>_C!azD+~}x79T#7uOi$Tl<$wP#7~GI> zscpPZiLy=fm>m_)BdpV+&>4*X3W23)<~diD6qikJ-oh%-?iC|E{i$HpE<Fn%%Q~Db z@Qzp`%~HJT2y+N5&X)I(Y8~qM5P8}io6|+-EOShECWhcgx7t*&?o!?dFGCFE<Yp>4 z>8{dM9#Cab%R?qtAmu<vP_V9DPPEphY;T!IZLgw^mHk^JmNd9WS`2O^tLg1QDyL-a zI0vrdQihXLENqIIR-7-?VHG3Nl|QFyVOmxN*J8A>VAgdGmt1o{-twbynB2E)$~pP! zv@%V%%9~nAkTEP(k3&o-wJoD>(d)=mOv!v_R`~VdNXk=F9wRc@mAG_@-Il$Of>BB} zPSoSPlnVF5u*A!ki!#-p;GQ<)m@1p4i(lCAHo^Nl*{`u-*gP>GTTw}YF3mA_r|plV z1CH_g_#b7pXejZk+$#<4-UeuWOx|vYG~P}uMea`*AAEJ5uD&;Oe3J3Ov40oWs%i#) z?cK(~{M7x^9fya!o&9#}yLN2pZg@aGb<6*C&+d0n9pm36!xvYW{k0=e5`E`@PU{ni z=MYRgJ2owNK(Aba$|coJmxL|;OEQ%j-zg0T(gfdUX4s#3<c4qM>JQq#IpD-lF<JGd zv`2>RxaqQ#*24;k{38cEQ(q7K+`YS%=#{SpFOJrnjhK(;?y3wS^Kqd5vJL)rmwr@N z%`@c!vFBs5lZ+3K7pL#b;+l?M%J+f#Yi*kbcp_-R0BsOIl766)dhgo*iy0<G_47mM z>v@VQrVnFl!(-irt+w}1kv@O>U2EwsRZQZwA1>z3mmjr{H&Vc%5YMdxQ>KQpIggV$ z@p?0j@Xqfh@dXsERZI60!=Mpyl)WBG6U(g)oZu^iQiH}Ooe`Emxr{inuosLL*)P0l zvmI}2A0s)j`E=vV#|12Ix)bV4VoYQYlN3L0rp+-ZKP5kW3pQFeoAw>TXpd2FVj#Hr z>)(MuK{ve?sEGJ0J*L#edI`~&J>7ak@s3^oB&quPBSjQKhhJnM)J##J4B=aQWS2Yh zr9Gcgc(2P#@i{N*JF|zUv8}7mP&@|OzBi?tSZ-;4#^`!NExkQFPX*7z5yJbHZSNLY zVTMg1h(O)I+fJAKOp*D2b6SdW<eKE!Tr||t@+WPLGM@j(!6y=#q*`Q#yW+j1-!-?C zg&?!<IM1`llBKIZk(KeHG9<;1c?|3}&<!=#T6SGPyw8OlberO$?r>l5gB)5zG04|L z)#psUK1F+V%DNvWpISPhsyA&PlA%|~X8W<ye@`6fB7o&qveO2NiLkCCW4GF5!fGz6 zHYM$mm#-J;FeR9Aao0U=dnA42sdiR(NRNke<qLkHq?w;O)DkmX-j4WG9lnMx)b~@F z14!NkCv0lsn$Ls)IfBHmR~e4OH$?Vuw8|2|9KaiIbbZ(#U*4S=c<r_rUemQ0_k5!( zi8k^rE5eFk7QcunX5I)STJU?xKz}5@f5vsSm`2B=J_PDT<%MTIi71lfQoK$Xeva&p z^xz{r&0U<jA(Vx$KbgORXFt^XK7UrPZA)S8lrqV4WL=%RZYWHrx^GGBK8u(XDF!vp zr*(TOTiTGQ7){(?WF);GXqSUMC_|1wdvCHZTW`1uc#ImN$~Dm%xpeCAdn)Y`2#Qo# zlA&kV`I3#)idc&z4$vfZ@@6`~6PP%2$=?x-+`7$EH?#m(-(qdDs{*D7TN7FaIQ?!m zykBMxvoo{F<k6M)4=%of-{}3P4`OXuQZC75w}0$&<lgGTTfC~Q1Ji$kJgQt)_u)~P zJKpjor5ziR1o{4SMUd;tf6azSxv^%Zc`Ou~n>s@ROe27+L9XZCML>mRN7gl-FjR4! zQ%A-!)6~?b_6D`Wc-EEi;BPfH%<-^ts~tvWz=y9K_Lai$?aTDntZYQTNxGb@N=p=# zyv@P_g-N)0YxtZdK}t*HplfW<5^K_Wpd~<9zhBG87Y4b?GjGMusq*}sQG>C?C*}l_ zudilNW;MSLU`jpfj83FX%T$+O#R@X3Xu_K;d=-^dU9tC6*~eb#{n^FS0}^~Y+CHJn zVyxo|P`;@O-`V3jV5s2|#QjrB*w(Z=->Vibqci)=8ODuU({027OfLaN=c|Ly7VCr% zUShn*<D4y1mp@_WGYfb9?8pa<1G8mcsaUWi{6230-6wC3r39rPP1yeAM8X(g`y>4@ z2+=xaGQj$b@Wn<n9PIL)WLgcc>Sxc7iAdXfSbfwsgC5ob+}jZ-XyGnvdn#5I@ANbn zzUE2I#MUTMq@dXj5;3%c)yT8CsEEWBJ3%YcW`7;O#Y29jYbm48{Q|22KbLkRSp#a# ztBgOYwULO?cS|CTx@-u1GcrsKYz!KvIj*+^)9{l0ZB*HPw?-}U3yFUl;li~}pDtpp z)2@~qP(c8`14KfX7vKQvV9uq96_;g3xMUj?VqJ@kj(Gp1w;xh<T)rcGEe4(FivhHL zCW1V{xc=j5Wm;F{kt@=1LtP33G*(09{9m50kBaV8!F?{Pr41=I2(l@bA#Dr*ITIkH zrYe^p<)ggt-P+%Yx_vBcsknSM?YJ+NN34qNZ#K%|>&1$8^HF2LEmw>;5AM*bYLaRa zIDbc}LWG`EIzy@y6VVzHcp6}UJt$HS9!;tfs|Z$(6VPB{aaWmiU9>??eOq#xuA5ph zJd|9aHH)W%QWHW=_W7cF3e|+vP8(Z{=4PmUfBH*RgjCI$SBt$!5@A1SLXyjvZ`q94 zZ^Wu)j>K0oI}X)u$g04^Y}!&Q6Gi9r8BSsI%aTEukc}jn+WqW`7+{-Itx9iwt?xIl zSYhQJXQ*8g*4ce)$!jGClC|FM@_aJb3^>rRdjAe0qF}_;{H({SX@~2QgPynqZh}{6 zJQGOZHUz6^7J*tZb~=e74QXmMo7AwS);#y4AgIQ8v$ClEaAM<4NJdV85Z4G;pkiN& zZu@eukjZWC)7pe+oEqq3k%%8TpHo{gqwSeWxmcKyP;c`O3P9Hax5^Y)wrTT*km)<H zFU;E_4p4*)Ap@zP5urK{$l;~t(RtG*DGUS%3?(4W106K<>!PSo52m_`Sy&L2X{XmQ z462pw{Vv+0YYd8^Ty&Q&Km+Wp_Vf}dGNFl3+k@W%r3=p3B`i>^ND~Y*Yhh{+&o}|r zljYDf!frcj0RGDlP-dsQ%#Gu2ZX}*RbRmn<OxG7M9mDU(d$->N<qcH>m#O`^U1MGT zaISzgj~Kvd4vRq1e&?~F-0Z{+g?7R6oe!c(%MnRBX%W-zoniaX1b#LA1_$}AZb!HR z0;ROpAz)x&M|e=mlbyD&y^;Y&m}DbPd47gtMOH$W<zD9|@)iJT?cR-FHBgs>EbgwR zYV5>T9V$`O;(K_tb~f9CV!UO9JRIt~*UhOq<qJG5yHEU^agOu+WIbF3A~;BphEB$H zNBVU4H6ic|f8=q28l!3K#~+s0eJ9d>3WD)L6hS1?v8<CrKi06t9JvBJEOEZLtnrTl zjyTP}Ee1;~uD2CCJFgah=y`d5B;JqA@%ylP4X&4!Q>$2aFu14tw3GJz9O&L0;A}un zWPdlNVY81$l;Pv4+_hw+(2|nP;A4e<E*gBrPylQLMd2Kj@mr;Ke9Fxt2ZYWq&nT?v z`={p9;ShEovr5?0+x{;+Lf?0umU~wEl%jJJ92>&c-$ieN!%Ze+tgzhxiS#k6?vRD= zk~79!dw+gswxC$|dX~c`q7ajkQ%8ne4Cas_51fgKdndxKri+XzlA<+8ANFDxX>&Rt zwy4YU_k4c5zMQ_?F22WacYnHe`KBK&^K`!=C`f~Xp#lK`K>?X18B22Rvxg~Q00Hf~ z0Rf?ZUv;*$b+xgyv!*w;w==UeS2lHFp!2Y`Y1Z|QC*n-}^5+BJ)2dvZb#YhiX%Sza ziV7;o<Sr8uaLqPrqDq$m&5@dGnwLbYe7iw6<o+$wi;#wC$ttbfb3=?1mpX7X-;<** zX)G){?D5*}`EpjUnrAs^oI=OP?#$``QvXuBgpkX{lifHJGQNZmJ6yWHdd-p;YtP*< zfl#}}j-4H1vI?g;J3R%heF!a$ub-SGO9H;9C`{ZzL);iLOx(Au+4!*D!{3E>DQxi* zx+P^sva$KiSsSXsmLNOK_1S7lIb*zPHO+4MW=cJA7}}Pt!$wq@c{taPk$6Q`;7h;f zt^K70lPwckK0q^DZdGL_1cXdAScU}23C7sIg-%a*g~6wqkVu}?hXdYvx`9$YgEmpx z4`<eRnk7e~!!7WY@^=gg-^wqZ?So1}X(T8f4^PXX&8V~}v-1zf-r89gN{f~Q$%`|D z5b8ojy4A4HwXwQ+M%e`)dV0SOpSxRfj8IoFS0j@4x|`QmO_+uw=sr<qP=9wEnE6~q zN8wx&`L{$E(V$rE@ZH1mqmuB;<gp~M6h7&nv#Iv9ce0AV!aa#rlT70CU^8g>ayxrx z{F7jTGjCosV?m48r5c5e-_k+L*>xHpVxhu5b|%-<#4K3+_+s~ZBnQo7iiD|BdBSET zcehx6lWNW*Nl>6+Ywg8CSdd4GR+R7H_BB=&wN0D^h}YGZCH0y`*QK~zn)HGHo=|Oc z9Z*L8%}Up1dQ1+>g%TnP3RnimE+v{iNTW0G)OkNCb>=&a26u}8M~X1$+I)2V(JPw) z>uFxn|3G(=(LvTqj$NBKacqAFX&M7yM}h(Hw0_KPcEl0KXAAsgOmwR9>z>Nf1um>= z30f2_${Ui6L%L6FGw_!AtDs&My+W=;T^KJoYm?qm%1|qol?E~R@X0m&5g2RbDm_BJ zwwbd5ySz0}tU{XPbo+Dh`;)kZ2+MGmC6B#aLUK-ine*n6{l%HM)n(=T5N>o0&MxoV zMRYu4FbjbUf4mX+l_*J*(FkT2#EZW`QcY2f+QGo&w_B4{u|zF=I^jHaCvmWN1RXrk z$zcK2L0HEiOR!C-lgMs);G;ih_JAJw$_gE*fVPg5?)pnKf%b9Dn%%vXH^*k819dyX ze3e^Hv|jCLCM5emg#&+YSxN|wS&d(}drU5oILV0{!U`9Gb1QG(ZuCiBF0Dc^lrW)N zu6E(o&W8}q*XuSmR{0wDaA!5`xukL*Eb(QYd09DtNE;4a|5OX!p9E0yMrjuo4!gi( zY5RxY)oIMZ^wzw`Icvm^a^dg-RZ_9cXZ*#J)*&)>h@j&30mq(+yeiF$Wh3e1>@qoh zKZbZeW?BDBH`7AUqkh3Jb-heG>8GOB%0k9)K0~q!JHe-h6=;T-@BO(ElLAKbiFOQ4 zYPkfcNy}o+7_4i9x|@mJxl21r*X(W45I{LrO4*fA06nQgBQugv*Rfew0(X7kO4Fk~ zOTRZurtqSGmLSW>gZF_a>ITO2)tjJO*RgdZs0%<Y5^0YCKG>O)6S!m2D8~>&VyJvG z$<?FQ<ea{2lk&LdC~?F~#~3Iei(SZD6`E}X?R$&HY!OW~sSHN1nCuuhzntR?Jh2b~ zdq+t*jiMWa*idn(b4G*5B?nysQpc3yOIyUIB8P4ZvY2p|<RL_vc|?{Y5iteN2epOp zNDZ3KLaVIb7oBuoCU{z!o|WeZuLinU%ZrtcZFa>h6k=LrdbB4`gl%xB0;uxk8jk{H z&cb)drIN&2_=pya;9V%X_pTAnA|vV}^AWdkQVixJxx#4)2Zsfb@#~J7stQ#jN&itC zfXGP#&Yw!q3x1t-QkI#feNweO#SjYY`(!*o(&BTv3B)e}902Kxo>%)~yj~}h03fCN z56V*PS_0yGdvs>PDAXv@y64UhvGIjFU1(FOqy+B8GqXc6bR#bSn+@&eJd#wPbqB3U z@(`1d@oUXIZN?vEZXu2hR!RuhTvO_1=BE#T2qP@=BsCQb<(V{WQhZzBg%6#k(l1Dv ztV<o;Q%scOsyU9#*(GY47JL9iV#?)BN7xu9;U+Z-)g&0mHwJdU`eP=TVu3S*OGwJe znISJC@W}K2W>oui6a|e9>)fb<wl&oaDRZj^dtXK!TgrqOw+4ELsexsQDZ0*NF`>+Y z@pNNOpQr*9RL(VeCZ73Na0SiVos_?D{BP%u>4ShfWoMHbe>hvAJSPs1{K@4%2#+Zx zo{{+xLyQ)r{fKIoVt|_0)sjsb>q5qQSWasiKA>2c9opO6d|7&jofx)1LZUl^_?(vb z90h34dm?CZNuw3IONQCb3D)AsMfT<otV_96afvgvgdKBe{C)82A~FKCqh9>@Nrnzq z6F0!eeAlG72WpKVNv(Rp#3)fhtB0B@ldkN|Ck#LlLPv{6ZZqv#K)?nHe<r!VC@7#F zaGXJxgfuxL>jujg_x*SfxDMizUSSw#Qz18Wor_~-SR&UYycb)t9RA%9io$edl_7fc zg3T<>|GCIyPG5HQVIU*iw7-2PQ!{g60@(C$FgQf{OE`vS`EI>nYLeij5Sn1l;TsV7 zo5F?9pG3{7nFoboIDUA(DpyVfwRdt4sDc~Q%Us)lF-y2T-R1*_$|4FBlzs?oIAcZ_ z`K@a4<>%E0v}Uq6CNNeoEdx}i9J529yEtUvnUO@1!8FGT520yzO|hciE-lRw&#wHZ zUck;}CZ&1}8iUV%DTS(jDt|GOhY_DzDp<2(C?W;8hSG|;E^>fgl!^l1j%I)u-Kk2| zH1du;M*d%;MMLEiM0ZqHx)4MhxpBGTFy>Wx6pu(H7(-`>I7+2aS~I2?ik0&2K;B&; zSc?8;(9`5;xU{-9^kUpZ5`mQ0kUoL8(+&hY4VhTr+iUyeS~BL0ADS&hOj=&;h>j*9 zBFfqtq@}1T6jWg}Nnn4%fM^X|12-GRYXmWXTjZjf<yS)HEOCl~Hs3&%#P!`N-*S{u zaek=yHn=65b6u6u#)d;11ClHILUHD=IZ>KyhJ{xFHz7|VsrlKxk6AYA%sC7U`PAxB zJC+iD#|1yE$zHI;Pr0&KB6YH%Pq$yQLa}sKIaeT&8)ex&a#9HdN;Q)DMxAW?H;)>Y z%Ah~SZG$p^P(1U4gE&KeZxzQ=uE5>nr1Vw+E$1(xN2PO8QF3z!>d;et9^zQ3^0*8* z!W#RrINSH_f#DFZ9rE7q!Jpjs)sFX0N{U1eRZ-H%7v^WS$r{D9BTF%zt#@K5-z%e4 zoz3qC*a>WlBR}Q_=^3wscH~DMHvI^A&W{DBoBG+1pFM2cK{m-mvO_<Uc7La$kfyi+ zsHt-r>g(P#Ta3K&<^`YDnaSG%P!Fa{xt2lgZv0eW_s=gcN2k_yqzRJDQ}=Zpk@0r7 z%(0w@&-$}vP*0NhngVxna;K$<CsPwlQrQ$p=9+<Q+?cGWvMFXk_G$@flOO^ObM_fV zy{?WklV%Ke=uue<0?_~(%qXD06E>>z3v7d9M~DDLprC*>?A=s?izp2OiYTt{o&p|5 z&gkA(e&@^X-WILxJVeIR3~eFIjk!0fFNNXNXtW+pCkhdM4lRxRz)z?Jr4A4Jxm!B% zYA-R*P{x93Tb~m_a_q8YL)s)n0bx-PVG*`Els^CfCX7N#YN*)5^uYp=D<-r;c?z=t zUylY%1oJ4^Bn=1Q765Li;efVTKEKiLzQrGXLvF_pMrPN8j5JVpqOU6nK|81}6IXUp z23B*3Xa<={licd^(g%5AEV->cfjI-uwo_&^;DBY#J4IDb#RhNLR0%K=&QK|~)BrsV zHv+N3S||Zycj0?7fb>vH7-NGXh@OP7Y;kA?vHZcl@U<%WS{Bc4EE6E#UK3OoTq_8k zh-xF%$ZDVzWTmFR0)5pU@xU2lUGbYVbAnNuMsR<W?dSR$t|zN3F-ix<!dWlz{kd<d zorVeE;8*O}L=Wu&e=fhD$IGtn{)l(V@H^$(&DC{_4ss3#_(c-cOrv^*!m(XB$mW|V z{^=H@YLof2N`AMl@=(efS&?C*vrt}V*S=V8hj*L;CSZf(Z;XU<)J=w7|DbyC(<6CF z?9n5arL6L5iMypI&2GWUr82v=cu);^e6Rfo@n7gWY5VLwx`2XiQ*y!q_WBBObRGX? zixEyav08OztPw6}VlPx)<TDE1-f>*xPF++#$X)zEcp=`IkIK!EPS+pZ)?M;bA{OW% zirS$ObQ-{k=f|$}QsItFktr<0lr%2A7ZmWyr}xCVDd|Ar$5q_JE{q<NlHaD;(G}Gh zhg=EK@%jRoI&s`7Wu+_ET7MlcZc}Yt8yXs)GgUIzp=>u*qD1<wM<#8uc0<%l293d3 zH<IE4zkqVbt6>QM37f{Yst!f`OShvW&tfhjpCtT;N-~%uoh#b*V#|AQp-wq~IHlz` zI3D!2*lSK=Ctp>TC8>Xw;DRf+`X$#Ho6DX({pO&W)-abR#CVUh2=iO(&BzRFEN>O= zOXW4Q5V{o|O3nb=BJ*E?9wiVe8R4(!V#UOfrrXwQ&eX4%g+oXlW>TX!26JePCw1wM zR{Y1h5C9&5MZ+iN^c^15&jD1#>9%nWRNFR4?qZ`MC8Bm%uBFsbqvV_Ztc>i%00>-q z7IZ_&I3}Xk{4{2t3K@E*mepmOQzqccZm$Qd&nI5;+jAL_+CtsHvjL%B4}ZgXf&4rO z&L2LXVBYguUq83=X3->#rI|Kkta{CYphkw-+iLy_>y#PMpAwbp3H|i@t|a|j*XCPO zSX?OcBl9=WDF@Ox_26$U@(PZKI_fYkJQ@KpYXk4~aRN(vhD`omIwY;S#Bj{dA*rX( z5?>jF-9A1J$vR|!v|8DzmuH2OW_nHK$1sz##R1iv8f<ub2_txN6+D~k?2-3+v99f- z>zITj>Itl21G9c+LxYlLT<KFD6}8r5ssL>zG<7gf=ksNC?dz1yLG4UXZ};12+TLHV z#j8wI7Bw~zRQkXiIafRT47<cESx)}czg}odr%-im5~4oHZmC5lH#q>d7`|+g;7m7( z+Y=J*;A#mt6KEM!_rI95KQvQLPxj-Ro#7^wZC(lb<GA|L?;#661#n$LQti&bs@(GK zbt^-E)tVSF`isWhMGZij2k@SpbegGY12u}O?e=xvWt<XkJqxTa+f?u1BM9+nVlPYp zm9=-XnYlg`ibsgSfHa$2vZ%SnkvRQ~$5wg|w>3)plDFCiO5q!Pr8yF;v7x<_$#AZA z>NoHFHMG!l?`hWo-&V<jnDkx9!A-A$ga*9mxC4(MY4?5nrEowTqB$-G6w~QY0|Hl- z>N3pbIV^*k89u4TzyaZ%#9nBhIxYzX_v{kC<CQLp(bn$Q)k5s7-Qg14Sq5x2AZ)GB z?byF=&O)rttDo1)eg_eYRfg~iQgqCqRiNzk@N=MZ_-M28c=(I;XPF|__w(h+Y1m|d zB#HLagtYC|6VG|BIM+A;QP-S2E0`usfl4&<VjTy0nN$O0*yuDA7sDh~<VqVgwMJZV z1NXk7>%3jbO+p~rdVA{U=38`EYy-V(e)rA=3FIYZi-iV=1fw{y(_yFgRR9qCcqiu8 z#&rNe*}l$xCC}Tq0C%KC`z89CvSa7Fm&8&{wA<UKImHq+wYcvT%I)3!&5k+*B1R7b zkmn8@#2n7E9k2`h^t3IB+@G)_;qpyt`bkfE{EXVr+eNu5yL7qT;mDdS2KQ{cYVZCe zsS1(O$w}SWv)KM<c5iVxb3XCM61*{7lN&mEkYMS<i|XZOpu3Y^q2NjO>nANPJd28R zkl~ZFiLkTlkv$@F6y=PuW-nLLECt@aLKfK9IP$qzkB01>3HXzgIpx>v`??6QrIR8( z*YPg&Vsb^ab8or$HTOVO$W`3qu>|k0B{{}GUx<9FDE{D@HlDS3L&6&y*(`x5_i4cl z^^O*rw3*Q=s-Dcz8~CRana8NCO(45oXG?Dn>o=Rd6A27Fu?iHA<9Sd^Z5lvvx72qH zPxD6a=1<UQR+0pcM0i-@?%x*@abuFvmY0<NMU*Lkl3g6^`D+bR&-?m#Vo#KZVt)AA zzL+%^!3D>vIp`h4`XYtz+V=vnR>#drHw)Y`ksAfSeQyT!;jG!!uJ|5llgvSOAk}ep zKI=iZu>2%)-fjhWF=lPLx|%?vOCek{hF8tdtmv{UhMbUPQ{GRx45_XLmj!lvsQDK! zu~MU>-7=gsJq-CEc7@WD6apl0>Vx>A^f+3~(m#ah?ZiT9X>+>Jtj{&HGF2^G^kVck z{$M~TpJAa9VD?~K@ow!BDW{0chPs2}P=`Ggpv$PPz{`3`nHw-=&=Tt3%VQNc{FGq# z=7>!gSI8PgHpQ3IV`lkLQ5Y9*GL6Ua;EY644p)L<2YKBYCH|L4?N8|`Z|=;p6Zn;- z$F}rCv(Aur##S`VAFf>s9;C8)6?(%KIqC|ce5{3N&(u~j*saqG?tQKgUl{N~L=8u& zrwNd!(X*OPs$FpHL=(4+Y~%g(P=K=f1eMR-W2ylQyj;|xJ7C^Oc~F^~q5IE|A7?!= zrKBIZs7v}`p$}Zi>@mNI5M<>YpXv*s_0^O@tzK_;4A#zXRiZ1UuoF?U`W*K9-4{}o z^2!MfcLyH%f9_vmWDou&(tB=8Rvcs}jsjKk*^J0sU-0-+;eCjT|31Hvh-NNYPV<i< zokasH+Bi95A8Ny?xg`SL`&~k_`B^%=>XxHdYM#ej*6}Lmf&qIBUH`=NZY5g@b$7nm z@$PuGMEO>4%j^fGU<M~}{2Xv5tG37anIPadq^rSS0(E)F_$a)5h&f3<^?00@JmUN< zMlcv2<$E}I5*2<kiGw+vMMzv<XKvejdo1_g*4Mqg?GT4SwMK#GYcGeX!|@+um)p2> zioCyd@qju$AnpNa8+%-rbmp%@vMRh9sBeR!ib&vlB^Ah6BWH)zgQ6EVM<0;k#ts49 z9#6Al9>rK*o{1;M>hkZ=Xq`f-Zl=w!pM2N*qw}DjhKot=1`T;N?!JneT}E9B)ple7 z#xO^SWs{MXh)Df*%SxM0@MN6NaG?U@`(o>|$~V(GQ9zkfqKC8#GF{#?5_Lj(3Ao-b z2L2t5e}T<(%j01dCx}VruG;-dw7MjBT=NjJf8=t+mGY7?mFK=~-!7os5G&7Oo+?eo zmT`-0P5JNigUOgpLv*yW?Z86G-!e-y-nNJOI2049kS1M@-E+0Ps(}H9ukDG8HUc`b zBwRr|RMXIZVBa;oP7FX0oYf~uA|QMVX!Ex#Z&pKCC3l*ju*PHAHcNONDEnVZ&N%&K zil0zXUK?9~Iqb8wsdU>y?3ju>9dOkldxjLyfeKW*=<ps3Tq(4Nd3fo<HY2xK4m}+Y zpHhyHC+?b7N6N~=?kQdgTGz-o3lp#^<ut=6j293wk@9hWbbevOgr25i)6Q`HWDMXp zqoek!yCQO^DBi5e&3J3#Ys1wCn`YEv?RK=OamEYTd|-r!mK!<u8r^TjjL)C(sw>0Y z`mW_Fes0QBeU7d0TuJoCPvg{t4vg1X({d9Wey@3KdD7_9>y1W;`mE3}LCP%gi=B}@ zYG*W>mKC{b+9Lkd&}%qAb&ejfk|#u<s^iNQyF-%fau$1=tr}Czg{O(Kov-c7okqP0 zeeUJjUiZ~60UmXwWS)_~HhleIx}#t9WJ^rZa;<C;if#OF%D(L>N=2|3O*5xY;d~Nc ztz(KrsdiI8Sn#JxxRP4c?OKV?WxF?f2~vnG@L>~B--upD_3|TdN>3>AE!=bWV3f$! zE@NV|R;0a4torSWMk5;kYWuRXdpAz3Z#Fz+PKT?&Zn&T0;fVTK+Y6O?WDWS8&?2Y9 z2RXLgvGX!-u53c<l021dR?kKrMo+MsU$Qvv4u>g>f1CvWu_wr44gG#lCEB*{x@(Ou z^qtyVI`El;)I@YJEX1(EjV8#x=gwL5GX26&ffZP4TDI=D=5&}L;e!+t9wrET)CD8A zk3Vv49Es9pdk<Om^GJ@L0U&ljC`I9AVc)O%EnN>$z%VJE8=qbr6xwbQKRIN9>-KCP z_uSd&PbXj}GQZGVZc$>;Yw2j{^MEmYnOX{l;@>=qivRx3hgZ1G%vY7!#8{+R%u%bw z3~C6im>?L<Zz#`_t~d~5*NjOTUYv%+?<=<xGYXZc$&I#Z!Rle%(${<6cpf>Nj-7Bv zzd7AMG~M5Z6Yj|zDqT+2ul(@;w<d(X|G<vtxA~C&-LU>$6GGC?%>ExfL}PvJ=#(Ob zG%Xcia=KBKX@OZmNn%PGAU`%K-Kt7OD>>h+(9pWy;0TzOo{&M1qrIJ!o@m`yQV@us z03-RC{7iaOvPN}^Zhn+<WO8JBPCj4)cOUSRf|7$Q)g%R2H3>DjglbjrKIJEA3XpB{ zY&bS}lLY=08PLD&@R_-A%EEU?&wzn|@c-uyn>!ggSXdex+DO{Dm^zsm8k_#3*Riv_ zR-lZC;5%ETh-WC=*|3)xsB(Wqadw|Uj95D{XX2T$Xvs?BZ5+r2D*|_o?>&?{E8UHN zr7(oa^>f&j1TYGR7~Gle?wgW3{ff87bh;f`?4W+Iq$9m1BT7XV-p-5}KbB&6LZwP% zne-@H>w@N{YYSmhHRAXeb9zJhXrpVi-y_ksp~wi3QnBQ43mf6q4>s#_K<;D7DeKGx z`A!%fC<#&XzMB;J*Ma@fmwLzINMivrVS)GGtvNgSalnXSmqB=0+e(CQc@@i(rM2vL z{=e8r5<m1WBfckM?7LC^&lBQc<7#ec=S(kRX=rX|@9bh}tnBLG;AHCTZ141ssj-dg zgXw2L6uJJ0GQD0a(vy;$i#De`K^W{<3T2^`)Eca9^+L-3;hZsYqw<D>OM{96S*v&j z4)Vgcv4Vhg?6bYNk|Bh<3eQ(G`Qe#UB0(8y0RyzyHx^gq2rGc{hpLnRs#Wh|5h<f0 zNF<?pKXs~7WPW9Z--GZMG8oR1pHlF%Ub&O@A>6<HeVM<IeEq(MvGUz0{=MPI*qd7# z3)&glczT&SDg1Mc|C!}^J0?FZ<2EThSzaYY3o}Y7J3ZO>y-4ez6>g*_Wt&xn65Q#f zXhuh6<R+ozXeoiQRH{tO3-JTAc?Wq&JKuT!j0Z8#2hw~MBrOo-<ts4T-q&-%{V!|u zc@n~JQyJ*nvxfls`9F`r*~QSs)Xc`-{U1HP^!0V#YioG=`b4d0XVn%U=wm~4T3IbM zYxv!G*Rh&@k>gFp8t&8!-3^<z@(W0w_o<PecC6u$eGd%M=ww00NZP8L^n*ltvwCUz z%bX7@k$c{e*8BY^*-OJ;bkcG9N_#((z1D30T<dM|>qYeC<!vD?V_Ep^6Fu}-uDF=J zL9DFN!}cGm1^rnDC|+{?*o2oO)oDgT$FD_t*RIFK?n+D7X3>R5{`+D6jMr)L<Aj5h zx77}(ALhVdw;E5c^ni^@{WaIuLa9hO$fdgLG~-VgVC8{!#?qMDrO4N)m@Xc(eRZPP zB=>C>?>N@<h7Et#+SpYGsc!AU)fucW+3sb4**;z@2|CTXaF4<0egyhq&l5!00IXe^ zq^Y8u-pAh-_H0a+i9&y_;cQl2im0UWr1veXr^`3z^=1zDR5)2;*^h&pqI@CkoL^xT zUlL?pjgxQFOQRVb0&3(|jjkRWB=>^h;iyCwQ1eBH0#_pTi-hfB{<syFUd+#y)f9J6 zm0z9@(!#RRJ6h_(7J(9fxH}7)wu|!$Ll|;ppM<~I&&_V=fzs}V96tRXCLEmteH+c= z$^723{XXyBhTiNq=eM`~IweZd=*Yfpdiq>-Qlm{DGq|bR#@Xc4!LxmI`*w(hrvVG5 zCa<OY1&30G0;931Sq6{j{KGI~5*a7df=D>vtqPZ>#OrPTcNpQ<WE|3DMwXh%-KX+_ zXQuo$^?{yF|4hINPRe*bldy?kre1~ZoD~jRq!d2U4AiX7`u?fAwPdHhwEQ7}tYm;J zL%ql6>rVF%I#D^Mlm)(sK<Z4TxxXLprC*PS_bnf<DU6X)84)k~_?Q#0=xldf!?anB zdXG*t=aKKzMc5xgz1&nWRVQUNRQmgdEy5dnmG+leMKx3F$LjJ+AGV*5Hm^}x@Nmna z8LP}}kKGtE>vu|p6)DNm&3+oSiDVzHI>*!Z@<Q}@qKaOFH)t?t*vbQ-I?6JgNlz>{ z?Yx<f6W9KFSzn&B9}ky9>mKbWBROsL8CY?~GzIxifFI_~gTwq%B%kR<CZch~&Rli7 z&W|5eZ@cIA*FC;%9$(f^d)vp3Dj}m}@Yx~N+`kn+U*B@C`FiAugQq1y5c;Y>dvP+H zd%-8p@1N+8bGN_Td#9*GbhvHkfEya^?R)-Q`+e|IKG@jEsxO32i!XT?a4oSUe0f0d z<CD4=FsuPFpxfB^?X-Ue`-DRowSA&<C;_I$lgQv)X#+cEL4R@kOJ@egU6?GqY?=!U z_+mUwy`*3I1gvFqKAz~e+_iEudetLf5^oashM9F<FHNP@JSA2T)LPn<ey!qc%Rv5W zYTi_=ODwwy-qrXK7JjrH4gpGpg(TY&c2aH}^Wro)(41mP`{rL5y$bk}&OO2`ZknE3 z3$K8X*7~S}>m+Ng!DYjSD`10{*NP>tb<izM?bg5<P#b3T)_Za7P!9ge@LS=r!<kRi z#@g&At(i2!{Mv9g#=S%r#lBsnf2C3pZOhMEFmc1e`pWE=uevt?)BbSAb}E&<I4l+{ zWYfAttCm9AwKrv5i4jV*m>NJ?WB#Ly!9RtjX|h3fkGuc*<|3#*w%tQ=#l4ZgD33o@ z*LD5@SNObnjo#CjvO92ETC^2qjzqI@Y-TT}{o!7UzpdVoK8O#OfAfWe4aFyN-$Y1s zx&98|+4YZKw&(Aj;`;bFUw$e@$N%)&{($1HiAL!0k5v`Ep|-a)cFH1dnU+JY$udEz z@#$tldu%lBPyU_szORJDDoa;SSRaw1<b!8~^z4xqHs96o7EQ+^1G$;Q`zVq|K`kkV z`(y8SID{ji32B_{D0Tx3bg}y;cc;|k>WoXr@UxjkhpFgpEqqfZ?7j4S{br(`>I81+ zAtt;M87OSf0gV)k4;O=BId0?(fzjUZ+&N3`^bs1`-aUc2n0C#KxP)#E@-kLxUY1iR zpNNt5g`mja`}{nK*I)%RmLg$z1O(AesYA#Y(qwugg!g_Bzu)8Nr`CREM80J{ugb8a zC)UX#enOmJr-Sk|ywLR+#Lu&eBGYqnWr$Hx0NB*Lmv#2>3sCMh1bxMTpJW4@>k}(o zk^ySIs#!ejL=8x*qT-K|c^3|N85N4FNW|161@4l;K}2k*^@o&3+V!0xNZNRvcgN`U ztnu@rHZ&KVoNl%wp{2wh>VM@&0xs33G5%_XL+>mU(%aMX_4ta1fG^sO?PgH2i9<WJ z9k~rTcuC!QM(oO*5944vPh0}L6lkQj5|!VKxq~u7wrB$mYy}UscjM@%#-j=}mIvFM zq#F~p=)PF8+$27JVOclCSQ5<K{)#h-dsFhFrR++{(UX^|9hsXh>y2Hon8ke+59X)Y zj0adddD_W(2UESYI_i^dU+msMDkdqbf@4vM8p)_Wqo6JaQqZD`hN}1_!7H-j71Sff z9u0u1@H<kBVEHQ%Yg%f-<ma9c5G1Y6-y`NvQ;3`j7AvK3Mx>11Ei|JF@hj456^NIG zLy?+U=)d$U2a7ErWF{lCyaO+M08v;|$(E)y-Q}sV?i2{;!LwSJc_=hvHC@FQCXz|w ziw>h^q?(1-DNsFm?<#eNt#APp5F1Fb+l{VP6K!bGDZB-QCkAm8We7@z82h9VQL40H z3eyPUs|W9*p|xUZQaG-Aaucs%-L2x>q`_vaiby?boaL;%I}1XRV2+8TfRgf_2{@bi zkBB3rPi8?P5I#H3GM1M^)~*C{QvsC+J|?lJ_QralD-8u%^Kj>!jg6ekE5yxJoXe}k z%_W@nbt4d)6y0P!8O!%1XI0*I3D)a`C9~LwZy8r0k;Vgf)76QD+W2wy5v-)jnL6nQ zVYrH}1j&qKuHa?ozbv80YZ&9k51_UJC~vp&Emcy)wA00mE$@>pT~bOCa>CSqVBpMl z%vK0g&KCD(OV-3tiqMQ^^JZbOleN2DAl0%qmGxt{Nm~z4sRoK&MkpkQSL`aphFk3_ zWQU*WQCzCgN7*%sGO7|aJm#`|N&3H-FTV3Wb6)j1B6J_&WexagV>>oueF<D(COsOG z(`l=|nB$$AgU0g~oJz&G^~BUK>>CJRIP<(llx;z)v<8C@hmpO6d{Dzf;=r3&4*)+P zl=+V;e$`2(guRCIm?TWs`f~t^{GWwH1GvirIkx^l6eR2Hm9QXMwj_C45Qw3Ymjz46 zUB<ud>&^&nxW7Fn{UNNHkk+wKCtW~vP$A8|+WDe=zg8cEg!(*5Yc-Xe?ghJynUhT& zn^5xj99_UnMBRd294DmwgI<v;tmHwzu<Sl+1#IlYjEx1~&K%BW;4jFEA0t}wy3-M8 zJ%6E(+0~QmJv_s^f0$G6IL*;!9=hG=bgh~2bUP;^DOPI^FB?8pvpZ+;sW)FCPP*oh zY+pEDy3V9b=mDn$JEF?BIeYS^@Z*;XpN_D=sq$BZE0FwO{Mg$M0Zc0^%(DU0vOhmA z1DTo@n3}>TW;`%oK}}D}O-~R~^XHjR1Mj74%_|12`CjuPA%{of;j?d}@+-$k%*8`v zM=+^uG$aZ(-th!OKoSZDR?)p0Pw^Jx-vUo@7cF0pPkU^~<E>FjA3+d;H*?k&J22pL zuh>{{klmg+a2z;(p)=z6unXndv9sXpQ6b~NbKrQew(#Mw_;cLPG601O$GA<01=EEM zgolR&Tf8NUgr)g;ragvkskFqCb#o9HHF+}-%)G)@_c%3uYMBlNEa{&&Z<kc{tX<M9 z>2H&q(~GVSQ4_9FmiFgP!^p_DhZrfV8CZ&0cxnW4T7ah*zKb)Y&Xj`Jfpq#TH;W&| z_Ej5{75d(~JnqA>TTpF!lQGfUhkcrn@OUOGIM-9Mqd7x3zgi3W)3z^Syypn-jDUmr z=?LY`H+%o`QXutp=3wnWpRBn^$`&EVAH(&ru@!%jxOBxJl_9)H^$7)mGvXu*xf?xf zxC_QxR<m&2{4#S7SCfqGPQGV44&ofR6MnZiqMVL?Lat!>6c;yIIEAO_t7JY=if)*| zQt1({lt2B>UL!CrbYC!03c*TPB~WaZLJ!T%#Tv$Qp+CSs{O-FLXZKRR;=pfG9|b<; zY&lO6(O1Nqz|9cRO$brTE}2y;n*GjDMzL_oqG-ULIcNKvWbRY4PVK8HjYFOZIvW0s z7JN7BViY4DuvS+$wBLlKZhL7i5#qivfM4&x6RBA6I)7ldOV%JCZj*OmaxRa|J4B9@ za>>d<a<-*N-ZL+1h-vzP`7w-PI-v?9-R*E$*UI%m*l8KDLakMT&0%{J3x#iA<dJQa zk1@U37-?**orDZ?Cj}eoSsd2iU#x6BdD@%auB>G?twN_EDwSK3<4gSIO8~+Dhk2#J zz^aM-6$i+r?~GPL_1ZmT0Tw<1q?k<6YU>)R7#*j0fmCYq4LAQjXdr2qt!~(aiDd^| zZH`?}`F%K};L&o2Jv1JB3kFxBKuU5!138&&wunTFCQ|J8i4rnzib%ZEdHR?V9py2L zh32_7{Pwd%H!FwF&i6j#@4cEe@3BsRewCjk4GfF0^BQTx{Ven{=7wCb`;$Jov7<J~ zro*~ZaQMCpsnA`Qcyoec%HCE#pu1owoB3iO*}Utma1i6&uLV&M>dhL4S<97An}8+` zHK#9x%K?{@Bq$?C*XpqCT?C!{9llF1P15`i!p8YR{U}-^(zRl9l}IuXp3+6jM5oPA z0tKfJ5?;JPDFL|-UpGJf>S%-Xc2R$g1+%bSQ?Gf$>?b@RTX%xaQa~28YzbGTdbA=; zaifq4nv?v!s;8I99UzxLzhoMX24z5E_jj4LVE>DNmyf?#5un&Uu)nDAM+@x)`BsZU zuM%b^(t{VZ*87$#_89sP8z+jb6WQ8<Ow*WVm8`)VL${%^pbwtdOxOOYO%ql}2-?eP zIGyfnU#`-@@7#!eCI@0ZmRSzP_35(#&Jm<(XEhWjHA`+U8EXV{TzniJ>&w8Zhw#R@ zc;cMqoHabj!i(~c;nn+Je>DjX8wJMA1CypZj^`=ffz3^wf!buO2&9;GQhG!G@*XSI zGfoY+^Hfw)5;u&S1>9pbjAfCzSlSNC5D?H&A&Po2-0^RZ47|DBTo1--oQ*>&y~3_Y zYV)c$A=`@{!s-&l<vsED;uVYGKR<#s<aH6yZ5FO4#JlvJnBRr@yvWN|>&*3Ao2Wn! z#L^8+K<_5Fa-yoz-F+Y@uthXES|b7ZS9!>r@<&~+=e;|5P+~W=4}h)JCsz}(B`ZKH z<|e)(@V3|_Iqjljg)!f@mOJsq`ZtZ!Zx6Xrw~Yd7hgyClp$u)7g?f?EF2rS!Lqeo$ z#$4V$OC(kO(%2G=wJJ~~%?T6YK*s}k@oG3{Z4wk9&5DY<a5qG3A(zlURA6l*5mXJ_ zLs@h7$k;g#v0<`@X>-l=n0vPwV|ug+^rknR1i%A;ZO<lMf`Ad@AaLLgL}MVnMh8p7 zQ&2tO!ae-=9C~+qE9)P2^X%V$QFI{o?%o)M2lrgMK%8$O{&M9hbHzdAAkaGtumA_$ z%a;yu#zyq$M}-`W#zh?I3(&B$63Eks!$G8X6KHb27Yry9Q~8Y^Xth0mF!D0Y2Eu{o z!1HJ3Ht)ra86Q1!4RWUfa%3PH7ol78VC1l*1^C1Ud1OEu7onrpq~zF;jfFt&FD{}* z|B)*ChzOst5ECiadddqH;4il5eH_-%Y4@+=c_4bdUPr{j&BpZ2RCv!%c{UcZI7gYC zG!IE*5Z&5>^F<up+8QU^h#K`}>mJ#5J=H}ScKaUI+N2x#h<F1K`m*EyM%_6^NBTAm zKDKS!wr$&(I1}5M*tTsa6Wit_6Wiv**`ELNy!-CEIA=fXm;G{govZtFU+TK+s`^#k z>XxC&AbSF;tv-Nfp8`zLHo3?5T$c*eq*`cj#14LMA4pcLCF*SC4waagW2$fzo=%`1 zwducxJ%U;u&xLkGc%Ld7<&PoJMS9waZ$ddz6M<9Q`z}TUg?uQ&{A@H#y-H;w)+tB; z3qGJnF9T;ErHD#Xde*HduyIuF>?!#p+{M5_U9FYEDdZTdAe^^wX&$9S=!_XkD%k;6 zd6{+~i|$dhrLx5^05@-Bk}FWJeiP21`yzx4|1|{y3`XI0$KE8?GpG(7g77PSM=vxn zLj(kuoRunLT$!cGiSkEbhTcyn-1uor9gNkfV_MaSkBf8<iA5Ed@F)v4e(uxK16FGH z=L3?wT>`UiU#|7UA`gmA4+-4_8{;9?w7sXyEW+R};wmI%ui3;2*aI4DeqlaVN7K`c zebaQ$-}=ONibM<*OvsVvu%=yk)+Ra>K@lbJ3#`Bhin4~HEO>?{XvMdawJ(XJ$|CH{ z-QoN<i&1#R55T<zccS8A6M|6aBlog0j3zb(10<(|g;X$LmVRr{=pvn&A)5}ZTbz<b zGq9LqFHaiR^R1*;8<8E(vMxPuAm31ior1&q{KoqPJcBU}9xkxRY02{4)vWP6R)SJc z&S;P(tk9`|k{`S9#7R<NgAVcaEb`Al)d@W-1vI2zlpY(*LG9!o3+j}7vk~A{S~iMW zKLlQEaeco64TAoRPMuJ0yysQ|b6Zsum!4jV#uO@0Qc|upSqUwn!Y8h*tAQ4V`4cP! zoKWM$^G>#;&oLBA-FQ88ZhS%;SD{f)AE0oSNO4P33t)<_`1SIF4dpM8al10%p70j1 zVXF%^W|8_UC27=M%NE&nzaoD&t<#?WQg(-`6Mf~Oqpka@viLKN>s&o&>6OJnR(Df; z5FoS%BkLhHh`5ttP{s4Zg%la_TA`J*IIX&o4&j77!=RjAWcQJj&;Og45)WyOrVQJ( zB1E%RnFt~6d!nZb=>>f_y?2+=4`U%FIAl0lVY<%6ExbRPE!(h42vVI{cK9ivZLQP? zTNLw2ACh2fAYPC_o5{XoM5V}!!=o;wRZ{4#pg&mA_K#g+cS%L;7|rMKhi`95`6h^y zO}{}M27G-NZO0EM2yLs}ge1Cts^oBpjrEY=!z7%w*4MH5tEYy=*l>FCcV%-!8LQY@ zET0<z^FMV{GB3mFV{E)V-C)DZz=!Yqd`BsG>D`=F=7&pNyPP|JWHvdoNzxj1Wb*)0 zw1@>_K6gS6m`7AL6b4|%-1(^a^Nd0J()logiY+?4b?;IMCJ@+vj^697We-xfIr9Er zGx{Cf=UZyf??rcft9TO3zoAtX#1W)s8}wVr#w^9!MGa8BFf!`Z@r-@a5$-jF0t`%| z)_!3XOTf|+ZX(H?l>9VSw&fYRT}Z(iG!sua>wh*HW)Z;|#Q0DqvAaRZz$dNw10rWY zHfr1D=xEVIj;_Z12X!3s>B=@3*)Bc`!E$?9?9(GZ725S7f?FUfc1zc8CpwbVdY;)g z`-6yWk6R|x!_U#<DdlMa0vQv^8~6fW-xaKfh5&?x;6{;zmMqoXJ5fVdx6Pen>y3-Z zLFmRhe~%FTD@60XZb749&wm<XBYm&eGg1Gx?n~zL6e}t47i*}`-fnGQZ&&y8`x8F* zJ=ZF;bAWlIWH=cAXR5wtxwXuTXZfxCe;&CRtnZUlAqRPXWCefH2XOcc^E-rj_ps5@ zMw;lO?oZH9%UHL+FFLFdKMs0z*Z%v=jj;0L?X;!%LC4FBpSqhsR?w88-=_Hl;iIUZ zF!f6En7y5^wX|C}<$b-aF46wU;W>zEqM{N6-qmh8z4C^VsuomPhbq!*^r^_@Oe`qO zl1{AX<p$`NBHl#9NZyi^MrNwW2_+8{l-Uy-zt{;YjIx(f1)4cRA^9DjD}BhEqFPky z3Gx}SNCftpW{<b~|9a+T^1o85!f}`<Rtm#mW92K?f!Fynsw|z9of;KQ&Bi#5U|g`o z>ZuGzZ%*|r0UO1Rz5t8HQiQ?7ESZcxR-vSEL-Gy0YI%T)cFc^m0a#o3961b3M6>le zT`WJvr1tC1?z^VyhWlR2<$4-ovs?d~VMkE=+wNo@qQR!ZG+9S(fzNYn{Z$Klu(9bA zsy)oTscIb@tcqBzo8htfA9=%zs}|zk4Sl;RlFb{2`xssQjk6>7X<mE+4`ie(?<A*< zG5PCHNr+?iW)Nz!0p-S^#2h|y-YPd{s?~8b+&19x8AsC2Z^uhmPvwVU(&-xL96r9K zs+-KjvyP-q@sz)O2TF_itlVdhi4OsO^6I?p*tc5)iFO4aA<2NGxnA)2a|cF*P3YFF z9YzG!Y!6YAa4OFRpFu;7WY4q^rkq~1K{C#$WG<Q}?b4wJ*==$^OAwl$w-ek>_BmGL zlh1-U+(fdsa^Jy0w!rZ#JR{;{g6A2?*F1$}q3GL~%)tvJ20x%D^zXRtXC(1(aP#NL znMW;9JHVPaOzauO=sUqIlN<7*$rZ6DEAhc6w47EGzYC2l7`V35!HGWqPWZ>65qt9f z9c~=c#?HK3=_i#*id&?(OrjR~CD&x>5Dhg-zTOZG!};D7)z&bTY6RlW6N4V4x5Dp= znEY*7P*fzrk|$=D2gGT=6gm<6dxvaC#_lxqVSmStCtIEjd3`q+iq!9v$;y;!Qk04G z0N?XB3hh{Hbb+!xK~@jq26b$CG87c{Z|JBps`m>uGN=dQtI)$V#|au_=qUDK3dTbm z4KpJ1@R4@QF10N}T$ig)o~?nGlVr2XIKhcyLwI@eDBPp%XvYfy<u`p#{1~BWA5h<e z-G~cf2Heno9#h*Il3R-ydowh4z(cJoHo~rxZdIuS&xD}2<$c3!vsr&KOwsTo0QqB3 z|64fFTjtCNDevM(--i>l?-iF``IUnekGC1E;VWCi>n3;#_Pt~z!mC6Lo>^D2p7UCc zCiF+sj(_SF?jsd>@$c>oQPp`t*iQ@W*lajDf*FK>yU_@nVHDRl6_#5N=+pfiR%~~A zkG7K(bnx^`h6+)dmcd-ig?l{&&a3WLgEV!Xha+vt1)vavwnMz9DPB{p*YSXv^D+8< zQ4zhHP>(j(LP1(xTI$=NnlzE-N_JIgZQ2dqBi9IaX5M~W7@eV@Bj}3gH>XmSE<5OB zqz44&q~TpS{9&!ak>;DLZU&wSz1UoLG{OzI>5CXhnDn<@HlW7)(2%kDHpW<t5MiW0 z_2t~!s(n*oSTY&P6WQteP0|^wD=5c|$^Gc~^P?<<Y2lV)F7wEn2-EW;{3bZe`Yv*B zoR5w2TmYZ9zKd9uEA~QLvV;^S;X);xm7XkVaTKDJeCWeBBjR%8r4Yy#hM-KV45VeK z^MSz*<jgAl>?-7?VMtfjMxfKeL)L+g=X$&0R3a!_uqOndH?Bq~VJ*^XccA6(FXbF- zxR;Qn?n~j){0XxYg^zfJ?PHe9XS<+{;TA*A1-BPA$la{CZGKyjY}Ze(+V_v)pTwBi zC4WFxI(cNzS@MU0>4(@%cxphv`<m-)+D~>1O$h_Kf}#*y7=y0N?pzp~CK^CG(zKg^ zIS&maQ~}9ylioH4uHKPfO{Sk_`P2YQ?k&xVylf-gJEQsT-hr{{ZtcxM;>4bUqq2xf z=HwFOIV)mAP2oCAHzaaldZ1xA<hy#J$E=ICGQj=pBol3>dB$uLw}kd!(j6h|{A}%W zS-;WY>wV_weM=|)?p|v2XFC~ia#b`*OmWABFBa#T7jm=8yO0faSYd{k3MDnAc^{Lj zJoqV7PDyaKG3<OXkli6=r^J^_E=i+OY#361j#fuu<`zb%M0GpU{&07RBp8Qqd*X*S z`WUfs(KbENI4y!mWgwLZnLNg|nhJHMQdfB^+-On0#u}(h8{I!v26xPXMvRWKOC=(L ztP)F7oZ?N6Mts<~x)A^+ZDWQ>EUt%koem}~n=nZx6(8G5CoDrNhzU9TKx-W{b-Uz% zVPQM(9QmW@V5whgdG9=>5GJ<kkpW#nX|@{LflAuFQB&GM(v6+Ws}LlxaSxjBsOKA1 z_%{<gf;OqhQV@J`x=v54T(L1kpFUHj!%f{bSm{~N>e=Bzk}C#Hl=I+rm?$5SDdw>D z1~*?(2GI&0vTWnPApsTdy&0$yfp#h19|=EFC8_SEr*2oj3G`C}m$9Nfpy4l%O7FRJ zw23&7w!uQ%C7TqYu_{s@RmSkjFgqvs*a}5faOTksZ?KDU@gF`lVp>9_nKY)Q5pT>D z>y9zVFsiCRnsWWf2=1W|c(`K`Z~hbH0Lujospxf@L6d?W(yIz>Mim-C={ZJ%QTF0E zsfE|d%^KRhiu6iC*Pi@CbCQ93kZ!;J#EF3bW6v17r<zv9ft!9AQ&Hwp0=x&=OIa~) zQwk!-WSn|l0G=FBy_TkFvRhe-noE@Uurwq&yc<iK7@YgB65q)Oqf~^RshozDad2Aw z_%8Hgajr?$LBT8wZ6HR)O)heAP8B9x)=_1cDhp*lo399qvi}`wn0ve;2zWExA1;z| zCIYvJT(`)KQ=%#{!gR~^FnTibjx#E#>pYB-5+CH64iQSph7SQG1vagud?gG2E|YD1 z3<rV!xo~a2r;3Ws&`*d(0}Pe4LCH~sB{x{RBSNk#DK28!Nm#(DLQCVp+kf8y8{ylD zI?|aEae)fL`%0|bAZ)lY_#uH5Fuo((lFb;5G|fjqxLb{sFIqN^JW1;B@FefX3bAz_ z9YVkKyF=WCZmz|$=jew-PPaBlUCr`<)a-*pqq-YQ7={87(T)!k<x7rQT}vrUa#06w zu@FdihfZl*n;$n49+)Uw<z_<kqPaSu>MZO_EC(dX8v&^WFHrQNLkeu-M21@MqO6^v z!d3Q~gYi0k1UR7y%=M$?I%DNJmRCQlcN1$Iwj06i)TOe+EJ{~<S-ku;$1kHz{NbcG z2@hiY5%eTrR(O2&kAmZ&H(?;`RUq^`iV<cKC1LLi8SSbL7K<lk10*NC0mq8*{m9fx z3iN4bPnX?fs^`boPDhJ{jz{BL#OU~f?}}qfd$LWR$>e9MHABPnf83-D@@7Lt85%h8 zaW(dY4p)sjhOqvO|L!UPwd7%v{ASJi5xbin&0&&CTRHYXB>YZ-Q5Uk8*5I)jbqweC zh#g+<X#r<ZO3N&MRdX8fKp$4;5bi5q;lVIh>0XaQ>5gQ<i~J<Z-g0qHf24dQ+7Lx` zUhvzjT-~a->3jNiAzk8&akjS~lWEL|3Ff?(e5}5N>7!G*9t_T8Zu<d$2u^FY8-H*E zE~zC*L1tq7n8(g|dOSCK&QV#BreR45jJs(%E3k{xC2@{WT<pdHG8d*e83JPOp-Ds3 zFBcu0O(%B!xwW!^rA)Z!UG~1YmJtd<j`!0wH!O#s(@>y*3OBU}$hmij=54<9@9Xpl zJU$XMDv~cT@SZYOyWhoi7`L5`SqZ+;xqfG}NYI(!p>9e0(;M^VFe89f_;Q!5QtLEf zsak7Sx6Z@3Xdf=qR*9a`32J2>!(l|OcN#fFduV`G<}|{Jt{H`fY0j$Zs8j8R+&I+| zRiB}kO(17PyKXLCLHj1cpq>dqqCZ9HG<>~vGP+8*Tg_?GV1m~)5;YvD9sY|QV?7^8 zPJ}3ha1jxT&UKWt^bd7HMo;K0670Q&Ct*SEQJ!e`5Kfy4$QJF^k|9KKa)9o&Z~wOI zZ4VtJ=!r&*IRri0fiuyaBSths@~p^=r0nb{tzpW9VElc?<jcwFi-(IfnIU~PqWy*8 zv`spZ@sAL23Lo$;#rAZDQ?tmM9FDgIN;MGZ*&5v9J3X1%Lq<zJFJga@{dw6Jo0OE^ zXLq?h)=y&D*V3Ch-8D+O2$P0LlMJzj2P%(4KSD%I+iAA@zAILHeah-4iPGH}JONnL zj;S9sI=;EThWngWHFL!M*n1*NI|$QFS$^gq7wZp@90vM$>etGC7GC%Rn;cM@vYpl& zemX^mjFP7E6;_ASkDM<CuD;=x(r9Hc)*4w^Cid_jLAI3EmxuHOg_v$b^yEYQP!6ia zC9hMd6MT?2g{m=|&2AQN<gK?D6sQI=I{hwW#Tk&HohOfNouW5g>Sta}^~~vPLAS^p zO$I?Zh;E}vbJxr1Y0jUnf;}My(N(DglG7qB&GySbd_*GGvhe0Du{UiOF?v;jt8PbX zGaC>5MN$Pk>>Ptu1$^`(byv;rV|(z*U+nnT9LlC{MwFU+GUarZ?unjL)xBr%3~MV+ zmZ;c5NOH1xRe!S7cyY09#ms>AfESbI)|qf)fcj`)1A?#k+h|VA5M(~&A~JZ_X5M4z z!9?~}R)8~(saMMR;$dE1T-fdB1WlGLB8g5L$P~+!n5jq~iP5|sScLY5o($jdlJK5c zyvGbH3<@KcYu8=b){@Xl!^k%fsS@;J7~u5+_4ra=;UpgN#m}48TBUqy^mHEO(Qpjp z!s1h2iDo+4-?FuUOo`eB>bcB?T+UH7mqT~*;Itn(oG+*5YsRPu(0&KUD}=!rcrG6? z>}H^!Fc4mOKoELCm7!fZ+?(_da30+{Lcr?Sf^?K8HLFxw8P9x+_^2h!uf78PI<~A+ zZ;{tcA}_%|b)4k(+$+(RQl4<$&lD%O&f<doHT)J97U)dO=m^wDNJOzGwXi28QyQYv zkgexc5e9Bplzf0KYM(D+rr)?04x&{g<Ir5<=caPBD5Q(5Tq&YF0IxQ#6q7?7EMc`7 zYi_-wlU#pNZ8UaO&oUReeqv{)-Sn6Ece6tjEWEEC2tO<nLTrOdr#6uJwHWpFAjm_O zvJq14l4UHjBGOqDx06jS2QOx8$MTv%{9;e%D@{$mGuq@VT*nNW=zoU}TD|d-&6Jb< zP7T%5>%$2IdLD@WJgA0f#Herx4So4W<C87FEO7)Sp!Tpcp0nF`rmxdxxF``wIV!gq zprU)MTeojtcM^5h{csY6L7gHe2kAukGJ0j@H&?D<l1A==wtc(2>U1!%O#`le1e=oE zTLCjV)|B2AlB_bWYmq`97d>QxaA1;}5ve^CW$f)huQx@alT`(1T!_pVjWW*i<ky>G z0kp`)EXy)VJg{uz4Ry}=!($wN-l^Dzh}x*o|JG@GtmvY`6yl0Jz`g2C)~Z`oHR)cK zi9JktSUIxgxCuV&FZ`9}Miz%7GdJDlU}42tyP>V~gpNqRF5bDExUOD{sk$9XGt3Ue zBsAWIp@tNCF%}>U`(@h6rTDa~=_Cf8v89_*9_T_QWjs}a#?Fr917;L?kEWI}INt4A zIwwR@6zO4<f_|xmjMxB7rc*~kFfcvAhV;HW#>l=Pz9nk%t}?`EdMgdWe*KIn_$<28 z1-qYHqRX_)Wa~4kLmdsRk0Wjic(gLyW^n_BX(2@%`%I=op$U^!GvyoF<wTN)pBi6m z7e)DN3|1w{*B%y#+Cvpz5H}bG4K)q|44XGcj)zI$Nn;Q}thCO&iwL`-)~rjS29qGc z4!is^#)*l+q*v)&*$Yb#5>)!PLE@+J>!IFbZLZ)$))dVbyYCA<8-ccI4Ui`%bJ$Iy zlp_c^Uo7mBN^(-(5>{mJn6!bwC8SKhjHNKl>e2J(EHKZ*7uV_BN={lu970F4mYcsX zgS{5AVu?5~+Ge?<uY3yAo=yhGOGuTe=L5wf5Q?Lp576Taw=Wsrt5;VEM#Y}v^M#TO zc2XOrM4w2w$chb1y3-o-51{F-i+BVP4SBjE?{O0*$v1BdXW$w4pfcIRrW<Yu1f1Tt zHuIm%=X}$9+hNKF7mR*8dY^I=5c-(G^L}7le_7AL>K4lrZNne_SCGJgBs9qWv!y^8 zISeQk1`oXpXPp3DXOj?JL!bzxAZCt2H;AJHR@j}`vjbM!Re@kLq<S>~*BNucx~vnH z8y~CIrd{&-;`2xLJa!_L{U~Qs!ESu-RKaFZs^-Mf6C8h!a-8G19i0h-m|AyjQf6r@ zB0G#oPIk8C?2)J#|2&arx4duo$!;E`Z+NqcUR-Zi=TURA&8L$iF-yBEoB28lg~%82 ztuel^oX9LjpTE?0t{Y=8tNr|+l5IdhcivaijM?n)(SP1%#crzMCT@D*)Yx>-yZcBO z2i}X{F-VLDUU|!HyW1kwh=z9qp*@*a)l|=9$;^#S0A)D=L3rtfFhQnPTmIYV)_@qv zSvZP>OyVG)EL-7Nj4*et$EA>sQS4h44oBzrObrV+t4ue!ukskvr$1UN&fTOl`#!Qi zHim{5qBaNf?@bxW#^>e<QP)|<R=w#iGft!He5QZ!WcQJLqYC!K4v-**gE78C8>n8h z%}1h0+gyVPW*V)D7Qv#i0S0)fTa0smj<{I(PAD*2q;!^3)`*Ph$Ep@nGb&vbmL%te zZ5+aQ>9bm;747`>o+iibPp0fa8yxA=AVGI@v-vl6ku%u6&<)WCCKnBm5!Q;&hQ5+u zy&^@_zBFQ`Mxq7}kbprJY+wb_g(h&tv&iiUi4i`RNYha|5<&T3D+$dJC&UuvmXD#n zsF^k_C{pp}5e=ymaqoRd;dZew78hH_s*oh3)X<XuP!6~wPDUg@48JR=2|_p&Wki^x zA{2R1%DpR4_a;e31U$WcBfzJ8(?d((;a69lNR)$Wwjm~x)uWi@H0xZ0UA2Jm53&TJ zs^8^X0@T63%QvNDcXezj(Gz++^gr~k(u3>K7bw}~-<zm!RVT<L+r#rl-~{xW-^bZB z#ro3b+QE^8^q;OPea$IE7$FjYm3XQ?mAk7N+s?{g8_rxVbIDRjA_3<7*R+`24SI<^ zdAHne!x$MuvG8y;D<k=#sC=FmVQ>mVErFuQb|z~1lqCuDIv~YZQQxc%^6m)}L6wFm zCwMW#PgPagG>c-0p{Z>)PQA*l6jR|l)+&Vz-rdAQF@K<x>?_jNFY34c<a)1>Apw~@ z18*mNm9Ks>yDnmFseQs4r&^PI3up7gsDK#<%n*=#_UT{(9@gkP!Z_CCuLH8L7f=iO z<PS8wsUF<W@9la*Or+_~yaon{+Igh^gan&ukoa{#rv(@|&dGog6ZeJ2wjXasFJD3z z_DK-MT+#`U>5p4s=6futXqE;`VD{Q~Jf8G<ADifUlyNWtfs|r*>7g(TW=rIxGVv)I za(bPizkl4OaBl70pGSuA;`Ty4j2ji)JYMV9NwYua{}7%KR|=X-Y&Vp-4V4rB`aCQy z!5DZyB<pO&X=yj>OhJ>)(Yw%y21G)FdnB?_0OxQ^fmLvO_Ot<<kj(1v9>$oC$1}<2 zSzC#-{|JL5&#KH@dI^(|9UqaqItdXuhLH0W?n2(k#BfSHn2Y=q|Bz(tFomE)l7ja5 zKZZX-00lhiTZw*N+=@Vl0{1hCF;#;#fHyEhUp)mL{a)a})wkXg;1!fEw`YGu2962X z0v6&llcxIXK=P5}Y^?l#izD2RJwfNpBI_e192p;#fbImbsf<S`D8d-26q`Vt4Eos$ zf9OW!g|%1d2JqXgSFI%p-39y&eh|zCc5|VZ|6P(0K=h+Fe^(|ql=g4*qwR0>W5PjP zv!yzec4Pi}=?FpBZF9FS_ek>ag|F3i-QFP+Sb+e7Y0AA?VsoqzTF%MZ-yocXvA_n_ z2!!>zhtytb?y|)5kFT9ykSHHjUgz~T^9tRm;P_`q6SCA*z;N6}p{CRBo2CD7oEu~I z!JVebPQqs#;bkq?d?(X=%wT8MlNdNphbWBk!#&jYfCp0lK3qsQuCsXbXgik$6!(Le z90x29nqfDWP|-8YuqJn8oyJw8l26Jchb!nFZB4GakE<Q%`keLhbGf|0T)6#1UrIPa zNJYWQRAP-pH&P;fO^?;M#+mv~7RvXMh~+z^?+wo0n{F#0efbWw03~Ge@BgEney;jg zzGUY?E#vAGb{%sz9NaeTZP^w0`xpG@pDG1+rH@~D3h+>GWz0C>{{Hu$UROSy3Q}TE znGey%_8i4r*i*G*Io!>_)v$-Pyg&q3W5Cef@B~cQ8FC!>T&(VuT|EI0eJUaMuY@&v zw^*lCY?Ww{K|cI$-OdI|1|i}y-<+s>0Z7|v#)SPtJ@!&2<<r8a#5nK4quFIF%<E1o zMDKan^n|`NqpIRCap+|Q^Ft$V(SV@QQLAN*78`b^d#NgGHZl@-D{B&!zYBGQLkM4a zZo}jjxyW<Zwp7Ji_O@TOwpNgYr9DPGqisrcZt@`fbRecw{#%>i5lzDREIy+oH^A^_ zVH>GOyLy}|IK_f9;4>XdgAuV|6Ai7z(yTwan)NC*IzZ5{{#o=6EY=K-09AwY;XCMu zJIobv410J%&vQ(h-U8m?^CW_z=+f99BqY)<IZwPfbp}P)f=*yT#WN%A(na4p%jLiK zp7E7Y@cq?SLX5QVUXbTujvTd(Bs>uvWtz8R>P8XH_sqbyFVGX!;sGQsa5HzFogE9d zcNYa5Sl>kmvg}yE^^L22UkhsfYE?@qD5)3}50(o<q}iJT<Go6UkDism4e75twXXY# zj*Nq8oHG4%$D{97$Y98W3px&RW1gfu3h~SwYw6rNsZrs9d%H8-6l7G)&t%eT=V7v6 zngCc|N@yROmCrQw7`sV54F4v2H50zAfz>?5g4?w8@&UVP<THnvSAm*vHeK8*_bpl* zbT<9_bu{+)S3Gtu%b=>c$As-Ut_GjkQOFK;6BnTH4`1PcD2`&rcV8Vj(5=`^|9xuK zY(d|`fg)_h4B|pju@FhNT$Xi4w(AoXP{oX0tUhdfz#IAQh;tqjaHAlx;CyBn<H(~T z0OD)}B$q{0NisYV(VEXp!hsJkHdS+G7O)mcH6NvY>L$xrE((+8H+G7fWNZ)}3L1+1 z+hjnmChwD1EB6rqJp%;mep5FsH)XRdy1yoC+k7cxw5U#us+ucj9t)T)4*<HKgq_Pg z$ZBrYsm^Em^n6K^%X}|#6Rn*McSt~>yh|KoG4)e`z7*JAGN$)78ha*BKzVmQ+F}Z6 zp15#;6lXU55;N1?B_q&c$^mXCIu`K8TqmR@pJ}Km@F++wbJRh&DX~PSg(>iCI&nFv z*f1n}E;H$0GGhn32@Ctj8YzuH`E9f|n<O48^V$avs>cW%Fg+?d>Ks6rO+WM;vHfKX z$!Gc#pusMpwcoU7(%Ic!qqV)iX3}$tljAI=3fX3TN2&qcyovt*W+Z3P+C`tqtmXic zc6rP9^D)^cK`}#^ih0DBWVl>%K{ou+XgQ9M9aIQoryQG2UnlaI$GY@voZRlLJR?_S zUoSROx!6VWmNmj-j*i1stRQW!1)R%rB$gqblkDVq!BE|A?n2jH?PKW!^z%!-rNh;2 zh|bAHPN_=r0Z#d}t_TH5J)m6A)bsiJ=Bv(WI)vSFoOcJDn?M+h7lT|u+%?k0>x6M5 zcxSu-U<%xV;n<mvGZ1yWq!&5Nn$zepNfl|^+m(eGWdtr#DHMs1HhnAoob!Yoa!!W3 zec!vG%R1Wgg9g_35qf)S(P)hgkPyNon9~smqePm6vb-Y!swv8W0^uP7Y}a`OuuCzg zW>oEpDly&!c3cNjHxg@8z(vN&7Io|5$OC72s*VXzXYElWJ*GSc5ZI8ukI$}Km2$Ur z_x+s@FYR<@q!Y2jRFDU2B<eJ-kHTv96c<k~4FzA)n<yufI3<0CA7UoK4>8F39MIM} z(_FlagKnp=fJs4~g7P5_O5BR$`&p&OK$y~ODRPCO`E9M5kf8OKdC7w&ym`)u^h>^@ zo?vy}(t7;GVOBm~QKRb@2RCnJzqoT{%{m+!f#~#Ty6UbE71v+|Y>eU!ZrAY-2{wU< zc;a0C!hwD47)7Kx7Uf&um=Q`S%ZT#l0EvB6ux2qeIiaFj0@p{+vop=pU?t7ozi^0V z9ll^)Z7ziQuZgNh3F79vwcC-FJKY{mtreAtSy5X1j&3`9v}N-`3<2YT@EwK%L)iR~ zuP8uXOI#Youig&LUy7T5eo40?d`XV*x$Iw8^A>bGLRTP5DGAUtkZtKoDu0@+JonTI zb-)~`)qCqxwxtNE?`87jgn@;YOGE<<4Z)704(V+%D06!kyeLy5u}(;qjAC3kW8olJ z&>`pfTfB01%5rcKp=+T0UqEy9u;Nmr#jwy;OP~b=REqp_G!<lLfy=giF{gnKPtIq7 z&H7K5HLa>J9)V@FixZM%8^)Q(8i!&`Nr26&beOMd=Q0sfnfE<nYMz?&N(8XMaB`e_ zqbnR|UE(|#P|B1e%5OYIoD;$={w+XRW&mao(DJXT{O^K9*~Z_N^Z*G^M7Eo;#Xi%N zS`>J`zdgbBU~2(fF4|PD%qNV0r&(Sn><Qv^TiGu@7qyeD3}E@^bAEp)y>yQ4L{;k+ zFv*K?Q_|IZ!Xywqk$*D-vYIVrXvSG>wZE}bEV5+(;gK2+6KBzkBP=utP-JX6F+};~ zg?pelH4;d3D9X&hF*0syjmH(=3`<Z&$ln0>5oU7ls+TUAC;f-gO>1+_GW&ISH<+pu z2;EXoyGKtjCg=|xphxbGehJRs>l&MA&WAB}^@HEuniDpZOGrBUN0{qp2hd!C@QFqF z0ABu4R=_9!_0s@BDl9w_+DdIFAB0j7d<HQ2G!B1<OzjY>J6q8=@4gEE<Vaf*fayWU z5~2?Hjsj0R^%+MWeN{engnxdq{B<>T3~$qDpCS1Iq;MYoX)+z>kKCVdNE}C;l)nSz zn+yNfhyg-CYD6TW<v#-8ZuFmmOHfQeDxf2lY&SxnaeVN68mBb#eWrgQk-$-DUsDJI z-YbZ=Vgo$yxc!*l-ubu}lGy%YK*@8n;7p%FoWD;X){pVrDa*ZlhXimh^MBS}F!F`Y z0r~>8kSnim$=+zcy|bAsF>eiaONWe3Fbi0Pe|6>WDgZnU|FH@tAUG)(<=<vi$9rTb zgJqroszg=h$z0#xfcy<G+)$3mT7~VOxEF3RFDDSZ_kYa4KYF75znXtZ@EMu^od2Z} zXBr0_-U|raOomPZi}g_w#a!jMAiMgeDkqY3>60~(a;G_X4!|1xn*AwubOM3vUhoYQ z39$5rBTH=-9g=`qUMv?=^WfVLlo)FIw*b~Gr{*IBX!)x@{s*B5*Y@8UB@hzF<G^aC zK}ItIg20AjX9SL~`3Z1wTZiXp{$_l^k3&t+30P*17(o&snUiA>!0yMjbqV_4?S6>= zN4sCt7cl<}9sPF2&p-VF?dlh`#5sSnOgmT2;@+kx-Yy*jM!#ufuj{HhmBQK4kC1e^ zDB&cT5(#J??Gu1ior8A^hP%D^yYhghzlH(f96%t(C!wJzRt^k;$>u}nswz$_@B16C zF730jK849v#R`q(e?Vh9n@?-S%-ilEwJ?aF?g&gbDJ`%nuE+!8Q!o6fC?%?2LaMFE zSk!tJuUFKI@XM_m`@NZ9X_9Twd3x5s&^Jw&gV;9YRl>$j+qdYiSL3yG<<ijyPX56^ zCy@v1Vj8_2Ln6$%Jy^g!n?`%CSDgj3ZlwFqUpzv5C0G81R2<T`=$QO};v=#E=|Ev& zfEt5aQw0?#dEj47aFPlT7>IcYQx*M$l(p!xOP8|aL$GAUaqctUHd=Oe3pF*+jDB{4 z+1Xf!@iP`5x8vDuc-wa~RJokQEHA(+m1|6LUu3wC)ITHv=d2{?{s;?h+kwAzI2ZHR z_^F|?2dT>#VySLZn%Jn(=00_fVzcMOj?)|tIgP4<{pV1w#A6d>hWI3h<rk?Fm#8Fj zDi2Ih%b$)DDrau5EoC1ER<<Ti0xF}cutlJ;8C(n!$^D)pG;!&1qHu40HMLq#tpq?4 zfX1HH@LvE$c%~<n%fFzy_9R>&6}ejsVDm@Cp14`Ya$F%VhMyLit_iBoaP0nzoxuO? z$P|bof<vtDAyvgv>_{II&md6Dj=hi+7?Llcgh{Z}0cTxmCITQIU=hzHENk5yYXQxK zOVeW@VEP+Ge|d<S-zZ>#F@0OWMud_W#85WDj|hEhnlvo90?nLjuyWVs$Vq25sK=K4 zVU`SBne2uMR2K!vv*E|hFla!tJs9)6O@ZgfzC!nQb$RTDaVLaM{n}oP4&7Bv%?zMA zcyl6hq@{~AN<eaN9jQ?S3_MT3W4vuALY!<Tp%jXoY*l!)`M8;Xtrk1W*!9)TxjD}b ztVG6TzB7-Zyn(2*A4gn1WugcSmOuT10&-RS2pBB&LW8fUV!>R5Q3+2*5e=|ZfH2vP z0l=$MZyE#zksnT*+Ntv&w*GZKywTvfy>7XWCMZKXmoP2>KSZ^gIMjF<%yJeCb1K$I zF31x(MK-BiGhm_leyv1ELH5(DC_)SX>XVmNc%EvMK;IQ!1e>JXOVK96M6`-JcBKsQ zz_v<i|CBswAA*(UvF{b)+O^{)qT#Fe-JR!_5uV3YG>M%(im`}wrk*JQR^AQVM969; zYDQioP-ZTO5%ENuIHpei3lSCg`~wjkuG0qJ{YM5K<)hSB%KIWS1!$E8+{={dTw#&I zzPp^!_Kdz!@AtIZ7>neUtmPPPj-%A|oX31Uv{lM7gwnt#hVY9Dn+K`cG;=d?<!T!f zz4j7qY5FvO90lHDK;rF+dMYzK7!Sch!OEM=f2IFSUUBF<M87O=!b;xeJ>?l@Ypm>* z$iGS%e)sk}ef^VfS0d2+J+1=Af1$$pR#hEVynUG~93XrAO}LXc19@S#kB%fnKhWA& zv?imKmnD8c#Rm&!@y;Y5dB6^#;xAW&VTGJW@yzY`iw0JT%RWFoA{7k5UDAf+^oF28 z#FP_q(2`p|gO<MmD=n)XO>P$FK(<r@W8#CjmJ72E237vbclF0hVH*LToS01)xnH<I z!gvLBqK+Ie4b_!bbEu|<^cyQ9oCpNBpn{ah5OG>Bk~201+^=nnlc^6HGkyoi?H0H9 z$Pv4tZpK2RE0C}R?7^ZhOh^`pfJ{5XqLbXnoEW0f<SPM(z)-0P6@b8?|9Dp_ziAW> z76EVPLZb;MLZb<88tcH2C=g-Dia5rkX+EQ6Xs|GDRNAfaEO{2}B<BtY9n*E1lVNZ& zO$-76J@I&0`&p}V4jr0q{`2ew2f!_dT|ui16sjWJBDN=z{i$>7;PIsCtX@0QfoGkY zh=!lVZ~f}!RGV~oo#*Kiggo_U%AmtYV|6veaJX)z4lMQMJ|xts6Tt7?7EUlRcKpVf zg>O<V6Hklr#_cTZLmEvJPb~?3bJ9Y;2^I(wreJF#Au1x|cDW@e_hPABn}w+3uf7M0 zMYIx|^@tq&EcD(lya+Puag>eL-D7VZO4x0vfp^*?@y|nQL44aU9@LB=#Liy1DVHHe zjzu9#20Eky)@hFthE`%&?}L{LSbE(j6WTN&0+qRqSJNVn*V$$#o@0gyG^j+P0{I!d zB|$uw6e5J0c69UWdCj=p6_8Q4=21>i^Dx8UbO!*F_{QWK@9c^Ko1rLi%2jt&XG3SF zjc2=9L&@)wfcY1hjTZ2*RX<h8lW5v&P#_5)G*Ys7`kHK%g^^3T0qQq#)VcjkHoaJ? z7v_)&zD_zLS+ztq&7dbY0^I-MFQa6I9+_bfpp>7Um5)hh-mz3=?Gt~2U8%GbTu6b& z4lXt<#ub^Vw3J*{ZuQFmT3o)}mV=Yn+ACT!S=ID+QCX_o0NsbN;i`q(XD5Zz#J0UB zfBRI-c=j6g;W4pu2Xh%5g8k?R7nagQGSiKFKjK8mU#9sgnDAwn5rOyqK2!`z`Oc)> zA-|gHo&nZ)RJ|CBVnw@nNcnb#g*;Z;lMFy*T1y|KI3H~BEGDMi`m;F+rS4@AI7542 zx)dLg3(z1-bS7IK1JfIu<P3ycio}GzVI|L3Qx_#j;N>O>@5%vm3`I7y`S+nMgYa)| z&~sE#!rF4RjaUy9O{H{4;2ud<RyCtzfFcn8hN%vsttj2(5Q@a<T%F<vi^qjI$iuij zCAj4jCB#sOlrT^UpLKlHRr$2#q?Dy=WT5WRQG!IN#m!aWSK*XpV`(zDj`THW+N!Di zo4Afpj}D4Ocl5_hmvG{OgboKDyGGb}57?~|6WH-|ZVp>UeKnP}dN$Ij0DKQngOag4 zn&LogQiL2IZ2{Gv1fK<!hU$}!oluA;?N9^o0t9pvn!`T-%Q3dD04#N-t3b3lWOFqG zQ4J}TQ%JF98}YNEz5$vDEfZ3Onb)jW|A>KLTte_3eS<cls*G{~b>b@JBjGiUE3{En zL+fM7XK)wdqz3T07d0Y5%U6C{YGV{q%V<a`FWc>Rq<kBcPNRUb19PA6uX*J>8~I5A zWgqNLyc@FywIp#+5u-(}D*9cFL1Y}>lJsHJl2pLwC5cc_U`<}r#p|;&oSsnBt~8_g zs30<6*8&b0wcK9{kVfw6i}`@Kf$@;#9-MCX*kxf2M^mrlwbI>GA=M>wg8K3CHrB;_ zGAN(YCs=0lXJX>~tMJ&ueyX8R$*MJ<1hV+}cdahUH?~4KcDM&MR^v%FhHDOdw>pSh zIT3yhqN+q;>*o5qdH8~018ZE3?ov^{PAL@=xHNR}O33{n^hqcyINe{85&3dQ6kj2* z3%=Z?mU<f<`AGLxZ@Z}2GEk%&09`s~e12q~5q&s6q~;KcGm`!7c*_aYLM>Z4D)w|A zXwl;g>Q>K#uhlF~vQ6kWrP1|CrRXmoDM6qEKzI?q+!ne)&w=jxiLB<8)`~`55A~M- zADrbN;(iaeU{emF(je<7!N;WAryHfjtlXLJ-+UtvcBQ7c%#Q(^Crzs=rKW#Q=S|yO zp26n+WsGI^;)n+|bt{VZSKZVtevw~)j(LndB56JWQHJz5Bf5el*!;aXLS{KWV~@;_ zaAR#esjRY`o&CV5r6TVE@~Z2H2rt+_p!{J9Q$cMPz}au_=3U+j`XQJ%kXm_BVdCmN zrm-JV484PTA)A3=>HF@Dl-c93C1>#tp^RVY1i6Wc<8ysPnsGbpf)5etYpj4WlKKj} zE*RvZfpbwokIV#%QHjKD{Dmeza7%KiE~ix2+O79v7iRRx2yx@xI0*N51xPM8S|-u5 z+P!~nKT%WAm%L{)sN!Y1RIQ3rTL7@%YEJj{3jSVk<v!x0`P|-FRQ|R5c=19>Z-Pd- zC(CWrmG8mi*(x{I*pwFOW_TEmGsA--d~~8F6PEpl&02=h*ls<9C2`Nc<G#&Nr}CkG z92bcJE|dpaa$E&Ws12={AbI*AY%*R-3rS_g7Qc?b$@$waJ~@a^t@uYw<;50INBnNd z`D-@tmo0UB2J15x#M{HYBu4rOiWc9a8*`TxxN3~OW?QFni)nl+5NG9@{LLOdYZKS8 zhd;3rJC<T%>Yo!6R1$r`geVpQg*cOi(|Drbsz(Y#Jm)c6)$gnp4$1q94*644Rt_A+ zWz~}+kJ|Y<9Awbmy*@VESgkf+>-qEjoI`)|6RSos?!Ky~mMeZ-8g96uDL4t>A|!QR zwp}2sHh79c&bb)HjxCwHg@l^2tc4rNt0h1$|9BRsGk_fizyTeYv)J!vtVqW9Ggvcn znkJDOx{JW4x(J5Q$Zwe{w|e>N*G3fzS41;zBo}Gc)~kQU1mjo;BlX3!5r-K>YjB*! z4;rO#rXo`ucR6vQ^u<isx!tg1%uvSj{}W0}i|HU3I4MmmkkPV}k^07W^G)t1AyeUg zkv{ruNp05-&Y2=Wp_acG^<+LFix1?uFnnltw^fhMtszrEwn(?O6jq0~&Dqlkt`0b~ zmYw6Jephkj=U@P?948o%T#b{sKhU(j(A#uU&zfDt(k`n?0?&lK?U<?ztUc|5*Gn#J zg?)U(Qp<d{xHa{8@sh#T7su5g_nT4p(WI(O`vi57d^^Btb>1b{OH8v{sqyU!p}2y5 zEg;3AgchYP*;_e#0((|Xk6uMDeOhkVs$orhjAeykz}(5viz%?iHVeI^_5!wD%?c;n zg*k5wz1O>l(852sX)Am<(s2rh5rfv8SYt)YHb@^OJ3z?VNnDVqehGg&eXC5&{1rz) zlx`~T&^Or2ea)dfO$$_0rq6pg>vb|98O7neoAJ4mVJq#>2xzl%ekwoYhYy07z|4>N zkUQ<M7fS$!c37qI0_h~+%uUG8PZ*~Vb5Ip>zZ>&W<q3~UCRbnI7hD(chZ=LyY}W0B zbK^obPYIfguhlO8EC!RzUwD5W_5~Fu&S1i@s``Dn*Ayl17EybFGsJ&$LBLoVElM42 zk}R@BvY+<Pn@5|GO=$+CTb}1Rk8ut=3%vW$jduE+8HU>Y*?lzwMCxSE8QopgtvcJU zk3PJlhRbN8%S10@y&T56N!M}1<PS!n==X2Y6!=e*hOrGd9z%(MT#|-i4__W8Z~s9x zaN7G}bUJwXh1OBMUpyh=^bh!ScyAmx;Ot1zEXT<UF9|Dz<>ykC^xj9s^og5+{J2lX z;6SqWpfa7nQ&X?D6G~MF)*O$lrsDm*8N8+$vBqS~T-dc*ohoL1-Q%q1{mBzb6f8UH zAt)!+@-l@LpQ3CWcVeg^+iCCJaQ;S9ZUdg+GPm5^Fn4jqFiZPU=oKL1FD%&;bzk1U zKjKchaC8d2X`K_!V(*GQondoi?OX-o<~)xyOr67}I^q)>E!opis56q2>3?Z+$!Z}U zP3ZDVVbq^-F)bI=S$?%OB|HN$ah3sjbPAr!kEd{Va{?c;jXcn-luZf>5+d$@q^NVO z5{NZBfTx>nM2rLni1!t?L!mUawI_SbR0Iu865VE7pph9koOv87c2@+}n#PQS#mmr2 zp+o)@ts;_l|3Tp@Q~I%MuU{afO2gz@7>i6#A|}1)9&M?eTA!v@_WMD<L^Yqigx@~4 z;$-4l28t1!*ZyvCx_OWS59NJqwoWh{b|?SbzM2~MMw4mo4UB0AN6r1<a_ZEsz@qQ` z7YI!G#IrHCu>G_||HRO7##K61%>4B|^s-5o@s_4f9-yjb^RGlxlwQ@6{MzP~9Zi3o zCk=nH_olm~)Kqh1TGQKd77XkOt&s^Wfy!vJu4tvGTqmT^w7@-BF6Utjd)uwi1PY5} z9<Sp3pkVW>Ar@&I`6^cJAy#P|eZVWl&jfCl>7}1<_&Ou)t$Ix`c`7T}BMsAYUBQS9 zALlj9Q0T9-6o`ebpG?mLQjO8%w^iVvPp$wSx8y|#nsU53*VBlbbedfICq?$rl+y-v zCrvX%(&!T4iGI~@5-x8hO5Ev!#`WveA%hom|2IV1(IM|(;IGbRhu+c{5XIPx4&V~M zY5VTj-tI!i%0CN5j5@_?EX??0z6ZE7^Y8h}HA4)tCsaNAHBE<ODZT12l~b5B{Qj!w zu?ZH;p0Ly<iLEm<x&+t}!+2xEbgbx2;h2L@J34LY;>{eIfW~5U);P>Tj(e}RbTdFp z22M?yLG+1P4|lkG&KC~d#K&RDZ<w&<Vx9UH^K(^CWrhF;v~kW2f9eK<rm`WgniRZA z+S9t}Roflt$sqA6#!D#z_T>C5$K9C)bG`Pa<_lT^ou5%|HRP>TdW@xq@amB^Kt=(H zp7iBJaH|QxK^UK-ZjQMZgLMbtFf84zG|Hf-Qt<=nveeerM9)xtXvfs$EMZCB=W+#s zViM@LeKfRd4I~66pi<2S;(WnbDON<!g9(P##Zg^hL(e7Qh9i4PVAi>t9PVpE|2IS$ zQxHcw+gg%uq}!o1pR8pZX&rQ>A8BaiST9#75c&trtPw(Bh)iT?5Xf|{JY}vHQO89- z14W_+TaMB+>N0CiG5S;-q=$SGAQGIu(wIyAVAT`N2nIs23LvlVcyF&gF%XPj<POz) zjJ?*<c;hcwo`CT2c}(3-hJF{^8<rkH0sPmqR58W7Cge={E?}iRaN~t=KS9u5FVe2i z$u35Bzo+7&&ffv7K8Zq4?zWg2BPd}uKZPnGV24XXVg}y~qy?zczn+|hm||FupRVn9 zB?wt{&wG%L_@$DgWKMpxyPI-t{2=o&CltJaR~iFe!PIR(LvA31!|%^XhVBEO9oICR zs<=ioHmVo~_z2VATJ`id>`tDNgNtPTQfGiLvct_a_tSLmjRG+q`rr8E|H7N03%8PZ zcA)>mn??S^o6#<4EN(_-4=}l05Wn;|lpURndE;l!%(vUjyt-Xh@rSmLvf<tN39uJ% zUpDN0U1WN%y2*rG(XE)2QY1V-<|H;J!EU50CQ1OZCZEYNn7~{|L4@^HiKwz+y{IA- z@h*eEtF~1|?G$`tsqd)e&Y8Q`GMdvUk@%)cN*wx14S0O5^bA9$bc#-DO3DEW@w$Vx zA55p1v{cNP*t-x%)G3vf55*y6`Is=9pt4FBPFIa}AEwda5pCTePkxn_3wmd1)$aqx zh*SYf!3;p+lV=RP;yPDDL4MiEoPa_oheD%w=pBAeyDvLKb-rWA79at4$0f$eGkNlu zI?a$AU!>iKVXws^VKS`9UjPTYJCNNR{-ufCt!$*tf+fRObmIl1FP75xQI^!f6hGr> z>#3CWNO$)nFZY^^JU7`9v^^Z+`9%s1@3?SPCn{=IlR^`<*x4~LFe>#Ej6rK1@@gUO z!4R5l;+xT9G;v-Vb{sS3Sw%HR9BaMTJDNrig!k9SlIl=#<Gl4Zqaxof3|vE7ujN0$ z60uE8g_Y;*W1JDF1<o>u<(o4D38l5e^Sbvk&|k%OMU@$uQigHF{_$q}(u<8ZOO^tG zWs8Bk9jV?AKes9Kz875!&h5YZPeu2Ldb8%R^P}2KmrX^_ukH+{33`g+^Zz!A(ZHzH zQM9U$c2+y0mica;q40}RUPakJbe|}vNTYPwM$imOj2ni}%3-u)$rr-4Eo(;aC-ubv z^_2M1nF}U_@9S`87A=Gj?<CONQkmQpvY(25M9i&AVgw~U;xlM*M>pB}4=UBnOtaFJ z2MGi@GkovNRPa+B(aF3rbodg^CZ=CgLDXlwPL|4oElU+z2PBDDrtti*rZr_kAA!pY ziy7ADCTAWw_WQh@h%utz1Y(}NJ%KM1#Qqtgos#%?)HgW?pK3k*Y)7T6YZJj=PpU^R zNJYtnRE|Ol-`7udO?ldLS;D+dyYMY=ASo3yhxoR7GXJRlCci6vbp=k)Pz+w~f@uB= z&7~kgFKF9Yyda#MsrG<={iq@EiR!ZY6G2OQNha%mem1@acee#msx@hL?W#Y0mofMF z$j#Sk3@YdfXXCR(L1-D=B?%P<pnF`7KB5XVShhFl?sX)Na5K^cx9IM@B#v|e(kk73 zO!QQ16VtZG0s>dc%b#sUn`?nDFPQ^=o+RA4!&<Z=0%^w6yELy-9!tdp&_g}Q61Jbv zn0Ny?McD==a-CP9pUH?y1nPx>r&BiC#d0x6uX%-KOm$|1$+?F%zbyI9TyvfASxhT4 z4)2#e7ABbDXlh2(XeR+->lxR?>8Y+<c-0Jzl<8Mh4i@eeV%AcHM!D{3dS3ubm~Oq? zWSf$?=0>q9K_SP^>PwXw^ZIlikFF|DKe@ENv2a{;3sl-zQ5?I1=|7w-aEg*_UYgPS zLKY&MTp=eiaO7CZATTccR8mVHZ)dJD-h9R#?ys8R8ytE~HW}8a?mrR6GV-0{#j`3G z+^>c*A~;EFg2MlMg|>ix4PWrU+5YfrjoiX+YA&LCT!Pn6mho_1#f6ViuF2Xx>(h+i z)<+<X)j<s@(`-bD-Rq<Rkp1kpwC&b{X45xFnx{X`H7MwH&kv~e4qXM<Mx1$1ZNBc2 zdFkBwo3H(qKL!75QB!_uo~8mo!CEQ^ARtsgK~P;$dq9y|I~PMWPX{w+{lC>fhm-AX z)|rq-dL!r8QD`rtSR}GlmN8&VVVmE8G+*eVP6#PWBL1AZE3jBtjg2kDbT_%o^7kH- zttVxrG!4_Lu=H#0HR45qbi=gVcA#wM5=sz?C9pi>*xqPGAS6-Ql_niCn9#JXmdP}8 zkH)D`{3;Am3k}bul_!GCNGmo2V~32nv*znbrFo7Ph;zCoE=}UKH8OU-wQAbd)dVqV zmJmMDyZg05uG=yxbiX91?LoZ>6Q1Ac!Aww&I{Xot#c66QD?)I~Q9Fy$y>))JGRm`6 zx=QHSj9*9AY$I<iFNaC@8`Ob4NACA@R<y3x{&7jwWuQf``DC3>$Tw>~+7_7LA}PHR zTZb%fh~(Y?Q_NE)QF!ccjM?xVcX7WvJ^hAf6!JR`dk+vSJiP)64mZdKWA4)Cus(uc zfIe0KTYG0673Y#H@WEX|a0@O$gS#eZ@ZdT)gh2*(5*&hL(BSUw1lQmeBxoQ&fDjyl z!<*c@dy~s%_wL*G=i8n$-^_gH^zU?6)l64c_jFMq^`GsHlY8G+r1)0lD#<Nwqiyn_ zF^X8(Eyb(An^$BmkS7iJ%6PPE#>USsR(6SKOeDu<@;#MQXDsY>Fk!ks&zEWcomT4M z>12!izUazIV83S(_YE&^MU1UB_&PiN=FSnXWqljIJW!3&zykniP>mXb&1@XmSifI$ z-+z?rV#h_?*F<SFe2;(cwR4jS&^7A>W@N6KtL9u1(zvsufLHH4Y&to(|9bDLkMd~U zz-8@z>3tnME_qcsW%alCVFbt7UT=hzKM55O3zSx5AUVY{6CCk=Z4VYKyVv_#IZIER zWN(<-q|93RrF@Mz9wed;$BR#A1pOI{y{UWB5~t^qcyOwzIzf$19k^7?DK^%K|Kg?G zv9dqXXW!~>2J%Dyj$4=y4M|nV){9$3-Z<?neKCV5jXMF>v#xr#-Lix}f%sy>iu2R7 zaq(Z>1eL0fUveiBz^Uti;C-drR7uG0VI0clG@(t{8!woSYmrS0Ea|1U1fiD_Y~BDA z^b9|Wa=wF6N!Op!4xn@8T@5OC2AiF4R*sOATOE>cje15E-4>{6t&&L<dp;oX+U+6u z^B1NM4Oz+w3jp|t4fyQ@U67d*&=lwdWOK4~1{vD|t!!BBZ7mixPc`ok;3y)eV#CfT z!@>9EX6vD~JQhF>sTo7aK~|Npoba!qkWqV#kP|9{rm#iEm~|`zpTmm)E3?<UV7SD; zXXxfR@-=0)+U#5M?A}l>36V7?Czul!05I1l!!QZkz0};aV)SlASYdhc$jFJ=8wRi( z=ZoO>P}CI#Ag1QbZJR7ILZzgXxSw%kRnKJV%)6O6nv$N;5w-fn+7rv?p<+m43+sUq z$``ftSy`(~@VWMuu4edd761HKRjjHo*CI*g%H2v7jyW8n>k(Tf)L<D|3Ct+DCpDqj z+@}?GV5X!Xsjg@mU)@b%eH%u!vOOmHXV@|%rT%cJ6|>p<leb88<0%i+F%vSZT#vA2 zOlq!n);nsuCkG~HW(#qPQ)!MK9UMAU?<gtuJW)t<4Er)pe5vVAWu$_XL~9r(n9>`} z()#*}`wUsG&BnJPAR`kYY;4Q^elSbk<-HhMV`uy+cu4ibv3T1RcGm}rCS5UySq{{z za91}q)I;LCa9u=LT!v?cyb{2%DN}Vlf#ImMG1YiN!OeLLfkzV~RjTmaqfue)G!C*z z%k~LrS48UV2hZRipLA~XMVRWJbczfWk+9vogL58ZtoEb)C_#j_$<c`??icICHXg~| z-jrGxhlGggA*fPoBt(+`Auz&2QAjr{$*fvI{aJ*5;wMNxy(Vh;WpBj8w=smv!Bd8Q zWN(_B6!S@`JLUmwpb!lT&$T?1Jajq&=)dn=H%K9iJ9YtDkk21U^7$Nc3x%GLg=v#I zQgydG)f?cdQ<U`J6GQ+)_QOE(Y4kDz#YWzr0#)H7v=+R|2J7fiZ|NYgS9Nr36ENoL zt1nwR&hODLqZPyx88GzGcS#y09`>@-oNsw-M_*P_z((s9Vb9|xSikR7b$?XeL^4_! z_pxc3k8AL@x;h)J#N?Z;p%}Z9iUry1UV^#X>8?LF8vdMGA|@h(l3l-($4ZM{7~Ha) zrB`3^(t?I?oPR0%bo^+R%2QHJn4ni0#U+3Rf&5!)-Zq4E5z0)b8YH9m-hQ7;JNAaS zhUvKN!rWX01=d)V#S0Q!9}0k9?$yHRwE84R)42@C^KiM+3eSV6Lk)2&#+a(As<wsX zc+W8G(bcG7iDei*HMU5;gICh{1B9z0)%=O2ef@*Q?lDbG++QcX=@vR*7{I3>ZDlq0 z?QvMOqb>6o#~@@9xWn^=nsWH$Ao_6MTKh<X8Vz`ludb?UQX7%3nm`&uT}%PwE6Emp zhvDK3=WnSf{b}LhV(cHB@V#0M#`9eE<l@0HJ4y7e!CYta%Nf-8y4TN7>L0k$Sl{Fl z>RyFcF(iL}S3+o_M401^Y{}0ra({P#83;aETYDT;G3!>FFWo%s6H^s~4?8Eq%Ucgw z`4Av%vyGh6=q;1>77q@V(448;lKyBo3V*3_U3+8slf?F7)#$G2?2$z!@4gz?j^oz2 z_j(^w;AU(9DPGQN4)RssyCVrBuRv#Fr#}%H8_&q#A!}9`HM&uxl;G3;#9b_Yf@F@? z>HM9FVDjL@VH3WiSDSkajno*3>heYTl$S;KL1n$#GQB#nAVGfI8F*g3dF`(XH`N+C znNo*HoSeR*x>zlI1}*E}k{UdbrUadO+l{#Zq>wgskMl#bfideMgO&ZS*M>x*TICIh zuj3^r=EbHiKWS-x&NT3E@rSFej5_~FLPDZ;97x7It1xU#%Eu@zIy}n4z~E*nf0&?t zN~z>iG=1FKEW*W35zSAL$lp$`*0t#3o*4r2D=#U#$<8t5)R<3(SJQHUmh@u?_mB#3 zB#_P;d5JpADB%*gpJEg=$$4|Krt9o*4w8RP0wE8SZcA>Bz+2Ic(toNY7vMfth{BSh zIj|JYQJ1#k<vquRmuAEosYf;x&$pDj@X>%+^bzn)V(i-H#_9MYWWU+8rt6(~UMeBk zZOd$P%O*qU{=d@qCo@JsAkYdgF6XJXo%pWB%R&K1M>3VRzO}7%1B7T5q28>K?Qe5Z zT;ELMPH$=@RNz;<moyBmMV|T&bt%k?HI|f=T<3`&rIV-OT9oBHfv0bHk93onbI{;P zcePABS30$KY6%I5lyDiHOX3qm3Lfp;aMN9yN=;40J0wF%_CQybkzuF?716GZ`N#!9 z@YV_iG-MXMR@FsyL2sTiN~J2@jFC{@0}_u<#;+xEXpJ-kV^_>PJWMrAxW!z~ve6VV zFtLfx1CN)r@DrLdE3hTsuV)RGgw4)MYL>8ed?pn2h9cHxhc~_OIVy$H+Y|!R*W=2N zw$YV5(5GsP*yb78@H~J^mvi)Hf-~vdTVSjyx-NQMT@{Wf%88&7diGOz|Bi2wk&#Vc z53eWOz3R({PlWPbfcW+(pErrNLlD&-h7lIvNj&8_`;_uRs4TmBB`T7C*^dL`+oyHK zvYV)jHYqw3EXKXC&`=bqs=Dg!H;1+{Rg6@fA|JW@22BdJ&tiRSWF~{jP1;V$ZJ#b! zilm^N3sR?s&W0@QT|CDaXG-laB5)&Hiz(y7uh}sdtF-DzqSeJg$iKR$f?8J6-%@fw z+?eG--C<&4QohvQ#H5zJau(6648ZJnxEJs?81mIxv{^_zik*kAQvXKTaK=j87!kTl z3tTIR$;S49#0)T5YvG#A*>st$;Bw3$NbM|mG`R{(liv&r`=O1mQh1mi2jsR{m>U<H zgm!kLqG4X=^+uEGCI`;piDMSOHyG@4Y1#q{60{}XW_NXI4&QS@pT$LZ=e&hW%!Kp7 zE%C)mA*>?I<>)of*VewL-jHKBG6lTkXCi0$O8UY*xaJHo_H|cNeNnEZ_=h93rNp03 zjzZ7?JxeLo_QU?d4`tBk_XE_W^YdK=f<>$FhInwHsYD+%^%Ie}J2-UAb11C%CB`I# zBiDV>zF7_2g}-I2(V{^Gz`ihAdMdQOo?jnIbXuOarmxwk6%j4$wGgH5B%oVn-;)cg z!-lo33}F^68Q$i6>)K=~xRIMm9O>fYbE{}_KCu$9ui(#6&pUz0jpaT(MDE^_%0nZ^ zlfC!3puMbWOlm4P717H<O7nx&K!>M`OBq^t$Sbc~+aOS(1DOsX<Cv|gGEozM2S<^` zIx3&uEPUl-4d?L{at#roGWWj32t4;<+{b3@h`ISbMHOZ7NEo6?QJ!y`RdlZyYvuh} z46=3i);8CV`u*sXsu{=Wb}xaK6&>=vy#=A~V`&*Ov<7wuRp}y=H11VzfIg*Ea?kfh zC23lDJ>oPWc*~nr+D~%1q%b^WW5v5E89GInWkTG^)v-Xkh=t<dX<^1)0B*H7Jb%G9 z^!CFdC8rcq3;A^To?**1UAmnpka&pw^|GQ^wDS<rc3K7HYqLp>(-ExNlEx^Di_4R| znR`||DK&d?gLv!7k1Q>9Wp}242eTED23@3qkG-sq3*yDm2uHzOz7=(eC3Bp43Uala zfNv3=bqbred6#E&h>0_Oxi(zfSH0d*JzPR{4BW@%u@*!v)F^HGm;r25@6gL$ySxyw zS+`|DwsWuNPH|V3-!FSmq^(0=s!eg(IxU^F;oQLyQWDoaS7T93_)uhISRu*$tGyVS zU>2(;cM`9ZKkCzTR6rr+yn}MkyD2M|p%xFa8@Own<kt`f<VsuoNJLn;Q1<7?Tp(?) zIsT2ojH8z|&)%z^a81MEBFb&dU|I;ri__4sJAg-1e9agRw1pb=8a`XoI~-n!^M6?) zQ~zj9E`bJW!d>mG2iG&_I{Ne+D5VJ*?$O*j3O7tWC&D#(<4mP#RO|`Uo2-urN(cc& zjGl8D;G8oPhq1%S<k;eJV8_*^XkZgM9O^!PkhUB`8LW%N%*;>1zFEVN=38CXRas{j zvZaaYgI7S${*g*i%7X{5m&0TJ)+>&+*L?OxsNJw|N`&P+-JID?Q{<Z`(lRSo{Thyw zOGKNLcBIjdwKl9}T}8{|d#b|WUsXTYsS<q{2i)ZTxHyGCZx>J%O;2B%cbN%?mQMDJ z%7scf=1dxoOx+Sjf0Yf@yQ(@<g*WU|Uh{`1Wx`^NR)kDzq2{aHuWk*b*8+CgnV<E) z!|x7OT)3oVM9{kz5bSk9p8uJjK|WOXO04@V$aG+kpQ%jq{#+c~bt^Od>n+Nf95$>@ z-BT}LWxl{MiN)=uAWRI!^8F&nJ*8~iR;DY4pxS!z`h_^rwN%%K$2&WVT$8@|H5?Tl z5nn`xn?iG^;D=MJyyrT6497jGc|KD@=-O(dXB3Jl1&<uARs*r6$%8K7Y>govwBJ~l zO#nSR(%TIWbcQF`CU14OTN^GiSG_tM>%(}_YZ~d&o;(}Csh2z1N5H9~o+$;`k8=m8 zHC|;kpS5=iTDM)$WWf94l8|c2l1@3>u`(g8tBGQSDr{)@<<1)tJ)W9z-HP$!2GR0< zIePO#BaJtYUb7&D*jnh>C4(1BMuDy`MHq9*EHWF4DlJ8Lgb05|x1<%Hnv`T?M!qjO z1!m!JOra?BY{Do@NLBc#sTTyUr-xqcA?1g`aQ5r&QU<!WDuQ{7Kv~JAIMozAA?H~e zw`XcBAV-FLa;YiF5b@K~E_g1YnhZbs61%ZR{Wc{@j0_##N31&Q(z*8pgT3it=ZzzX zOK2C>si>@>xqSpoC)i24?=v2qlBllEhP{Ye67~4XLTB^E21VP&w~u@2DD_dNZF#$^ zQY?0wH9B!4a*;t3;qGH`9{JFW0Hu?YGX)XW;-yKL+mp`YjmPgNUWcU|QB)N_P<a1s zz@BbtZiDk3EMYoO$GFtah@w3~`-{kqt^2|`XC%hCqrJ{xA@FP<4?VM{UTWf#W*AkC zEoI>2(~C_3s#Pf|gFJSYH&Y$;n>VGzG9sls%BmPUd$BA;o}H%b8aG-qZ@H3hK$q=> zHdB{OUO1wr$-!X1!^Y-<w|K@XU5Rg{UvPm6G4>|<Z{Ct>5P!6I#<ribsmXKvoGm?> zR#xWRnK==SA&80GCli%JMAh{T4Ob$&<q)H#Lc`D%t#L@7zIbeqY(F>HsYOvInl~o^ z+3#Rk1*4^TlsQ)sHNY~TmBfdn;>hcR7?P~7Aok`84CaDBI3|BH0~NDivg4VJo$pDy z3rMb#@?1AqyzO>52S-cOh;x+fO1`p=OMq<M=?0<TaKUzWB3dBbC78L#VC~s*)y^vq z(nEdBLpNZSC^lczfjt3vo5J~egzyv%2ao6r4jJm3;K3WLA<n6yqGURl$*fX<-1{l6 zNs5A5(epdWhay9@1A)*mNH;XFMe}o}o8RLh#x`~)&rPBEhrmG4_aN7A@sXY>{pX#~ z_{egbD!46g<n1sp?ge@PO4Zg0pL`UE-H^uNi_dkIiDPO{Cw9xzk$z8dR0R+JTHJ9# zop-eZGE9mx0byGy#Z=VQTdPxKp(#jl{$r?|RpQcF;%%p|V7>TO<!tqEC1M9<wptqV zCo6Gi8?;ECWpd1Dyu^~%Rfe;HL73R4Y0UiQidbkal`TXqi5WOC;`ptKt2fJW4q}N~ zCzgJXIvznYa@x5EXuG*UD5Q)a-#Fp2Vw^|otjCI=8D2S}0<XbTTD3V7i=q|1+2u-A zgLsjHHbRaYGK@6WzuTQzowqeK^hQz;9;>{x#=8lrbsd}<4ALol2gaE0{OsF0@*sTy zzx9a3VG&X9^koAVf24d&_{v<V?IoeDZW|3Ns698K+nLxt)o~RSEpH9ITP9G{0~7tU zvukdv43gC7+`RwLEd{M*uGpteG59=`6ppEJPQ`NlV9OWw&!LpG#=Y<wsA|ZdYNGu| z6`9!Cnp;_@nK}JE&)07{GK=c4?qWv|GVIxGWgyFbbuYiZqwM)5pjU+~MvEtYrqs?b zRjw=YBCu8I*8WVsxKTAOakjH;y94`D=m{qNNd9PoEBgeglI`$Qd|MhL%+-B`;^!XJ zj?BimoyI`hQZI_IbVmLyFy-_x?aW$IB)5@+kHd@o+Pzb)bfOBgr1Jikqh6saG74=1 zjl>1Q7O7R-ZFm<J8XvEcx2aM`QE2nhxev3Z7w4zLut=Brmh-0EkbZQ#Juh5tPAV_A z3)<xZsAbas+-+l1klSyeBy~qK@MCC9$?y>uCoe0=4G0DU-A#;+kIewEA`}K4L+$N| zIsAT!p)jyonO;&f==Usu*#3t{etguGA2`{lYZ<C(xO>_%XgD9x^hIlEK+@B@{17KN z9OYEQQ;v?p<iq4*<PXCu!Ugbi2{_#ZnrPx_vXTJ~<uGuaEh$gW76;)?A4!}zQ*7N2 z7~t%*!bdc;xHZBy1cW%=mj~m-9LsT@EO5M+4_6hx5RN`R$_l(slGH-c3LoH}fTDo; znH-7cNUI`15DP*M!yt-)tLMRJCDn7@Q?cLRXNpOU@0b|fE&k<x^kg+qWi%)!?LP6+ zEJgw>zEYyG@AYzrr!*aNW$*!Ik;n&np_UA%%Z;dOUJ<W@FdI)}tg3e}{e)jxezRw9 zZ%3-|fsvY+pdDJ25c|57qM3w7qo#V~N3&prIIzIYcid(qA$O~Fyk{h#c#ACpr|Oen zM8%?~o#};*F+k1k$jXkBkS^xl!@^0=-ONy#K~c*fLSEzxOTFtf`06vJJ%5ki{6{>? zFK;r8pDKTC2gshHC_4}a!N{;mn|dOW0{Gch;Jo-2B6gLIt6+q^jlv%wB2J!V*7>Y~ zada=jjKnZDkSkt<90%$tszO@D06zt4t&79uQq`Vg9zykx4fpTZ0smb)!2aC~`2N8R zsQ=LnM6q%nvT)|p)b{a<mN(=Sa5d7jg}@XSn5cL>^3Si9H<qP>BL*}M`oXNQD$-r; z8pBo*W?qm+A6FV3U|~T-zH4!fuO*f%`_q+i;x$3^5D<DK%zX%-j5jRAgNOOcZ1kj~ z#C5`=J)_Y<0OPkAEb?Yo(@q>u!UtJj{JlHhqsi6#-hA*~?II}etE2x$;mM5rp)153 z3rXmisNV@1I|TnDyDJ(@Wxk_<6>IcU*<m<{y+09y<4pTD(*H$lT<rf98!`YpI_`gC zZJdwzIsYrR|3qwD{}tPRA~x>-&tijtuIb=HhXG`Od8~=-fogNS0n|BYfZip6-u+&n zAOBYVSZp$}1Dh#>?d;9KPF7})-yK+G`9Fg&!&vHiq1B|JwaNZg{dZ6T^yLo_$n~#L z+5{^ciBQA@^hx(8R3fyM{}lDa4Z4u*Xk};ntLDwnX?PB8zyO-Hi2+1^Vmd*GLq{u+ zvyGMQbGEx~`rTggukr>d69ND$E&u?*pD?c5Fh4MVxRUI@YRlbBv)?(ti|Psv_7{-9 z`=fUob2kC(4^AokPn=(;gS`v8n>_UgtQFxW*k7emy^Fn@#PkO?0`V8vf0EMlF7<9& z(H~S5q@SpNN-}zvad#)e4~DTW?63AE+y&fS`2GRl(ue(d8T@X=yGy#?EB;<$3}AoQ z_n#Jc?=tRAH^0~a-G&5hf0Dqzn0($P-klx&ATHVc1Mv?7|GRDeHdp!?`Ky`7@16X9 zowEN4`LE|8KSO`z#{PgVg8vHohg19SLvfw{0{X+{`x*Kx7wAVz<(>Z}^k;|Y--o_* o`77uj?!vzhZFK!B=pTcrvOEHGh6w=RK_9x%cl&P8Uu(es0Gl%L&;S4c diff --git a/controls/model/test_model_R2015A.mdl b/controls/model/test_model_R2015A.mdl deleted file mode 100644 index ce48e8a27..000000000 --- a/controls/model/test_model_R2015A.mdl +++ /dev/null @@ -1,12432 +0,0 @@ -Model { - Name "test_model_R2015A" - Version 8.5 - MdlSubVersion 0 - SavedCharacterEncoding "windows-1252" - GraphicalInterface { - NumRootInports 0 - NumRootOutports 0 - ParameterArgumentNames "" - ComputedModelVersion "1.2002" - NumModelReferences 0 - NumTestPointedSignals 0 - } - ScopeRefreshTime 0.035000 - OverrideScopeRefreshTime off - DisableAllScopes off - DataTypeOverride "UseLocalSettings" - DataTypeOverrideAppliesTo "AllNumericTypes" - MinMaxOverflowLogging "UseLocalSettings" - MinMaxOverflowArchiveMode "Overwrite" - FPTRunName "Run 1" - MaxMDLFileLineLength 120 - Object { - $PropName "BdWindowsInfo" - $ObjectID 1 - $ClassName "Simulink.BDWindowsInfo" - Object { - $PropName "WindowsInfo" - $ObjectID 2 - $ClassName "Simulink.WindowInfo" - IsActive [1] - Location [69.0, 48.0, 1743.0, 940.0] - Object { - $PropName "ModelBrowserInfo" - $ObjectID 3 - $ClassName "Simulink.ModelBrowserInfo" - Visible [0] - DockPosition "Left" - Width [50] - Height [50] - Filter [9] - } - Object { - $PropName "ExplorerBarInfo" - $ObjectID 4 - $ClassName "Simulink.ExplorerBarInfo" - Visible [1] - } - Array { - Type "Simulink.EditorInfo" - Dimension 2 - Object { - $ObjectID 5 - IsActive [1] - ViewObjType "SimulinkTopLevel" - LoadSaveID "0" - Extents [1693.0, 762.0] - ZoomFactor [1.25] - Offset [113.60000000000002, 92.0] - } - Object { - $ObjectID 6 - IsActive [0] - ViewObjType "SimulinkSubsys" - LoadSaveID "658" - Extents [1693.0, 762.0] - ZoomFactor [1.0] - Offset [0.0, 0.0] - } - PropName "EditorsInfo" - } - } - } - Created "Thu Nov 03 18:34:52 2016" - Creator "Andy" - UpdateHistory "UpdateHistoryNever" - ModifiedByFormat "%<Auto>" - LastModifiedBy "m87rich" - ModifiedDateFormat "%<Auto>" - LastModifiedDate "Sun Feb 19 17:01:58 2017" - RTWModifiedTimeStamp 409366141 - ModelVersionFormat "1.%<AutoIncrement:2002>" - ConfigurationManager "none" - SampleTimeColors on - SampleTimeAnnotations off - LibraryLinkDisplay "disabled" - WideLines off - ShowLineDimensions on - ShowPortDataTypes off - ShowDesignRanges off - ShowLoopsOnError on - IgnoreBidirectionalLines off - ShowStorageClass off - ShowTestPointIcons on - ShowSignalResolutionIcons on - ShowViewerIcons on - SortedOrder off - ExecutionContextIcon off - ShowLinearizationAnnotations on - ShowMarkup on - BlockNameDataTip off - BlockParametersDataTip off - BlockDescriptionStringDataTip off - ToolBar on - StatusBar on - BrowserShowLibraryLinks off - BrowserLookUnderMasks off - SimulationMode "normal" - PauseTimes "5" - NumberOfSteps 1 - SnapshotBufferSize 10 - SnapshotInterval 10 - NumberOfLastSnapshots 0 - LinearizationMsg "none" - Profile off - ParamWorkspaceSource "MATLABWorkspace" - AccelSystemTargetFile "accel.tlc" - AccelTemplateMakefile "accel_default_tmf" - AccelMakeCommand "make_rtw" - TryForcingSFcnDF off - Object { - $PropName "DataLoggingOverride" - $ObjectID 7 - $ClassName "Simulink.SimulationData.ModelLoggingInfo" - model_ "test_model_R2015A" - overrideMode_ [0.0] - Array { - Type "Cell" - Dimension 1 - Cell "test_model_R2015A" - PropName "logAsSpecifiedByModels_" - } - Array { - Type "Cell" - Dimension 1 - Cell [] - PropName "logAsSpecifiedByModelsSSIDs_" - } - } - RecordCoverage off - CovPath "/" - CovSaveName "covdata" - CovMetricSettings "dwe" - CovNameIncrementing off - CovHtmlReporting off - CovForceBlockReductionOff on - CovEnableCumulative on - covSaveCumulativeToWorkspaceVar off - CovSaveSingleToWorkspaceVar off - CovCumulativeVarName "covCumulativeData" - CovCumulativeReport off - CovReportOnPause on - CovModelRefEnable "Off" - CovExternalEMLEnable on - CovSFcnEnable on - CovBoundaryAbsTol 0.000010 - CovBoundaryRelTol 0.010000 - CovUseTimeInterval off - CovStartTime 0 - CovStopTime 0 - ExtModeBatchMode off - ExtModeEnableFloating on - ExtModeTrigType "manual" - ExtModeTrigMode "normal" - ExtModeTrigPort "1" - ExtModeTrigElement "any" - ExtModeTrigDuration 1000 - ExtModeTrigDurationFloating "auto" - ExtModeTrigHoldOff 0 - ExtModeTrigDelay 0 - ExtModeTrigDirection "rising" - ExtModeTrigLevel 0 - ExtModeArchiveMode "off" - ExtModeAutoIncOneShot off - ExtModeIncDirWhenArm off - ExtModeAddSuffixToVar off - ExtModeWriteAllDataToWs off - ExtModeArmWhenConnect on - ExtModeSkipDownloadWhenConnect off - ExtModeLogAll on - ExtModeAutoUpdateStatusClock on - ShowModelReferenceBlockVersion off - ShowModelReferenceBlockIO off - Array { - Type "Handle" - Dimension 1 - Simulink.ConfigSet { - $ObjectID 8 - Version "1.15.0" - Array { - Type "Handle" - Dimension 8 - Simulink.SolverCC { - $ObjectID 9 - Version "1.15.0" - StartTime "0.0" - StopTime "20" - AbsTol "auto" - FixedStep "auto" - InitialStep "auto" - MaxNumMinSteps "-1" - MaxOrder 5 - ZcThreshold "auto" - ConsecutiveZCsStepRelTol "10*128*eps" - MaxConsecutiveZCs "1000" - ExtrapolationOrder 4 - NumberNewtonIterations 1 - MaxStep "auto" - MinStep "auto" - MaxConsecutiveMinStep "1" - RelTol "1e-3" - SolverMode "SingleTasking" - EnableConcurrentExecution off - ConcurrentTasks off - Solver "ode45" - SolverName "ode45" - SolverJacobianMethodControl "auto" - ShapePreserveControl "DisableAll" - ZeroCrossControl "UseLocalSettings" - ZeroCrossAlgorithm "Nonadaptive" - AlgebraicLoopSolver "TrustRegion" - SolverResetMethod "Fast" - PositivePriorityOrder off - AutoInsertRateTranBlk off - SampleTimeConstraint "Unconstrained" - InsertRTBMode "Whenever possible" - } - Simulink.DataIOCC { - $ObjectID 10 - Version "1.15.0" - Decimation "1" - ExternalInput "[t, u]" - FinalStateName "xFinal" - InitialState "xInitial" - LimitDataPoints off - MaxDataPoints "1000" - LoadExternalInput off - LoadInitialState off - SaveFinalState off - SaveCompleteFinalSimState off - SaveFormat "Dataset" - SignalLoggingSaveFormat "Dataset" - SaveOutput on - SaveState off - SignalLogging on - DSMLogging on - InspectSignalLogs off - VisualizeSimOutput on - SaveTime on - ReturnWorkspaceOutputs off - StateSaveName "xout" - TimeSaveName "tout" - OutputSaveName "yout" - SignalLoggingName "logsout" - DSMLoggingName "dsmout" - OutputOption "RefineOutputTimes" - OutputTimes "[]" - ReturnWorkspaceOutputsName "out" - Refine "1" - } - Simulink.OptimizationCC { - $ObjectID 11 - Version "1.15.0" - Array { - Type "Cell" - Dimension 8 - Cell "BooleansAsBitfields" - Cell "PassReuseOutputArgsAs" - Cell "PassReuseOutputArgsThreshold" - Cell "ZeroExternalMemoryAtStartup" - Cell "ZeroInternalMemoryAtStartup" - Cell "OptimizeModelRefInitCode" - Cell "NoFixptDivByZeroProtection" - Cell "UseSpecifiedMinMax" - PropName "DisabledProps" - } - BlockReduction on - BooleanDataType on - ConditionallyExecuteInputs on - InlineParams off - UseDivisionForNetSlopeComputation "off" - UseFloatMulNetSlope off - DefaultUnderspecifiedDataType "double" - UseSpecifiedMinMax off - InlineInvariantSignals off - OptimizeBlockIOStorage on - BufferReuse on - EnhancedBackFolding off - CachingGlobalReferences off - GlobalBufferReuse on - StrengthReduction off - ExpressionFolding on - BooleansAsBitfields off - BitfieldContainerType "uint_T" - EnableMemcpy on - MemcpyThreshold 64 - PassReuseOutputArgsAs "Structure reference" - PassReuseOutputArgsThreshold 12 - ExpressionDepthLimit 128 - LocalBlockOutputs on - RollThreshold 5 - StateBitsets off - DataBitsets off - ActiveStateOutputEnumStorageType "Native Integer" - ZeroExternalMemoryAtStartup on - ZeroInternalMemoryAtStartup on - InitFltsAndDblsToZero off - NoFixptDivByZeroProtection off - EfficientFloat2IntCast off - EfficientMapNaN2IntZero on - OptimizeModelRefInitCode off - LifeSpan "inf" - MaxStackSize "Inherit from target" - BufferReusableBoundary on - SimCompilerOptimization "off" - AccelVerboseBuild off - } - Simulink.DebuggingCC { - $ObjectID 12 - Version "1.15.0" - RTPrefix "error" - ConsistencyChecking "none" - ArrayBoundsChecking "none" - SignalInfNanChecking "none" - SignalRangeChecking "none" - ReadBeforeWriteMsg "UseLocalSettings" - WriteAfterWriteMsg "UseLocalSettings" - WriteAfterReadMsg "UseLocalSettings" - AlgebraicLoopMsg "error" - ArtificialAlgebraicLoopMsg "warning" - SaveWithDisabledLinksMsg "warning" - SaveWithParameterizedLinksMsg "warning" - CheckSSInitialOutputMsg on - UnderspecifiedInitializationDetection "Simplified" - MergeDetectMultiDrivingBlocksExec "error" - CheckExecutionContextPreStartOutputMsg off - CheckExecutionContextRuntimeOutputMsg off - SignalResolutionControl "UseLocalSettings" - BlockPriorityViolationMsg "warning" - MinStepSizeMsg "warning" - TimeAdjustmentMsg "none" - MaxConsecutiveZCsMsg "error" - MaskedZcDiagnostic "warning" - IgnoredZcDiagnostic "warning" - SolverPrmCheckMsg "none" - InheritedTsInSrcMsg "warning" - DiscreteInheritContinuousMsg "warning" - MultiTaskDSMMsg "error" - MultiTaskCondExecSysMsg "error" - MultiTaskRateTransMsg "error" - SingleTaskRateTransMsg "none" - TasksWithSamePriorityMsg "warning" - SigSpecEnsureSampleTimeMsg "warning" - CheckMatrixSingularityMsg "none" - IntegerOverflowMsg "warning" - Int32ToFloatConvMsg "warning" - ParameterDowncastMsg "error" - ParameterOverflowMsg "error" - ParameterUnderflowMsg "none" - ParameterPrecisionLossMsg "warning" - ParameterTunabilityLossMsg "warning" - FixptConstUnderflowMsg "none" - FixptConstOverflowMsg "none" - FixptConstPrecisionLossMsg "none" - UnderSpecifiedDataTypeMsg "none" - UnnecessaryDatatypeConvMsg "none" - VectorMatrixConversionMsg "none" - InvalidFcnCallConnMsg "error" - FcnCallInpInsideContextMsg "EnableAllAsError" - SignalLabelMismatchMsg "none" - UnconnectedInputMsg "warning" - UnconnectedOutputMsg "warning" - UnconnectedLineMsg "warning" - SFcnCompatibilityMsg "none" - FrameProcessingCompatibilityMsg "error" - UniqueDataStoreMsg "none" - BusObjectLabelMismatch "warning" - RootOutportRequireBusObject "warning" - AssertControl "UseLocalSettings" - ModelReferenceIOMsg "none" - ModelReferenceMultiInstanceNormalModeStructChecksumCheck "error" - ModelReferenceVersionMismatchMessage "none" - ModelReferenceIOMismatchMessage "none" - UnknownTsInhSupMsg "warning" - ModelReferenceDataLoggingMessage "warning" - ModelReferenceSymbolNameMessage "warning" - ModelReferenceExtraNoncontSigs "error" - StateNameClashWarn "none" - SimStateInterfaceChecksumMismatchMsg "warning" - SimStateOlderReleaseMsg "error" - InitInArrayFormatMsg "warning" - StrictBusMsg "ErrorLevel1" - BusNameAdapt "WarnAndRepair" - NonBusSignalsTreatedAsBus "none" - BlockIODiagnostic "none" - SFUnusedDataAndEventsDiag "warning" - SFUnexpectedBacktrackingDiag "error" - SFInvalidInputDataAccessInChartInitDiag "warning" - SFNoUnconditionalDefaultTransitionDiag "error" - SFTransitionOutsideNaturalParentDiag "warning" - SFUnconditionalTransitionShadowingDiag "warning" - SFUndirectedBroadcastEventsDiag "warning" - SFTransitionActionBeforeConditionDiag "warning" - SFOutputUsedAsStateInMooreChartDiag "error" - IntegerSaturationMsg "warning" - } - Simulink.HardwareCC { - $ObjectID 13 - Version "1.15.0" - ProdBitPerChar 8 - ProdBitPerShort 16 - ProdBitPerInt 32 - ProdBitPerLong 32 - ProdBitPerLongLong 64 - ProdBitPerFloat 32 - ProdBitPerDouble 64 - ProdBitPerPointer 64 - ProdLargestAtomicInteger "Char" - ProdLargestAtomicFloat "Float" - ProdIntDivRoundTo "Zero" - ProdEndianess "LittleEndian" - ProdWordSize 32 - ProdShiftRightIntArith on - ProdLongLongMode off - ProdHWDeviceType "Specified" - TargetBitPerChar 8 - TargetBitPerShort 16 - TargetBitPerInt 32 - TargetBitPerLong 32 - TargetBitPerLongLong 64 - TargetBitPerFloat 32 - TargetBitPerDouble 64 - TargetBitPerPointer 32 - TargetLargestAtomicInteger "Char" - TargetLargestAtomicFloat "None" - TargetShiftRightIntArith on - TargetLongLongMode off - TargetIntDivRoundTo "Undefined" - TargetEndianess "Unspecified" - TargetWordSize 32 - TargetPreprocMaxBitsSint 32 - TargetPreprocMaxBitsUint 32 - TargetHWDeviceType "Specified" - TargetUnknown off - ProdEqTarget on - } - Simulink.ModelReferenceCC { - $ObjectID 14 - Version "1.15.0" - UpdateModelReferenceTargets "IfOutOfDateOrStructuralChange" - CheckModelReferenceTargetMessage "error" - EnableParallelModelReferenceBuilds off - ParallelModelReferenceErrorOnInvalidPool on - ParallelModelReferenceMATLABWorkerInit "None" - ModelReferenceNumInstancesAllowed "Multi" - PropagateVarSize "Infer from blocks in model" - ModelReferencePassRootInputsByReference on - ModelReferenceMinAlgLoopOccurrences off - PropagateSignalLabelsOutOfModel on - SupportModelReferenceSimTargetCustomCode off - } - Simulink.SFSimCC { - $ObjectID 15 - Version "1.15.0" - SFSimOverflowDetection on - SFSimEcho on - SimCtrlC on - SimIntegrity on - SimUseLocalCustomCode off - SimParseCustomCode on - SimBuildMode "sf_incremental_build" - SimGenImportedTypeDefs off - } - Simulink.RTWCC { - $BackupClass "Simulink.RTWCC" - $ObjectID 16 - Version "1.15.0" - Array { - Type "Cell" - Dimension 13 - Cell "IncludeHyperlinkInReport" - Cell "GenerateTraceInfo" - Cell "GenerateTraceReport" - Cell "GenerateTraceReportSl" - Cell "GenerateTraceReportSf" - Cell "GenerateTraceReportEml" - Cell "PortableWordSizes" - Cell "GenerateWebview" - Cell "GenerateCodeMetricsReport" - Cell "GenerateCodeReplacementReport" - Cell "GenerateMissedCodeReplacementReport" - Cell "GenerateErtSFunction" - Cell "CreateSILPILBlock" - PropName "DisabledProps" - } - SystemTargetFile "grt.tlc" - TLCOptions "" - GenCodeOnly off - MakeCommand "make_rtw" - GenerateMakefile on - PackageGeneratedCodeAndArtifacts off - PackageName "" - TemplateMakefile "grt_default_tmf" - PostCodeGenCommand "" - Description "" - GenerateReport off - SaveLog off - RTWVerbose on - RetainRTWFile off - ProfileTLC off - TLCDebug off - TLCCoverage off - TLCAssert off - RTWUseLocalCustomCode off - RTWUseSimCustomCode off - CustomSourceCode "" - CustomHeaderCode "" - CustomInclude "" - CustomSource "" - CustomLibrary "" - CustomInitializer "" - CustomTerminator "" - Toolchain "Automatically locate an installed toolchain" - BuildConfiguration "Faster Builds" - IncludeHyperlinkInReport off - LaunchReport off - PortableWordSizes off - CreateSILPILBlock "None" - CodeExecutionProfiling off - CodeExecutionProfileVariable "executionProfile" - CodeProfilingSaveOptions "SummaryOnly" - CodeProfilingInstrumentation off - SILDebugging off - TargetLang "C" - IncludeBusHierarchyInRTWFileBlockHierarchyMap off - GenerateTraceInfo off - GenerateTraceReport off - GenerateTraceReportSl off - GenerateTraceReportSf off - GenerateTraceReportEml off - GenerateWebview off - GenerateCodeMetricsReport off - GenerateCodeReplacementReport off - GenerateMissedCodeReplacementReport off - RTWCompilerOptimization "off" - RTWCustomCompilerOptimizations "" - CheckMdlBeforeBuild "Off" - SharedConstantsCachingThreshold 1024 - Array { - Type "Handle" - Dimension 2 - Simulink.CodeAppCC { - $ObjectID 17 - Version "1.15.0" - Array { - Type "Cell" - Dimension 25 - Cell "IgnoreCustomStorageClasses" - Cell "IgnoreTestpoints" - Cell "InsertBlockDesc" - Cell "InsertPolySpaceComments" - Cell "SFDataObjDesc" - Cell "MATLABFcnDesc" - Cell "SimulinkDataObjDesc" - Cell "DefineNamingRule" - Cell "SignalNamingRule" - Cell "ParamNamingRule" - Cell "InternalIdentifier" - Cell "InlinedPrmAccess" - Cell "CustomSymbolStr" - Cell "CustomSymbolStrGlobalVar" - Cell "CustomSymbolStrType" - Cell "CustomSymbolStrField" - Cell "CustomSymbolStrFcn" - Cell "CustomSymbolStrModelFcn" - Cell "CustomSymbolStrFcnArg" - Cell "CustomSymbolStrBlkIO" - Cell "CustomSymbolStrTmpVar" - Cell "CustomSymbolStrMacro" - Cell "CustomSymbolStrUtil" - Cell "CustomUserTokenString" - Cell "ReqsInCode" - PropName "DisabledProps" - } - ForceParamTrailComments off - GenerateComments on - CommentStyle "Auto" - IgnoreCustomStorageClasses on - IgnoreTestpoints off - IncHierarchyInIds off - MaxIdLength 31 - PreserveName off - PreserveNameWithParent off - ShowEliminatedStatement off - OperatorAnnotations off - IncAutoGenComments off - SimulinkDataObjDesc off - SFDataObjDesc off - MATLABFcnDesc off - IncDataTypeInIds off - MangleLength 1 - CustomSymbolStrGlobalVar "$R$N$M" - CustomSymbolStrType "$N$R$M_T" - CustomSymbolStrField "$N$M" - CustomSymbolStrFcn "$R$N$M$F" - CustomSymbolStrFcnArg "rt$I$N$M" - CustomSymbolStrBlkIO "rtb_$N$M" - CustomSymbolStrTmpVar "$N$M" - CustomSymbolStrMacro "$R$N$M" - CustomSymbolStrUtil "$N$C" - DefineNamingRule "None" - ParamNamingRule "None" - SignalNamingRule "None" - InsertBlockDesc off - InsertPolySpaceComments off - SimulinkBlockComments on - MATLABSourceComments off - EnableCustomComments off - InternalIdentifier "Shortened" - InlinedPrmAccess "Literals" - ReqsInCode off - UseSimReservedNames off - } - Simulink.GRTTargetCC { - $BackupClass "Simulink.TargetCC" - $ObjectID 18 - Version "1.15.0" - Array { - Type "Cell" - Dimension 15 - Cell "IncludeMdlTerminateFcn" - Cell "SuppressErrorStatus" - Cell "ERTCustomFileBanners" - Cell "GenerateSampleERTMain" - Cell "ExistingSharedCode" - Cell "GenerateTestInterfaces" - Cell "ModelStepFunctionPrototypeControlCompliant" - Cell "GenerateAllocFcn" - Cell "PurelyIntegerCode" - Cell "SupportComplex" - Cell "SupportAbsoluteTime" - Cell "SupportContinuousTime" - Cell "SupportNonInlinedSFcns" - Cell "RemoveDisableFunc" - Cell "RemoveResetFunc" - PropName "DisabledProps" - } - TargetFcnLib "ansi_tfl_table_tmw.mat" - TargetLibSuffix "" - TargetPreCompLibLocation "" - GenFloatMathFcnCalls "NOT IN USE" - TargetLangStandard "C99 (ISO)" - CodeReplacementLibrary "None" - UtilityFuncGeneration "Auto" - ERTMultiwordTypeDef "System defined" - ERTMultiwordLength 256 - MultiwordLength 2048 - GenerateFullHeader on - InferredTypesCompatibility off - GenerateSampleERTMain off - GenerateTestInterfaces off - ModelReferenceCompliant on - ParMdlRefBuildCompliant on - CompOptLevelCompliant on - ConcurrentExecutionCompliant on - IncludeMdlTerminateFcn on - GeneratePreprocessorConditionals "Use local settings" - CombineOutputUpdateFcns on - CombineSignalStateStructs off - SuppressErrorStatus off - ERTFirstTimeCompliant off - IncludeFileDelimiter "Auto" - ERTCustomFileBanners off - SupportAbsoluteTime on - LogVarNameModifier "rt_" - MatFileLogging on - MultiInstanceERTCode off - CodeInterfacePackaging "Nonreusable function" - SupportNonFinite on - SupportComplex on - PurelyIntegerCode off - SupportContinuousTime on - SupportNonInlinedSFcns on - SupportVariableSizeSignals off - ParenthesesLevel "Nominal" - CastingMode "Nominal" - MATLABClassNameForMDSCustomization "Simulink.SoftwareTarget.GRTCustomization" - ModelStepFunctionPrototypeControlCompliant off - CPPClassGenCompliant on - AutosarCompliant off - GRTInterface off - GenerateAllocFcn off - GenerateSharedConstants on - UseMalloc off - ExtMode off - ExtModeStaticAlloc off - ExtModeTesting off - ExtModeStaticAllocSize 1000000 - ExtModeTransport 0 - ExtModeMexFile "ext_comm" - ExtModeIntrfLevel "Level1" - RTWCAPISignals off - RTWCAPIParams off - RTWCAPIStates off - RTWCAPIRootIO off - GenerateASAP2 off - MultiInstanceErrorCode "Error" - } - PropName "Components" - } - } - PropName "Components" - } - Name "Configuration" - CurrentDlgPage "Diagnostics" - ConfigPrmDlgPosition [ 195, 142, 1085, 882 ] - } - PropName "ConfigurationSets" - } - Simulink.ConfigSet { - $PropName "ActiveConfigurationSet" - $ObjectID 8 - } - Object { - $PropName "DataTransfer" - $ObjectID 19 - $ClassName "Simulink.GlobalDataTransfer" - DefaultTransitionBetweenSyncTasks "Ensure deterministic transfer (maximum delay)" - DefaultTransitionBetweenAsyncTasks "Ensure data integrity only" - DefaultTransitionBetweenContTasks "Ensure deterministic transfer (minimum delay)" - DefaultExtrapolationMethodBetweenContTasks "None" - AutoInsertRateTranBlk [0] - } - ExplicitPartitioning off - BlockDefaults { - ForegroundColor "black" - BackgroundColor "white" - DropShadow off - NamePlacement "normal" - FontName "Helvetica" - FontSize 10 - FontWeight "normal" - FontAngle "normal" - ShowName on - BlockRotation 0 - BlockMirror off - } - AnnotationDefaults { - HorizontalAlignment "center" - VerticalAlignment "middle" - ForegroundColor "black" - BackgroundColor "white" - DropShadow off - FontName "Helvetica" - FontSize 10 - FontWeight "normal" - FontAngle "normal" - UseDisplayTextAsClickCallback off - } - LineDefaults { - FontName "Helvetica" - FontSize 9 - FontWeight "normal" - FontAngle "normal" - } - MaskDefaults { - SelfModifiable "off" - IconFrame "on" - IconOpaque "on" - RunInitForIconRedraw "off" - IconRotate "none" - PortRotate "default" - IconUnits "autoscale" - } - MaskParameterDefaults { - Evaluate "on" - Tunable "on" - NeverSave "off" - Internal "off" - ReadOnly "off" - Enabled "on" - Visible "on" - ToolTip "on" - } - BlockParameterDefaults { - Block { - BlockType BusCreator - Inputs "4" - DisplayOption "none" - OutDataTypeStr "Inherit: auto" - NonVirtualBus off - InheritFromInputs on - } - Block { - BlockType BusSelector - OutputSignals "signal1,signal2,signal3" - OutputAsBus off - } - Block { - BlockType Constant - Value "1" - VectorParams1D on - SamplingMode "Sample based" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: Inherit from 'Constant value'" - LockScale off - SampleTime "inf" - FramePeriod "inf" - PreserveConstantTs off - } - Block { - BlockType Delay - DelayLengthSource "Dialog" - DelayLength "2" - DelayLengthUpperLimit "100" - InitialConditionSource "Dialog" - InitialCondition "0.0" - ExternalReset "None" - ShowEnablePort off - PreventDirectFeedthrough off - DiagnosticForOutOfRangeDelayLength "None" - RemoveProtectionDelayLength off - InputProcessing "Elements as channels (sample based)" - UseCircularBuffer off - SampleTime "-1" - StateMustResolveToSignalObject off - CodeGenStateStorageClass "Auto" - } - Block { - BlockType Demux - Outputs "4" - DisplayOption "none" - BusSelectionMode off - } - Block { - BlockType DiscreteIntegrator - IntegratorMethod "Integration: Forward Euler" - gainval "1.0" - ExternalReset "none" - InitialConditionSource "internal" - InitialCondition "0" - InitialConditionSetting "Output" - SampleTime "1" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: Inherit via internal rule" - LockScale off - RndMeth "Floor" - SaturateOnIntegerOverflow off - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - ShowSaturationPort off - ShowStatePort off - IgnoreLimit off - StateMustResolveToSignalObject off - RTWStateStorageClass "Auto" - ICPrevOutput "DiscIntNeverNeededParam" - ICPrevScaledInput "DiscIntNeverNeededParam" - } - Block { - BlockType DiscreteTransferFcn - NumeratorSource "Dialog" - Numerator "[1]" - DenominatorSource "Dialog" - Denominator "[1 0.5]" - InitialStatesSource "Dialog" - InitialStates "0" - InputProcessing "Elements as channels (sample based)" - ExternalReset "None" - InitialDenominatorStates "0" - FilterStructure "Direct form II" - SampleTime "-1" - a0EqualsOne off - NumCoefMin "[]" - NumCoefMax "[]" - DenCoefMin "[]" - DenCoefMax "[]" - OutMin "[]" - OutMax "[]" - StateDataTypeStr "Inherit: Same as input" - MultiplicandDataTypeStr "Inherit: Same as input" - NumCoefDataTypeStr "Inherit: Inherit via internal rule" - DenCoefDataTypeStr "Inherit: Inherit via internal rule" - NumProductDataTypeStr "Inherit: Inherit via internal rule" - DenProductDataTypeStr "Inherit: Inherit via internal rule" - NumAccumDataTypeStr "Inherit: Inherit via internal rule" - DenAccumDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - LockScale off - RndMeth "Floor" - SaturateOnIntegerOverflow off - StateMustResolveToSignalObject off - RTWStateStorageClass "Auto" - } - Block { - BlockType Gain - Gain "1" - Multiplication "Element-wise(K.*u)" - ParamMin "[]" - ParamMax "[]" - ParamDataTypeStr "Inherit: Same as input" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: Same as input" - LockScale off - RndMeth "Floor" - SaturateOnIntegerOverflow on - SampleTime "-1" - } - Block { - BlockType Ground - } - Block { - BlockType Inport - Port "1" - OutputFunctionCall off - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: auto" - LockScale off - BusOutputAsStruct off - PortDimensions "-1" - VarSizeSig "Inherit" - SampleTime "-1" - SignalType "auto" - SamplingMode "auto" - LatchByDelayingOutsideSignal off - LatchInputForFeedbackSignals off - Interpolate on - } - Block { - BlockType Integrator - ExternalReset "none" - InitialConditionSource "internal" - InitialCondition "0" - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - WrapState off - WrappedStateUpperValue "pi" - WrappedStateLowerValue "-pi" - ShowSaturationPort off - ShowStatePort off - AbsoluteTolerance "auto" - IgnoreLimit off - ZeroCross on - ContinuousStateAttributes "''" - } - Block { - BlockType Mux - Inputs "4" - DisplayOption "none" - UseBusObject off - BusObject "BusObject" - NonVirtualBus off - } - Block { - BlockType Outport - Port "1" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: auto" - LockScale off - BusOutputAsStruct off - PortDimensions "-1" - VarSizeSig "Inherit" - SampleTime "-1" - SignalType "auto" - SamplingMode "auto" - SourceOfInitialOutputValue "Dialog" - OutputWhenDisabled "held" - InitialOutput "[]" - } - Block { - BlockType Quantizer - QuantizationInterval "0.5" - LinearizeAsGain on - SampleTime "-1" - } - Block { - BlockType RandomNumber - Mean "0" - Variance "1" - Seed "0" - SampleTime "-1" - VectorParams1D on - } - Block { - BlockType RateTransition - Integrity on - Deterministic on - X0 "0" - OutPortSampleTimeOpt "Specify" - OutPortSampleTimeMultiple "1" - OutPortSampleTime "-1" - } - Block { - BlockType S-Function - FunctionName "system" - SFunctionModules "''" - PortCounts "[]" - SFunctionDeploymentMode off - EnableBusSupport off - } - Block { - BlockType Saturate - UpperLimitSource "Dialog" - UpperLimit "0.5" - LowerLimitSource "Dialog" - LowerLimit "-0.5" - LinearizeAsGain on - ZeroCross on - SampleTime "-1" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: Same as input" - LockScale off - RndMeth "Floor" - } - Block { - BlockType Scope - ModelBased off - TickLabels "OneTimeTick" - ZoomMode "on" - Grid "on" - ShowLegends off - TimeRange "auto" - YMin "-5" - YMax "5" - SaveToWorkspace off - SaveName "ScopeData" - DataFormat "Array" - LimitDataPoints on - MaxDataPoints "5000" - Decimation "1" - SampleInput off - SampleTime "-1" - ScrollMode off - } - Block { - BlockType Step - Time "1" - Before "0" - After "1" - SampleTime "-1" - VectorParams1D on - ZeroCross on - } - Block { - BlockType SubSystem - ShowPortLabels "FromPortIcon" - Permissions "ReadWrite" - PermitHierarchicalResolution "All" - TreatAsAtomicUnit off - MinAlgLoopOccurrences off - PropExecContextOutsideSubsystem off - CheckFcnCallInpInsideContextMsg off - SystemSampleTime "-1" - RTWSystemCode "Auto" - RTWFcnNameOpts "Auto" - RTWFileNameOpts "Auto" - FunctionInterfaceSpec "void_void" - FunctionWithSeparateData off - RTWMemSecFuncInitTerm "Inherit from model" - RTWMemSecFuncExecute "Inherit from model" - RTWMemSecDataConstants "Inherit from model" - RTWMemSecDataInternal "Inherit from model" - RTWMemSecDataParameters "Inherit from model" - SimViewingDevice off - DataTypeOverride "UseLocalSettings" - DataTypeOverrideAppliesTo "AllNumericTypes" - MinMaxOverflowLogging "UseLocalSettings" - Opaque off - MaskHideContents off - SFBlockType "NONE" - Variant off - GeneratePreprocessorConditionals off - ContentPreviewEnabled off - IsWebBlock off - } - Block { - BlockType Sum - IconShape "rectangular" - Inputs "++" - CollapseMode "All dimensions" - CollapseDim "1" - InputSameDT on - AccumDataTypeStr "Inherit: Inherit via internal rule" - OutMin "[]" - OutMax "[]" - OutDataTypeStr "Inherit: Same as first input" - LockScale off - RndMeth "Floor" - SaturateOnIntegerOverflow on - SampleTime "-1" - } - Block { - BlockType Terminator - } - Block { - BlockType ZeroOrderHold - SampleTime "1" - } - } - System { - Name "test_model_R2015A" - Location [69, 48, 1812, 988] - Open on - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "125" - ReportName "simulink-default.rpt" - SIDHighWatermark "904" - Block { - BlockType SubSystem - Name " Sensors " - SID "650" - Ports [6, 4] - Position [1195, 272, 1415, 508] - ZOrder 73 - ForegroundColor "yellow" - ShowName off - RequestExecContextInheritance off - Object { - $PropName "MaskObject" - $ObjectID 20 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{B}Omega', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on');" - "\nport_label('input', 3, '^{B}v_o', 'texmode', 'on');\nport_label('input', 4, '^{E}r_o', 'texmode', 'on');\nport_labe" - "l('input', 5, '^{B}dv_o/dt', 'texmode', 'on');\nport_label('input', 6, '^{B}g', 'texmode', 'on');\nport_label('output" - "', 1, '\\Theta_{filtered}', 'texmode', 'on');\nport_label('output', 2, 'd\\Theta_{gyro}/dt', 'texmode', 'on');\nport_" - "label('output', 3, '^{E}r_o', 'texmode', 'on');\ndisp('Sensors', 'texmode', 'on'); " - } - System { - Name " Sensors " - Location [69, 48, 1812, 988] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "125" - Block { - BlockType Inport - Name "B_Omega" - SID "651" - Position [1015, 678, 1045, 692] - ZOrder 265 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles" - SID "652" - Position [1440, 1043, 1470, 1057] - ZOrder 266 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_vo" - SID "653" - Position [1015, 613, 1045, 627] - ZOrder 267 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "E_ro" - SID "654" - Position [1440, 963, 1470, 977] - ZOrder 268 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_vo_dot" - SID "655" - Position [1015, 548, 1045, 562] - ZOrder 269 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_g" - SID "656" - Position [1015, 743, 1045, 757] - ZOrder 273 - Port "6" - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "3D Graphical Simulation" - SID "698" - Ports [2] - Position [1725, 1075, 1875, 1135] - ZOrder 287 - Commented "on" - RequestExecContextInheritance off - Object { - $PropName "MaskObject" - $ObjectID 21 - $ClassName "Simulink.Mask" - Display "port_label('input',1,'r_{o}','texmode','on')\nport_label('input',2,'\\Theta','texmode','on')" - } - System { - Name "3D Graphical Simulation" - Location [-8, -8, 1928, 1048] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "Displacement" - SID "699" - Position [110, 218, 140, 232] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Euler Angles" - SID "700" - Position [125, 108, 155, 122] - ZOrder -2 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType BusCreator - Name "Bus\nCreator" - SID "701" - Ports [3, 1] - Position [600, 76, 610, 154] - ZOrder -3 - ShowName off - Inputs "3" - DisplayOption "bar" - } - Block { - BlockType BusCreator - Name "Bus\nCreator1" - SID "702" - Ports [3, 1] - Position [630, 191, 640, 269] - ZOrder -4 - ShowName off - Inputs "3" - DisplayOption "bar" - } - Block { - BlockType BusCreator - Name "Bus\nCreator2" - SID "703" - Ports [3, 1] - Position [385, 75, 390, 155] - ZOrder -5 - ShowName off - Inputs "3" - DisplayOption "bar" - } - Block { - BlockType BusSelector - Name "Bus\nSelector" - SID "704" - Ports [1, 3] - Position [500, 77, 505, 153] - ZOrder -6 - ShowName off - OutputSignals "phi,theta,psi" - Port { - PortNumber 1 - Name "<phi>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "<theta>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "<psi>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux" - SID "705" - Ports [1, 3] - Position [440, 183, 450, 267] - ZOrder -7 - BackgroundColor "black" - ShowName off - Outputs "3" - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux1" - SID "706" - Ports [1, 3] - Position [290, 75, 295, 155] - ZOrder -8 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "phi" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "theta" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "psi" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Gain - Name "Gain" - SID "707" - Position [550, 240, 580, 270] - ZOrder -10 - Gain "-1" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Gain - Name "Gain1" - SID "708" - Position [670, 208, 710, 252] - ZOrder -11 - Gain "eye(3)*1" - Multiplication "Matrix(K*u)" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Gain - Name "Gain2" - SID "709" - Position [550, 190, 580, 220] - ZOrder -12 - Gain "-1" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType SubSystem - Name "MATLAB Function" - SID "710" - Ports [1, 1] - Position [655, 92, 725, 138] - ZOrder 5 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ExplicitOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - System { - Name "MATLAB Function" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "21" - Block { - BlockType Inport - Name "u" - SID "710::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "710::20" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "710::19" - Tag "Stateflow S-Function test_model_R2015A 11" - Ports [1, 2] - Position [180, 100, 230, 160] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[1 2]" - EnableBusSupport on - Port { - PortNumber 2 - Name "y" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "710::21" - Position [460, 241, 480, 259] - ZOrder 12 - } - Block { - BlockType Outport - Name "y" - SID "710::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "u" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - Name "y" - ZOrder 2 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "y" - DstPort 1 - } - Line { - ZOrder 3 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType RateTransition - Name "Rate Transition" - SID "711" - Position [755, 94, 795, 136] - ZOrder -13 - NamePlacement "alternate" - OutPortSampleTime "0.06" - } - Block { - BlockType RateTransition - Name "Rate Transition1" - SID "712" - Position [735, 210, 770, 250] - ZOrder -14 - OutPortSampleTime "0.06" - } - Block { - BlockType Reference - Name "VR Sink" - SID "713" - Ports [2] - Position [865, 76, 1055, 234] - ZOrder -15 - LibraryVersion "1.34" - SourceBlock "vrlib/VR Sink" - SourceType "Virtual Reality Sink" - InstantiateOnLoad on - SampleTime "-1" - ViewEnable on - RemoteChange off - RemoteView off - FieldsWritten "Helicopter.rotation.4.1.1.double#Helicopter.translation.3.1.1.double" - WorldFileName "quadrotor_world_ucart.wrl" - AutoView on - VideoDimensions "[]" - AllowVariableSize off - } - Line { - ZOrder 1 - SrcBlock "Displacement" - SrcPort 1 - DstBlock "Demux" - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "Bus\nCreator2" - SrcPort 1 - DstBlock "Bus\nSelector" - DstPort 1 - } - Line { - ZOrder 3 - SrcBlock "Demux" - SrcPort 1 - Points [40, 0; 0, 40; 120, 0] - DstBlock "Bus\nCreator1" - DstPort 3 - } - Line { - ZOrder 4 - SrcBlock "Gain" - SrcPort 1 - Points [5, 0; 0, -25] - DstBlock "Bus\nCreator1" - DstPort 2 - } - Line { - ZOrder 5 - SrcBlock "Gain2" - SrcPort 1 - DstBlock "Bus\nCreator1" - DstPort 1 - } - Line { - ZOrder 6 - SrcBlock "Rate Transition1" - SrcPort 1 - Points [35, 0; 0, -35] - DstBlock "VR Sink" - DstPort 2 - } - Line { - ZOrder 7 - SrcBlock "Rate Transition" - SrcPort 1 - DstBlock "VR Sink" - DstPort 1 - } - Line { - ZOrder 8 - SrcBlock "Demux" - SrcPort 3 - DstBlock "Gain" - DstPort 1 - } - Line { - ZOrder 9 - SrcBlock "Demux" - SrcPort 2 - Points [80, 0] - DstBlock "Gain2" - DstPort 1 - } - Line { - ZOrder 10 - SrcBlock "Bus\nCreator1" - SrcPort 1 - DstBlock "Gain1" - DstPort 1 - } - Line { - Name "<phi>" - ZOrder 11 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 1 - Points [0, -10; 45, 0; 0, 60] - DstBlock "Bus\nCreator" - DstPort 3 - } - Line { - Name "<psi>" - ZOrder 12 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 3 - Points [0, -10; 75, 0] - DstBlock "Bus\nCreator" - DstPort 2 - } - Line { - Name "<theta>" - ZOrder 13 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 2 - Points [30, 0; 0, -25] - DstBlock "Bus\nCreator" - DstPort 1 - } - Line { - ZOrder 14 - SrcBlock "Gain1" - SrcPort 1 - DstBlock "Rate Transition1" - DstPort 1 - } - Line { - Name "psi" - ZOrder 15 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 3 - DstBlock "Bus\nCreator2" - DstPort 3 - } - Line { - Name "theta" - ZOrder 16 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 2 - DstBlock "Bus\nCreator2" - DstPort 2 - } - Line { - Name "phi" - ZOrder 17 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 1 - DstBlock "Bus\nCreator2" - DstPort 1 - } - Line { - ZOrder 18 - SrcBlock "Euler Angles" - SrcPort 1 - DstBlock "Demux1" - DstPort 1 - } - Line { - ZOrder 19 - SrcBlock "Bus\nCreator" - SrcPort 1 - DstBlock "MATLAB Function" - DstPort 1 - } - Line { - ZOrder 20 - SrcBlock "MATLAB Function" - SrcPort 1 - DstBlock "Rate Transition" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "3D Graphical Simulation1" - SID "714" - Ports [2] - Position [2635, 815, 2785, 875] - ZOrder 290 - Commented "on" - RequestExecContextInheritance off - Object { - $PropName "MaskObject" - $ObjectID 22 - $ClassName "Simulink.Mask" - Display "port_label('input',1, '\\Theta','texmode','on')\nport_label('input',2,'r_{o}','texmode','on')" - } - System { - Name "3D Graphical Simulation1" - Location [108, 36, 1850, 976] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "Euler Angles\n" - SID "715" - Position [180, 108, 210, 122] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "Displacement" - SID "716" - Position [180, 218, 210, 232] - ZOrder -2 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType BusCreator - Name "Bus\nCreator" - SID "717" - Ports [3, 1] - Position [600, 76, 610, 154] - ZOrder -3 - ShowName off - Inputs "3" - DisplayOption "bar" - } - Block { - BlockType BusCreator - Name "Bus\nCreator1" - SID "718" - Ports [3, 1] - Position [630, 191, 640, 269] - ZOrder -4 - ShowName off - Inputs "3" - DisplayOption "bar" - } - Block { - BlockType BusCreator - Name "Bus\nCreator2" - SID "719" - Ports [3, 1] - Position [385, 75, 390, 155] - ZOrder -5 - ShowName off - Inputs "3" - DisplayOption "bar" - } - Block { - BlockType BusSelector - Name "Bus\nSelector" - SID "720" - Ports [1, 3] - Position [500, 77, 505, 153] - ZOrder -6 - ShowName off - OutputSignals "phi,theta,psi" - Port { - PortNumber 1 - Name "<phi>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "<theta>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "<psi>" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux" - SID "721" - Ports [1, 3] - Position [440, 183, 450, 267] - ZOrder -7 - BackgroundColor "black" - ShowName off - Outputs "3" - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux1" - SID "722" - Ports [1, 3] - Position [290, 75, 295, 155] - ZOrder -8 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "phi" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "theta" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "psi" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Gain - Name "Gain" - SID "723" - Position [550, 240, 580, 270] - ZOrder -10 - Gain "-1" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Gain - Name "Gain1" - SID "724" - Position [670, 208, 710, 252] - ZOrder -11 - Gain "eye(3)*1" - Multiplication "Matrix(K*u)" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Gain - Name "Gain2" - SID "725" - Position [550, 190, 580, 220] - ZOrder -12 - Gain "-1" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType SubSystem - Name "MATLAB Function" - SID "726" - Ports [1, 1] - Position [655, 92, 725, 138] - ZOrder 5 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ExplicitOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - System { - Name "MATLAB Function" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "21" - Block { - BlockType Inport - Name "u" - SID "726::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "726::20" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "726::19" - Tag "Stateflow S-Function test_model_R2015A 3" - Ports [1, 2] - Position [180, 100, 230, 160] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[1 2]" - EnableBusSupport on - Port { - PortNumber 2 - Name "y" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "726::21" - Position [460, 241, 480, 259] - ZOrder 12 - } - Block { - BlockType Outport - Name "y" - SID "726::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "u" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - Name "y" - ZOrder 2 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "y" - DstPort 1 - } - Line { - ZOrder 3 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType RateTransition - Name "Rate Transition" - SID "727" - Position [755, 94, 795, 136] - ZOrder -13 - NamePlacement "alternate" - OutPortSampleTime "0.06" - } - Block { - BlockType RateTransition - Name "Rate Transition1" - SID "728" - Position [735, 210, 770, 250] - ZOrder -14 - OutPortSampleTime "0.06" - } - Block { - BlockType Reference - Name "VR Sink" - SID "729" - Ports [2] - Position [865, 76, 1055, 234] - ZOrder -15 - LibraryVersion "1.34" - SourceBlock "vrlib/VR Sink" - SourceType "Virtual Reality Sink" - InstantiateOnLoad on - SampleTime "-1" - ViewEnable on - RemoteChange off - RemoteView off - FieldsWritten "Helicopter.rotation.4.1.1.double#Helicopter.translation.3.1.1.double" - WorldFileName "quadrotor_world_ucart.wrl" - AutoView on - VideoDimensions "[]" - AllowVariableSize off - } - Line { - ZOrder 1 - SrcBlock "Bus\nCreator2" - SrcPort 1 - DstBlock "Bus\nSelector" - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "Demux" - SrcPort 1 - Points [40, 0; 0, 40; 120, 0] - DstBlock "Bus\nCreator1" - DstPort 3 - } - Line { - ZOrder 3 - SrcBlock "Gain" - SrcPort 1 - Points [5, 0; 0, -25] - DstBlock "Bus\nCreator1" - DstPort 2 - } - Line { - ZOrder 4 - SrcBlock "Gain2" - SrcPort 1 - DstBlock "Bus\nCreator1" - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock "Rate Transition1" - SrcPort 1 - Points [35, 0; 0, -35] - DstBlock "VR Sink" - DstPort 2 - } - Line { - ZOrder 6 - SrcBlock "Rate Transition" - SrcPort 1 - DstBlock "VR Sink" - DstPort 1 - } - Line { - ZOrder 7 - SrcBlock "Demux" - SrcPort 3 - DstBlock "Gain" - DstPort 1 - } - Line { - ZOrder 8 - SrcBlock "Demux" - SrcPort 2 - Points [80, 0] - DstBlock "Gain2" - DstPort 1 - } - Line { - ZOrder 9 - SrcBlock "Bus\nCreator1" - SrcPort 1 - DstBlock "Gain1" - DstPort 1 - } - Line { - Name "<phi>" - ZOrder 10 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 1 - Points [0, -10; 45, 0; 0, 60] - DstBlock "Bus\nCreator" - DstPort 3 - } - Line { - Name "<psi>" - ZOrder 11 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 3 - Points [0, -10; 75, 0] - DstBlock "Bus\nCreator" - DstPort 2 - } - Line { - Name "<theta>" - ZOrder 12 - Labels [0, 0] - SrcBlock "Bus\nSelector" - SrcPort 2 - Points [30, 0; 0, -25] - DstBlock "Bus\nCreator" - DstPort 1 - } - Line { - ZOrder 13 - SrcBlock "Gain1" - SrcPort 1 - DstBlock "Rate Transition1" - DstPort 1 - } - Line { - Name "psi" - ZOrder 14 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 3 - DstBlock "Bus\nCreator2" - DstPort 3 - } - Line { - Name "theta" - ZOrder 15 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 2 - DstBlock "Bus\nCreator2" - DstPort 2 - } - Line { - Name "phi" - ZOrder 16 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 1 - DstBlock "Bus\nCreator2" - DstPort 1 - } - Line { - ZOrder 17 - SrcBlock "Bus\nCreator" - SrcPort 1 - DstBlock "MATLAB Function" - DstPort 1 - } - Line { - ZOrder 18 - SrcBlock "MATLAB Function" - SrcPort 1 - DstBlock "Rate Transition" - DstPort 1 - } - Line { - ZOrder 19 - SrcBlock "Displacement" - SrcPort 1 - DstBlock "Demux" - DstPort 1 - } - Line { - ZOrder 20 - SrcBlock "Euler Angles\n" - SrcPort 1 - DstBlock "Demux1" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Aeb\n\n\n\n\n\n\n\n\n\n" - SID "679" - Ports [2, 1] - Position [1470, 689, 1885, 811] - ZOrder 275 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ExplicitOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Object { - $PropName "MaskObject" - $ObjectID 23 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Gyroscope Reading', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{IMU" - "}', 'texmode', 'on');\nport_label('output', 1, 'd\\Theta_{Gyro}/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode'," - " 'on');" - } - System { - Name "Aeb\n\n\n\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "25" - Block { - BlockType Inport - Name "gyro_reading" - SID "679::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles_IMU" - SID "679::22" - Position [20, 136, 40, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "679::24" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 15 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "679::23" - Tag "Stateflow S-Function test_model_R2015A 12" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 14 - FunctionName "sf_sfun" - PortCounts "[2 2]" - EnableBusSupport on - Port { - PortNumber 2 - Name "euler_rates_IMU" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "679::25" - Position [460, 241, 480, 259] - ZOrder 16 - } - Block { - BlockType Outport - Name "euler_rates_IMU" - SID "679::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "gyro_reading" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "euler_angles_IMU" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "euler_rates_IMU" - ZOrder 3 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "euler_rates_IMU" - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1" - SID "680" - Ports [2, 2] - Position [1480, 484, 1875, 631] - ZOrder 284 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ExplicitOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Object { - $PropName "MaskObject" - $ObjectID 24 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Accelerometer Reading', 'texmode', 'on');\nport_label('output', 1, '\\theta" - "_{accel}', 'texmode', 'on');\nport_label('output', 2, '\\phi_{accel}', 'texmode', 'on');\ndisp('Calculate Pitch a" - "nd Roll', 'texmode', 'on');" - } - System { - Name "Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "26" - Block { - BlockType Inport - Name "accel_reading" - SID "680::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "accel_roll_prev" - SID "680::23" - Position [20, 136, 40, 154] - ZOrder 14 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "680::20" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "680::19" - Tag "Stateflow S-Function test_model_R2015A 13" - Ports [2, 3] - Position [180, 105, 230, 185] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[2 3]" - EnableBusSupport on - Port { - PortNumber 2 - Name "accel_pitch" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "accel_roll" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "680::21" - Position [460, 241, 480, 259] - ZOrder 12 - } - Block { - BlockType Outport - Name "accel_pitch" - SID "680::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "accel_roll" - SID "680::22" - Position [460, 136, 480, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "accel_reading" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "accel_roll_prev" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "accel_pitch" - ZOrder 3 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "accel_pitch" - DstPort 1 - } - Line { - Name "accel_roll" - ZOrder 4 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 3 - DstBlock "accel_roll" - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 6 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Complimentary Filter\n\n\n\n\n\n\n\n" - SID "657" - Ports [3, 1] - Position [2025, 483, 2210, 787] - ZOrder 274 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ExplicitOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Object { - $PropName "MaskObject" - $ObjectID 25 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '\\theta_{accel}', 'texmode', 'on');\nport_label('input', 2, '\\phi_{accel}'" - ", 'texmode', 'on');\nport_label('input', 3, '\\Theta_{Gyro}', 'texmode', 'on');\n%port_label('input', 4, '\\Theta" - "_{IMU}', 'texmode', 'on');\nport_label('output', 1, '\\Theta_{IMU}', 'texmode', 'on');\ndisp('Complimentary Filte" - "r', 'texmode', 'on');" - } - System { - Name "Complimentary Filter\n\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "34" - Block { - BlockType Inport - Name "accel_pitch" - SID "657::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "accel_roll" - SID "657::29" - Position [20, 136, 40, 154] - ZOrder 20 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles_gyro" - SID "657::22" - Position [20, 171, 40, 189] - ZOrder 13 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "657::20" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "657::19" - Tag "Stateflow S-Function test_model_R2015A 9" - Ports [3, 2] - Position [180, 145, 230, 225] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[3 2]" - EnableBusSupport on - Port { - PortNumber 2 - Name "euler_angles_IMU" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "657::21" - Position [460, 241, 480, 259] - ZOrder 12 - } - Block { - BlockType Outport - Name "euler_angles_IMU" - SID "657::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 58 - SrcBlock "accel_pitch" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 59 - SrcBlock "accel_roll" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - ZOrder 60 - SrcBlock "euler_angles_gyro" - SrcPort 1 - DstBlock " SFunction " - DstPort 3 - } - Line { - Name "euler_angles_IMU" - ZOrder 61 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "euler_angles_IMU" - DstPort 1 - } - Line { - ZOrder 62 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 63 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType Delay - Name "Delay1" - SID "731" - Ports [1, 1] - Position [1660, 638, 1695, 672] - ZOrder 285 - BlockMirror on - ForegroundColor "red" - InputPortMap "u0" - DelayLength "1" - InitialCondition "0" - SampleTime "5e-3" - } - Block { - BlockType Delay - Name "Delay2" - SID "772" - Ports [1, 1] - Position [1075, 538, 1110, 572] - ZOrder 304 - InputPortMap "u0" - DelayLength "1" - InitialCondition "0" - SampleTime "5e-3" - } - Block { - BlockType Delay - Name "Delay3" - SID "881" - Ports [1, 1] - Position [2055, 953, 2090, 987] - ZOrder 313 - InputPortMap "u0" - DelayLength "6" - SampleTime "0.01" - } - Block { - BlockType Delay - Name "Delay4" - SID "882" - Ports [1, 1] - Position [2100, 998, 2135, 1032] - ZOrder 314 - InputPortMap "u0" - DelayLength "6" - SampleTime "0.01" - } - Block { - BlockType Demux - Name "Demux" - SID "732" - Ports [1, 3] - Position [1530, 1023, 1535, 1077] - ZOrder 294 - ShowName off - Outputs "3" - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux1" - SID "733" - Ports [1, 2] - Position [2280, 605, 2285, 660] - ZOrder 300 - ShowName off - Outputs "2" - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux2" - SID "903" - Ports [1, 3] - Position [2275, 1038, 2280, 1092] - ZOrder 316 - ShowName off - Outputs "3" - DisplayOption "bar" - } - Block { - BlockType DiscreteIntegrator - Name "Discrete-Time\nIntegrator" - SID "877" - Ports [1, 1] - Position [1935, 732, 1970, 768] - ZOrder 309 - InitialConditionSetting "State (most efficient)" - SampleTime "5e-3" - } - Block { - BlockType Reference - Name "First-Order\nHold" - SID "734" - Ports [1, 1] - Position [2530, 780, 2565, 810] - ZOrder 292 - Commented "on" - LibraryVersion "1.356" - DisableCoverage on - SourceBlock "simulink/Discrete/First-Order\nHold" - SourceType "First-Order Hold" - ContentPreviewEnabled off - Ts "5e-3" - } - Block { - BlockType Reference - Name "First-Order\nHold1" - SID "735" - Ports [1, 1] - Position [2530, 875, 2565, 905] - ZOrder 296 - Commented "on" - LibraryVersion "1.356" - DisableCoverage on - SourceBlock "simulink/Discrete/First-Order\nHold" - SourceType "First-Order Hold" - ContentPreviewEnabled off - Ts "5e-3" - } - Block { - BlockType SubSystem - Name "IMU\n\n\n\n\n\n" - SID "658" - Ports [4, 2] - Position [1145, 520, 1340, 785] - ZOrder 272 - ShowName off - RequestExecContextInheritance off - Object { - $PropName "MaskObject" - $ObjectID 26 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{B}dv_o/dt', 'texmode', 'on')\nport_label('input', 2, '^{B}v_o', 'texmode'" - ", 'on')\nport_label('input', 3, '^{B}\\Omega', 'texmode', 'on')\nport_label('input', 4, '^{B}g', 'texmode', 'on')" - "\nport_label('output', 1, 'Accelerometer Reading', 'texmode', 'on')\nport_label('output', 2, 'Gyroscope Reading'," - " 'texmode', 'on')\ndisp('IMU', 'texmode', 'on');" - } - System { - Name "IMU\n\n\n\n\n\n" - Location [239, 71, 1982, 1011] - Open on - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - Block { - BlockType Inport - Name "B_vo_dot" - SID "659" - Position [110, 173, 140, 187] - ZOrder 17 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_vo" - SID "660" - Position [110, 208, 140, 222] - ZOrder 25 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_Omega" - SID "661" - Position [110, 243, 140, 257] - ZOrder 26 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_g" - SID "662" - Position [110, 278, 140, 292] - ZOrder 27 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "\n\n\n\n\n\n\n" - SID "663" - Ports [5, 2] - Position [250, 165, 445, 335] - ZOrder 1 - LibraryVersion "1.32" - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ExplicitOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Object { - $PropName "MaskObject" - $ObjectID 27 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{B}dv_o/dt', 'texmode', 'on')\nport_label('input', 2, '^{B}v_o', 'texmode', 'on'" - ")\nport_label('input', 3, '^{B}\\Omega', 'texmode', 'on')\nport_label('input', 4, '^{B}g', 'texmode', 'on')\nport_la" - "bel('input', 5, 'r_{oc}', 'texmode', 'on')\nport_label('output', 1, 'Accelerometer Reading', 'texmode', 'on')\nport_" - "label('output', 2, 'Gyroscope Reading', 'texmode', 'on')\ndisp('Ideal IMU', 'texmode', 'on');" - } - System { - Name "\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "31" - Block { - BlockType Inport - Name "B_vo_dot" - SID "663::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_vo" - SID "663::22" - Position [20, 136, 40, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_Omega" - SID "663::19" - Position [20, 171, 40, 189] - ZOrder 10 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_g" - SID "663::20" - Position [20, 206, 40, 224] - ZOrder 11 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "r_oc" - SID "663::23" - Position [20, 246, 40, 264] - ZOrder 14 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "663::25" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 16 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "663::24" - Tag "Stateflow S-Function test_model_R2015A 10" - Ports [5, 3] - Position [180, 110, 230, 230] - ZOrder 15 - FunctionName "sf_sfun" - Parameters "g" - PortCounts "[5 3]" - EnableBusSupport on - Port { - PortNumber 2 - Name "accelReading" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "gyroReading" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "663::26" - Position [460, 241, 480, 259] - ZOrder 17 - } - Block { - BlockType Outport - Name "accelReading" - SID "663::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "gyroReading" - SID "663::21" - Position [460, 136, 480, 154] - ZOrder 12 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "B_vo_dot" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "B_vo" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - ZOrder 3 - SrcBlock "B_Omega" - SrcPort 1 - DstBlock " SFunction " - DstPort 3 - } - Line { - ZOrder 4 - SrcBlock "B_g" - SrcPort 1 - DstBlock " SFunction " - DstPort 4 - } - Line { - ZOrder 5 - SrcBlock "r_oc" - SrcPort 1 - DstBlock " SFunction " - DstPort 5 - } - Line { - Name "accelReading" - ZOrder 6 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "accelReading" - DstPort 1 - } - Line { - Name "gyroReading" - ZOrder 7 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 3 - DstBlock "gyroReading" - DstPort 1 - } - Line { - ZOrder 8 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 9 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType Delay - Name "Delay" - SID "899" - Ports [1, 1] - Position [605, 193, 640, 227] - ZOrder 45 - InputPortMap "u0" - DelayLength "4" - } - Block { - BlockType Delay - Name "Delay1" - SID "900" - Ports [1, 1] - Position [605, 278, 640, 312] - ZOrder 46 - InputPortMap "u0" - DelayLength "4" - } - Block { - BlockType DiscreteTransferFcn - Name "Discrete\nTransfer Fcn" - SID "897" - Ports [1, 1] - Position [490, 187, 570, 233] - ZOrder 43 - InputPortMap "u0" - Numerator "[0.02469]" - Denominator "[1 -0.9752]" - SampleTime "5e-3" - } - Block { - BlockType DiscreteTransferFcn - Name "Discrete\nTransfer Fcn1" - SID "898" - Ports [1, 1] - Position [490, 272, 570, 318] - ZOrder 44 - InputPortMap "u0" - Numerator "[0.02469]" - Denominator "[1 -0.9752]" - SampleTime "5e-3" - } - Block { - BlockType DiscreteIntegrator - Name "Discrete-Time\nIntegrator" - SID "835" - Ports [1, 1] - Position [985, 372, 1020, 408] - ZOrder 30 - InitialConditionSetting "State (most efficient)" - SampleTime "-1" - } - Block { - BlockType DiscreteIntegrator - Name "Discrete-Time\nIntegrator1" - SID "837" - Ports [1, 1] - Position [1170, 342, 1205, 378] - ZOrder 32 - InitialConditionSetting "State (most efficient)" - SampleTime "-1" - } - Block { - BlockType DiscreteIntegrator - Name "Discrete-Time\nIntegrator2" - SID "839" - Ports [1, 1] - Position [1210, 247, 1245, 283] - ZOrder 34 - InitialConditionSetting "State (most efficient)" - SampleTime "-1" - } - Block { - BlockType DiscreteIntegrator - Name "Discrete-Time\nIntegrator3" - SID "841" - Ports [1, 1] - Position [835, 437, 870, 473] - ZOrder 36 - InitialConditionSetting "State (most efficient)" - SampleTime "-1" - } - Block { - BlockType Ground - Name "Ground" - SID "664" - Position [810, 340, 830, 360] - ZOrder 23 - } - Block { - BlockType Ground - Name "Ground1" - SID "665" - Position [810, 145, 830, 165] - ZOrder 24 - } - Block { - BlockType Integrator - Name "Integrator" - SID "844" - Ports [1, 1] - Position [240, 360, 270, 390] - ZOrder 39 - } - Block { - BlockType Scope - Name "Scope" - SID "836" - Ports [1] - Position [1065, 374, 1095, 406] - ZOrder 31 - Floating off - Location [680, 330, 1240, 750] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-0.0001" - YMax "0.00021" - SaveName "ScopeData1" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope1" - SID "838" - Ports [1] - Position [1250, 344, 1280, 376] - ZOrder 33 - Floating off - Location [306, 114, 866, 534] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-0.0001" - YMax "0.00021" - SaveName "ScopeData2" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope2" - SID "840" - Ports [1] - Position [1290, 249, 1320, 281] - ZOrder 35 - Floating off - Location [680, 330, 1240, 750] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-1.00000" - YMax "1.00000" - SaveName "ScopeData3" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope3" - SID "842" - Ports [1] - Position [915, 439, 945, 471] - ZOrder 37 - Floating off - Location [306, 114, 866, 534] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-1.00000" - YMax "1.00000" - SaveName "ScopeData4" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope4" - SID "843" - Ports [1] - Position [840, 389, 870, 421] - ZOrder 38 - Floating off - Location [306, 114, 866, 534] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-0.00912" - YMax "0.01325" - SaveName "ScopeData5" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope5" - SID "845" - Ports [1] - Position [295, 359, 325, 391] - ZOrder 40 - Floating off - Location [306, 114, 866, 534] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-1.00000" - YMax "1.00000" - SaveName "ScopeData6" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Sum - Name "Sum" - SID "666" - Ports [2, 1] - Position [950, 285, 970, 305] - ZOrder 7 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum1" - SID "667" - Ports [2, 1] - Position [950, 200, 970, 220] - ZOrder 8 - ShowName off - IconShape "round" - Inputs "++|" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum2" - SID "668" - Ports [2, 1] - Position [830, 285, 850, 305] - ZOrder 11 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum3" - SID "669" - Ports [2, 1] - Position [830, 200, 850, 220] - ZOrder 12 - ShowName off - IconShape "round" - Inputs "++|" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType RandomNumber - Name "accelerometer_noise" - SID "670" - Position [890, 140, 920, 170] - ZOrder 2 - Mean "zeros(3,1)" - Variance "[ 3e-7 ; 3.3e-7 ; 7.2e-7 ] " - Seed "[0,1,2]" - SampleTime "5e-3" - } - Block { - BlockType Quantizer - Name "accelerometer_quantizer" - SID "671" - Position [1030, 195, 1060, 225] - ZOrder 9 - QuantizationInterval "2.4400e-04" - } - Block { - BlockType ZeroOrderHold - Name "accelerometer_sampling" - SID "672" - Position [755, 195, 790, 225] - ZOrder 15 - SampleTime "5e-3" - } - Block { - BlockType RandomNumber - Name "gyroscope_noise" - SID "673" - Position [890, 315, 920, 345] - ZOrder 6 - Mean "zeros(3,1)" - Variance "[ 2.2e-8 ; 1.1e-7 ; 2.4e-8 ]" - Seed "[0,1,2]" - SampleTime "5e-3" - } - Block { - BlockType Quantizer - Name "gyroscope_qunatizer" - SID "674" - Position [1030, 280, 1060, 310] - ZOrder 10 - QuantizationInterval "1.1e-3" - } - Block { - BlockType ZeroOrderHold - Name "gyroscope_sampling" - SID "675" - Position [755, 280, 790, 310] - ZOrder 16 - SampleTime "5e-3" - } - Block { - BlockType Constant - Name "r_oc" - SID "676" - Position [30, 307, 95, 333] - ZOrder 28 - Value "zeros(3,1)" - } - Block { - BlockType Outport - Name "accelerometer" - SID "677" - Position [1100, 203, 1130, 217] - ZOrder 29 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "gyroscope" - SID "678" - Position [1100, 288, 1130, 302] - ZOrder 21 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 3 - SrcBlock "accelerometer_noise" - SrcPort 1 - Points [35, 0] - DstBlock "Sum1" - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock "Sum" - SrcPort 1 - Points [22, 0] - Branch { - ZOrder 39 - Points [0, 65] - DstBlock "Discrete-Time\nIntegrator1" - DstPort 1 - } - Branch { - ZOrder 38 - DstBlock "gyroscope_qunatizer" - DstPort 1 - } - } - Line { - ZOrder 5 - SrcBlock "Sum2" - SrcPort 1 - DstBlock "Sum" - DstPort 1 - } - Line { - ZOrder 6 - SrcBlock "Sum3" - SrcPort 1 - DstBlock "Sum1" - DstPort 2 - } - Line { - ZOrder 8 - SrcBlock "gyroscope_noise" - SrcPort 1 - Points [28, 0] - Branch { - ZOrder 35 - Points [0, 60] - DstBlock "Discrete-Time\nIntegrator" - DstPort 1 - } - Branch { - ZOrder 34 - Points [7, 0] - DstBlock "Sum" - DstPort 2 - } - } - Line { - ZOrder 10 - SrcBlock "Sum1" - SrcPort 1 - DstBlock "accelerometer_quantizer" - DstPort 1 - } - Line { - ZOrder 11 - SrcBlock "gyroscope_sampling" - SrcPort 1 - Points [8, 0] - Branch { - ZOrder 45 - Points [0, -29; -1, 0] - Branch { - ZOrder 52 - Points [0, -1] - DstBlock "Discrete-Time\nIntegrator2" - DstPort 1 - } - Branch { - ZOrder 51 - Points [-81, 0; 0, 189; 72, 0] - Branch { - ZOrder 47 - Points [0, -50] - DstBlock "Scope4" - DstPort 1 - } - Branch { - ZOrder 46 - DstBlock "Discrete-Time\nIntegrator3" - DstPort 1 - } - } - } - Branch { - ZOrder 44 - DstBlock "Sum2" - DstPort 1 - } - } - Line { - ZOrder 12 - SrcBlock "accelerometer_sampling" - SrcPort 1 - DstBlock "Sum3" - DstPort 2 - } - Line { - ZOrder 13 - SrcBlock "Ground" - SrcPort 1 - Points [5, 0] - DstBlock "Sum2" - DstPort 2 - } - Line { - ZOrder 14 - SrcBlock "Ground1" - SrcPort 1 - Points [5, 0] - DstBlock "Sum3" - DstPort 1 - } - Line { - ZOrder 15 - SrcBlock "B_vo_dot" - SrcPort 1 - DstBlock "\n\n\n\n\n\n\n" - DstPort 1 - } - Line { - ZOrder 16 - SrcBlock "B_vo" - SrcPort 1 - DstBlock "\n\n\n\n\n\n\n" - DstPort 2 - } - Line { - ZOrder 17 - SrcBlock "B_Omega" - SrcPort 1 - Points [48, 0] - Branch { - ZOrder 50 - Points [0, 125] - DstBlock "Integrator" - DstPort 1 - } - Branch { - ZOrder 49 - DstBlock "\n\n\n\n\n\n\n" - DstPort 3 - } - } - Line { - ZOrder 18 - SrcBlock "B_g" - SrcPort 1 - DstBlock "\n\n\n\n\n\n\n" - DstPort 4 - } - Line { - ZOrder 19 - SrcBlock "r_oc" - SrcPort 1 - DstBlock "\n\n\n\n\n\n\n" - DstPort 5 - } - Line { - ZOrder 36 - SrcBlock "Discrete-Time\nIntegrator" - SrcPort 1 - DstBlock "Scope" - DstPort 1 - } - Line { - ZOrder 37 - SrcBlock "Discrete-Time\nIntegrator1" - SrcPort 1 - DstBlock "Scope1" - DstPort 1 - } - Line { - ZOrder 40 - SrcBlock "Discrete-Time\nIntegrator2" - SrcPort 1 - DstBlock "Scope2" - DstPort 1 - } - Line { - ZOrder 43 - SrcBlock "Discrete-Time\nIntegrator3" - SrcPort 1 - DstBlock "Scope3" - DstPort 1 - } - Line { - ZOrder 48 - SrcBlock "Integrator" - SrcPort 1 - DstBlock "Scope5" - DstPort 1 - } - Line { - ZOrder 64 - SrcBlock "gyroscope_qunatizer" - SrcPort 1 - DstBlock "gyroscope" - DstPort 1 - } - Line { - ZOrder 65 - SrcBlock "accelerometer_quantizer" - SrcPort 1 - DstBlock "accelerometer" - DstPort 1 - } - Line { - ZOrder 79 - SrcBlock "\n\n\n\n\n\n\n" - SrcPort 1 - DstBlock "Discrete\nTransfer Fcn" - DstPort 1 - } - Line { - ZOrder 80 - SrcBlock "\n\n\n\n\n\n\n" - SrcPort 2 - DstBlock "Discrete\nTransfer Fcn1" - DstPort 1 - } - Line { - ZOrder 81 - SrcBlock "Discrete\nTransfer Fcn" - SrcPort 1 - DstBlock "Delay" - DstPort 1 - } - Line { - ZOrder 82 - SrcBlock "Discrete\nTransfer Fcn1" - SrcPort 1 - DstBlock "Delay1" - DstPort 1 - } - Line { - ZOrder 83 - SrcBlock "Delay" - SrcPort 1 - DstBlock "accelerometer_sampling" - DstPort 1 - } - Line { - ZOrder 84 - SrcBlock "Delay1" - SrcPort 1 - DstBlock "gyroscope_sampling" - DstPort 1 - } - } - } - Block { - BlockType Mux - Name "Mux" - SID "736" - Ports [3, 1] - Position [2455, 608, 2460, 682] - ZOrder 301 - ShowName off - Inputs "3" - DisplayOption "bar" - } - Block { - BlockType SubSystem - Name "OptiTrack Camera System\n\n " - SID "681" - Ports [2, 2] - Position [1720, 906, 1950, 1039] - ZOrder 299 - ShowName off - RequestExecContextInheritance off - Object { - $PropName "MaskObject" - $ObjectID 28 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{E}r_o', 'texmode', 'on');\nport_label('input', 2, '\\psi', 'texmode', 'on" - "');\nport_label('output', 1, '^{E}r_o camera', 'texmode', 'on');\nport_label('output', 2, '\\psi camera', 'texmod" - "e', 'on');\ndisp('OptiTrack Camera System', 'texmode', 'on');" - } - System { - Name "OptiTrack Camera System\n\n " - Location [69, 48, 1812, 988] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "150" - Block { - BlockType Inport - Name "E_ro" - SID "682" - Position [295, 238, 325, 252] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "yaw" - SID "683" - Position [295, 338, 325, 352] - ZOrder 4 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType RandomNumber - Name "E_ro_noise" - SID "684" - Position [545, 175, 575, 205] - ZOrder 30 - Mean "zeros(3,1)" - Variance "[ 7.9664e-10 ; 1.1928e-10 ; 5.0636e-10 ] " - Seed "[0,1,2]" - SampleTime "0.01" - } - Block { - BlockType Quantizer - Name "E_ro_quantizer" - SID "685" - Position [685, 230, 715, 260] - ZOrder 34 - QuantizationInterval "2.4400e-04" - } - Block { - BlockType ZeroOrderHold - Name "E_ro_sampling" - SID "686" - Position [410, 230, 445, 260] - ZOrder 38 - SampleTime "0.01" - } - Block { - BlockType Ground - Name "Ground1" - SID "687" - Position [465, 180, 485, 200] - ZOrder 42 - } - Block { - BlockType Ground - Name "Ground2" - SID "688" - Position [465, 390, 485, 410] - ZOrder 56 - } - Block { - BlockType Sum - Name "Sum1" - SID "689" - Ports [2, 1] - Position [605, 235, 625, 255] - ZOrder 33 - ShowName off - IconShape "round" - Inputs "++|" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum3" - SID "690" - Ports [2, 1] - Position [485, 235, 505, 255] - ZOrder 37 - ShowName off - IconShape "round" - Inputs "++|" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum4" - SID "691" - Ports [2, 1] - Position [605, 335, 625, 355] - ZOrder 47 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum6" - SID "692" - Ports [2, 1] - Position [485, 335, 505, 355] - ZOrder 51 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType RandomNumber - Name "yaw_noise" - SID "693" - Position [545, 365, 575, 395] - ZOrder 46 - Mean "zeros(3,1)" - Variance "1.0783e-9*ones(3,1)" - SampleTime "0.01" - } - Block { - BlockType Quantizer - Name "yaw_quantizer" - SID "694" - Position [685, 330, 715, 360] - ZOrder 50 - QuantizationInterval "1.1e-3" - } - Block { - BlockType ZeroOrderHold - Name "yaw_sampling" - SID "695" - Position [410, 330, 445, 360] - ZOrder 54 - SampleTime "0.01" - } - Block { - BlockType Outport - Name "E_ro_camera" - SID "696" - Position [800, 238, 830, 252] - ZOrder 43 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "yaw_camera" - SID "697" - Position [800, 338, 830, 352] - ZOrder 55 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 2 - SrcBlock "E_ro_noise" - SrcPort 1 - Points [35, 0] - DstBlock "Sum1" - DstPort 1 - } - Line { - ZOrder 3 - SrcBlock "Sum3" - SrcPort 1 - DstBlock "Sum1" - DstPort 2 - } - Line { - ZOrder 4 - SrcBlock "Sum1" - SrcPort 1 - DstBlock "E_ro_quantizer" - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock "E_ro_sampling" - SrcPort 1 - DstBlock "Sum3" - DstPort 2 - } - Line { - ZOrder 6 - SrcBlock "Ground1" - SrcPort 1 - Points [5, 0] - DstBlock "Sum3" - DstPort 1 - } - Line { - ZOrder 8 - SrcBlock "Sum4" - SrcPort 1 - DstBlock "yaw_quantizer" - DstPort 1 - } - Line { - ZOrder 9 - SrcBlock "Sum6" - SrcPort 1 - DstBlock "Sum4" - DstPort 1 - } - Line { - ZOrder 10 - SrcBlock "yaw_noise" - SrcPort 1 - Points [35, 0] - DstBlock "Sum4" - DstPort 2 - } - Line { - ZOrder 11 - SrcBlock "yaw_sampling" - SrcPort 1 - DstBlock "Sum6" - DstPort 1 - } - Line { - ZOrder 12 - SrcBlock "Ground2" - SrcPort 1 - Points [5, 0] - DstBlock "Sum6" - DstPort 2 - } - Line { - ZOrder 17 - SrcBlock "yaw" - SrcPort 1 - DstBlock "yaw_sampling" - DstPort 1 - } - Line { - ZOrder 18 - SrcBlock "E_ro" - SrcPort 1 - DstBlock "E_ro_sampling" - DstPort 1 - } - Line { - ZOrder 19 - SrcBlock "E_ro_quantizer" - SrcPort 1 - DstBlock "E_ro_camera" - DstPort 1 - } - Line { - ZOrder 20 - SrcBlock "yaw_quantizer" - SrcPort 1 - DstBlock "yaw_camera" - DstPort 1 - } - } - } - Block { - BlockType Scope - Name "Scope" - SID "737" - Ports [1] - Position [1385, 669, 1415, 701] - ZOrder 270 - Floating off - Location [680, 330, 1240, 750] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-0.00277" - YMax "0.00209" - SaveName "ScopeData1" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope1" - SID "738" - Ports [1] - Position [1385, 599, 1415, 631] - ZOrder 271 - Floating off - Location [10, 76, 1918, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-2.04337" - YMax "0.22704" - SaveName "ScopeData2" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope2" - SID "849" - Ports [1] - Position [2550, 534, 2580, 566] - ZOrder 308 - Floating off - Location [1, 76, 1921, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-182.40701" - YMax "117.99145" - SaveName "ScopeData7" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope3" - SID "739" - Ports [1] - Position [2255, 534, 2285, 566] - ZOrder 278 - Floating off - Location [1, 76, 1921, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-0.05134" - YMax "0.44242" - SaveName "ScopeData4" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope6" - SID "740" - Ports [1] - Position [1955, 469, 1985, 501] - ZOrder 280 - Floating off - Location [1, 76, 1909, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-1.00000" - YMax "1.00000" - SaveName "ScopeData5" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope7" - SID "741" - Ports [1] - Position [1955, 544, 1985, 576] - ZOrder 281 - Floating off - Location [1, 76, 1909, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-1.00000" - YMax "1.00000" - SaveName "ScopeData6" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType S-Function - Name "Soft Real Time" - SID "742" - Ports [] - Position [2618, 735, 2705, 766] - ZOrder 288 - ShowName off - Commented "on" - FunctionName "sfun_time" - Parameters "x" - Object { - $PropName "MaskObject" - $ObjectID 29 - $ClassName "Simulink.Mask" - Display "color('red')\ndisp('Soft Real Time')\n" - Object { - $PropName "Parameters" - $ObjectID 30 - $ClassName "Simulink.MaskParameter" - Type "edit" - Name "x" - Prompt "Time Scaling Factor" - Value "1" - } - } - } - Block { - BlockType Outport - Name "euler_angles_filtered" - SID "743" - Position [2535, 638, 2565, 652] - ZOrder 262 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "euler_rates" - SID "744" - Position [1395, 798, 1430, 812] - ZOrder 259 - ForegroundColor "red" - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "current_position" - SID "745" - Position [2335, 963, 2365, 977] - ZOrder 289 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "camera_euler" - SID "904" - Position [2430, 1038, 2460, 1052] - ZOrder 317 - Port "4" - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "IMU\n\n\n\n\n\n" - SrcPort 1 - Points [23, 0] - Branch { - ZOrder 2 - Points [0, -70] - DstBlock "Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1" - DstPort 1 - } - Branch { - ZOrder 3 - Points [0, 25] - DstBlock "Scope1" - DstPort 1 - } - } - Line { - ZOrder 4 - SrcBlock "IMU\n\n\n\n\n\n" - SrcPort 2 - Points [15, 0] - Branch { - ZOrder 5 - Points [0, -35] - DstBlock "Scope" - DstPort 1 - } - Branch { - ZOrder 6 - Points [19, 0] - Branch { - ZOrder 160 - Points [0, 85] - DstBlock "euler_rates" - DstPort 1 - } - Branch { - ZOrder 159 - DstBlock "Aeb\n\n\n\n\n\n\n\n\n\n" - DstPort 1 - } - } - } - Line { - ZOrder 8 - SrcBlock "B_vo" - SrcPort 1 - DstBlock "IMU\n\n\n\n\n\n" - DstPort 2 - } - Line { - ZOrder 9 - SrcBlock "B_Omega" - SrcPort 1 - DstBlock "IMU\n\n\n\n\n\n" - DstPort 3 - } - Line { - ZOrder 10 - SrcBlock "B_g" - SrcPort 1 - DstBlock "IMU\n\n\n\n\n\n" - DstPort 4 - } - Line { - ZOrder 11 - SrcBlock "Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1" - SrcPort 2 - Points [17, 0] - Branch { - ZOrder 12 - Points [0, 60] - DstBlock "Delay1" - DstPort 1 - } - Branch { - ZOrder 13 - Points [31, 0] - Branch { - ZOrder 14 - Points [82, 0] - DstBlock "Complimentary Filter\n\n\n\n\n\n\n\n" - DstPort 2 - } - Branch { - ZOrder 15 - Points [0, -35] - DstBlock "Scope7" - DstPort 1 - } - } - } - Line { - ZOrder 16 - SrcBlock "Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1" - SrcPort 1 - Points [47, 0] - Branch { - ZOrder 17 - Points [83, 0] - DstBlock "Complimentary Filter\n\n\n\n\n\n\n\n" - DstPort 1 - } - Branch { - ZOrder 18 - Points [0, -35] - DstBlock "Scope6" - DstPort 1 - } - } - Line { - ZOrder 25 - SrcBlock "Delay1" - SrcPort 1 - Points [-199, 0; 0, -60] - DstBlock "Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1" - DstPort 2 - } - Line { - ZOrder 26 - SrcBlock "euler_angles" - SrcPort 1 - Points [23, 0] - Branch { - ZOrder 210 - Points [0, -45] - DstBlock "OptiTrack Camera System\n\n " - DstPort 2 - } - Branch { - ZOrder 27 - Points [0, 70] - DstBlock "3D Graphical Simulation" - DstPort 2 - } - Branch { - ZOrder 28 - DstBlock "Demux" - DstPort 1 - } - } - Line { - ZOrder 29 - SrcBlock "Complimentary Filter\n\n\n\n\n\n\n\n" - SrcPort 1 - Points [16, 0] - Branch { - ZOrder 77 - Points [0, 222; -789, 0; 0, -77] - DstBlock "Aeb\n\n\n\n\n\n\n\n\n\n" - DstPort 2 - } - Branch { - ZOrder 30 - DstBlock "Demux1" - DstPort 1 - } - Branch { - ZOrder 69 - Points [0, -85] - DstBlock "Scope3" - DstPort 1 - } - } - Line { - ZOrder 33 - SrcBlock "First-Order\nHold" - SrcPort 1 - Points [50, 0] - DstBlock "3D Graphical Simulation1" - DstPort 1 - } - Line { - ZOrder 34 - SrcBlock "E_ro" - SrcPort 1 - Points [196, 0] - Branch { - ZOrder 35 - Points [0, 120] - DstBlock "3D Graphical Simulation" - DstPort 1 - } - Branch { - ZOrder 36 - Points [0, -30] - DstBlock "OptiTrack Camera System\n\n " - DstPort 1 - } - } - Line { - ZOrder 38 - SrcBlock "First-Order\nHold1" - SrcPort 1 - Points [30, 0; 0, -30] - DstBlock "3D Graphical Simulation1" - DstPort 2 - } - Line { - ZOrder 39 - SrcBlock "Demux1" - SrcPort 1 - DstBlock "Mux" - DstPort 1 - } - Line { - ZOrder 40 - SrcBlock "Demux1" - SrcPort 2 - DstBlock "Mux" - DstPort 2 - } - Line { - ZOrder 41 - SrcBlock "OptiTrack Camera System\n\n " - SrcPort 2 - Points [70, 0; 0, 10] - DstBlock "Delay4" - DstPort 1 - } - Line { - ZOrder 42 - SrcBlock "Mux" - SrcPort 1 - Points [31, 0] - Branch { - ZOrder 117 - Points [0, -95] - DstBlock "Scope2" - DstPort 1 - } - Branch { - ZOrder 98 - Points [0, 150] - DstBlock "First-Order\nHold" - DstPort 1 - } - Branch { - ZOrder 97 - DstBlock "euler_angles_filtered" - DstPort 1 - } - } - Line { - ZOrder 45 - SrcBlock "OptiTrack Camera System\n\n " - SrcPort 1 - Points [48, 0; 0, 30] - DstBlock "Delay3" - DstPort 1 - } - Line { - ZOrder 62 - SrcBlock "B_vo_dot" - SrcPort 1 - DstBlock "Delay2" - DstPort 1 - } - Line { - ZOrder 63 - SrcBlock "Delay2" - SrcPort 1 - DstBlock "IMU\n\n\n\n\n\n" - DstPort 1 - } - Line { - ZOrder 202 - SrcBlock "Aeb\n\n\n\n\n\n\n\n\n\n" - SrcPort 1 - DstBlock "Discrete-Time\nIntegrator" - DstPort 1 - } - Line { - ZOrder 201 - SrcBlock "Discrete-Time\nIntegrator" - SrcPort 1 - Points [20, 0; 0, -15] - DstBlock "Complimentary Filter\n\n\n\n\n\n\n\n" - DstPort 3 - } - Line { - ZOrder 203 - SrcBlock "Delay3" - SrcPort 1 - Points [183, 0] - Branch { - ZOrder 100 - Points [0, -80] - DstBlock "First-Order\nHold1" - DstPort 1 - } - Branch { - ZOrder 99 - DstBlock "current_position" - DstPort 1 - } - } - Line { - ZOrder 211 - SrcBlock "Delay4" - SrcPort 1 - Points [81, 0; 0, 16] - Branch { - ZOrder 214 - Points [144, 0; 0, 14] - DstBlock "camera_euler" - DstPort 1 - } - Branch { - ZOrder 213 - Points [0, 34] - DstBlock "Demux2" - DstPort 1 - } - } - Line { - ZOrder 212 - SrcBlock "Demux2" - SrcPort 3 - Points [14, 0; 0, -415] - DstBlock "Mux" - DstPort 3 - } - } - } - Block { - BlockType SubSystem - Name "Actuation" - SID "436" - Ports [1, 6] - Position [850, 276, 1100, 504] - ZOrder 71 - ShowName off - RequestExecContextInheritance off - Object { - $PropName "MaskObject" - $ObjectID 31 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Rotor Duty Cycles', 'texmode', 'on');\nport_label('output', 1, '^{B}Omega', 'texmo" - "de', 'on');\nport_label('output', 2, '\\Theta', 'texmode', 'on');\nport_label('output', 3, '^{B}v_o', 'texmode', 'on'" - ");\nport_label('output', 4, '^{E}r_o', 'texmode', 'on');\nport_label('output', 5, '^{B}dv_o/dt', 'texmode', 'on');\np" - "ort_label('output', 6, '^{B}g', 'texmode', 'on');\ndisp('Actuation', 'texmode', 'on'); " - } - System { - Name "Actuation" - Location [108, 36, 1850, 976] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "80" - Block { - BlockType Inport - Name "Rotor Duty Cycles" - SID "437" - Position [20, 393, 50, 407] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SID "446" - Ports [2, 1] - Position [1435, 303, 1670, 452] - ZOrder 81 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ExplicitOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Object { - $PropName "MaskObject" - $ObjectID 32 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^B\\Omega', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode'," - " 'on');\nport_label('output', 1, 'd\\Theta/dt', 'texmode', 'on');\ndisp('A_{EB}', 'texmode', 'on');" - } - System { - Name "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "25" - Block { - BlockType Inport - Name "B_omega" - SID "446::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles" - SID "446::22" - Position [20, 136, 40, 154] - ZOrder 13 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "446::24" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 15 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "446::23" - Tag "Stateflow S-Function test_model_R2015A 7" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 14 - FunctionName "sf_sfun" - PortCounts "[2 2]" - EnableBusSupport on - Port { - PortNumber 2 - Name "euler_rates" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "446::25" - Position [460, 241, 480, 259] - ZOrder 16 - } - Block { - BlockType Outport - Name "euler_rates" - SID "446::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "B_omega" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "euler_angles" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "euler_rates" - ZOrder 3 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "euler_rates" - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType Demux - Name "Demux1" - SID "449" - Ports [1, 3] - Position [1870, 526, 1875, 574] - ZOrder 107 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "x position" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "y position" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "z position" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux2" - SID "450" - Ports [1, 3] - Position [1870, 301, 1875, 349] - ZOrder 109 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "Roll" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "Pitch" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "Yaw" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux3" - SID "451" - Ports [1, 3] - Position [1870, 406, 1875, 454] - ZOrder 117 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "Body x velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "Body y velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "Body z velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux4" - SID "452" - Ports [1, 3] - Position [1870, 161, 1875, 209] - ZOrder 115 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "Body roll velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "Body pitch velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "Body yaw velocity" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Demux - Name "Demux5" - SID "453" - Ports [1, 3] - Position [1870, 641, 1875, 689] - ZOrder 119 - ShowName off - Outputs "3" - DisplayOption "bar" - Port { - PortNumber 1 - Name "Body x acceleration" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 2 - Name "Body y acceleration" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "Body z acceleration" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType SubSystem - Name "ESC System" - SID "442" - Ports [1, 1] - Position [95, 282, 330, 518] - ZOrder 36 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ExplicitOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Object { - $PropName "MaskObject" - $ObjectID 33 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Rotor Duty Cycle', 'texmode', 'on');\nport_label('output', 1, 'Vb_{eff}', '" - "texmode', 'on');\ndisp('ESC System');" - } - System { - Name "ESC System" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "37" - Block { - BlockType Inport - Name "rotor_duty_cycles" - SID "442::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "442::36" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 17 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "442::35" - Tag "Stateflow S-Function test_model_R2015A 4" - Ports [1, 2] - Position [180, 105, 230, 165] - ZOrder 16 - FunctionName "sf_sfun" - Parameters "Pmax,Pmin,Vb" - PortCounts "[1 2]" - EnableBusSupport on - Port { - PortNumber 2 - Name "Vb_eff" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "442::37" - Position [460, 241, 480, 259] - ZOrder 18 - } - Block { - BlockType Outport - Name "Vb_eff" - SID "442::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 34 - SrcBlock "rotor_duty_cycles" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - Name "Vb_eff" - ZOrder 35 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "Vb_eff" - DstPort 1 - } - Line { - ZOrder 36 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 37 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Gravity\n\n" - SID "443" - Ports [0, 1] - Position [375, 664, 525, 786] - ZOrder 96 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ExplicitOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Object { - $PropName "MaskObject" - $ObjectID 34 - $ClassName "Simulink.Mask" - Display "port_label('output', 1, '^EF_g', 'texmode', 'on');\nfprintf('Gravity');\n" - } - System { - Name "Gravity\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "30" - Block { - BlockType Demux - Name " Demux " - SID "443::28" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 19 - Outputs "1" - } - Block { - BlockType Ground - Name " Ground " - SID "443::30" - Position [20, 121, 40, 139] - ZOrder 21 - } - Block { - BlockType S-Function - Name " SFunction " - SID "443::27" - Tag "Stateflow S-Function test_model_R2015A 1" - Ports [1, 2] - Position [180, 100, 230, 160] - ZOrder 18 - FunctionName "sf_sfun" - Parameters "g,m" - PortCounts "[1 2]" - EnableBusSupport on - Port { - PortNumber 2 - Name "E_Fg" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "443::29" - Position [460, 241, 480, 259] - ZOrder 20 - } - Block { - BlockType Outport - Name "E_Fg" - SID "443::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - Name "E_Fg" - ZOrder 1 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "E_Fg" - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock " Ground " - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 3 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType Integrator - Name "Integrator" - SID "454" - Ports [1, 1] - Position [770, 340, 800, 370] - ZOrder 49 - InitialCondition "[omega_o, omega_o, omega_o, omega_o]" - } - Block { - BlockType Integrator - Name "Integrator1" - SID "455" - Ports [1, 1] - Position [1265, 445, 1295, 475] - ZOrder 53 - InitialCondition "[0; 0; 0]" - } - Block { - BlockType Integrator - Name "Integrator2" - SID "456" - Ports [1, 1] - Position [1265, 325, 1295, 355] - ZOrder 54 - InitialCondition "[0; 0; 0]" - } - Block { - BlockType Integrator - Name "Integrator3" - SID "457" - Ports [1, 1] - Position [1725, 590, 1755, 620] - ZOrder 98 - InitialCondition "[0; 0; 0]" - } - Block { - BlockType Integrator - Name "Integrator4" - SID "458" - Ports [1, 1] - Position [1725, 365, 1755, 395] - ZOrder 77 - InitialCondition "[0; 0; 0]" - ContinuousStateAttributes "['phi' 'theta' 'psi']" - } - Block { - BlockType SubSystem - Name "Lbe\n\n\n\n\n\n" - SID "444" - Ports [2, 1] - Position [1435, 499, 1670, 706] - ZOrder 75 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ExplicitOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Object { - $PropName "MaskObject" - $ObjectID 35 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^Bv_o', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on" - "');\nport_label('output', 1, '^Ev_o', 'texmode', 'on');\ndisp('L_{EB}', 'texmode', 'on');" - } - System { - Name "Lbe\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "31" - Block { - BlockType Inport - Name "B_vo" - SID "444::24" - Position [20, 101, 40, 119] - ZOrder 15 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles" - SID "444::28" - Position [20, 136, 40, 154] - ZOrder 19 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "444::30" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 21 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "444::29" - Tag "Stateflow S-Function test_model_R2015A 2" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 20 - FunctionName "sf_sfun" - PortCounts "[2 2]" - EnableBusSupport on - Port { - PortNumber 2 - Name "E_ro" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "444::31" - Position [460, 241, 480, 259] - ZOrder 22 - } - Block { - BlockType Outport - Name "E_ro" - SID "444::26" - Position [460, 101, 480, 119] - ZOrder 17 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "B_vo" - SrcPort 1 - Points [120, 0] - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "euler_angles" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "E_ro" - ZOrder 3 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "E_ro" - DstPort 1 - } - Line { - ZOrder 4 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SID "447" - Ports [2, 2] - Position [640, 694, 810, 816] - ZOrder 97 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ExplicitOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Object { - $PropName "MaskObject" - $ObjectID 36 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^EF_g', 'texmode', 'on');\nport_label('input', 2, '\\Theta', 'texmode', 'on" - "');\nport_label('output', 1, '^BF_g', 'texmode', 'on');\ndisp('L_{BE}', 'texmode', 'on');" - } - System { - Name "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "33" - Block { - BlockType Inport - Name "E_Fg" - SID "447::24" - Position [20, 101, 40, 119] - ZOrder 15 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles" - SID "447::28" - Position [20, 136, 40, 154] - ZOrder 19 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "447::30" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 21 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "447::29" - Tag "Stateflow S-Function test_model_R2015A 8" - Ports [2, 3] - Position [180, 100, 230, 180] - ZOrder 20 - FunctionName "sf_sfun" - Parameters "m" - PortCounts "[2 3]" - EnableBusSupport on - Port { - PortNumber 2 - Name "B_Fg" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "B_g" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "447::31" - Position [460, 241, 480, 259] - ZOrder 22 - } - Block { - BlockType Outport - Name "B_Fg" - SID "447::26" - Position [460, 101, 480, 119] - ZOrder 17 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "B_g" - SID "447::32" - Position [460, 136, 480, 154] - ZOrder 23 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "E_Fg" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "euler_angles" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "B_Fg" - ZOrder 3 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "B_Fg" - DstPort 1 - } - Line { - Name "B_g" - ZOrder 4 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 3 - DstBlock "B_g" - DstPort 1 - } - Line { - ZOrder 5 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 6 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Motor System" - SID "441" - Ports [2, 1] - Position [460, 280, 680, 520] - ZOrder 48 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ExplicitOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Object { - $PropName "MaskObject" - $ObjectID 37 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Vb_{eff}', 'texmode', 'on');\nport_label('input', 2, '\\omega', 'texmode', " - "'on');\nport_label('output', 1, '\\alpha', 'texmode', 'on');\ndisp('Motor System');\n" - } - System { - Name "Motor System" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "35" - Block { - BlockType Inport - Name "Vb_eff" - SID "441::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "angular_velocity" - SID "441::35" - Position [20, 136, 40, 154] - ZOrder 20 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "441::32" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 17 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "441::31" - Tag "Stateflow S-Function test_model_R2015A 5" - Ports [2, 2] - Position [180, 100, 230, 160] - ZOrder 16 - FunctionName "sf_sfun" - Parameters "If,Jreq,Kd,Kq,Kv,Rm" - PortCounts "[2 2]" - EnableBusSupport on - Port { - PortNumber 2 - Name "angular_acceleration" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "441::33" - Position [460, 241, 480, 259] - ZOrder 18 - } - Block { - BlockType Outport - Name "angular_acceleration" - SID "441::23" - Position [460, 101, 480, 119] - ZOrder 14 - IconDisplay "Port number" - } - Line { - ZOrder 33 - SrcBlock "Vb_eff" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 34 - SrcBlock "angular_velocity" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - Name "angular_acceleration" - ZOrder 35 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "angular_acceleration" - DstPort 1 - } - Line { - ZOrder 36 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 37 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Rotor System\n\n\n\n\n\n\n\n" - SID "758" - Ports [5, 2] - Position [985, 281, 1185, 519] - ZOrder 122 - ShowName off - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ExplicitOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - Object { - $PropName "MaskObject" - $ObjectID 38 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '\\alpha', 'texmode', 'on');\nport_label('input', 2, '\\omega', 'texmode', '" - "on');\nport_label('input', 3, '^BF_g', 'texmode', 'on');\nport_label('input', 4, '^B\\Omega', 'texmode', 'on');\n" - "port_label('input', 5, '^Bv_o', 'texmode', 'on');\nport_label('output', 1, '^Bd\\Omega/dt', 'texmode', 'on');\npo" - "rt_label('output', 2, '^Bdv_o/dt', 'texmode', 'on');\ndisp('Rotor System', 'texmode', 'on');" - } - System { - Name "Rotor System\n\n\n\n\n\n\n\n" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "50" - Block { - BlockType Inport - Name "angular_acceleration" - SID "758::27" - Position [20, 101, 40, 119] - ZOrder 18 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "angular_velocity" - SID "758::28" - Position [20, 136, 40, 154] - ZOrder 19 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_Fg" - SID "758::47" - Position [20, 171, 40, 189] - ZOrder 20 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_omega" - SID "758::25" - Position [20, 206, 40, 224] - ZOrder 16 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "B_vo" - SID "758::24" - Position [20, 246, 40, 264] - ZOrder 15 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "758::49" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 22 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "758::48" - Tag "Stateflow S-Function test_model_R2015A 6" - Ports [5, 3] - Position [180, 100, 230, 220] - ZOrder 21 - FunctionName "sf_sfun" - Parameters "Jreq,Jxx,Jyy,Jzz,Kd,Kt,m,rhx,rhy,rhz" - PortCounts "[5 3]" - EnableBusSupport on - Port { - PortNumber 2 - Name "B_omega_dot" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - Port { - PortNumber 3 - Name "B_vo_dot" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "758::50" - Position [460, 241, 480, 259] - ZOrder 23 - } - Block { - BlockType Outport - Name "B_omega_dot" - SID "758::22" - Position [460, 101, 480, 119] - ZOrder 13 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "B_vo_dot" - SID "758::5" - Position [460, 136, 480, 154] - ZOrder -5 - Port "2" - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "angular_acceleration" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 2 - SrcBlock "angular_velocity" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - ZOrder 3 - SrcBlock "B_Fg" - SrcPort 1 - DstBlock " SFunction " - DstPort 3 - } - Line { - ZOrder 4 - SrcBlock "B_omega" - SrcPort 1 - DstBlock " SFunction " - DstPort 4 - } - Line { - ZOrder 5 - SrcBlock "B_vo" - SrcPort 1 - DstBlock " SFunction " - DstPort 5 - } - Line { - Name "B_omega_dot" - ZOrder 6 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "B_omega_dot" - DstPort 1 - } - Line { - Name "B_vo_dot" - ZOrder 7 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 3 - DstBlock "B_vo_dot" - DstPort 1 - } - Line { - ZOrder 8 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 9 - SrcBlock " SFunction " - SrcPort 1 - Points [20, 0] - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType Scope - Name "Scope" - SID "459" - Ports [1] - Position [390, 279, 420, 311] - ZOrder 46 - Floating off - Location [188, 365, 512, 604] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-1.3875" - YMax "12.4875" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope1" - SID "460" - Ports [1] - Position [780, 229, 810, 261] - ZOrder 50 - Floating off - Location [1, 76, 1909, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - ShowLegends on - YMin "-10513.81558" - YMax "11401.07279" - SaveName "ScopeData1" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope10" - SID "461" - Ports [3] - Position [1975, 303, 2015, 347] - ZOrder 108 - Floating off - Location [1, 76, 1909, 1039] - Open off - NumInputPorts "3" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - ShowLegends on - YMin "-60.66007~-1.00000~-1.00000" - YMax "18.5091~1.00000~1.00000" - SaveName "ScopeData1" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope11" - SID "462" - Ports [3] - Position [1975, 163, 2015, 207] - ZOrder 114 - Floating off - Location [1, 76, 1921, 1039] - Open off - NumInputPorts "3" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - ShowLegends on - YMin "-3.00603~-1.00000~-1.00000" - YMax "4.56766~1.00000~1.00000" - SaveName "ScopeData3" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope2" - SID "463" - Ports [1] - Position [930, 229, 960, 261] - ZOrder 51 - Floating off - Location [1, 76, 1921, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-88.20659" - YMax "679.8109" - SaveName "ScopeData2" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope3" - SID "464" - Ports [3] - Position [1975, 408, 2015, 452] - ZOrder 116 - Floating off - Location [1, 76, 1921, 1039] - Open off - NumInputPorts "3" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - ShowLegends on - YMin "-1.00000~-71.40595~-81.80792" - YMax "1.00000~93.1255~67.47699" - SaveName "ScopeData2" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope4" - SID "465" - Ports [3] - Position [1975, 643, 2015, 687] - ZOrder 118 - Floating off - Location [1, 76, 1921, 1039] - Open off - NumInputPorts "3" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - ShowLegends on - YMin "-1019.9483~-1019.9483~-1019.9483" - YMax "1049.2638~1049.2638~1049.2638" - SaveName "ScopeData4" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope6" - SID "466" - Ports [3] - Position [1975, 528, 2015, 572] - ZOrder 79 - Floating off - Location [1, 76, 1921, 1039] - Open off - NumInputPorts "3" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - axes2 "%<SignalLabel>" - axes3 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - ShowLegends on - YMin "-1.00000~-1.00000~-0.09265" - YMax "1.00000~1.00000~0.0667" - SaveName "ScopeData4" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope7" - SID "467" - Ports [1] - Position [575, 644, 605, 676] - ZOrder 99 - Floating off - Location [1, 76, 1921, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-1.45924" - YMax "13.13314" - SaveName "ScopeData1" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope8" - SID "468" - Ports [1] - Position [860, 629, 890, 661] - ZOrder 100 - Floating off - Location [1, 76, 1921, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-14.59237" - YMax "14.59237" - SaveName "ScopeData2" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope9" - SID "469" - Ports [1] - Position [1265, 229, 1295, 261] - ZOrder 102 - Floating off - Location [1, 76, 1921, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-9.72639" - YMax "9.72632" - SaveName "ScopeData3" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Outport - Name "B_omega" - SID "471" - Position [1855, 238, 1885, 252] - ZOrder 61 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "euler_angles" - SID "472" - Position [1910, 373, 1940, 387] - ZOrder 91 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "B_vo" - SID "473" - Position [1855, 468, 1885, 482] - ZOrder 58 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "E_ro" - SID "474" - Position [1870, 598, 1900, 612] - ZOrder 88 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "B_vo_dot" - SID "475" - Position [1870, 718, 1900, 732] - ZOrder 103 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "B_g" - SID "476" - Position [1870, 778, 1900, 792] - ZOrder 104 - Port "6" - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "ESC System" - SrcPort 1 - Points [23, 0; 0, -59] - Branch { - ZOrder 2 - Points [2, 0; 0, -46] - DstBlock "Scope" - DstPort 1 - } - Branch { - ZOrder 3 - Points [0, -1] - DstBlock "Motor System" - DstPort 1 - } - } - Line { - ZOrder 4 - SrcBlock "Motor System" - SrcPort 1 - Points [40, 0; 0, -45] - Branch { - ZOrder 5 - DstBlock "Integrator" - DstPort 1 - } - Branch { - ZOrder 6 - Points [0, -45] - Branch { - ZOrder 101 - DstBlock "Rotor System\n\n\n\n\n\n\n\n" - DstPort 1 - } - Branch { - ZOrder 7 - Points [0, -65] - DstBlock "Scope1" - DstPort 1 - } - } - } - Line { - ZOrder 9 - SrcBlock "Integrator" - SrcPort 1 - Points [68, 0] - Branch { - ZOrder 290 - Points [0, 210; -473, 0; 0, -105] - DstBlock "Motor System" - DstPort 2 - } - Branch { - ZOrder 292 - DstBlock "Rotor System\n\n\n\n\n\n\n\n" - DstPort 2 - } - Branch { - ZOrder 291 - Points [0, -110] - DstBlock "Scope2" - DstPort 1 - } - } - Line { - ZOrder 103 - SrcBlock "Rotor System\n\n\n\n\n\n\n\n" - SrcPort 1 - Points [39, 0] - Branch { - ZOrder 15 - Points [0, -95] - DstBlock "Scope9" - DstPort 1 - } - Branch { - ZOrder 16 - DstBlock "Integrator2" - DstPort 1 - } - } - Line { - ZOrder 22 - SrcBlock "Integrator2" - SrcPort 1 - Points [55, 0] - Branch { - ZOrder 105 - Points [0, 252; -416, 0; 0, -147] - DstBlock "Rotor System\n\n\n\n\n\n\n\n" - DstPort 4 - } - Branch { - ZOrder 23 - Points [0, -95; 454, 0] - Branch { - ZOrder 24 - DstBlock "B_omega" - DstPort 1 - } - Branch { - ZOrder 25 - Points [0, -60] - DstBlock "Demux4" - DstPort 1 - } - } - Branch { - ZOrder 27 - DstBlock "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - DstPort 1 - } - } - Line { - ZOrder 28 - SrcBlock "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SrcPort 1 - DstBlock "Integrator4" - DstPort 1 - } - Line { - ZOrder 29 - SrcBlock "Gravity\n\n" - SrcPort 1 - Points [7, 0] - Branch { - ZOrder 30 - Points [0, -65] - DstBlock "Scope7" - DstPort 1 - } - Branch { - ZOrder 31 - DstBlock "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - DstPort 1 - } - } - Line { - ZOrder 32 - SrcBlock "Lbe\n\n\n\n\n\n" - SrcPort 1 - DstBlock "Integrator3" - DstPort 1 - } - Line { - ZOrder 33 - SrcBlock "Integrator3" - SrcPort 1 - Points [64, 0] - Branch { - ZOrder 34 - Points [0, -55] - DstBlock "Demux1" - DstPort 1 - } - Branch { - ZOrder 35 - DstBlock "E_ro" - DstPort 1 - } - } - Line { - ZOrder 36 - SrcBlock "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SrcPort 1 - Points [24, 0; 0, -1] - Branch { - ZOrder 107 - Points [82, 0; 0, -324] - DstBlock "Rotor System\n\n\n\n\n\n\n\n" - DstPort 3 - } - Branch { - ZOrder 106 - Points [0, -79] - DstBlock "Scope8" - DstPort 1 - } - } - Line { - ZOrder 39 - SrcBlock "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - SrcPort 2 - DstBlock "B_g" - DstPort 1 - } - Line { - Name "y position" - ZOrder 45 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 2 - DstBlock "Scope6" - DstPort 2 - } - Line { - Name "x position" - ZOrder 46 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 1 - DstBlock "Scope6" - DstPort 1 - } - Line { - Name "z position" - ZOrder 47 - Labels [0, 0] - SrcBlock "Demux1" - SrcPort 3 - DstBlock "Scope6" - DstPort 3 - } - Line { - Name "Pitch" - ZOrder 57 - Labels [0, 0] - SrcBlock "Demux2" - SrcPort 2 - DstBlock "Scope10" - DstPort 2 - } - Line { - Name "Roll" - ZOrder 58 - Labels [0, 0] - SrcBlock "Demux2" - SrcPort 1 - DstBlock "Scope10" - DstPort 1 - } - Line { - Name "Yaw" - ZOrder 59 - Labels [0, 0] - SrcBlock "Demux2" - SrcPort 3 - DstBlock "Scope10" - DstPort 3 - } - Line { - Name "Body pitch velocity" - ZOrder 60 - Labels [0, 0] - SrcBlock "Demux4" - SrcPort 2 - DstBlock "Scope11" - DstPort 2 - } - Line { - Name "Body roll velocity" - ZOrder 61 - Labels [0, 0] - SrcBlock "Demux4" - SrcPort 1 - DstBlock "Scope11" - DstPort 1 - } - Line { - Name "Body yaw velocity" - ZOrder 62 - Labels [0, 0] - SrcBlock "Demux4" - SrcPort 3 - DstBlock "Scope11" - DstPort 3 - } - Line { - Name "Body y velocity" - ZOrder 63 - Labels [0, 0] - SrcBlock "Demux3" - SrcPort 2 - DstBlock "Scope3" - DstPort 2 - } - Line { - Name "Body x velocity" - ZOrder 64 - Labels [0, 0] - SrcBlock "Demux3" - SrcPort 1 - DstBlock "Scope3" - DstPort 1 - } - Line { - Name "Body z velocity" - ZOrder 65 - Labels [0, 0] - SrcBlock "Demux3" - SrcPort 3 - DstBlock "Scope3" - DstPort 3 - } - Line { - Name "Body y acceleration" - ZOrder 66 - Labels [0, 0] - SrcBlock "Demux5" - SrcPort 2 - DstBlock "Scope4" - DstPort 2 - } - Line { - Name "Body x acceleration" - ZOrder 67 - Labels [0, 0] - SrcBlock "Demux5" - SrcPort 1 - DstBlock "Scope4" - DstPort 1 - } - Line { - Name "Body z acceleration" - ZOrder 68 - Labels [0, 0] - SrcBlock "Demux5" - SrcPort 3 - DstBlock "Scope4" - DstPort 3 - } - Line { - ZOrder 69 - SrcBlock "Integrator1" - SrcPort 1 - Points [34, 0; 0, 90] - Branch { - ZOrder 104 - Points [-370, 0; 0, -60] - DstBlock "Rotor System\n\n\n\n\n\n\n\n" - DstPort 5 - } - Branch { - ZOrder 71 - Points [76, 0] - Branch { - ZOrder 72 - DstBlock "Lbe\n\n\n\n\n\n" - DstPort 1 - } - Branch { - ZOrder 73 - Points [0, -75; 401, 0] - Branch { - ZOrder 74 - Points [0, -45] - DstBlock "Demux3" - DstPort 1 - } - Branch { - ZOrder 75 - DstBlock "B_vo" - DstPort 1 - } - } - } - } - Line { - ZOrder 102 - SrcBlock "Rotor System\n\n\n\n\n\n\n\n" - SrcPort 2 - Points [27, 0] - Branch { - ZOrder 205 - Points [0, 265; 607, 0] - Branch { - ZOrder 201 - Points [0, -60] - DstBlock "Demux5" - DstPort 1 - } - Branch { - ZOrder 200 - DstBlock "B_vo_dot" - DstPort 1 - } - } - Branch { - ZOrder 198 - DstBlock "Integrator1" - DstPort 1 - } - } - Line { - ZOrder 48 - SrcBlock "Integrator4" - SrcPort 1 - Points [20, 0] - Branch { - ZOrder 277 - Points [60, 0] - Branch { - ZOrder 50 - Points [0, -55] - DstBlock "Demux2" - DstPort 1 - } - Branch { - ZOrder 51 - DstBlock "euler_angles" - DstPort 1 - } - } - Branch { - ZOrder 52 - Points [0, 502; -385, 0] - Branch { - ZOrder 352 - Points [0, -227] - Branch { - ZOrder 54 - DstBlock "Lbe\n\n\n\n\n\n" - DstPort 2 - } - Branch { - ZOrder 55 - Points [0, -240] - DstBlock "Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - DstPort 2 - } - } - Branch { - ZOrder 56 - Points [-787, 0; 0, -97] - DstBlock "Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - DstPort 2 - } - } - } - Line { - ZOrder 286 - SrcBlock "Rotor Duty Cycles" - SrcPort 1 - DstBlock "ESC System" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Communication System" - SID "582" - Ports [0, 1] - Position [405, 282, 460, 328] - ZOrder 70 - RequestExecContextInheritance off - Object { - $PropName "MaskObject" - $ObjectID 39 - $ClassName "Simulink.Mask" - Display "port_label('output', 1, 'Setpoints', 'texmode', 'on');" - } - System { - Name "Communication System" - Location [126, 17, 1868, 957] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "300" - Block { - BlockType Step - Name "Step" - SID "583" - Position [925, 390, 955, 420] - ZOrder 32 - Before "[0; 0; 0; 0]" - After "[1; 0; 0; 0]" - SampleTime "0.1" - } - Block { - BlockType Outport - Name "setpoints" - SID "584" - Position [1050, 398, 1080, 412] - ZOrder 6 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "Step" - SrcPort 1 - DstBlock "setpoints" - DstPort 1 - } - } - } - Block { - BlockType SubSystem - Name "Control System" - SID "573" - Ports [4, 1] - Position [540, 275, 795, 500] - ZOrder 69 - ShowName off - RequestExecContextInheritance off - Object { - $PropName "MaskObject" - $ObjectID 40 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, 'Setpoints', 'texmode', 'on');\nport_label('input', 2, '\\Theta_{filtered}', 'texmo" - "de', 'on');\nport_label('input', 3, 'd\\Theta_{gyro}/dt', 'texmode', 'on');\nport_label('input', 4, '^{E}r_o', 'texmo" - "de', 'on');\nport_label('output', 1, 'Motor Commands', 'texmode', 'on');\ndisp('Control System', 'texmode', 'on');" - } - System { - Name "Control System" - Location [69, 48, 1812, 988] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "125" - Block { - BlockType Inport - Name "setpoints" - SID "574" - Position [230, 353, 260, 367] - ZOrder 2 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_angles_filtered" - SID "575" - Position [230, 513, 260, 527] - ZOrder 9 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "euler_rates" - SID "576" - Position [215, 588, 245, 602] - ZOrder 11 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "current_position" - SID "577" - Position [215, 438, 245, 452] - ZOrder -1 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType SubSystem - Name "Controller" - SID "604" - Ports [13, 4] - Position [395, 307, 530, 633] - ZOrder 31 - RequestExecContextInheritance off - Object { - $PropName "MaskObject" - $ObjectID 41 - $ClassName "Simulink.Mask" - Display "port_label('input', 1, '^{E}r_{x,setpoint}', 'texmode', 'on');\nport_label('input', 2, '^{E}r_{y,se" - "tpoint}', 'texmode', 'on');\nport_label('input', 3, '^{E}r_{z,setpoint}', 'texmode', 'on');\nport_label('input', " - "4, '\\psi_{setpoint}', 'texmode', 'on');\nport_label('input', 5, '^{E}r_x', 'texmode', 'on');\nport_label('input'" - ", 6, '^{E}r_y', 'texmode', 'on');\nport_label('input', 7, '^{E}r_z', 'texmode', 'on');\nport_label('input', 8, '\\" - "phi', 'texmode', 'on');\nport_label('input', 9, '\\theta', 'texmode', 'on');\nport_label('input', 10, '\\psi', 't" - "exmode', 'on');\nport_label('input', 11, 'd\\phi/dt', 'texmode', 'on');\nport_label('input', 12, 'd\\theta/dt', '" - "texmode', 'on');\nport_label('input', 13, 'd\\psi/dt', 'texmode', 'on');\nport_label('output', 1, 'u_T', 'texmode" - "', 'on');\nport_label('output', 2, 'u_A', 'texmode', 'on');\nport_label('output', 3, 'u_E', 'texmode', 'on');\npo" - "rt_label('output', 4, 'u_R', 'texmode', 'on');\ndisp('Controller', 'texmode', 'on');" - } - System { - Name "Controller" - Location [69, 48, 1812, 988] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "125" - Block { - BlockType Inport - Name "x_setpoint" - SID "605" - Position [135, 403, 165, 417] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "y_setpoint" - SID "607" - Position [135, 248, 165, 262] - ZOrder 45 - ForegroundColor "gray" - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "z_setpoint" - SID "608" - Position [130, 128, 160, 142] - ZOrder 46 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "yaw_setpoint" - SID "632" - Position [130, 553, 160, 567] - ZOrder 103 - ForegroundColor "gray" - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "x_position" - SID "622" - Position [165, 468, 195, 482] - ZOrder 60 - Port "5" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "y_position" - SID "623" - Position [165, 313, 195, 327] - ZOrder 61 - Port "6" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "z_position" - SID "624" - Position [160, 183, 190, 197] - ZOrder 62 - Port "7" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "roll" - SID "630" - Position [300, 313, 330, 327] - ZOrder 68 - Port "8" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "pitch" - SID "631" - Position [300, 468, 330, 482] - ZOrder 69 - Port "9" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "yaw" - SID "649" - Position [160, 608, 190, 622] - ZOrder 105 - Port "10" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "roll_rate" - SID "633" - Position [525, 313, 555, 327] - ZOrder 71 - Port "11" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "pitch_rate" - SID "634" - Position [525, 468, 555, 482] - ZOrder 72 - Port "12" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "yaw_rate" - SID "635" - Position [300, 608, 330, 622] - ZOrder 73 - Port "13" - IconDisplay "Port number" - } - Block { - BlockType Gain - Name "Gain1" - SID "891" - Position [810, 117, 860, 153] - ZOrder 151 - Gain "5e4" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Gain - Name "Gain2" - SID "892" - Position [810, 237, 860, 273] - ZOrder 152 - Gain "5e4" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Gain - Name "Gain3" - SID "893" - Position [810, 392, 860, 428] - ZOrder 153 - Gain "5e4" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Gain - Name "Gain4" - SID "894" - Position [810, 542, 860, 578] - ZOrder 154 - Gain "5e4" - ParamDataTypeStr "Inherit: Inherit via internal rule" - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Reference - Name "PID Controller1" - SID "873" - Ports [1, 1] - Position [645, 392, 685, 428] - ZOrder 142 - LibraryVersion "1.356" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "P" - TimeDomain "Discrete-time" - SampleTime "5e-3" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter on - ControllerParametersSource "internal" - P "0.015166894231541" - I "1575.82088970639" - D "504.111397357926" - N "244.660686071579" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller10" - SID "833" - Ports [1, 1] - Position [260, 542, 300, 578] - ZOrder 122 - LibraryVersion "1.356" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "PD" - TimeDomain "Discrete-time" - SampleTime "0.01" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter off - ControllerParametersSource "internal" - P "1.69332227925298" - I "0.373031053213692" - D "0.0846661139626488" - N "17.8214030142826" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller11" - SID "834" - Ports [1, 1] - Position [260, 117, 300, 153] - ZOrder 123 - LibraryVersion "1.356" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "PID" - TimeDomain "Discrete-time" - SampleTime "0.01" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter off - ControllerParametersSource "internal" - P "-0.0153859651723572" - I "-0.000331343308727455" - D "-0.178612271980841" - N "5.79502261645411" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller2" - SID "832" - Ports [1, 1] - Position [645, 541, 685, 579] - ZOrder 121 - LibraryVersion "1.356" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "PI" - TimeDomain "Discrete-time" - SampleTime "5e-3" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter on - ControllerParametersSource "internal" - P "0.137082785475467" - I "1.78239822850373" - D "2.32" - N "1/0.0818" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross off - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller3" - SID "874" - Ports [1, 1] - Position [505, 392, 545, 428] - ZOrder 143 - LibraryVersion "1.356" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "P" - TimeDomain "Discrete-time" - SampleTime "5e-3" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter on - ControllerParametersSource "internal" - P "1.37514874127105" - I "35.1207902652377" - D "0.410623594074865" - N "40.0107970227961" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller4" - SID "876" - Ports [1, 1] - Position [260, 392, 300, 428] - ZOrder 145 - LibraryVersion "1.356" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "PD" - TimeDomain "Discrete-time" - SampleTime "0.01" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter off - ControllerParametersSource "internal" - P "-0.00209477698719004" - I "-5.49963745752816e-05" - D "-0.116816668948546" - N "16.9491526069154" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller6" - SID "867" - Ports [1, 1] - Position [260, 237, 300, 273] - ZOrder 136 - LibraryVersion "1.356" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "PD" - TimeDomain "Discrete-time" - SampleTime "0.01" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter off - ControllerParametersSource "internal" - P "0.00209477698719004" - I "9.56340991394167e-06" - D "0.116816668948546" - N "16.9491526069154" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller8" - SID "868" - Ports [1, 1] - Position [505, 237, 545, 273] - ZOrder 137 - LibraryVersion "1.356" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "P" - TimeDomain "Discrete-time" - SampleTime "5e-3" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter on - ControllerParametersSource "internal" - P "1.37514874127105" - I "35.1207902652377" - D "0.2" - N "40.0107970227961" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Reference - Name "PID Controller9" - SID "869" - Ports [1, 1] - Position [645, 237, 685, 273] - ZOrder 138 - LibraryVersion "1.356" - SourceBlock "simulink/Continuous/PID Controller" - SourceType "PID 1dof" - ContentPreviewEnabled off - Controller "P" - TimeDomain "Discrete-time" - SampleTime "5e-3" - IntegratorMethod "Forward Euler" - FilterMethod "Forward Euler" - Form "Parallel" - UseFilter on - ControllerParametersSource "internal" - P "0.015166894231541" - I "1575.82088970639" - D "504.111397357926" - N "244.660686071579" - InitialConditionSource "internal" - InitialConditionForIntegrator "0" - InitialConditionForFilter "0" - ExternalReset "none" - IgnoreLimit off - ZeroCross on - LimitOutput off - UpperSaturationLimit "inf" - LowerSaturationLimit "-inf" - LinearizeAsGain on - AntiWindupMode "none" - Kb "1" - TrackingMode off - Kt "1" - RndMeth "Floor" - SaturateOnIntegerOverflow off - LockScale off - PParamMin "[]" - PParamMax "[]" - PParamDataTypeStr "Inherit: Inherit via internal rule" - IParamMin "[]" - IParamMax "[]" - IParamDataTypeStr "Inherit: Inherit via internal rule" - DParamMin "[]" - DParamMax "[]" - DParamDataTypeStr "Inherit: Inherit via internal rule" - NParamMin "[]" - NParamMax "[]" - NParamDataTypeStr "Inherit: Inherit via internal rule" - KbParamMin "[]" - KbParamMax "[]" - KbParamDataTypeStr "Inherit: Inherit via internal rule" - KtParamMin "[]" - KtParamMax "[]" - KtParamDataTypeStr "Inherit: Inherit via internal rule" - POutMin "[]" - POutMax "[]" - POutDataTypeStr "Inherit: Inherit via internal rule" - PGainOutDataTypeStr "Inherit: Inherit via internal rule" - PProdOutDataTypeStr "Inherit: Inherit via internal rule" - IOutMin "[]" - IOutMax "[]" - IOutDataTypeStr "Inherit: Inherit via internal rule" - IGainOutDataTypeStr "Inherit: Inherit via internal rule" - IProdOutDataTypeStr "Inherit: Inherit via internal rule" - DOutMin "[]" - DOutMax "[]" - DOutDataTypeStr "Inherit: Inherit via internal rule" - DGainOutDataTypeStr "Inherit: Inherit via internal rule" - DProdOutDataTypeStr "Inherit: Inherit via internal rule" - NOutMin "[]" - NOutMax "[]" - NOutDataTypeStr "Inherit: Inherit via internal rule" - NGainOutDataTypeStr "Inherit: Inherit via internal rule" - NProdOutDataTypeStr "Inherit: Inherit via internal rule" - KbOutMin "[]" - KbOutMax "[]" - KbOutDataTypeStr "Inherit: Inherit via internal rule" - KtOutMin "[]" - KtOutMax "[]" - KtOutDataTypeStr "Inherit: Inherit via internal rule" - IntegratorOutMin "[]" - IntegratorOutMax "[]" - IntegratorOutDataTypeStr "Inherit: Inherit via internal rule" - FilterOutMin "[]" - FilterOutMax "[]" - FilterOutDataTypeStr "Inherit: Inherit via internal rule" - SumOutMin "[]" - SumOutMax "[]" - SumOutDataTypeStr "Inherit: Inherit via internal rule" - SumI1OutMin "[]" - SumI1OutMax "[]" - SumI1OutDataTypeStr "Inherit: Inherit via internal rule" - SumI2OutMin "[]" - SumI2OutMax "[]" - SumI2OutDataTypeStr "Inherit: Inherit via internal rule" - SumI3OutMin "[]" - SumI3OutMax "[]" - SumI3OutDataTypeStr "Inherit: Inherit via internal rule" - SumDOutMin "[]" - SumDOutMax "[]" - SumDOutDataTypeStr "Inherit: Inherit via internal rule" - SumAccumDataTypeStr "Inherit: Inherit via internal rule" - SumI1AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI2AccumDataTypeStr "Inherit: Inherit via internal rule" - SumI3AccumDataTypeStr "Inherit: Inherit via internal rule" - SumDAccumDataTypeStr "Inherit: Inherit via internal rule" - SaturationOutMin "[]" - SaturationOutMax "[]" - SaturationOutDataTypeStr "Inherit: Same as input" - IntegratorContinuousStateAttributes "''" - IntegratorStateMustResolveToSignalObject off - IntegratorRTWStateStorageClass "Auto" - FilterContinuousStateAttributes "''" - FilterStateMustResolveToSignalObject off - FilterRTWStateStorageClass "Auto" - DifferentiatorICPrevScaledInput "0" - DifferentiatorOutMin "[]" - DifferentiatorOutMax "[]" - DifferentiatorOutDataTypeStr "Inherit: Inherit via internal rule" - } - Block { - BlockType Saturate - Name "Saturation1" - SID "887" - Ports [1, 1] - Position [410, 240, 440, 270] - ZOrder 147 - Commented "through" - InputPortMap "u0" - UpperLimit "20*pi/180" - LowerLimit "-20*pi/180" - } - Block { - BlockType Saturate - Name "Saturation2" - SID "888" - Ports [1, 1] - Position [410, 395, 440, 425] - ZOrder 148 - Commented "through" - InputPortMap "u0" - UpperLimit "20*pi/180" - LowerLimit "-20*pi/180" - } - Block { - BlockType Saturate - Name "Saturation3" - SID "889" - Ports [1, 1] - Position [410, 545, 440, 575] - ZOrder 149 - Commented "through" - InputPortMap "u0" - UpperLimit "20*pi/180" - LowerLimit "-20*pi/180" - } - Block { - BlockType Scope - Name "Scope" - SID "791" - Ports [1] - Position [510, 649, 540, 681] - ZOrder 97 - Floating off - Location [1, 76, 1921, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-4.53199" - YMax "5.80666" - SaveName "ScopeData1" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope1" - SID "792" - Ports [1] - Position [235, 649, 265, 681] - ZOrder 106 - Floating off - Location [10, 76, 1926, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-0.00426" - YMax "0.00536" - SaveName "ScopeData2" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope2" - SID "795" - Ports [1] - Position [265, 174, 295, 206] - ZOrder 107 - Floating off - Location [593, 266, 1926, 1046] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.5 0.5 0.5]" - AxesColor "[0 0 0]" - AxesTickColor "[1 1 1]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-0.14356" - YMax "1.29207" - SaveName "ScopeData5" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope3" - SID "797" - Ports [1] - Position [650, 334, 680, 366] - ZOrder 109 - Floating off - Location [10, 76, 1926, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-0.13447" - YMax "1.21019" - SaveName "ScopeData1" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope4" - SID "798" - Ports [1] - Position [365, 334, 395, 366] - ZOrder 110 - Floating off - Location [10, 76, 1926, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-0.2" - YMax "0.5" - SaveName "ScopeData2" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope5" - SID "799" - Ports [1] - Position [240, 334, 270, 366] - ZOrder 111 - Floating off - Location [1, 49, 1921, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.5 0.5 0.5]" - AxesColor "[0 0 0]" - AxesTickColor "[1 1 1]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-0.035" - YMax "0.03" - SaveName "ScopeData3" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope6" - SID "825" - Ports [1] - Position [650, 484, 680, 516] - ZOrder 117 - Floating off - Location [10, 76, 1926, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-0.48276" - YMax "2.87086" - SaveName "ScopeData1" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope7" - SID "826" - Ports [1] - Position [365, 484, 395, 516] - ZOrder 118 - Floating off - Location [10, 76, 1926, 1039] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "-0.04704" - YMax "0.39309" - SaveName "ScopeData2" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Scope - Name "Scope8" - SID "827" - Ports [1] - Position [245, 484, 275, 516] - ZOrder 119 - Floating off - Location [2, 57, 1918, 1038] - Open on - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.5 0.5 0.5]" - AxesColor "[0 0 0]" - AxesTickColor "[1 1 1]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - TimeRange "20" - YMin "2200" - YMax "4300" - SaveName "ScopeData3" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Sum - Name "Sum" - SID "598" - Ports [2, 1] - Position [350, 550, 370, 570] - ZOrder 40 - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum1" - SID "599" - Ports [2, 1] - Position [340, 245, 360, 265] - ZOrder 41 - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum2" - SID "600" - Ports [2, 1] - Position [590, 245, 610, 265] - ZOrder 42 - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum3" - SID "602" - Ports [2, 1] - Position [335, 400, 355, 420] - ZOrder 43 - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum4" - SID "603" - Ports [2, 1] - Position [590, 400, 610, 420] - ZOrder 44 - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum5" - SID "618" - Ports [2, 1] - Position [215, 400, 235, 420] - ZOrder 56 - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum6" - SID "619" - Ports [2, 1] - Position [210, 245, 230, 265] - ZOrder 57 - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum7" - SID "620" - Ports [2, 1] - Position [210, 125, 230, 145] - ZOrder 58 - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum8" - SID "648" - Ports [2, 1] - Position [210, 550, 230, 570] - ZOrder 104 - ShowName off - IconShape "round" - Inputs "|+-" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Outport - Name "height_controlled" - SID "606" - Position [925, 128, 955, 142] - ZOrder -2 - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "y_controlled" - SID "636" - Position [925, 248, 955, 262] - ZOrder 74 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "x_controlled" - SID "637" - Position [925, 403, 955, 417] - ZOrder 75 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Outport - Name "yaw_controlled" - SID "638" - Position [925, 553, 955, 567] - ZOrder 76 - Port "4" - IconDisplay "Port number" - } - Line { - ZOrder 283 - SrcBlock "Sum" - SrcPort 1 - DstBlock "Saturation3" - DstPort 1 - } - Line { - ZOrder 43 - SrcBlock "pitch" - SrcPort 1 - Points [9, 0] - Branch { - ZOrder 233 - Points [0, 25] - DstBlock "Scope7" - DstPort 1 - } - Branch { - ZOrder 232 - Points [1, 0] - DstBlock "Sum3" - DstPort 2 - } - } - Line { - ZOrder 42 - SrcBlock "roll" - SrcPort 1 - Points [15, 0] - Branch { - ZOrder 218 - DstBlock "Scope4" - DstPort 1 - } - Branch { - ZOrder 215 - DstBlock "Sum1" - DstPort 2 - } - } - Line { - ZOrder 48 - SrcBlock "pitch_rate" - SrcPort 1 - Points [40, 0] - Branch { - ZOrder 229 - DstBlock "Sum4" - DstPort 2 - } - Branch { - ZOrder 228 - Points [0, 25] - DstBlock "Scope6" - DstPort 1 - } - } - Line { - ZOrder 47 - SrcBlock "roll_rate" - SrcPort 1 - Points [40, 0] - Branch { - ZOrder 123 - Points [0, 30] - DstBlock "Scope3" - DstPort 1 - } - Branch { - ZOrder 122 - DstBlock "Sum2" - DstPort 2 - } - } - Line { - ZOrder 49 - SrcBlock "yaw_rate" - SrcPort 1 - Points [25, 0] - Branch { - ZOrder 173 - Points [0, 50] - DstBlock "Scope" - DstPort 1 - } - Branch { - ZOrder 87 - DstBlock "Sum" - DstPort 2 - } - } - Line { - ZOrder 26 - SrcBlock "z_setpoint" - SrcPort 1 - DstBlock "Sum7" - DstPort 1 - } - Line { - ZOrder 28 - SrcBlock "y_setpoint" - SrcPort 1 - DstBlock "Sum6" - DstPort 1 - } - Line { - ZOrder 31 - SrcBlock "x_position" - SrcPort 1 - Points [25, 0] - Branch { - ZOrder 237 - DstBlock "Sum5" - DstPort 2 - } - Branch { - ZOrder 236 - Points [0, 25] - DstBlock "Scope8" - DstPort 1 - } - } - Line { - ZOrder 32 - SrcBlock "x_setpoint" - SrcPort 1 - DstBlock "Sum5" - DstPort 1 - } - Line { - ZOrder 33 - SrcBlock "y_position" - SrcPort 1 - Points [20, 0] - Branch { - ZOrder 241 - Points [0, 30] - DstBlock "Scope5" - DstPort 1 - } - Branch { - ZOrder 128 - DstBlock "Sum6" - DstPort 2 - } - } - Line { - ZOrder 34 - SrcBlock "z_position" - SrcPort 1 - Points [25, 0] - Branch { - ZOrder 108 - DstBlock "Scope2" - DstPort 1 - } - Branch { - ZOrder 107 - DstBlock "Sum7" - DstPort 2 - } - } - Line { - ZOrder 100 - SrcBlock "yaw" - SrcPort 1 - Points [25, 0] - Branch { - ZOrder 172 - DstBlock "Scope1" - DstPort 1 - } - Branch { - ZOrder 102 - DstBlock "Sum8" - DstPort 2 - } - } - Line { - ZOrder 98 - SrcBlock "yaw_setpoint" - SrcPort 1 - DstBlock "Sum8" - DstPort 1 - } - Line { - ZOrder 434 - SrcBlock "Sum2" - SrcPort 1 - DstBlock "PID Controller9" - DstPort 1 - } - Line { - ZOrder 416 - SrcBlock "Sum6" - SrcPort 1 - DstBlock "PID Controller6" - DstPort 1 - } - Line { - ZOrder 461 - SrcBlock "Sum5" - SrcPort 1 - DstBlock "PID Controller4" - DstPort 1 - } - Line { - ZOrder 281 - SrcBlock "Sum7" - SrcPort 1 - DstBlock "PID Controller11" - DstPort 1 - } - Line { - ZOrder 285 - SrcBlock "Sum8" - SrcPort 1 - DstBlock "PID Controller10" - DstPort 1 - } - Line { - ZOrder 451 - SrcBlock "Sum4" - SrcPort 1 - DstBlock "PID Controller1" - DstPort 1 - } - Line { - ZOrder 456 - SrcBlock "PID Controller1" - SrcPort 1 - DstBlock "Gain3" - DstPort 1 - } - Line { - ZOrder 459 - SrcBlock "Sum3" - SrcPort 1 - DstBlock "Saturation2" - DstPort 1 - } - Line { - ZOrder 462 - SrcBlock "PID Controller4" - SrcPort 1 - DstBlock "Sum3" - DstPort 1 - } - Line { - ZOrder 464 - SrcBlock "PID Controller9" - SrcPort 1 - DstBlock "Gain2" - DstPort 1 - } - Line { - ZOrder 473 - SrcBlock "PID Controller11" - SrcPort 1 - DstBlock "Gain1" - DstPort 1 - } - Line { - ZOrder 478 - SrcBlock "PID Controller2" - SrcPort 1 - DstBlock "Gain4" - DstPort 1 - } - Line { - ZOrder 482 - SrcBlock "Sum1" - SrcPort 1 - DstBlock "Saturation1" - DstPort 1 - } - Line { - ZOrder 486 - SrcBlock "Saturation2" - SrcPort 1 - DstBlock "PID Controller3" - DstPort 1 - } - Line { - ZOrder 488 - SrcBlock "Gain1" - SrcPort 1 - DstBlock "height_controlled" - DstPort 1 - } - Line { - ZOrder 489 - SrcBlock "Gain2" - SrcPort 1 - DstBlock "y_controlled" - DstPort 1 - } - Line { - ZOrder 490 - SrcBlock "Gain3" - SrcPort 1 - DstBlock "x_controlled" - DstPort 1 - } - Line { - ZOrder 491 - SrcBlock "Gain4" - SrcPort 1 - DstBlock "yaw_controlled" - DstPort 1 - } - Line { - ZOrder 492 - SrcBlock "PID Controller3" - SrcPort 1 - DstBlock "Sum4" - DstPort 1 - } - Line { - ZOrder 493 - SrcBlock "Saturation3" - SrcPort 1 - DstBlock "PID Controller2" - DstPort 1 - } - Line { - ZOrder 496 - SrcBlock "Saturation1" - SrcPort 1 - DstBlock "PID Controller8" - DstPort 1 - } - Line { - ZOrder 498 - SrcBlock "PID Controller10" - SrcPort 1 - DstBlock "Sum" - DstPort 1 - } - Line { - ZOrder 500 - SrcBlock "PID Controller8" - SrcPort 1 - DstBlock "Sum2" - DstPort 1 - } - Line { - ZOrder 501 - SrcBlock "PID Controller6" - SrcPort 1 - DstBlock "Sum1" - DstPort 1 - } - Annotation { - SID "901" - Name "<!DOCTYPE HTML PUBLIC \"-//W3C//DTD HTML 4.0//EN\" \"http://www.w3.org/TR/REC-html40/strict.dtd\">" - "\n<html><head><meta name=\"qrichtext\" content=\"1\" /><style type=\"text/css\">\np, li { white-space: pre-wrap" - "; }\n</style></head><body style=\" font-family:'Helvetica'; font-size:10px; font-weight:400; font-style:normal;" - "\">\n<p style=\"-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px;" - " -qt-block-indent:0; text-indent:0px;\"><br /></p></body></html>" - Position [264, 366, 266, 381] - InternalMargins [0, 0, 0, 0] - FixedHeight off - FixedWidth off - HorizontalAlignment "left" - VerticalAlignment "top" - Interpreter "rich" - } - } - } - Block { - BlockType Demux - Name "Demux" - SID "586" - Ports [1, 4] - Position [300, 309, 305, 406] - ZOrder 13 - ShowName off - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux1" - SID "639" - Ports [1, 3] - Position [300, 484, 305, 556] - ZOrder 32 - ShowName off - Outputs "3" - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux2" - SID "588" - Ports [1, 3] - Position [285, 409, 290, 481] - ZOrder 15 - ShowName off - Outputs "3" - DisplayOption "bar" - } - Block { - BlockType Demux - Name "Demux4" - SID "640" - Ports [1, 3] - Position [275, 559, 280, 631] - ZOrder 33 - ShowName off - Outputs "3" - DisplayOption "bar" - } - Block { - BlockType SubSystem - Name "MATLAB Function" - SID "647" - Ports [4, 1] - Position [725, 308, 925, 632] - ZOrder 35 - ErrorFcn "Stateflow.Translate.translate" - PermitHierarchicalResolution "ExplicitOnly" - TreatAsAtomicUnit on - RequestExecContextInheritance off - SFBlockType "MATLAB Function" - System { - Name "MATLAB Function" - Location [223, 338, 826, 833] - Open off - ModelBrowserVisibility off - ModelBrowserWidth 200 - ScreenColor "white" - PaperOrientation "landscape" - PaperPositionMode "auto" - PaperType "usletter" - PaperUnits "inches" - TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] - TiledPageScale 1 - ShowPageBoundaries off - ZoomFactor "100" - SIDHighWatermark "27" - Block { - BlockType Inport - Name "height_controlled" - SID "647::1" - Position [20, 101, 40, 119] - ZOrder -1 - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "y_controlled" - SID "647::23" - Position [20, 136, 40, 154] - ZOrder 14 - Port "2" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "x_controlled" - SID "647::22" - Position [20, 171, 40, 189] - ZOrder 13 - Port "3" - IconDisplay "Port number" - } - Block { - BlockType Inport - Name "yaw_controlled" - SID "647::24" - Position [20, 206, 40, 224] - ZOrder 15 - Port "4" - IconDisplay "Port number" - } - Block { - BlockType Demux - Name " Demux " - SID "647::20" - Ports [1, 1] - Position [270, 230, 320, 270] - ZOrder 11 - Outputs "1" - } - Block { - BlockType S-Function - Name " SFunction " - SID "647::19" - Tag "Stateflow S-Function test_model_R2015A 14" - Ports [4, 2] - Position [180, 107, 230, 208] - ZOrder 10 - FunctionName "sf_sfun" - PortCounts "[4 2]" - EnableBusSupport on - Port { - PortNumber 2 - Name "motorCommands" - RTWStorageClass "Auto" - DataLoggingNameMode "SignalName" - } - } - Block { - BlockType Terminator - Name " Terminator " - SID "647::21" - Position [460, 241, 480, 259] - ZOrder 12 - } - Block { - BlockType Outport - Name "motorCommands" - SID "647::5" - Position [460, 101, 480, 119] - ZOrder -5 - IconDisplay "Port number" - } - Line { - ZOrder 105 - SrcBlock "height_controlled" - SrcPort 1 - DstBlock " SFunction " - DstPort 1 - } - Line { - ZOrder 106 - SrcBlock "y_controlled" - SrcPort 1 - DstBlock " SFunction " - DstPort 2 - } - Line { - ZOrder 107 - SrcBlock "x_controlled" - SrcPort 1 - DstBlock " SFunction " - DstPort 3 - } - Line { - ZOrder 108 - SrcBlock "yaw_controlled" - SrcPort 1 - DstBlock " SFunction " - DstPort 4 - } - Line { - Name "motorCommands" - ZOrder 109 - Labels [0, 0] - SrcBlock " SFunction " - SrcPort 2 - DstBlock "motorCommands" - DstPort 1 - } - Line { - ZOrder 110 - SrcBlock " Demux " - SrcPort 1 - DstBlock " Terminator " - DstPort 1 - } - Line { - ZOrder 111 - SrcBlock " SFunction " - SrcPort 1 - DstBlock " Demux " - DstPort 1 - } - } - } - Block { - BlockType Saturate - Name "Saturation" - SID "756" - Ports [1, 1] - Position [960, 455, 990, 485] - ZOrder 44 - InputPortMap "u0" - UpperLimit "Pmax*ones(4,1)" - LowerLimit "Pmin*ones(4,1)" - } - Block { - BlockType Scope - Name "Scope1" - SID "794" - Ports [1] - Position [1080, 564, 1110, 596] - ZOrder 46 - Floating off - Location [188, 365, 512, 604] - Open off - NumInputPorts "1" - List { - ListType AxesTitles - axes1 "%<SignalLabel>" - } - List { - ListType ScopeGraphics - FigureColor "[0.156862745098039 0.156862745098039 0.156862745098039]" - AxesColor "[0 0 0]" - AxesTickColor "[0.686274509803922 0.686274509803922 0.686274509803922]" - LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" - LineStyles "-|-|-|-|-|-" - LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" - MarkerStyles "none|none|none|none|none|none" - } - YMin "87500.00000" - YMax "212500.00000" - SaveName "ScopeData4" - DataFormat "StructureWithTime" - LimitDataPoints off - } - Block { - BlockType Sum - Name "Sum" - SID "748" - Ports [2, 1] - Position [655, 340, 675, 360] - ZOrder 36 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum1" - SID "749" - Ports [2, 1] - Position [655, 420, 675, 440] - ZOrder 37 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum2" - SID "750" - Ports [2, 1] - Position [655, 500, 675, 520] - ZOrder 38 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Sum - Name "Sum3" - SID "751" - Ports [2, 1] - Position [655, 580, 675, 600] - ZOrder 39 - ShowName off - IconShape "round" - Inputs "|++" - InputSameDT off - OutDataTypeStr "Inherit: Inherit via internal rule" - SaturateOnIntegerOverflow off - } - Block { - BlockType Constant - Name "height_controlled_o" - SID "752" - Position [605, 375, 635, 405] - ZOrder 40 - Value "height_controlled_o" - SampleTime "5e-3" - } - Block { - BlockType Constant - Name "x_controlled_o" - SID "754" - Position [605, 535, 635, 565] - ZOrder 42 - Value "x_controlled_o" - SampleTime "5e-3" - } - Block { - BlockType Constant - Name "y_controlled_o" - SID "753" - Position [605, 455, 635, 485] - ZOrder 41 - Value "y_controlled_o" - SampleTime "5e-3" - } - Block { - BlockType Constant - Name "yaw_controlled_o" - SID "755" - Position [605, 620, 635, 650] - ZOrder 43 - Value "yaw_controlled_o" - SampleTime "5e-3" - } - Block { - BlockType Outport - Name "Motor Commands" - SID "578" - Position [1055, 463, 1085, 477] - ZOrder -2 - IconDisplay "Port number" - } - Line { - ZOrder 1 - SrcBlock "setpoints" - SrcPort 1 - DstBlock "Demux" - DstPort 1 - } - Line { - ZOrder 30 - SrcBlock "euler_angles_filtered" - SrcPort 1 - DstBlock "Demux1" - DstPort 1 - } - Line { - ZOrder 3 - SrcBlock "current_position" - SrcPort 1 - DstBlock "Demux2" - DstPort 1 - } - Line { - ZOrder 34 - SrcBlock "euler_rates" - SrcPort 1 - DstBlock "Demux4" - DstPort 1 - } - Line { - ZOrder 27 - SrcBlock "Demux" - SrcPort 1 - DstBlock "Controller" - DstPort 1 - } - Line { - ZOrder 28 - SrcBlock "Demux" - SrcPort 2 - DstBlock "Controller" - DstPort 2 - } - Line { - ZOrder 29 - SrcBlock "Demux" - SrcPort 3 - DstBlock "Controller" - DstPort 3 - } - Line { - ZOrder 40 - SrcBlock "Demux2" - SrcPort 1 - DstBlock "Controller" - DstPort 5 - } - Line { - ZOrder 41 - SrcBlock "Demux2" - SrcPort 2 - DstBlock "Controller" - DstPort 6 - } - Line { - ZOrder 42 - SrcBlock "Demux2" - SrcPort 3 - DstBlock "Controller" - DstPort 7 - } - Line { - ZOrder 68 - SrcBlock "Controller" - SrcPort 2 - DstBlock "Sum1" - DstPort 1 - } - Line { - ZOrder 69 - SrcBlock "Sum1" - SrcPort 1 - DstBlock "MATLAB Function" - DstPort 2 - } - Line { - ZOrder 71 - SrcBlock "Sum2" - SrcPort 1 - DstBlock "MATLAB Function" - DstPort 3 - } - Line { - ZOrder 72 - SrcBlock "Controller" - SrcPort 4 - DstBlock "Sum3" - DstPort 1 - } - Line { - ZOrder 73 - SrcBlock "Sum3" - SrcPort 1 - DstBlock "MATLAB Function" - DstPort 4 - } - Line { - ZOrder 74 - SrcBlock "Controller" - SrcPort 1 - DstBlock "Sum" - DstPort 1 - } - Line { - ZOrder 75 - SrcBlock "Sum" - SrcPort 1 - DstBlock "MATLAB Function" - DstPort 1 - } - Line { - ZOrder 77 - SrcBlock "y_controlled_o" - SrcPort 1 - Points [25, 0] - DstBlock "Sum1" - DstPort 2 - } - Line { - ZOrder 78 - SrcBlock "x_controlled_o" - SrcPort 1 - Points [25, 0] - DstBlock "Sum2" - DstPort 2 - } - Line { - ZOrder 79 - SrcBlock "yaw_controlled_o" - SrcPort 1 - Points [25, 0] - DstBlock "Sum3" - DstPort 2 - } - Line { - ZOrder 80 - SrcBlock "MATLAB Function" - SrcPort 1 - DstBlock "Saturation" - DstPort 1 - } - Line { - ZOrder 81 - SrcBlock "Saturation" - SrcPort 1 - Points [21, 0] - Branch { - ZOrder 122 - Points [0, 110] - DstBlock "Scope1" - DstPort 1 - } - Branch { - ZOrder 121 - DstBlock "Motor Commands" - DstPort 1 - } - } - Line { - ZOrder 84 - SrcBlock "Demux1" - SrcPort 1 - DstBlock "Controller" - DstPort 8 - } - Line { - ZOrder 86 - SrcBlock "Demux1" - SrcPort 2 - DstBlock "Controller" - DstPort 9 - } - Line { - ZOrder 90 - SrcBlock "Demux4" - SrcPort 1 - DstBlock "Controller" - DstPort 11 - } - Line { - ZOrder 91 - SrcBlock "Demux4" - SrcPort 2 - DstBlock "Controller" - DstPort 12 - } - Line { - ZOrder 93 - SrcBlock "Demux4" - SrcPort 3 - DstBlock "Controller" - DstPort 13 - } - Line { - ZOrder 94 - SrcBlock "Demux" - SrcPort 4 - DstBlock "Controller" - DstPort 4 - } - Line { - ZOrder 95 - SrcBlock "Demux1" - SrcPort 3 - DstBlock "Controller" - DstPort 10 - } - Line { - ZOrder 131 - SrcBlock "Controller" - SrcPort 3 - DstBlock "Sum2" - DstPort 1 - } - Line { - ZOrder 133 - SrcBlock "height_controlled_o" - SrcPort 1 - Points [25, 0] - DstBlock "Sum" - DstPort 2 - } - } - } - Line { - ZOrder 52 - SrcBlock "Control System" - SrcPort 1 - DstBlock "Actuation" - DstPort 1 - } - Line { - ZOrder 55 - SrcBlock "Communication System" - SrcPort 1 - DstBlock "Control System" - DstPort 1 - } - Line { - ZOrder 189 - SrcBlock "Actuation" - SrcPort 1 - DstBlock " Sensors " - DstPort 1 - } - Line { - ZOrder 191 - SrcBlock "Actuation" - SrcPort 3 - DstBlock " Sensors " - DstPort 3 - } - Line { - ZOrder 192 - SrcBlock "Actuation" - SrcPort 4 - DstBlock " Sensors " - DstPort 4 - } - Line { - ZOrder 193 - SrcBlock "Actuation" - SrcPort 5 - DstBlock " Sensors " - DstPort 5 - } - Line { - ZOrder 194 - SrcBlock "Actuation" - SrcPort 6 - DstBlock " Sensors " - DstPort 6 - } - Line { - ZOrder 195 - SrcBlock " Sensors " - SrcPort 3 - Points [9, 0; 0, 210; -903, 0; 0, -160] - DstBlock "Control System" - DstPort 4 - } - Line { - ZOrder 196 - SrcBlock " Sensors " - SrcPort 2 - Points [16, 0; 0, 302; -924, 0; 0, -247] - DstBlock "Control System" - DstPort 3 - } - Line { - ZOrder 190 - SrcBlock "Actuation" - SrcPort 2 - DstBlock " Sensors " - DstPort 2 - } - Line { - ZOrder 208 - SrcBlock " Sensors " - SrcPort 4 - Points [2, 0; 0, 42; -903, 0; 0, -162] - DstBlock "Control System" - DstPort 2 - } - } -} -#Finite State Machines -# -# Stateflow 80000005 -# -# -Stateflow { - machine { - id 1 - name "test_model_R2015A" - created "03-Nov-2016 18:34:53" - isLibrary 0 - firstTarget 145 - sfVersion 80000005 - } - chart { - id 2 - name "Actuation/Gravity\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 3 0 0] - firstTransition 8 - firstJunction 7 - viewObj 2 - machine 1 - ssIdHighWaterMark 7 - decomposition CLUSTER_CHART - type EML_CHART - firstData 4 - chartFileNumber 1 - disableImplicitCasting 1 - eml { - name "gravity" - } - } - state { - id 3 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 2 - treeNode [2 0 0 0] - superState SUBCHART - subviewer 2 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function E_Fg = gravity(m, g)\n\nE_Fg = [0; 0; m*g];\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 4 - ssIdNumber 5 - name "E_Fg" - linkNode [2 0 5] - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 5 - ssIdNumber 6 - name "m" - linkNode [2 4 6] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 1 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 6 - ssIdNumber 7 - name "g" - linkNode [2 5 0] - scope PARAMETER_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - junction { - id 7 - position [23.5747 49.5747 7] - chart 2 - linkNode [2 0 0] - subviewer 2 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - } - transition { - id 8 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 7 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 2 - linkNode [2 0 0] - dataLimits [21.175 25.975 14.625 42.575] - subviewer 2 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - } - instance { - id 9 - name "Actuation/Gravity\n\n" - machine 1 - chart 2 - } - chart { - id 10 - name "Actuation/Lbe\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 11 0 0] - firstTransition 16 - firstJunction 15 - viewObj 10 - machine 1 - ssIdHighWaterMark 11 - decomposition CLUSTER_CHART - type EML_CHART - firstData 12 - chartFileNumber 2 - disableImplicitCasting 1 - eml { - name "linear_body_earth_conversion" - } - } - state { - id 11 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 10 - treeNode [10 0 0 0] - superState SUBCHART - subviewer 10 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function E_ro = linear_body_earth_conversion(B_vo, euler_angles)\n\neuler_rates = zeros(3,1);\nE" - "_ro = zeros(3,1);\n\nphi = euler_angles(1);\ntheta = euler_angles(2);\npsi = euler_angles(3);\n\nLeb = [cos(thet" - "a)*cos(psi), sin(phi)*sin(theta)*cos(psi)-cos(phi)*sin(psi), cos(phi)*sin(theta)*cos(psi)+sin(phi)*sin(psi); ..." - "\n cos(theta)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), cos(phi)*sin(theta)*sin(psi)-sin(p" - "hi)*cos(psi); ...\n -sin(theta) , sin(phi)*cos(theta) , c" - "os(phi)*cos(theta) ];\n\nE_ro = Leb * B_vo;" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 12 - ssIdNumber 7 - name "B_vo" - linkNode [10 0 13] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 13 - ssIdNumber 11 - name "euler_angles" - linkNode [10 12 14] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 14 - ssIdNumber 9 - name "E_ro" - linkNode [10 13 0] - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - junction { - id 15 - position [23.5747 49.5747 7] - chart 10 - linkNode [10 0 0] - subviewer 10 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - } - transition { - id 16 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 15 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 10 - linkNode [10 0 0] - dataLimits [21.175 25.975 14.625 42.575] - subviewer 10 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - } - instance { - id 17 - name "Actuation/Lbe\n\n\n\n\n\n" - machine 1 - chart 10 - } - chart { - id 18 - name " Sensors /3D Graphical Simulation1/MATLAB Function" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 19 0 0] - firstTransition 23 - firstJunction 22 - viewObj 18 - machine 1 - ssIdHighWaterMark 5 - decomposition CLUSTER_CHART - type EML_CHART - firstData 20 - chartFileNumber 3 - disableImplicitCasting 1 - eml { - name "eigenaxis_ucart" - } - } - state { - id 19 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 18 - treeNode [18 0 0 0] - superState SUBCHART - subviewer 18 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function y = eigenaxis_ucart(u)\n\n\nif abs(u(1))< 0.0001\n u(1) = 0.0001;\nend\n\nif abs(u(2)" - ")< 0.0001\n u(2) = 0.0001;\nend\n\nif abs(u(3))< 0.0001\n u(3) = 0.0001;\nend\n\nu = [ -u(1); -u(2); u(3) " - "];% [Pitch, Yaw, Roll] \n\nC11 = cos(u(2))*cos(u(3));\nC12 = cos(u(2))*sin(u(3));\nC13 = -sin(u(2));\nC21 = sin(" - "u(1))*sin(u(2))*cos(u(3))-cos(u(1))*sin(u(3));\nC22 = sin(u(1))*sin(u(2))*sin(u(3))+cos(u(1))*cos(u(3));\nC23 = " - "sin(u(1))*cos(u(2));\nC31 = cos(u(1))*sin(u(2))*cos(u(3))+sin(u(1))*sin(u(3));\nC32 = cos(u(1))*sin(u(2))*sin(u(" - "3))-sin(u(1))*cos(u(3));\nC33 = cos(u(1))*cos(u(2));\n \ntheta = acos(0.5*(C11+C22+C33-1));\n\ne = [C23-C32; " - "C31-C13; C12-C21]/(2*sin(theta));\n \ny = [e; theta];\n\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 20 - ssIdNumber 4 - name "u" - linkNode [18 0 21] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 21 - ssIdNumber 5 - name "y" - linkNode [18 20 0] - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - junction { - id 22 - position [23.5747 49.5747 7] - chart 18 - linkNode [18 0 0] - subviewer 18 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - } - transition { - id 23 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 22 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 18 - linkNode [18 0 0] - dataLimits [21.175 25.975 14.625 42.575] - subviewer 18 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - } - instance { - id 24 - name " Sensors /3D Graphical Simulation1/MATLAB Function" - machine 1 - chart 18 - } - chart { - id 25 - name "Actuation/ESC System" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 26 0 0] - firstTransition 33 - firstJunction 32 - viewObj 25 - machine 1 - ssIdHighWaterMark 18 - decomposition CLUSTER_CHART - type EML_CHART - firstData 27 - chartFileNumber 4 - disableImplicitCasting 1 - eml { - name "ESC" - } - } - state { - id 26 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 25 - treeNode [25 0 0 0] - superState SUBCHART - subviewer 25 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function Vb_eff = ESC(rotor_duty_cycles, Pmin, Pmax, Vb)\n\nrotor_0_duty_cycle = rotor_duty_cyc" - "les(1);\nrotor_1_duty_cycle = rotor_duty_cycles(2);\nrotor_2_duty_cycle = rotor_duty_cycles(3);\nrotor_3_duty_cy" - "cle = rotor_duty_cycles(4);\n\n% Define u_Pi for each of the rotors, limiting it to be greater than 0\n% u_P0 = " - "(rotor_0_duty_cycle/100 - Pmin) / (Pmax - Pmin);\n% u_P1 = (rotor_1_duty_cycle/100 - Pmin) / (Pmax - Pmin);\n% u" - "_P2 = (rotor_2_duty_cycle/100 - Pmin) / (Pmax - Pmin);\n% u_P3 = (rotor_3_duty_cycle/100 - Pmin) / (Pmax - Pmin)" - ";\nu_P0 = (rotor_0_duty_cycle - Pmin) / (Pmax - Pmin);\nu_P1 = (rotor_1_duty_cycle - Pmin) / (Pmax - Pmin);\nu_P" - "2 = (rotor_2_duty_cycle - Pmin) / (Pmax - Pmin);\nu_P3 = (rotor_3_duty_cycle - Pmin) / (Pmax - Pmin);\n\n\n% Det" - "ermine the effective battery voltage from each ESC\nVb_eff_0 = u_P0 * Vb;\nVb_eff_1 = u_P1 * Vb;\nVb_eff_2 = u_P" - "2 * Vb;\nVb_eff_3 = u_P3 * Vb;\n \nVb_eff = [Vb_eff_0, Vb_eff_1, Vb_eff_2, Vb_eff_3];\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 27 - ssIdNumber 4 - name "rotor_duty_cycles" - linkNode [25 0 28] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 28 - ssIdNumber 5 - name "Vb_eff" - linkNode [25 27 29] - scope OUTPUT_DATA - machine 1 - props { - array { - size "1,4" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 29 - ssIdNumber 16 - name "Pmin" - linkNode [25 28 30] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 1 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 30 - ssIdNumber 17 - name "Pmax" - linkNode [25 29 31] - scope PARAMETER_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 31 - ssIdNumber 18 - name "Vb" - linkNode [25 30 0] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 2 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - junction { - id 32 - position [23.5747 49.5747 7] - chart 25 - linkNode [25 0 0] - subviewer 25 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - } - transition { - id 33 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 32 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 25 - linkNode [25 0 0] - dataLimits [21.175 25.975 14.625 42.575] - subviewer 25 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - } - instance { - id 34 - name "Actuation/ESC System" - machine 1 - chart 25 - } - chart { - id 35 - name "Actuation/Motor System" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 36 0 0] - firstTransition 47 - firstJunction 46 - viewObj 35 - machine 1 - ssIdHighWaterMark 16 - decomposition CLUSTER_CHART - type EML_CHART - firstData 37 - chartFileNumber 5 - disableImplicitCasting 1 - eml { - name "motor" - } - } - state { - id 36 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 35 - treeNode [35 0 0 0] - superState SUBCHART - subviewer 35 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function angular_acceleration = motor(Vb_eff, angular_velocity, Rm, Kv, Kq, Kd, If, Jreq)\n\n% De" - "fine each motors effective battery voltage\nVb_eff_0 = Vb_eff(1);\nVb_eff_1 = Vb_eff(2);\nVb_eff_2 = Vb_eff(3);\n" - "Vb_eff_3 = Vb_eff(4);\n\n% Determine the angular velocity of each rotor from feedback\nw_0 = angular_velocity(1)" - ";\nw_1 = angular_velocity(2);\nw_2 = angular_velocity(3);\nw_3 = angular_velocity(4);\n\n% w_0 = (-1 + sqrt(1 - " - "4*Rm*Kv*Kq*Kd*(Kv*Rm*If - Kv*Vb_eff_0)))/2*Rm*Kv*Kq*Kd;\n% w_1 = (-1 + sqrt(1 - 4*Rm*Kv*Kq*Kd*(Kv*Rm*If - Kv*Vb_" - "eff_1)))/2*Rm*Kv*Kq*Kd;\n% w_2 = (-1 + sqrt(1 - 4*Rm*Kv*Kq*Kd*(Kv*Rm*If - Kv*Vb_eff_2)))/2*Rm*Kv*Kq*Kd;\n% w_3 =" - " (-1 + sqrt(1 - 4*Rm*Kv*Kq*Kd*(Kv*Rm*If - Kv*Vb_eff_3)))/2*Rm*Kv*Kq*Kd;\n% angular_velocity = [w_0, w_1, w_2, w_" - "3];\n\n% Determine angular acceleration of each rotor\nw_0_dot = 1/(Jreq*Rm*Kq) * Vb_eff_0 - 1/(Jreq*Rm*Kq*Kv) *" - " w_0 - 1/(Jreq*Kq)*If - (Kd/Jreq) * w_0^2;\nw_1_dot = 1/(Jreq*Rm*Kq) * Vb_eff_1 - 1/(Jreq*Rm*Kq*Kv) * w_1 - 1/(J" - "req*Kq)*If - (Kd/Jreq) * w_1^2;\nw_2_dot = 1/(Jreq*Rm*Kq) * Vb_eff_2 - 1/(Jreq*Rm*Kq*Kv) * w_2 - 1/(Jreq*Kq)*If " - "- (Kd/Jreq) * w_2^2;\nw_3_dot = 1/(Jreq*Rm*Kq) * Vb_eff_3 - 1/(Jreq*Rm*Kq*Kv) * w_3 - 1/(Jreq*Kq)*If - (Kd/Jreq)" - " * w_3^2;\n\n\n\nangular_acceleration = [w_0_dot, w_1_dot, w_2_dot, w_3_dot]; " - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 37 - ssIdNumber 4 - name "Vb_eff" - linkNode [35 0 38] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 38 - ssIdNumber 16 - name "angular_velocity" - linkNode [35 37 39] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 39 - ssIdNumber 7 - name "angular_acceleration" - linkNode [35 38 40] - scope OUTPUT_DATA - machine 1 - props { - array { - size "1,4" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 40 - ssIdNumber 9 - name "Rm" - linkNode [35 39 41] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 5 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 41 - ssIdNumber 10 - name "Kv" - linkNode [35 40 42] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 4 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 42 - ssIdNumber 11 - name "Kq" - linkNode [35 41 43] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 3 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 43 - ssIdNumber 12 - name "Kd" - linkNode [35 42 44] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 2 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 44 - ssIdNumber 13 - name "If" - linkNode [35 43 45] - scope PARAMETER_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 45 - ssIdNumber 14 - name "Jreq" - linkNode [35 44 0] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 1 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - junction { - id 46 - position [23.5747 49.5747 7] - chart 35 - linkNode [35 0 0] - subviewer 35 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - } - transition { - id 47 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 46 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 35 - linkNode [35 0 0] - dataLimits [21.175 25.975 14.625 42.575] - subviewer 35 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - } - instance { - id 48 - name "Actuation/Motor System" - machine 1 - chart 35 - } - chart { - id 49 - name "Actuation/Rotor System\n\n\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 50 0 0] - firstTransition 69 - firstJunction 68 - viewObj 49 - machine 1 - ssIdHighWaterMark 30 - decomposition CLUSTER_CHART - type EML_CHART - firstData 51 - chartFileNumber 6 - disableImplicitCasting 1 - eml { - name "rotor" - } - } - state { - id 50 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 49 - treeNode [49 0 0 0] - superState SUBCHART - subviewer 49 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function [B_omega_dot, B_vo_dot]= rotor(angular_acceleration, angular_velocity, B_Fg, B_omega, B_" - "vo, m, Kt, Kd, rhx, rhy, rhz, Jreq, Jxx, Jyy, Jzz)\n\n%B_vo_dot = zeros(3,1);\n%B_omega_dot = zeros(3,1);\n\n% C" - "reate J vector\nJ = [Jxx, 0 , 0 ; ...\n 0 , Jyy, 0 ; ...\n 0 , 0 , Jzz;];\n\n% Create r_hi vector\n" - "% rh_0 = [-rhx; rhy; rhz];\n% rh_1 = [rhx; rhy; rhz];\n% rh_2 = [-rhx; -rhy; rhz];\n% rh_3 = [rhx; -rhy; rhz];\n" - "rh_0 = [-rhx; rhy; -rhz];\nrh_1 = [rhx; rhy; -rhz];\nrh_2 = [-rhx; -rhy; -rhz];\nrh_3 = [rhx; -rhy; -rhz];\n\n% " - "Define vector from body frame origin to center of mass\nbr_oc = [0; 0; 0];\n\n% Define 3x3 Identity Matrix\nI = " - "eye(3);\n\n% Create gamma vectors\ngamma_Ti = [0; 0; -1];\n%gamma_omega_03 = [0; 0; -1]; %Rotors 0 and 3 use th" - "is gamma_omega vector\n%gamma_omega_12 = [0; 0; 1]; %Rotors 1 and 2 use this gamma_omega vector\ngamma_omega_03 " - "= [0; 0; 1]; %Rotors 0 and 3 use this gamma_omega vector\ngamma_omega_12 = [0; 0; -1]; %Rotors 1 and 2 use this" - " gamma_omega vector\n\n% Define angular velocities for each rotor\nw_0 = angular_velocity(1);\nw_1 = angular_vel" - "ocity(2);\nw_2 = angular_velocity(3);\nw_3 = angular_velocity(4);\n\n% Define angular acceleration for each roto" - "r\nw_0_dot = angular_acceleration(1);\nw_1_dot = angular_acceleration(2);\nw_2_dot = angular_acceleration(3);\nw" - "_3_dot = angular_acceleration(4);\n\n% Define the rotor force in the z-direction from each rotor\nB_Fr_0 = Kt * " - "w_0 * w_0 * gamma_Ti;\nB_Fr_1 = Kt * w_1 * w_1 * gamma_Ti;\nB_Fr_2 = Kt * w_2 * w_2 * gamma_Ti;\nB_Fr_3 = Kt * w" - "_3 * w_3 * gamma_Ti;\n\n% Sum up the rotor forces in the z-direction from each vector to get the\n% total body f" - "orce in the z-direction\nB_Fr = B_Fr_0 + B_Fr_1 + B_Fr_2 + B_Fr_3;\n\n% Define the in-plane drag and induced tor" - "que produced by each rotor\n B_Q_d0 = -1 * Kd * w_0 * w_0 * gamma_omega_03;\n B_Q_d1 = -1 * Kd * w_1 * w_1 * gam" - "ma_omega_12;\n B_Q_d2 = -1 * Kd * w_2 * w_2 * gamma_omega_12;\n B_Q_d3 = -1 * Kd * w_3 * w_3 * gamma_omega_03;\n" - "\n% Sum up the total in-plane drag and induced torque to get the total\n% in-plane drag and induced torque on th" - "e body\nB_Q_d = B_Q_d0 + B_Q_d1 + B_Q_d2 + B_Q_d3;\n\n% Define the force lever arm torque created from the force" - " produced by each\n% rotor in the z-direction\nB_Q_F0 = cross( rh_0, B_Fr_0 );\nB_Q_F1 = cross( rh_1, B_Fr_1 );\n" - "B_Q_F2 = cross( rh_2, B_Fr_2 );\nB_Q_F3 = cross( rh_3, B_Fr_3 );\n\nB_Q_F = B_Q_F0 + B_Q_F1 + B_Q_F2 + B_Q_F3;\n" - "\n%Define the change in angular momentum torque produced by each rotor \nB_Q_L0 = -1 * Jreq * ( cross(B_omega, w" - "_0 * gamma_omega_03) + w_0_dot * gamma_omega_03 );\nB_Q_L1 = -1 * Jreq * ( cross(B_omega, w_1 * gamma_omega_12) " - "+ w_1_dot * gamma_omega_12 ); \nB_Q_L2 = -1 * Jreq * ( cross(B_omega, w_2 * gamma_omega_12) + w_2_dot * gamma_om" - "ega_12 ); \nB_Q_L3 = -1 * Jreq * ( cross(B_omega, w_3 * gamma_omega_03) + w_3_dot * gamma_omega_03 );\n\n% Sum u" - "p the total change in angular momentum torque produced by each rotor\nB_Q_L = B_Q_L0 + B_Q_L1 + B_Q_L2 + B_Q_L3;" - "\n\n% Define the total rotor system torque as the sum of the in-plane drag and\n% induced torque, force lever ar" - "m torque, and change in angular momentum\n% torques\nB_Q = B_Q_d + B_Q_F + B_Q_L;\n\n% Define the body forces in" - " the z-direction from each vector to get the\n% total body force in the z-direction\nB_F = B_Fr + B_Fg; \n\n% De" - "fine the body frame linear velocities\nB_vo_dot = (m*I)^(-1) * ( B_F - cross( B_omega, m*(B_vo + cross(B_omega, " - "br_oc)) ) );\n\n% Define the body frame angular velocities\nB_omega_dot = J ^(-1) * ( B_Q - cross(B_omega, J * B" - "_omega) - cross(br_oc, B_F) );\n\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 51 - ssIdNumber 6 - name "B_omega_dot" - linkNode [49 0 52] - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 52 - ssIdNumber 10 - name "angular_acceleration" - linkNode [49 51 53] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 53 - ssIdNumber 11 - name "angular_velocity" - linkNode [49 52 54] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 54 - ssIdNumber 30 - name "B_Fg" - linkNode [49 53 55] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 55 - ssIdNumber 8 - name "B_omega" - linkNode [49 54 56] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 56 - ssIdNumber 5 - name "B_vo_dot" - linkNode [49 55 57] - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 57 - ssIdNumber 7 - name "B_vo" - linkNode [49 56 58] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 58 - ssIdNumber 12 - name "m" - linkNode [49 57 59] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 6 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 59 - ssIdNumber 14 - name "Kt" - linkNode [49 58 60] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 5 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 60 - ssIdNumber 13 - name "Kd" - linkNode [49 59 61] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 4 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 61 - ssIdNumber 15 - name "rhx" - linkNode [49 60 62] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 7 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 62 - ssIdNumber 16 - name "rhy" - linkNode [49 61 63] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 8 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 63 - ssIdNumber 17 - name "rhz" - linkNode [49 62 64] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 9 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 64 - ssIdNumber 18 - name "Jreq" - linkNode [49 63 65] - scope PARAMETER_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 65 - ssIdNumber 19 - name "Jxx" - linkNode [49 64 66] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 1 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 66 - ssIdNumber 20 - name "Jyy" - linkNode [49 65 67] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 2 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 67 - ssIdNumber 21 - name "Jzz" - linkNode [49 66 0] - scope PARAMETER_DATA - paramIndexForInitFromWorkspace 3 - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - junction { - id 68 - position [23.5747 49.5747 7] - chart 49 - linkNode [49 0 0] - subviewer 49 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - } - transition { - id 69 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 68 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 49 - linkNode [49 0 0] - dataLimits [21.175 25.975 14.625 42.575] - subviewer 49 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - } - instance { - id 70 - name "Actuation/Rotor System\n\n\n\n\n\n\n\n" - machine 1 - chart 49 - } - chart { - id 71 - name "Actuation/Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 72 0 0] - firstTransition 77 - firstJunction 76 - viewObj 71 - machine 1 - ssIdHighWaterMark 6 - decomposition CLUSTER_CHART - type EML_CHART - firstData 73 - chartFileNumber 7 - disableImplicitCasting 1 - eml { - name "angular_body_earth_conversion" - } - } - state { - id 72 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 71 - treeNode [71 0 0 0] - superState SUBCHART - subviewer 71 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function euler_rates = angular_body_earth_conversion(B_omega, euler_angles)\n\neuler_rates = zero" - "s(3,1);\n\nphi = euler_angles(1);\ntheta = euler_angles(2);\n\nAeb = [1, sin(phi)*tan(theta), cos(phi)*tan(theta" - "); ...\n 0, cos(phi) , -sin(phi) ; ...\n 0, sin(phi)/cos(theta), cos(phi)/cos(th" - "eta)];\n\n \neuler_rates = Aeb * B_omega;\n " - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 73 - ssIdNumber 4 - name "B_omega" - linkNode [71 0 74] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 74 - ssIdNumber 5 - name "euler_rates" - linkNode [71 73 75] - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 75 - ssIdNumber 6 - name "euler_angles" - linkNode [71 74 0] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - junction { - id 76 - position [23.5747 49.5747 7] - chart 71 - linkNode [71 0 0] - subviewer 71 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - } - transition { - id 77 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 76 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 71 - linkNode [71 0 0] - dataLimits [21.175 25.975 14.625 42.575] - subviewer 71 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - } - instance { - id 78 - name "Actuation/Aeb\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - machine 1 - chart 71 - } - chart { - id 79 - name "Actuation/Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 80 0 0] - firstTransition 87 - firstJunction 86 - viewObj 79 - machine 1 - ssIdHighWaterMark 13 - decomposition CLUSTER_CHART - type EML_CHART - firstData 81 - chartFileNumber 8 - disableImplicitCasting 1 - eml { - name "linear_earth_body_conversion" - } - } - state { - id 80 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 79 - treeNode [79 0 0 0] - superState SUBCHART - subviewer 79 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function [B_Fg, B_g] = linear_earth_body_conversion(E_Fg, euler_angles, m)\n\nphi = euler_angles" - "(1);\ntheta = euler_angles(2);\npsi = euler_angles(3);\n\nLbe = [ cos(theta)*cos(psi) ," - " cos(theta)*sin(psi) , -sin(theta) ; ...\n sin(phi)*sin(theta)*cos(psi)-c" - "os(phi)*sin(psi), sin(phi)*sin(theta)*sin(psi)+cos(phi)*cos(psi), sin(phi)*cos(theta); ...\n cos(phi)*sin(" - "theta)*cos(psi)+sin(phi)*sin(psi), cos(phi)*sin(theta)*sin(psi)-sin(phi)*cos(psi), cos(phi)*cos(theta)];\n\nB_Fg" - " = Lbe * E_Fg;\n\nB_g = B_Fg/m;" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 81 - ssIdNumber 7 - name "E_Fg" - linkNode [79 0 82] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 82 - ssIdNumber 11 - name "euler_angles" - linkNode [79 81 83] - scope INPUT_DATA - machine 1 - props { - array { - size "3" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 83 - ssIdNumber 9 - name "B_Fg" - linkNode [79 82 84] - scope OUTPUT_DATA - machine 1 - props { - array { - size "3" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 84 - ssIdNumber 12 - name "B_g" - linkNode [79 83 85] - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 85 - ssIdNumber 13 - name "m" - linkNode [79 84 0] - scope PARAMETER_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - junction { - id 86 - position [23.5747 49.5747 7] - chart 79 - linkNode [79 0 0] - subviewer 79 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - } - transition { - id 87 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 86 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 79 - linkNode [79 0 0] - dataLimits [21.175 25.975 14.625 42.575] - subviewer 79 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - } - instance { - id 88 - name "Actuation/Lbe\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n" - machine 1 - chart 79 - } - chart { - id 89 - name " Sensors /Complimentary Filter\n\n\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 90 0 0] - firstTransition 96 - firstJunction 95 - viewObj 89 - visible 1 - machine 1 - subviewS { - } - ssIdHighWaterMark 16 - decomposition CLUSTER_CHART - type EML_CHART - firstData 91 - chartFileNumber 9 - disableImplicitCasting 1 - eml { - name "complimentaryFilter" - } - } - state { - id 90 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 89 - treeNode [89 0 0 0] - superState SUBCHART - subviewer 89 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "%function euler_angles_IMU = complimentaryFilter(accel_pitch, accel_roll, euler_angles_gyro, pre" - "v_euler_angles_IMU)\nfunction euler_angles_IMU = complimentaryFilter(accel_pitch, accel_roll, euler_angles_gyro" - ")\n\n% LOOP_TIME = 5*10^-3;\n% \n% prev_phi = prev_euler_angles_IMU(1);\n% prev_theta = prev_euler_angles_IMU(2)" - ";\n% \n% phi_dot_gyro = euler_angles_gyro(1);\n% theta_dot_gyro = euler_angles_gyro(2);\n\n% phi = 0.98 * ( prev" - "_phi + phi_dot_gyro * LOOP_TIME ) + 0.02 * accel_roll;\n% theta = 0.98 * ( prev_theta + theta_dot_gyro * LOOP_TI" - "ME) + 0.02 * accel_pitch;\nk_gyro = 0.98; \nk_accel = 1-k_gyro; \n\nphi = k_gyro * ( euler_angles_gyro(1) ) + k_" - "accel * accel_roll;\ntheta = k_gyro * ( euler_angles_gyro(2) ) + k_accel * accel_pitch;\n\neuler_angles_IMU = [p" - "hi; theta];\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 91 - ssIdNumber 4 - name "accel_pitch" - linkNode [89 0 92] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 92 - ssIdNumber 13 - name "accel_roll" - linkNode [89 91 93] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 93 - ssIdNumber 5 - name "euler_angles_IMU" - linkNode [89 92 94] - scope OUTPUT_DATA - machine 1 - props { - array { - size "[2,1]" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 94 - ssIdNumber 6 - name "euler_angles_gyro" - linkNode [89 93 0] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - junction { - id 95 - position [23.5747 49.5747 7] - chart 89 - linkNode [89 0 0] - subviewer 89 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - } - transition { - id 96 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 95 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 89 - linkNode [89 0 0] - dataLimits [21.175 25.975 14.625 42.575] - subviewer 89 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - } - instance { - id 97 - name " Sensors /Complimentary Filter\n\n\n\n\n\n\n\n" - machine 1 - chart 89 - } - chart { - id 98 - name " Sensors /IMU\n\n\n\n\n\n/\n\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 99 0 0] - firstTransition 109 - firstJunction 108 - viewObj 98 - machine 1 - ssIdHighWaterMark 15 - decomposition CLUSTER_CHART - type EML_CHART - firstData 100 - chartFileNumber 10 - disableImplicitCasting 1 - eml { - name "idealIMU" - } - } - state { - id 99 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 98 - treeNode [98 0 0 0] - superState SUBCHART - subviewer 98 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function [accelReading,gyroReading] = idealIMU(B_vo_dot, B_vo, B_Omega, B_g, r_oc, g)\n%#codegen\n" - "\na = B_vo_dot + cross(B_Omega,B_vo) ; % body frame acceleration \n\naccelReading = (a - B_g)/g ; % acceleromete" - "r reading (ideal)\n\ngyroReading = B_Omega ; % gyroscope reading (ideal) \n\nend\n\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 100 - ssIdNumber 4 - name "B_vo_dot" - linkNode [98 0 101] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 101 - ssIdNumber 9 - name "B_vo" - linkNode [98 100 102] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 102 - ssIdNumber 5 - name "accelReading" - linkNode [98 101 103] - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 103 - ssIdNumber 6 - name "B_Omega" - linkNode [98 102 104] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 104 - ssIdNumber 7 - name "B_g" - linkNode [98 103 105] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 105 - ssIdNumber 8 - name "gyroReading" - linkNode [98 104 106] - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 106 - ssIdNumber 10 - name "r_oc" - linkNode [98 105 107] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 107 - ssIdNumber 12 - name "g" - linkNode [98 106 0] - scope PARAMETER_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - junction { - id 108 - position [23.5747 49.5747 7] - chart 98 - linkNode [98 0 0] - subviewer 98 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - } - transition { - id 109 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 108 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 98 - linkNode [98 0 0] - dataLimits [21.175 25.975 14.625 42.575] - subviewer 98 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - } - instance { - id 110 - name " Sensors /IMU\n\n\n\n\n\n/\n\n\n\n\n\n\n" - machine 1 - chart 98 - } - chart { - id 111 - name " Sensors /3D Graphical Simulation/MATLAB Function" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 112 0 0] - firstTransition 116 - firstJunction 115 - viewObj 111 - machine 1 - ssIdHighWaterMark 5 - decomposition CLUSTER_CHART - type EML_CHART - firstData 113 - chartFileNumber 11 - disableImplicitCasting 1 - eml { - name "eigenaxis_ucart" - } - } - state { - id 112 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 111 - treeNode [111 0 0 0] - superState SUBCHART - subviewer 111 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function y = eigenaxis_ucart(u)\n\n\nif abs(u(1))< 0.0001\n u(1) = 0.0001;\nend\n\nif abs(u(2)" - ")< 0.0001\n u(2) = 0.0001;\nend\n\nif abs(u(3))< 0.0001\n u(3) = 0.0001;\nend\n\nu = [ -u(1); -u(2); u(3) " - "];% [Pitch, Yaw, Roll] \n\nC11 = cos(u(2))*cos(u(3));\nC12 = cos(u(2))*sin(u(3));\nC13 = -sin(u(2));\nC21 = sin(" - "u(1))*sin(u(2))*cos(u(3))-cos(u(1))*sin(u(3));\nC22 = sin(u(1))*sin(u(2))*sin(u(3))+cos(u(1))*cos(u(3));\nC23 = " - "sin(u(1))*cos(u(2));\nC31 = cos(u(1))*sin(u(2))*cos(u(3))+sin(u(1))*sin(u(3));\nC32 = cos(u(1))*sin(u(2))*sin(u(" - "3))-sin(u(1))*cos(u(3));\nC33 = cos(u(1))*cos(u(2));\n \ntheta = acos(0.5*(C11+C22+C33-1));\n\ne = [C23-C32; " - "C31-C13; C12-C21]/(2*sin(theta));\n \ny = [e; theta];\n\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 113 - ssIdNumber 4 - name "u" - linkNode [111 0 114] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 114 - ssIdNumber 5 - name "y" - linkNode [111 113 0] - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - junction { - id 115 - position [23.5747 49.5747 7] - chart 111 - linkNode [111 0 0] - subviewer 111 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - } - transition { - id 116 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 115 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 111 - linkNode [111 0 0] - dataLimits [21.175 25.975 14.625 42.575] - subviewer 111 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - } - instance { - id 117 - name " Sensors /3D Graphical Simulation/MATLAB Function" - machine 1 - chart 111 - } - chart { - id 118 - name " Sensors /Aeb\n\n\n\n\n\n\n\n\n\n" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 119 0 0] - firstTransition 124 - firstJunction 123 - viewObj 118 - machine 1 - ssIdHighWaterMark 6 - decomposition CLUSTER_CHART - type EML_CHART - firstData 120 - chartFileNumber 12 - disableImplicitCasting 1 - eml { - name "angular_body_earth_conversion" - } - } - state { - id 119 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 118 - treeNode [118 0 0 0] - superState SUBCHART - subviewer 118 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function euler_rates_IMU = angular_body_earth_conversion(gyro_reading, euler_angles_IMU)\n\nphi =" - " euler_angles_IMU(1);\ntheta = euler_angles_IMU(2);\n\nAeb = [1, sin(phi)*tan(theta), cos(phi)*tan(theta); ...\n" - " 0, cos(phi) , -sin(phi) ; ...\n 0, sin(phi)/cos(theta), cos(phi)/cos(theta)];\n" - "\n \neuler_rates_IMU = Aeb * gyro_reading;\n " - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 120 - ssIdNumber 4 - name "gyro_reading" - linkNode [118 0 121] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 121 - ssIdNumber 5 - name "euler_rates_IMU" - linkNode [118 120 122] - scope OUTPUT_DATA - machine 1 - props { - array { - size "[3,1]" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 122 - ssIdNumber 6 - name "euler_angles_IMU" - linkNode [118 121 0] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - junction { - id 123 - position [23.5747 49.5747 7] - chart 118 - linkNode [118 0 0] - subviewer 118 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - } - transition { - id 124 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 123 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 118 - linkNode [118 0 0] - dataLimits [21.175 25.975 14.625 42.575] - subviewer 118 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - } - instance { - id 125 - name " Sensors /Aeb\n\n\n\n\n\n\n\n\n\n" - machine 1 - chart 118 - } - chart { - id 126 - name " Sensors /Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 127 0 0] - firstTransition 133 - firstJunction 132 - viewObj 126 - machine 1 - ssIdHighWaterMark 10 - decomposition CLUSTER_CHART - type EML_CHART - firstData 128 - chartFileNumber 13 - disableImplicitCasting 1 - eml { - name "getPitchAndRoll" - } - } - state { - id 127 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 126 - treeNode [126 0 0 0] - superState SUBCHART - subviewer 126 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function [accel_pitch, accel_roll] = getPitchAndRoll(accel_reading, accel_roll_prev)\n\nmag = nor" - "m(accel_reading);\n\nx_accel = accel_reading(1)/mag;\ny_accel = accel_reading(2)/mag;\nz_accel = accel_reading(3" - ")/mag;\n\naccel_pitch = atan(x_accel/sqrt(y_accel^2 + z_accel^2));\n%unwrapped_pitch = unwrap([accel_pitch_prev " - "accel_pitch]);\n%accel_pitch = unwrapped_pitch(2);\n\naccel_roll = atan2( -y_accel,(sign(-z_accel)*sqrt(z_accel^" - "2 + (1/100)*x_accel^2)) );\nunwrapped_roll = unwrap([accel_roll_prev accel_roll]);\naccel_roll = unwrapped_roll(" - "2); \n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 128 - ssIdNumber 4 - name "accel_reading" - linkNode [126 0 129] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 129 - ssIdNumber 5 - name "accel_pitch" - linkNode [126 128 130] - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 130 - ssIdNumber 6 - name "accel_roll" - linkNode [126 129 131] - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 131 - ssIdNumber 7 - name "accel_roll_prev" - linkNode [126 130 0] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - junction { - id 132 - position [23.5747 49.5747 7] - chart 126 - linkNode [126 0 0] - subviewer 126 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - } - transition { - id 133 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 132 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 126 - linkNode [126 0 0] - dataLimits [21.175 25.975 14.625 42.575] - subviewer 126 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - } - instance { - id 134 - name " Sensors /Calculate Pitch and Roll\n\n\n\n\n\n\n\n\n\n\n\n1" - machine 1 - chart 126 - } - chart { - id 135 - name "Control System/MATLAB Function" - windowPosition [422 539.941 189 413] - viewLimits [0 156.75 0 153.75] - screen [1 1 3600 1200 1.180555555555556] - treeNode [0 136 0 0] - firstTransition 143 - firstJunction 142 - viewObj 135 - visible 1 - machine 1 - subviewS { - } - ssIdHighWaterMark 11 - decomposition CLUSTER_CHART - type EML_CHART - firstData 137 - chartFileNumber 14 - disableImplicitCasting 1 - eml { - name "signal_mixer" - } - } - state { - id 136 - labelString "eML_blk_kernel()" - position [18 64.5 118 66] - fontSize 12 - chart 135 - treeNode [135 0 0 0] - superState SUBCHART - subviewer 135 - ssIdNumber 1 - type FUNC_STATE - decomposition CLUSTER_STATE - eml { - isEML 1 - script "function motorCommands = signal_mixer(height_controlled, y_controlled, x_controlled, yaw_control" - "led)\n\ncontroller_outputs = [ height_controlled; x_controlled; y_controlled; yaw_controlled ];\nsignal_mixer = " - "[ 1, -1, -1, -1; ... \n 1, 1, -1, 1; ...\n 1, -1, 1, 1; ...\n " - " 1, 1, 1, -1 ];\n\n% signal_mixer = [ 1, 1, -1, -1; ... \n% 1, -1, -1, 1; ...\n% " - " 1, 1, 1, 1; ...\n% 1, -1, 1, -1 ];\n\nmotorCommands = signal_mixer * controller_out" - "puts;\n" - editorLayout "100 M4x1[10 5 700 500]" - } - } - data { - id 137 - ssIdNumber 4 - name "height_controlled" - linkNode [135 0 138] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 138 - ssIdNumber 7 - name "y_controlled" - linkNode [135 137 139] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 139 - ssIdNumber 5 - name "motorCommands" - linkNode [135 138 140] - scope OUTPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_NO - } - dataType "Inherit: Same as Simulink" - } - data { - id 140 - ssIdNumber 6 - name "x_controlled" - linkNode [135 139 141] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - data { - id 141 - ssIdNumber 8 - name "yaw_controlled" - linkNode [135 140 0] - scope INPUT_DATA - machine 1 - props { - array { - size "-1" - } - type { - method SF_INHERITED_TYPE - primitive SF_DOUBLE_TYPE - isSigned 1 - wordLength "16" - } - complexity SF_COMPLEX_INHERITED - frame SF_FRAME_INHERITED - } - dataType "Inherit: Same as Simulink" - } - junction { - id 142 - position [23.5747 49.5747 7] - chart 135 - linkNode [135 0 0] - subviewer 135 - ssIdNumber 3 - type CONNECTIVE_JUNCTION - } - transition { - id 143 - labelString "{eML_blk_kernel();}" - labelPosition [28.125 13.875 102.544 14.964] - fontSize 12 - src { - intersection [0 0 1 0 23.5747 14.625 0 0] - } - dst { - id 142 - intersection [1 0 -1 0 23.5747 42.5747 0 0] - } - midPoint [23.5747 24.9468] - chart 135 - linkNode [135 0 0] - dataLimits [21.175 25.975 14.625 42.575] - subviewer 135 - drawStyle SMART - slide { - sticky BOTH_STICK - } - executionOrder 1 - ssIdNumber 2 - } - instance { - id 144 - name "Control System/MATLAB Function" - machine 1 - chart 135 - } - target { - id 145 - name "sfun" - description "Default Simulink S-Function Target." - machine 1 - linkNode [1 0 0] - } -} diff --git a/controls/model/test_model_R2015Ax.slx b/controls/model/test_model_R2015Ax.slx deleted file mode 100644 index feb8b73e27a6546344f8e37555adce78811d6436..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 44942 zcmaHSQ;;aIwq@J4ZR@mc+qP|<wr$(CZQHhOcfWJz>)n~E`N&65sqCyIwf0^+@>0Mc zC;$Ke5C9y2ijq@dYsW@_005mp007wkT5U|64U7$(4d{*R98KgM?d(k)oh?k9=-h3r zeH15c2MG|qP$N47>mP+<3VD;1h*fMVRJ#e+NXo!y@+7`qhh?uy6qc~3re@$KPa+Gc z3VGDYqjQLv#N|OUunC`CV|G?1-6M!j)6uF}uujUrLJLIVA0r%%_SZ9@s#5m~^owwh zmvOGUYAHryZuuG6AfRx^qU$5x?VGi<8GnXb{1!<tjX-lCPcUs^4lCS*&7}IhCNDNq zs{QvcB<1tE2aWmfYE>ol)a)Azi0PN`svOydX&0$uWnU@=_ZirYtLcu&-;AE0HhBM} zbYP-_J7>T@*8ORrQx)Y;Ka`^2Yc1Il>=Q=8np3)q@tDQKTa{8Sg2WsR8j@&{WzK*- zr}&<_SMf1&=fu|9vQS`)z%yS+ntDeNwj~Ms?2um!Pxf9d=_vTHzKHt9w?!hikS@72 zmL89SBS+uo3}p2S?zV2Jg82QDX<~DVX9aRfOQRcb9@gv)o*nXPwi|&j|6ka|%~XYr z{KG`-A3nJM8yg$9{}&yTSOHmJMi`M=B$L^q>YyNbvTYY|!D5^~5>@hyp_qd?rdD!j zH0HXd<JYfVp1-F>w(6uz(Vl!)O@a?NL^@*M4jeq(7NoEg{DuPx^c0%7+0$;bsJm3? zRkQ_VH-wnaOPU_6qF+In#$$6OT&o&jv+F2#%-ZufuAhPH4;vb@OK}?}lxKNKC_GI$ z6I&Ej+(?gV5iIcOz+_e{OPUT9h?GUgs7xKNdg9$*fvj#VzY=#IBS8dbGdyR+>W$kk z?{Xfm!2i7g{fiTYY5xpg_*cmOe;Xj;?rdV~WMOCfpL41c(+?NGfB@=SyxvKRz-Ug9 z^>iiBU26givXNj*{Pt?dy?<}=K&G@3i8~w#^txjqZUPjLbuV+P3H!QfqUN_3R?|Pv zwQxrUrl3}w9S!dc`?mnW%dp-P$Lh>5OIEV}e2hpcvOd!XLmkU*ImomxMLDI&tNA-O zRs04UuoC+)Y<85sg36c<IUVouDlXM>a^-tf!3W^KZL|90@8bjs0I&@O0D$(tZF4qv zu`#qYu&}1Hw>4W<Jyk<qLlUbfNK!#W2WmixCoqHzXb|8GDi#+Mqz`y%A>bMEgQ(Jo zMj(KIq7m_A1QH|>DVOADjn_4vmoKs;2tokL^f~<o|2*#Yn%UxTI@#iKo5<efZnLl> zB`qhQBq1RIt!E8|dh7H(t83G@v$vo@W0>bEK`0#zNcMhvu>*P^t6iya3koXg{LL5g z*jR`V6ihG=YY$f%XlzbTmv@U%+<hhVbQ<iW@XMcaSB~+I(wtX6aq_s<qL<dI2R1+W z`!V~C-|}G<`4aQ`1TH~QlX8qyq$kpJFTy#xtD&vaVTOv6gp81!$jE)B#rm@sl>sW+ zUDWmd>fab`CG&&8?V9YQ%uYq-0j-KQ%T%-zZh9ln8q?!p!C6K_;-#hh_GB<0*%0cZ zY`lw6SyY4t9bN<#4vo+G;+y{#Uhg?J8f${A2hl^Hs>>S~C?j9280(xkpEI8wIMJQR zHC(aJJtV#M@nZ)tJ)R^)oK9{%16YE?hxJ_RrHLa(7dYYC%$eaYJ|iI=r376;zWkyr zvTnF&CHLwecFF{{UiKNrYFmEZc(BOJl%d^1)&{!4Qub)yUQEQ`%>4)w;tJAZaejbX z0dgt91NlNG1SGaX!`3z#bzHtMl&S|5D%Sq0f?qY+ysSNJYWB;}n?4qERo08U+Yic8 zrX7?Gz8)GSGXAF$Fy1im5!?l)p~YAaiP?_FJc0<{3sf7k1t0K~^7oCHrw&Br{Hl3Z zoXGWwOWaDq(C!7soPP_cF036F$|V)VU)SwKQAPg-fFYl)nI}7jeyT2|+<6?hs98E> zWjLXNCCNBNklvZ)P<owh$STBaB4oMid9=rW9@mLl{HNMJU9R2n4g|#3a`}iw3YI70 zwnG7(rI;KsIs=DT_rZ3hY<?98+58DHjP15#p>TaVzWn_{e1l{qh^YeihXN8qA2o0X z^mH0T3+Hrmh+>eQkQQR9bLdG5OWaz>`qSO*36eR=Gt0GJa3F!Xf;?OjM)G<-na{#) zb;!nm+kwHwg|wrX@`;Oe{7%C&_ZST4=yc{uw}_IY&7fi^n!N{=jvm+kt^1N5$_`#9 zqn7Ezsgepwd@JkXH_7;zvVanNeS!9g^rea6@v%R!p|{v(JQXMZ+%JwCSsTlo1er5f zk7wPLOs-ojq{C+~br~MKOUPlT<R*kB?x~M0$ch}6rn>3`IkHua7=i=k+A@#^@zu%( z<YRA6c(;Q#fZNZQevpT9ye7ju(DIQNK4Xyh)MzRi_UQR5O9zLgyrPRLpmp<=MiiHQ zP*E{L%9MQZeAhi`9A|_Y_be$@C45x%3XQNb{vdjG+yo<oG~c;U^VWg3fkNP_&j%7R zT%GOgn9saO{_S;$=EZ!hpy(sC$unl&T<xh~ys1{}#l5f>CXl__SwUGP<pQyVHuIns zJRv%&F1!u(@#lWk+U)IR@^7cnAGxG}bPf6&9~@;?Rxp2KGYic&Qae?TGrf<5bB0VC z{un1h9fYn8a!KctuvT5?0j1Wq?$E{TshRqC=*(Q*(I2E<-fN70BCR{Y{c^AvIk*-a z2An3;K!*W_vwizR^u4}q&&!6GiH@PEsj0PgS;il_PZ$|9&H$-Q1@Gv4I|$@x+;h+O zK<51iHTAKppX>CI;C`sk496G_y)6+~0eOf^nW}V#${Hym)GSImw8a53q|As*<dP^G z$jM@K4-jlaikboMc?aGDfS(?7G|#^UmUirk&GO^IWRBfkSDQS&M!RTm^>-P`?VUm! z^Bp<1n+n+7ijG3V_Bl0dJv^zNQu<mAx6NIrUP4Fc#VhJbpxfNP%$%4FKi66t#ErQD zKB^2|<FxAE7c;TKw&r7CY`{u)&}2XAd}2r#dDLMVF`pLd>tx2dk9i}W6JeJoe5VT` zz^{Z6-j5%i*%6U@AVt@>1qTl-a>jFqd#~d$3D&0r+-8b_lMm2Hg*(nSf7iVj81nAB zTei7$-j#;^a}!ceFlkB3GQDs%uuq?Y>|l;>dlPQF=P2!E^^qae1F@nmSo|%u)qUf_ zK+^yhJyuWU`)sUxfR8)KJUBD}+ObfQ}KH(r7&DUw$#PtKuGX+v&(Hxg_xRpJtw zwnYxg>iyfS^aqbm{#u7$s#;qmRaalPXT6?2wd-10Bv6j{HEl&jC9a~1FWpsgXb)R$ zGa&M0%g`$Z93F%g#6~Fptj_qbsioDSrLVqS4Te6IOp7;w`O>q$(4~fRv3tROUyd;) z@8l^~*(=@gqId|qDQRkQ2DzDuPoA@M0inL5^Ey<iQZMI~K^QglE^@HGHc^1IKfef+ z?%jScS7d>4-%VvqUkwjPZM(W0XMHYa3%GU#WlNTW@t=&-&<;IV7v0ooFnFy{!T^*Z zAfo^MZ0L@25_d1ygrIGiSGjDLSC-!sw>JoJZ<Yr^UDw;s3;u22*l3LaWkx=-XE`w% zQFw<I5D-{7%f{T^LIOQ|AIgO1Rc{|X-;b(AYByX@fB&05v{z&Or*eO~TSkII>b)7R ztx?mz7BVR|?k3|i<n!W#ToBj?cmkJjT|$N7(I|&poyDNMSx=*qJws7a5s))s(y+0g z?JR=_F3-h!k#0g(5;rT>-n{kT{a(|HfdA|1sxK>cOv$o_RCXh)(XcC{VMjM~<YPd% zAnlYlb5yt?=Y3;zN`REVF$E8r6A;~5JhI~Dq&Ok>MG1DOmXxl#I8{7INw;%=3oK{h zB%AK2R(q6unI_K5uXM@frIc$M3%&2mXCc(kKD#H?;IOVqp}orRb*I_-suX#WnmOlc z61&(momOw**vTK>pY16`L+z#;@!Oi8-dYhB+(MT4%t5!`1WS|%g-K3oj`vmlOLGQ3 z_VWlEePA67RnTy>9vgA9q0seoeHPf*b{%lV5_$G*G<TXaaQ(xI@Vg!v@|c+WUe+(V zlFy%e!2ECEL`hCTkE0ko@Gs~@;99a`NJR)EETij3B%<1F7GAAi%8BX{^0huuKT|bz z(9Mo(PMVhNcJ*|bWa=;8Y#GXuiwbF&P%D-+#QnHwG~aoWxz(D*??B;{YA<S^;dMxW zbGP><a?nTR9OQ7QnrBd~1nQ@whB16^!Xe!`_T$X>b8+2c<NaM5C!W%BXfLtF@{1J9 zkJ(7>2xVA})Gu=2Y_9@NSd#134MdeK9@<o?AOf`4qo`7@m+${YK~t!|#oH_Z0NPJM z05Jd2G$#ui7i$Y!D|$m~J0mM&3j;Gp1DpS_&g*U~x6QG5hA*Dp05Ohn30Ab|Pm`-< zCz8pW`w^_qc$P!9bYmBNq=dUPA`FD4;&kc1pPT3aL&fyV1O($bJ5_&Bmd%w_)YMkH zbANL;Gl!3qvZ@oE-*>%Emew+dCN((aQq+FCTgT~N1G|5n?mAD&&$)HGbahMCWs(Z> z6Y(!&alUMs@`dimpWe5RKF`R0Zo3=Ll(>Bza82fEVjEM3hrGaZ6OXySyLQ-US3Q58 zbUw>9IwIr_Cuwx`a>?25cl;UuSg$ff-K@1jywIeNZksJkPTt%d8sqw?4~0g8dgxDM zqaDw`Z&T5k?Q*>t;Py(G%^%RrI0X%8{!Hy#Hj5uTdvv(@>ArrSkj*4u;`O<|kZ9xx zx4w-}ihR7wc)Ey;k@#9X_77USW_w56OJ3pb(es%};JM{`KHq#fHxA{#!p((-kEgMB z@NoQnq|z9&OECE&)73p*^#U(Z(F$nA|Iy=~B)@HN7Rlwv=q<gBz%;QF{QddBxF6d& z8Ya@LjXajIWsNj`ckp!9#+NfQnVw8vHk_3dV=JlJfA;iYpG1s~F#Gkgi`OL$8-i$s zY8(M}2V@vkgP&T2J;>`0%#|ii!;&Lw3H8nBG1~tPfje0CWi7oR5N?@J2(gc7WL0Iw zuACv>e7EZRNvlGJ(FW%z1XRejT3jD>JLj~>V;ACbz1@@XPJhJn%AG>wOFB$6vDNYd zr+cN{9UfnHfy0k|gBy>0d8?CHDNQmb6722Lp<SSvi79}~#%0aklq-v0R}Qt$IkH&U zw@C%Y#heC*nb?NaKA1i0R%d8l>Gi%`KN<Y6o%Z^X!J4j5^Yz*C++xPrVWzixbWg9v z)S7@Er+eUO?T)mJ{pFFd)6GXFo#tdtQ<^;Hd3kwo#68_kz46*vV#V2I7J68Gwr+|Y zEI0Dp{DtoFg<5TS_quFFKYw6q=L}DoSIJ5q=<;j`x(!|Co;bWs_#=1)2l@L^yE`hL zu?ny@Vc}e$OLqTtc7w{1`3m=QH!AXTWuI8;+cl9Jjwb-F3iJ2u>C5LGhgWy@;mowz zZ4V>=`19|X(+)B{6i>c)EJyXulPAaI0rn91ZkmBP+s@}#xu4<eIoV#qJ&Zt07-Jm0 zVpH-xVz04(E3R9cb_oaK1FcWq%*l8t&BV=|!5iW^LZwKMs<~`(IENKCQrywe(X6{` zw5%t~0fs=GHafkTP=siYRAbi?!;ll+=;e{62NrFuF}>X4^2haqNlJe7kjL|7C22y4 z*f{q%0v9nsVK7c5a}&4u_82cR9Cz&Mdnby->nbzkhZ#h%xdT@1;xJesp$|ahA7@3V zP{M?f$JTZ3nKt>Ju4uEP;4s3+w-f*>op}nWzhqZS#x!(Q<O(kijR(=}nt8-nz9f^m zRc*E8z`KMxpJbw;r&ugFjFU7{su)9!+(MrcFH0U7bTLG9y#(!Xb}IpZ!B9dHDmIk7 znJ9;dwST`1!c{LwG+V{^d?ykhX2<VE!e-G?mk}zM=<Aa->-yZ$ZB~R;^V~YC0L6QM z5zOr9XCK^~ZSh(+S7{5EKRBmjSyNNPK*nd^`j~`?^@vL*dE*~5IcmHwGtIM8XR9(d zbY%jT*&mI4g6DNcq>US&m^6mA{t$A%@J{pAsLj*xO0liO!18i%`#QNR`%HV@*|SEX zo4H+b_i)5ERI>Yu=pygemcAQ~_?&QyHelhZk<X95IetzJbN58CMt%|X8URV=49|9n z+u0Tzd*AMXeLKb<=cZR>?=w4xupeJ7TYG#}1p1133}zNHtWZhSmkfDWliE(Yym?ft zqc`4FrC@WP6cp<pi+k$M^=4^?oa5~@(55v3!1kUM6#fu66~C_;q=>lvA&H0bXyery zZWNp)xT~2Lexvxf?MA;htY<5SV>G_{PF+`)y@%j9a#z;rCeo(}ba8$8P)BVE%>AMC z@X=~N3{N=~-xS!B53H{g9ByRE?CqQMmleCY5d_{5SzG%%@lL(cQhv=V#Yc$Cco4-E z9xt4mj6mda%<QC85dS7r9D_IujNfwmfb9%dJGV}W8TP6u4VS*?-a|M6ywK-y3go$W zjAW%m&zjVdYq&FqN!sta=b<T)jZgfep&NGt)88%cZu*JGQdjW#vT5`KWeu(n5w0sF z)}@n>D9TSda9Vm#TD-E;uXPi(HZc*m^7L>d!;!{Co#MVAAa-ubAx8ePANubhCMW>@ z#{V>~faMc;=)|zaav|4sdV_!R+s5+<FqtZ(q2~_VB0R6)Ie1^Z`SI3Ogj`I{|2cm9 zETqWQQ9|{vBv0^93aUl3P`-jAqm1l7)o>J<vUR4SWwY)sWK}LHSPJPO?iyJVuq@Q2 z8~ZC}cK#sC^yHqXK)&WbuE9UDM~g{hd?SJPL8mhn?jARThrB7pS;eCM0@q+1ofjA7 z8whh1?7k7=rZNQ{?DOf0Ni34udmTA%P6G7$?b5|PWm}{)duk@`D{VWg6u(C$+B*uj zH#i(n_I&QulcTfm9=OlHGJ_N^H_&H>pSbMs;Ss*#vEwcI23K@R5Juu;1f>WM@rP1( zFR<tyM)8wN>(zr2_mD=HXgR6!&8V`HF$qUGxKYr2j}g!7yTv9htgmk;Z=FoYcbxjN z0hmH*nR~Y2_yg%vq?NN|c7?H5rwG45<d87L)LnYnj48<7FZSTe35S06CZ*BI(EQJH zOX}n^StPlWwcZZNq;WQRql9jk{zGZz8Cv%**f*}tJYQq7!VWe3YJwY)G8rT%b`65q zuFS&mf$TNtn%`|8@&{BHvf(I=W^u3p=IQFW_QTC>CYbuRBOwq7X3sn21`tMi;jmb} zR_|f_)=k+mQ93CH)25?fe9VF9myKbLx9oHa(DF@;Cwg@pVFsyr$U%`hL7)|nkY1yV zI7?R)mwfmH7s;5sr>yM?GziKjqGZT-opjxICXLzZea4>)9L!iJrY8{0Jjj>HFJoy3 z^Ld6GY2kmDBJGBXS7;LPaq90?kB||R4+Wz8?1cgzlCd~i*rvdsh44wAA^xnHc>Ab# zTVGAj>}qt`p3=$!Fa4HK*0JaW&qg>#zTpgfr1?wyd7r>8n<(q9?yji#TDFeZ;}bKw z!Pg_Mr&4~~U2?vf`KW@<cc=S3rKnd%dEub}5g*LYrx#XdLe~`nHfn)D8Z?D45ZkVW z<_#VhyYZBSBD*y<c3QpmZ0n8K4d>rf)A3n|FLQ@B@tTyRsz&$mb>lO?p`t4I9*L7j zP$wSzFfqK{1>(t)FwCsc)_1}MlZ5qA^m)U3LLyEXBSMeJm#iVEw@(Gcb9<PqT)u0d zcN{P4cKh7nNGU8eDr>oy48zvXO6fYUJHOV-Gd=8^u*K<zKb*J-N(c3&_uP?h+`=Jy zCSjnuipIvtMo@etb`=Ne1LRv+_$V$i^+LFUbraFE#amLw#CBto>u))BK_}dh6ozgP zxnNQiI!@qOBlBOh3xjVTy#D$#!1+-Hj|k$6pwYrKT2BWEryk4z3;8(jk3nBWH~qxM zs>TjMhhs3PSI>^k{go?GhIXWg+w*p6%DVLJ6<eD!sBK)6^O?HzwMIpQf0->Pxu1t6 zQu)X<dcx5lhFCqY2@=Y6P0nQ?Z4y(S)DaW`uKV0a2myg`rzMT-%y0g@>+|OSHb?w! zXgAF_hFXDvDb~fYcFYiacQ~JZBi8#&O|QJi?+Lo=+u*g1DWr0-zeP4_Rd_DQ-yI1x z*@8G_u4R#!r~7`8|K845-`!f1QSeIB&11>_giVD$HzIvP?(8#u$M9TY3)c%i9zBe) zPDMW(&JYl3?Go}YwCgW*(uhW!l(vD~Y5SN!-@;CY2>Rw(n40jPvxmp!4>Gq`?2Df! z$GjT^v;44)%OoJfquH?$T9IfHT%8Qj`1j5K4MCJE=U@%v=81Mdi|Bh9%pgL|zQy1@ zJn{4v<iv1s>5ecm1|T54xX`?V7&x{}H^fHA4GN>&)y+8&_6Os5kINomJ1>3HNjX_+ zU2&HtD2^lGho3%p&PdA%K6Ky-UqLp8pijLw<auB0Xo2JiVO1>BC0Vy_3}eC)0)6=A z71PvTRrGGqI3=kE07ojTDhz4Te?S+v_Qs|kf1I`s9ZW%`-bG-`)av<1gTKm+y-h4C zZ`O^Yt46cjPimQd95jBCJ9z7&3U~8f|1t|)y>LvNB&KGH3^tWb+oO_7VO@gR67tS; zRcE1a!n!j9mzLHfbOU#oJBA$H9iEj=l?HLnGr*FqoAwjpA8B*w%-jp!;&y2kQJRU& z7T}Bm9kfafKs%_CQ9+-ODrPJwFhoE+8G1GW1e>4cXxlB!M(uxY-IE-bVbLKDvK&L^ zQ(}ral}ETenq5*S%Fgai9xLExp}&1mP)4(HXp$JBdB?^eU9AX8`kyHb5IPZU6V6H< zPqiYReBW%Iy=Kum1t@=ke6m6JN;tG!`O2=`=l*bh*TSAs5Y9oeVdD~R*cyX)4dzed z9UjtZI3D+#XX4)7e6H;gO=r5$O}+=ZhrRS2BAO+@j;puHdN(=U^=#0Lhlg*o01-vE zgn1t#G`OBk(O=WET#Hh$iJMx`f+v^Kd}G8X{UM2_VsM-53X?9>_2I3Mp_buC!pY_9 zAikiO85Z<Jrh_E9MZo>@#z@o~=Nj;Ab`@J$rQ^>V2`7(qdj3XtL_?{Vj~D6rND;I5 zs?o$*xbue&!hMP=C(!^TYk;Fp^5_tfd-%;~2e|MIFce=LjhS;jo(hN7OmHQH64p1i z@ku15W)m(iWIRBrla;aoj3Fx2BZm|p0p$$w!tjh8t7yx6phY{xF^kX&ev&bLM+sZW z=W1Uy(J+!tc=k~kAMv`{@m353HQtUMnowMUzNL4pUkLo*Dy6^~g_2<PKH!kddTK{g zkuvamS0<?CZ1zey`XE*q&PM4ds(cc8pJknkS6k`X!`<bIMRR5mJHvk_;Eg2aO$_EB zDJX(>=VCN%A*+<|iuefxIId6wUBrN7byuM95oZH$)k*Sg@P{ujlERRr>$T;LsJz{c zzcGj7ojzL(3R>dK#hf>P0@CcWxMhk+`JL@+bEiM!2+KaD87G4E(Ug!qU9;dEv;q3g ze=sp`xoh;^GJeP4Gwv9o(#mk?JA%h76P4LPO)_DC!4T2-GAhJ9?Xt$|$8~f9#(m=2 zylJ5`62b2QaJ^2iiigGwY|GM*l1SnQ&ea`y$17)ww<nx;XpPLHlSFt(&tZi~#tv%d zgl4!^V<Bd&#d(cwEKYAm1Pvi%A7vC)nEYmU%<{&m?b6Pemcw_*;aoGIXKqq&MG%3g z)$#ta0pq)vMv$}_7ibYYmeeF1C`NQ|HMAX!zQQ@m_*o{Mn|1>?nAoP(Z-hn)JyKWq zuXfwWfkOV^2StzY3gqh>XV;L*mtm6|`!FDrc+ATQu#B(KzAoBM$|gMc#{DgOX`mC% zKCrJ&**LqvfzQg6v1ROZuT&gj81tmr^M~pJb5P^E{lvij2ZNkl0_F@2;vLLJKxibj z_SvVa=p&ce_SGP#xJJhSWS&T~)wwt!EC59G8)E&X`^)`u)Y~Kid9UsPc%+4RJz;L` z_!5F?AD%7K8>oSOj}<noaNgdmxE>N`|NWRTqEJYRB*=UZy~94S;@}G$Z}IpS&@Tet zGw*oq?14&9G7t^>P|O#yaGZNc?l9W0N7N(`Ryt6TJKP=n^hvZAceFnZ@b_iTtesMr zCr?kcNr;?%%GTb3o%T46uVj!}s9+-gzLTFQ-?dEn(pBlbee%)B_QU+gq1*9Jp%{kS zX?F$4{!ag^U9T@?!?Lj9$)-D|(a7J_VQQ>XxyFfU3fB@e{R4L-%@&&xjMev!zxclF zR1pFwa&53mV@3vlU2zSt_PC*nR`$Mta(v`;w0z&8;WPia{ne3JghQ~29>=VRd=6P# z_VAJqs#U{yxsP&vLL_?}{S?Dzw`UP=CJEJ#wRGGrvew@rc6uK$s#@Z}P})BuOZ@B- zz|rZEdhQnSPg7MnRfz5KQV!(QTca1_LonJ~gA=c5%W!sTjJ>RudlM0wvAMvDhArB8 zsExr|`4rw8^h^$=>k;YEUN0YSoktfRK0!Rp3L!z_2rOji6k)?C##@*hOBOAnxi4g9 zMJv01+;a@1A%(Rv(M9Mw?ebk1gkHyo9%!48V#0YlMEg80Zbf#Haufe*P_ymb<Y8o! zTy~Y*qH-m3o^Z~(Y^LQGme_Z%QY`?<0yDFuZ8ue1l`d9A4_JBC_eH$smi>l~L4P2| zpGw5jy!ZCve1E)<^+Zhc&ixWu*Cot-G3hM){=Bc>4mD~WBmc7Z#ykp?wp{x8c8G^& zZLZIJKdf4>wQqB7If1+_dhi~7>H7Rs;+n~Z|8@^jJO82o+fK55eDGcy*i&Md;qjhR z*-7*5;>P($&*-*k%&BQL!U7tx<ms!360zg^I>St+_fgdIB+C8<U>5HMQGp~Qi8mga zD7L~Wf88O7_zjlkng>6Am<8vHv1wzEF{t;r+288CS*4Q68%`#LM0HWLw7ig?A<6;n zR3u2sZv{024Mb*?5h8?@chCD_{aGN)^Gkr`!;%MtG$!s?PoXb_zR5xj+NS^R)#Pmx z-v4(p(mJvi_{49n5`*B$;0>JVYjc|H*5;f3#6owz5A@ORQaN+`SwE8}X?{<jsDFM~ zCAbG%bl0tdc5hJFkABZSqK97;Cj9RxQC%$guIYS4n?3pFjy$Q#fS(+yC2m+suPn!| zBjddH7c&8$%x3T$9YPrV7B(#UmusP5v_ZrQkO!JMV-SC2KA;?YWxux|pD}uGQSr^F zqL-#-th!Tk4udpkUzLufOB3aTjas2)Tz-klHL-udZ+gCnh}4`3te@#J21}Ofvhh?$ zh)L5Xe_}pTxln4aIf%S%Q{5mPHy1XbWqO+A8+(KG2$=PNmUYp$EB5gUdtO@p<Tm0T zgf5BisiV3YulEqZ;mis6sMbh64gIdp4V6n=YgB9JgC$A#$wTwTpTk=__*@k|bQa6X zecU%jt3zf9!2~Q0p1`Jxkq;bI6CH5L=^Kd^jM3L^XA4dCB2wlSM>;;?L!|AhvYi&F zki3rQa9pCw9pcPY=zQbbiZDI&_3DT#8zp0ahD|_)<+yD;BvZ39T<Z$A<OTZZ3zcy1 z$g9m;=!RBW0<!h#7;1H4*VHi#{LX;-Ay<=FRpVQ#L7(xR3n0IzEpm<(mz=5<$Ww_R z%hyXZ+KDNJmv~KV>HZ;`!}&_B@AGu{I7xN`M4ZEXO?tgAk$DV1f@ohe;*X^0axB2L zQL;pUpc_3x$ThBvY2ZtGfAGG8;1%E0+tOZ?g`#VzGkH0k4EbLzKa$?VgvLYz54N1@ zA&FH#>!?d-d&^f(L+(PFfE%qRw^h^1wI&{1V49d<cvbHK&HPH|0aqWR*nk;gT#z#a z_oGbTB49s=-&z=#yuDKktXOb|I(fqOr{T-<Q^A5ae&QX{1Z-$Ww!U2NlFH!oE`1J7 zOJIwP-l<W-GS5&_EEm(QdK(cl-ryEwF1no;Zu3ufkIK{iywG4B23`ljcKg*tW1X{$ zVYmC-E56@UW9v?<0f{8D@$1~54cpW_biKMaEhp>?HxjK?n96Fa{??kI){@p5>t{{{ zY)`%EA}Sqfw8bQLCF*I}VUytQ>ipmrZil`N=}~T@b<!GSN2k?FOiy6S^AY2WgaVPR z4E>DMToQe#N`#4>dArT;7Ouy-38aqwq7h;qLCNS-?Dxs)V`IK?xDpn!YEWewXiUkL z=zlS8kF(Heg_Fxq0R&}>1gp6|Nh3=S`(lY<S;?Z|<ss7k@M%|MpGVlq{T+9Q?I*%= z0&^wA&!r=G=S=koA*SehsCe)P9IcW%$~guk@}pLXY#21DoTf8^L`v-jL=<K^v(e zC??3!d2%cxYOlCSM5>~SWysX03P~qy7G@1_OW?Z4vkJ0jvdwhz?apE{1Zk_tzWFit zNPVy%kI7^Po??+bo7s&uRlw)t;Sa~b6g%9giV1V%Ak@MujVGd*{8fKJ(^FQwJoN_n z%oTam#M*m({Ki=6zIqSTSAlB9ye;s}+Kd4qkuXj?MwogO(v9LuB2f;g5+YNR*d)V; zPEI-+w-N+YPXdq&av&`m%P8DC;XaoKd7?=`u1QlbaAk-e-tD7Z06Y%e(_`ZO+eFe= z#EtB3dbkFkb%B)L&DIW81+`CPRXYG`ZDLvRGGO=76wVv>Axejn_Qo`J^^gxJt&=zL zy1^qHl89h=p@FkNVGlV8JLtOQ#bR#Zxz@yw)!?Coqe$g~3G$ZgKx?jp=2ouqD;%oZ zOeB1+AC1mS5={hRP1701jCKsAKvWpK6x(F-siY!rYe=(0`A~_0&7-yeE+LX|9HY6s zuE|Q_-_gZ!jfO9E1K5eSxc3jsB}nen6SQ<NQ-(<}a`behS^<Y^N0-%fj%Jf^#-dVb z1?NvnEfV}3v@@Zc!V`~qcN<46u{TNLzQtOLYY)LL0lS5;?A#4+!rpNHf0SFLopDIP zA@Srs(rV*D_#!oL@E#f<P>=N9uxG@E$nlEvjZT-O(K-0#gN6FWKb=zv`8!s3?elZP zZ(%TSbgh~30KG@9ak$Icv(D|VR)$5)PO>p__6;6AQzPkkadush8(Os)8isV}lQDhN zqT6dr4oQ|*n;<a;C7W3L%;t|}58uo?;NnPzSr&T4OzX<Jsr?_Amvk^t<%7@S(0T)E zfQu;LGMd_WpbJ3&TI|cOARfVy#&CZhp;@w$VKvlEaZL;fH1SSCO5_w22|Y-O)**-8 z1d)HzXg!7z+mZ3OCkjV0k3saHWy2F|MV_W)rM_LNzlv&q-%Qh}2AD*PjDPl+pfM2V z7t@%c+y$3zijv^_Fh2O4?KKL%yhVdoKRuu}ngi_Pc3pzV6Lb^*W}Y7l2AX1p@mK;| z{)`3ctUxA2Oae{czwEVvzH(!r+1gFAJdUe+CE`4SN5qTS&1}B}oh?EFS#zcQE&Bmy zDGrAX>r_`H9Ir(<Ds^ii4g9^2U{@3d1{-pD_HZy&h%>53rTI;W@hYR|=4TXHHZPd{ zJ~^1H0{Zz(&q8{GYt9d$TYFtWb99ez&1GzlwQ<e_DANIFhWN&I*m5?cA_h`vk?Ld5 z1h=L(0ng-eekCOd{zmWZz?Bla?dE_QSjpk@l+fwYJ`&g}`)c*QK*_~Hx^k<Srg_U5 znZuok8IA5DFlsKfDwEp<tJMl85Bl7ZL_ODKkM56*BmmV-amA{|88pa<xllpKm%!8< zX2}~LB}MSXq0FQ$<Stano8GqtC#8h-TB+Gl3LZ96%=eBbZ}A4T_PeR2Zrt%2soCP< z(<z!oxOJEFb~>Kb;?s^NZB@@1X|8RBjI)Ku?UfQmYZ`euTpiDUV*$f17o0FJdi@ui zq!PNyq-OC2zNuQDwi2AP7m82yb`R7}T0oz<E*2g~^*n6_GNH~F9!I$U&4{L9k#Jc_ z$J5HK<Ea}bkeXAOoP)fA+46)Vk5EQEYoz1xQ${r#e)T3vHOolX@qnZ2A#0qcDM62# z*&96Z2&7az;WXeETlSDe1$IIG^>3^dbbiPXy1a+20Jgxz#G~nPJLq-)n~F+~R$dUa zjz<mk>}H_Lv4@$Z`LRb}gjy!e$oYsv3OS?aBt6S&%a-DFC(FIiv>gK-wf6hs*9Rz8 znur*C&Gg5hLjXPXt+d?l*xx_joA8zR5-0MHc3Pt{kDo$auxJuZqF_>w^t;3J-tpQx zt$lw3doN&qct4)#G)E#&TFrEh>U6p_@I^E}tw?~CKGVKwMXs)ok2z=7iF>?!cD@Gx zX&an&9I<vzO)1sX3gZ%u5p^&<R==d-ns>colaA>wD;WE~ug>c^m_A+$?bfJ19xV}v zGX=E_=I)POl8u>VgEY&zoiMIgvkTU?xV_?bst}!jdRTd~BS*h>VG&cV1g`9c>3yGX zqW<1nKO}Pf(fmdK9cGv-fhtvfg(v$6<a+L&!KZlw_rh|{t^3jF>4uyf26J%g2|Gn6 z`wZA5Pt1kEv+m-%%ADf+YMj;1;)6If?A2vQM?YZwqu;A17C8xj-A$5x^w3b?0UCQA z6k_37f_jThhJU#eM>mgm6wv>E;OMZL19IJ)LNb}SqU77w6_zqSJ&d2SII~OS?5EQ9 z8En<<pZ_jL$KD)XC<keGphpfxb?SGm=$)^y!a6oWwG#kf>0dGBdMjuMcIZq9*sNL4 z&tvf6MwmYayZZyA>}>7-F}4JVo3qS+tw<y9@&u<NUS*$U0`RO}&!263;Rn|Xljlk~ z90R^=p#{HAR}A3%Mn|$D{$0**(p@4L3t+YPqr9}EY$r%0p{Z1hj?SsuDYe-N8Gg<e zLq-zl=0FL-u8WK$**-cKWPArk2YNkXC1@D4)G2XNOE(An=Zz9%ib5x5Pez;sN;bB+ zc`p<@dYQ)<IicUH4&^K`BQ6ctN@{o`Ff$Hj$A4JS{B}5Y@up400QXYadAL3!uFshv zc!X|6-4MP+t(>1zF_l8U69qJITJZwuk9KF$;2Usxt;&Z&&;fTZZp3BCewv4C6-Czh z-dquSP@8#7lM<tdoGSIco5`gsX3(<wa$Qe*w-(FC>9eX+pQERhKmD^TBdUh7qeuU@ z$&}XxJ##tMl($!E@#R0A+o8;9C%m8KbD)X4$oDUqEgN%vhK)7dUk{&$!CI~!0#eEx zT<()&Y6ihx-t1G$+H_(pG<x=~x8vh@tfXzw-DUwenq;p`!Mir>BjwDJ%#P`W3uB8- zHS=(KrimIY#)+9d({Ks(7gk~wfdoJXPv&e4H>8d*aq@iVrqqkENh<HmwZk2$7)4}^ zbe?B@S{D$=>m-H*#a3QWra56(6Kc`4KDb(3Ad(uT4Twng<r^vBCT*%F%-}8}^OlZ= zW|&z;JAHYRGA%`#zV-7$6g?#cf2qZ=qBx$XVrAk$$9YOCp-7y3k28isoG1zE*REz= z7wIGfK;wKjc-C-vEPhLPk4`X-i)8JCyE!XDRD8M-?W|+{!d9@mxgE+d2nAS1YOV^& zue==24x<qbKJlP-c@C6SI}$&__!Cb5eE{m=jgZHtt}ry_tti%<E~$V17m4N!dFi=f z{=c-Q9}1=Z?mV4$h$Wr191NO(?7sdS3>@(X>o{_<vxl^oA?_gZkq$SxseNlSV*kvY zp)pRpG3-HylrQ4ao&<<qNA=LDmE*<^*^lo0lgRxWx9jY7^jjFE!DM#Iv4qxbX24V1 z*V+jlCH<JUN5kad+>5rrPSWS+8FA-CvGZ(5ceZW5G&j)!!Pm3@R5o6pW&pa}f<p@D z0PF5%+KS!C{8|8#NF}asvf~Zz>vk}yC{^F2y^eA)Re%7nk8DJaiAR0)XHgJ6<^t<_ z%_6R$&Q8-S?k#a6Yx}7|g>aoLjK1^Y(IPlGrUL1iR+x%bV{pvv>4ABE@#f&gnp=1Q z;IBgyanTMx_n@}=c-e{YN5oT-aIh=zI<qMNB{FG_hJig_%VMfWMvP3n1tf(oP(pyK zlu=moxR|;%Xzk10@l4zj)gW&?@-u#qTe#euogH7g(X9{vWg0r$_c}+mR6t<BE_Oc5 zt?G`B?z=SIZeOyOQO6~IEpH-I{Po|Sp(8HWv$T5)d_$f2Cart+724LDKoZ|j^Th8_ zG*!b&8?7_YYX7mDP|_6BT1hrnBQK{p{OZpt3ZUW3x?IbPSIo%Odk_V1#r2bx8_)Z6 zB|#oA7h_tCmp&S|k1>|;kdQG`nR#%M<ZB?M#qFZ!Yxov1ez!pm@YR}8Zn*BHF{7dn z#4ddJ<F1@v11-*ji>hNU2axPc{H{r0;u4Is2!4S0Vb4Et36)#`KO~e26ez5LKAE2h znuHPHlWlw&b3_l!QBnR-*b-Fe@kSu>>Vh;#*n^M0>mbcdIlOsKuTrYs>9YWkELAda zXn=WRP`UPGPpmtOPKsu`2n-sW0TP)A^0_}`TdQV)#&*Lyb->}v(msS{<c?JR0>`RT z-k?JxUBh<&K-FtX+0u-OyoLWD(vgM!gdnYX8-Fp9omu8ZXX%2Pu*+KNs-X-_?%83i zAamv8A`oeb4Rm{{CgIbW_ZI=Ct(a!Po!z<q*kF&kQZVjz(-fntQ?VEOR3B+64eQ$F zLPEZj=*;iRI=-Qj0mgpQYD;g5#TtQ+*>N6^N5ms_V*??8i9193eJ_E85|~SP-b_#d zA0-#kEp`^dR?-F>>8-Wsh2-P~!p2OXp$u}WuC>aqsbxSG82Xj-PQBS5#)2BjEu!h_ z!c1t9Nn^HwJ$C%qQDYmA?zbV9BNqha(x{B(t~g&Lc#w7oCh`Ti2LYjT*gMvN8Ygf| zXE59gC3~3T21tj!kj%G3V)dP*r%T#YqHC&?jR($C+C}rESF*vSNA8Z`>HD8>OD$@< zigHV27Os9*t~5X_!$lBf9Sn41#4_y$%7ns*{9@QG&NsZqMxu(3ef_*D682y*9xG>M z{E17JZcT(GP|foPkxzuEdGbpK&9_4HV3rj7#hZso&ze+wGrW=6DDHxA0wcfwE|LjD zsBR&H5zHt`mUZkh5#Nsz|C&pTQ~IC}dOB=#s~C|n6aon$@eSx4kQ?l?NRA(wFw09W z=xtXo=5O}D;1#OYD1Rcs-IMtX;J<K|((mE5j5jJQd#6&aPB{#0)_t8*KXx0MO(~h! z^A}XtFg|Pcz|&lZ7h!u!x;g^b;^%Mik&?LJz8HG$LZnBAS^{zgA^#VBNh~cb*01TB zhK#yD59BEPuThqiH;;sTXE=R(N%o$V#+=ngI&7LI`2z7+IC}>HP)z|e%Z1qaL6WzA zyF9Oc3a{(g1AqsDO@}gR3LXn{(85ryJ1NLxgt47`hPY$RXr6=^s?u2RGf8r~hR3A8 zAaCGtg09Fv(qU!R(nQKvmk^NOE#+F$<ETR@lgbUbEUyC!+YFenqKIFbvXQn%i$6y9 zSHesZvR$wFhby*l*w~CV?FzhvO!{YFB?LQDoTI<(zDb<Y76wO^(N>yPEe3lK6LNG5 z+X6M&a@N!ghi&Iq_RnQocoq9&8>4GqXN?MrO=hANbx{Bdc)A3rY>dsNjCc2E|Jd?U zzm2S6d7R-wlrihD`zLT&JRinz4c6Ci!-?=xLsUR7jZ}CqK&Nz3B_Bd_L!|Qx0lE}3 zdcq{-_%UTXG(V^$T}!pM-4Rl8A96rFlQ@@o*y3LM6KKgmBjprp3ARx%<^4nvQ1J+I zMtuh`8-UVfBM^#mu*|rM3VRCI^ee3z(6_t>2*B&W<8dZ|=-Z2CQ940WjXp@3;*|~p zVxPs!6Qyj04>*)YhtDCPB#L5(a@l-bsj}h?HvEf3CpohHN83{&%rEz~JXk7~PkN97 z5^dcE2$2?dFffc}?wq^sL9^;m)bjUH)A}fEAt<{^k`-#2y2Ax3meDA;oz_#?y_-?8 ziZ!{p6b2a&JMD_rZHI5Ce>TpHr~n+sG$Q#*Fo8(dJ%kK$=_m)iOcqf;unH(RfI}-g zL?m^PxV=;#m;jJI`7)YdQWd>$z$TnE0trBbmkp`#A0$B%_gYLaNWZvBLc$Ai65)W? zjO{r2xp2-f;3y#eceq&jn7p7+Aqrc}S$XFGb8%dz`<NHPagaE$KYtI<;IC!L@3Tj_ zNrc^o?&J1$P}p&ht}+DhkP33{xk)@7Xe!ww{=(A^?^05?Clamm*XZT<#D3zf_XIB{ zIPAIv#%FH1yJqIngsa}B6>Ozd<&;c41;us&nKpx558VN#5DeKuZVE^tB&4;%>jG&w zj;}U>s5XNnNSEkJ?I9sAj5f=$8xY3*>90=VPiegWLo1--b0VG)_Cezx+1QMWP3s@} z8h99(%Aa8OB%Zpbr6{JE(EU}-5JQSyYZHEgG%r9!c29mss)yDI;RC)_Imyp$&ISg= zEi>?9u>z0cZaPTej-{S?+DTr`JTmPDr$dMY#Gfm8rnydI1Cg^I+=wnI9jON;FyYwX z5+7uQfpPTaXio*WGZg|pET7Q*Y#A@=JS(}FVtEdW_kz4$<QO-%<7R?_ZpLOUlQ1o# z5<L#vN#KG$j`|f?Gq`Wl#Vhw9(uGFOA!3e$RO|b8NaQQ3(>NsheyB1t3D$ob*PBc8 z-Kx>lA!~|+piBDC!J?Dg@?|P1xdhEQ=Bhyi3&E8I*cDG?XW*z{lZNTJUv@v>PWRaw zSavTok@?rN8-VKj05<T6>}1F-^h<Wa`~?3!lneWS`OETF-!~Fu_KvIZ`t7Us8~88v zD*bd-<X|f3Uhd;2k>V4>?07Tvoau+{HWbS)nf`54B7k+Ohw)F8?6<v{xwF(o6zpI^ zb9W5y@X{5zbYvk~gDtxGSS3qmxTANKS*At|#+y%q-eIC95ko>I$>?mV+l~X%&*$W3 z_5ECpt|h>N&|U~3#}BR|b~N9IemM1b?+v+wO_qy6#v8yL_tu=iik>{QHm!YgU$xAW zIY>=a;Gz*)TXJQeze|g<d8>Kc6(YD=Jf?6mys?}blA0o2k&8C1WAm6#7tv}~!j*H_ z6ez68nD%-%My$q(txsTrA*V_DW&03gm~c&~Ph$*xN?Sq!SM{N#e<kRRoyMMI09&l) zo@(|bjyz_KBuU6wl7PCXAx&Lh@)Ow#klKHif?wS?ToVwNNV)k;mDW-P2qv^And80$ zv|0^9M*}NH$Q1U8v1uDd9duWUKxL1+P70^F_kX50LT!7^+n01S!b|MiR^~Au8zo8y zNh;K*BsFv=bl5s5sUmrdS;lU-uVT-2m-=h)*gGPxE$HZqyT3w3;vvf9DRIg5`<>bg z0G5*<J9-L0uwy&+VenAcyvs%LG3d=q$t%rEIuBB9lSOF3InD|VDV8M?=2gJ`x03|& zkHgE0Qr7;&tiOj*rUi)P$kiZD8$PH3++=|1`PhvKW+unaL#nUU$=a4Ws*_*9wdIt+ z!&2Chy%6a*Vdt`RWX$J2T<5_*h1voCrmrB-9$edb%$kmtYvdqi(VRohE+XQ3A)$;d zwL`sRykjcu$=h5>B39Vgfj>oC%_yLjFUfvD;@|%lU(vbhUt>N-((wsCQ4PV)?r)a* zLm%G<YeTt6_@AW#{2z|^INp)$JYS}qG&y6PFOuq`<dx%J+X9oEuPLo0Uz=ZT8knZa zV!3}&+iqM8$yZWITSjUCGBOs^g)5~d{z?uPoWZbH%-1Cfgu`11J0Q^O!dap*ti>Kx zo$dClP%(J$#DKX$l`cNTi!aO=Z1v8k3hSwrjeI0Ccc;*e60IxwO@AV~`m&E(dFb0Q z02>)6%LSf@HE>_zO}AL%NL#fdy-bs(t(-Yeuv{v2(Rv=66(6`Mm3SSqiJjb_1ug~u zcDB}}vn#1PndE#egn{N|2*UkYLXAC<4(-#hnkrW1o+0~M2GTRkwugu(uVB@0btJFL zQS<t6QtbL$l_J=6EkYVb(N-0tqS+LKLujfya^x*_4M(u(dHl5bF(aKy!h7%V<mCZQ z2&gI>;4MxKL(XlrOq)HPm^>>SpSj}1VxwzvZE51oUlEH&zM1Q!1bz>N$ZJXi6AkaG z7$#>bUFhtlfeVTk?0QbR*B>NFFxJ$BAQAREO2C=QCA;c!dh@A)K;uzrFM&$jzFNZP zHd<iUE*4afvH_oR=U*7#VurH?Q@y49pnBf`gBSSLZb+x!F<{x@A4C>)4D(<6%t>c} zSI}vmw5kaXS<!VHrsd{6L;RWHA8|JnsqVC-Xb~Qf4l8CDbS_ElF1z4avd@w*>bF}{ zNNIVm`i)OQTH#2aq3)Dyn3Ee46BPbzJ7|;_VChaX<c;XJ^`TSzV?}ZG$Z@-^L1K#9 ztNdq};&P)%bE*<cc<Z<AjE*=+Y!Hc+OnMdY_|_QZ9W*4CHaj1Y3%*iEi6yz3Xd(6( zyuNe2os{Q-5K*0<P%ZF&arOQw;ASVl7*sXEn=n*ySXY%MshX{IM8z~b7$(lkxR^f5 z1{5f$@-iQjRHZBfWe7FTMB(otMvt6_8tGeuUP?*Ra!74Gl^6&tF{VHmd^r)O&90sV zE<q}X8dNigv0;VKBvN75K;;$pYU?QSvxBu3^tP6bn7Du|P<Z1Pv^Y&-0jT)AwUS^# ztTp0xZetM}&?0*)#=7>8jTl}bh+M-@Fqm?qC=g0v>cI{UoQ3$eCI2xc?}I)<T#H*T zg6z3ap^JCo`*QGwNAI@_ubu?-oMmMc=jfO57fIxY`Zlp{Tz4yBNpW_-zp)*GR(3qz z92FuTwO;;bj@Q?a%fmiWvTLa8CYFkBR<_|Xz?^n!C>!t!Tv>~^Ope^U9%%Ur^mDfw zEcw1WJH8syDj|IVt~U~)duU&>jtS0K2b=EF3yBNHXrK&&fjZA3$p=Qdk~chk#YgnM z(@Qr--eBFA_xP1A4TnQnk+9HZ<jeyefjxzQKDFpew#-M@@!&oC*w9qoLP3~&-N+4{ z1}bvA8PGjGCGiC9kC(?HsyhAX{EOY<#p%Iz-XzJUDbUdaPBr*Ae_r##Z*`v91<^B( zM4&IJoNX97kdBZ0YhHLwj0X%v&B^*f_g?DT-Yd=%;i}Sb``)jZu$z3*viM+mX2V}) z0!;^kRpq}9WMOAt#^{Mnst+nwbW}?dk;GC;605NI6Z^z_ksbBYW06s5?cMY=)GoYc zRY`-)$p=B_P#8-)TBEh0YWTs^+gbJwpuLE|=Z+Y_^?YRMDxJm-9%}}#C23k3UBUM% zB{Kjr4n_Q02a(*tvzpEtw&*)mLqUm?+}**}<JTw(PRZ5vC$wQYh7SKi`w7Zh@&CEW z(?W9!wJLKM6;eyFydl8Pj^N@)$9amwbtUDpW^l7#AiRm?a=s^cKU3KPv~*Y%a$QTl z@^b<wcMx+LJ=^MM8i`BZXc`tQtCqB8+@!W)<N}EVm$<UD(n(huguimvL%YCPBpCp? zP!}d#(tkdqqogHz^C8dL>lq@#D(8h*%(H<B-kTt3yn4H2w<L)ZF$U9qQC){%{4JZT zA3(SKn&*_c8iW)NCfW)mR%pM?*9N0^hPJU!Mkx2KoD1o!(UxGpj9;GgQ+x$#4q|uj zmS#}A!JwF?R~8?G5|tDO5wQRc#%a|ra%Z9t$EGMc4H{ub0X;qd&HI9R)*iDjf`OFB zQY%9sf^U~_=mdnCIDkTZm>#INq~zDo&exPc(7sb>5*5D#DfSM&6Q=4?KcoS;Is#N_ ze_ktF5h7aygQ9fX7YD*k!NQ`jUe+&4;!?LX&l^}I7O?COiV$2-apx<S-jag)o(b;6 z<%4EO9d80&xB}MOKF~j$XA_oFC3)^-sRj%GtW+ITzO`Ea5N!J&#@;c=(q`KhF59+U ztJr0A7rSiRw%KJ@mu=g&ZQHiZuim}moH+Y_H%{D$j1d_#*2;LETt8OkoMViM4YPn` zrl1rURJxE)Goh$9LBEh%Y(2s$4Z2|dNA_-h@K_F~$ofU!r?BMjh%USWZq&V5Vk`XJ z)ihPY2>U^QL*#to7VoV2-Y9n^KrkK{vPIUG_9Z?wcd?k-Dr8jwBQ=51^0&SVYLK-m zwBS?_v>@=xd|*x}L&i`_qzKi7<9x1cc<)v%RefQQ!H?a3d^uC%zXfLt$f3QJ=(n!I zJCEjF&d$Ge<V<5MhPBpuI*n#+#|-lSI`evpEd9Y2KvOTo2&B_Dmn#<5(?U!2Wp#qn zQ8biinPC4g!%B_VBqFh+imr*0##>D==1AtK*K9%yuAgHS#Z&LZ2v)~4w;N90CWtUx zGBosbVG$gv!BXobk)uj><VjI3RC~!-OY_iZBW@9hZ~hb@nbWQ8(v@AxYIJUpoMVPB z-nFabHm7y1)yt+mCa7{hQpuH7Hz+5A(HbfdA}$k+C5CC(lL;4~gTY4i?8&W8E4?=r z+W9P-uouY}hW_K8A|t(L%0!G^TA*oZvg@)>GJX0m4m3iR{?p)v<7+cmt;4tb6ueQ( zHD+_Ye+&<^yime7n(mn2L{rB)5wpdXdQ(_U2xp#@X5BfMpPT);&&fJ@$4Z+8X?WLd z1~Pk7IlE=}0BG^@%tuGC3E@vSWS6@@d`$RCO`r&mj6H<t!yQzW++EHk3=1Z$#J76& z3|rEFWChS`wu`z7_{9U;ahJ^r&F$pBV(NQCXIj@7o4GeZGD)9%fQ}M^nKS|-hsEU5 zqPKQ{WSPWM65Bg6l^9M-!lV4?;KJ?>a)yySvred|X;51^ZHdWJ?O)x@>q`jneTh>L z06`5Xqz!Q-O~KcR+0ED;7OBS+`{hjk>?Lc}IKoW!M6XQFFFxA<OPq`+KvN(vHCO<g zEGUp=7Y-q)4J-OPl=zsv9+U~IMBZvyh%U~wNKTtZAKt%~wS8h-aQ{C3JXS3Kie;6) z?uvCS6O@G^DlUH9niCp4RxPm)BzB{?4mxkj!f(j0ChY}6O-D|$v9r@}LsieH_D(V< z-=Hx~ud)h07oYOCZPSBMBiOM#$-d#b{acYUdnV;bYPkYgw9<iG?6pUy{abnOj?wTJ zJya$Gm6cxQm~J}#Y$$cn-E5QwRrC0tg%2MTqhPsg*9BO~?A6&KLfHrsA2!AIFboPs zE9^N`niDxREL*vOP7hET@MN{u@r;p5f6H(hY1Sd@+_05}4%qyOHd_I`D+yeMgeG$+ zdKGiK$nDXz4PkW6TKmb=N>g;S{RrA6EUU$pH;~+1PVP%s<qSxF_~kI7U}%Uf%yN_{ zd^C9NudSWLWt4)jZSp}Bu-5)Jipi>irTp`{epCe+g2U#z{PxpZ8jB!yO5OIbGGd~3 z9DD1U<-aN^PhyQSh|<)nKJSz&3a$xx5qV2%W-C~3Pdu<=wVA{kjLY`iV>m~q#exiE zb*y?G#GIIR=cYB)_x6p=25HDvRGc{Pw&#P#;)@tA?dmo3+8lqCY4$zi%&;H8bgUKn zdf59m8e#7Ucn?q0Ff_;EFIkaO7X~=<v&o(`Irt-udR*=uQLaty9CP)97g$0=*BOHW zc^!th@Y-@zeO!z*ESAS?I8g8_IsOOa{V)$JN!s`KNh6kfC^T{}0`R4JrU%1T2B=_4 zNQ?=gnX;j?uT&NJf51{wV3c2d3!#l2oukSya_|BTkPwWa8l@y3H~g$9_FUhc1LQ@= zdTHckjooXL#%X9$v?+){9%p6|Y2@mwI6ewyljNhl%4B7V^J&nZ2m}fxY_N&}g5rRz zrTwCYfb%h_S3h#pqGu=FA5I>AsrJG?tvo?Dd+I@!3!pCuE9SX)Rq(1HKW2TJgP=qk z?bLnFsn!Ax<%!qOHrHKF3`K;xFZg?Pd#VcuIOQn-im2GAjcexhB;!8ZRtP396s5u| z8H05EtUO_cvy^eluL@Sfjl%ei&w$urvt4Va${kyRQcW0&x2t!>67!JV3zqHoLZsxa zdaY(H>jF-xJC-y&o7=XL@U|5a?I@?e<1<w@HoIjt*3q2b1U9{+#<Ohi)tAl8!~MzX zBoJ0gm$T?8<YSqmmu!aXQ-<bKFC!Upka%NL?fMxhWP|ldg$uNTG`G?s*O$!&pB?M{ zmC>SAE1ry8!j%D*3|_4fRsOSFD+<(0NVHW|cM=g+A~nf~HrG-nK?+MJnV9FkM~wOm z?|4J|e9XlfZnL^#GcFE>akgu8m&_<?m{B}5C3c`WR~=)u)Q(g-yH>~eq2`|Zd%P2> zGw@fdZ%z%EYX6E<tannsTKq(1oLW7{-=!0MK_(BkHg&Q(GVeCc^_wG(sa>j{nuLcZ zQp|69Df_$WyL{}ON``JqcB7j;BRel?eR*OjdFx&<t~eTlA6uv{_ff>s;*-L5eT4Do z+YVeUw`K}IQNGJtZue)PI;+NdUvyTEmTt{!H6KQrs}yXt(WY<oEv<i|8a<s+jR;e6 zj9ymk9b@zl*TY6_I%C!)XE;<P`}%`nl&4da_^bO0n5^H!H&0*oocifTDqy9?Yiju! zUGRwx#{rp(X7@x%o%loSYiZj55O(|-V=rG4q>60u0}ql^tXD8<ZnL!xji`Uxgt8bY zpHN5VYY?(<(sr56inxCCx;ZLwS5dC1QF3x&GE@_3YW`c>B~6y0G?3JBdn{S`%KSHW znW8zZ3xHa##o*{G5wwrhF3KKADHt{|W^}KIOlY<EO(tIH0%-a3`F^f`v_2f}62MPF zl))EbErih<BBp0{{S;*8ZVe0dt9G$%9#L2kY!11Qat}m^qJ1BL)(7vW$wxr@niRRG zhE-rx$TEPp#opN~Fg(3bk*b8y!SH3UYQ*z|0V6{vaED{G-#}xG!5BsY#7AfUR?Buy z6f>Op*supW36qj>DR7=E9GGk|jiAUJ6u^p{cg70K0KYoa1a)nuUtye?fsYOkj%mH_ z&7s$bz@c-Uu|S{`G4F$K0m_|bMq9cBX7DRU#X_i_O#tiA&|<IWybV`_7Is5r$d3Z% zB?eyH)(n4MKZfsu6HZ3vMkzS#)+9~{ql5}W*T>u<jqLeAatfqZu+lAs8)vn+d|4Ay zGoiwPT|jfUfCj(=M;29M`0ctqv2IfXin3il-&JqUsX<3O3nOW5+zY5cEz3FOuywg} zrD-*=iNvAa?2Wq3T2*<Nt+8F7y8bEnVMdVX?tRg{z7Hdvx9nY*4~=<nQ(w9c6-#>s zAAFu(x{6G0E>-VE&3;Reoo}f{U}N?-x<``gegLIq5qUhZ62T&Yf~{l`($?|{`zeHi znQ4$J#pt>xpy*-~k^Afnf0zpi1hM!IjdB}^2BI&*c0vT?#O~0)zN^k$P~)zPvq5oD zJ;cFhDvUrd_>2Tq&HbX94>bK2BHCf_3Y^*FCG61hV^y;8=m)$R8F%n_Fj03=dxj#R zgCr{juEnc0=Yh2}PqKmze^BLuIA+KXkd0AMD;;(eDK?;z42^id-t-MH+#D3BzsmEz znYEcX+AFjh*rVoUCy_U$hVo$_#)Wh4#)Yeq+AY>}j<Qhd5g-bzSX1^k+IDX75Qw#o zc^%&9u0q9u$KSf<)5X(pl^xwQD-lGMr^GPM<g!)D5Xe;AUA3hhKaRAe8NTcfA=<Z> zofF>0n0yiK5dJ7IG&omDeD-hRZ_CdX9tKA7PIj8%MfE;rUO;|^KX_+sjbj-^Pl3T; zJSh@YB&xMt9)~$eJk6ybwvURy3d7_f9mJs{4O$@yglDWO0fE%j&YRC5PE23G|1PB| zw-$GPJzQCNJgxy=<M&-6^odKJ#(>fq*lt|i5TxUJ{x*Y(j(y3lHAMAQHi*<)xEVDt z=x9-4=xSHi8m8!A+$CCSeJbImcfd;@y0XTNeIDYLdF8n8H9T3_i@kCo8rXYDSVI<@ z3V2%~4OkZu*)fq%jEk?OdEFp^%A65MinKQhXsL}D#vdA7=`uf3edv}P_oYOr$XIuh zNZcF@l$C8IXN0(QWr(el>|HwN4xn}OUI?{|I$e8%D(41px265D4G#|y1rHx1nAr7O zh>DIA>+#Ha{%c_C3q9Ue7YJFsJsWgW#?y!g44FJv;HV3F!^+HAS=+i_=B+>`0(Ge= z|JU`E%nqlF6__vEDiL9cyq1V|m$kM!*3{Rs$n6C|e#I+>FU9t!<7>jXcxmZu|M!t4 zUz~QX7n6}QGCYAFkH*<kZm+B~^0(uhe3E)|$zoll=~@ceTEB-GE{am@va&FW#&Sv{ zNoY3u3U91oS_;5aH%}6UP@!+&V@8s2i~p>qmB?j-&JUyQNi^2V*mzBMJ%w!lm027m zZ2_@C5Jg1ik$|j(HvpeFG$9)C^nUuqGyX4R){%F|L+Ey{brlZWL-R_ac*ig4r( z(XE@Wju#}*G)S?)PV+k=NS)PRX^<}v{iMfNnN(%GeuA!G7m%g|^&VxdZ&!HtT?`31 zl?4;+GgAJSGZQ28<pomyd<7aWR9A>~7W9A155_<n;OzG=H!?IJ#CRH`>WrdEU2ZnZ zw$e@z3D&RR?{K-9w^CxaRBLaa)|o?2YS(6L-pL!_+}&ctI$Cv7Xt8XZOeu`KRTz(M zyE7}d%iUbXVo6+{z{i;J2{n?4AXmc+RMLn{cqqxnC(fwcrD%PEtx@~YF-tGE2|C@v z(AL>y*hU3gBk_fgc#tI#SBOj{^f<cH&nO`uoyxccAx?S$4-YjBXo*yh)fg9n2+ZS> z=K}2fp-OE{MAO#s#OqX(A8m5;ccldWxCf%xr-ir&#|6%L>v6b&YB)4@G%T?w?_1@# z154IujsL<*+yTP*za%3rWz<xXFW?S&)i%AYl<eYkAJXJ6ld&Z4)dWd-Ls_0hVVrA= z2D+ci$b_p4``&hyg?W#_U#!ik`=ac&jX6m)vgso$1XTE!i=-{eda{J+Rm+Gg-lkQl zRmVzqL${@NQ2`#;r7vOHtlq9wsn3qGPMsG*pwM1TEY&GXdyhrFsd<ws_kh<uHw?YN zoX%X68Sn2i0QAZHtT`T;)o+-o;@l%1K8AK5M^eaw85sG`deUgAL^(X)%MNakw}*S* zSCF|L8=(rIuiy2mTC|f|4iJk^IrIn{8yibUr47neFn48^{PRMb>e^Nqa?WzjqvfOw z*3EToQ!<CbZs~kK6|9*)jN4dJm?3>)r(|;RHXTmqhqY3*b@*Pg0G~^7U6Wbw=pXO* z`-&5=&&_w0;!LC`tt+m#v<{Iw9mMUSwopgQ*%fK3;mW^%d)Dj{O)`hxctmBS>po-_ zs#8)r@Cc$WyN@bbLMig|)GI&%h+C5pwnD@7p`TDv_O!|&Ero^aQ3jmwVD(jLOX>dZ zAkn(z1l`4?FIxR*$fwcKraShFEA91h)Ef*d2>sa#;9o`0jR*;SEaVAbA82#25hpC_ z_j;AbQCQ>7R|++8Zv63G1)kPz6HElLN1ZrCyDqx(oMu;TU?)0GD5`R+mgXh^WX!YG zCXEF){4!|s#4_jQsxXwQgAlck+rQ;Wo(tFi(vWhrz>HQ7MGgRDtlJW+y~k3kx{NT6 zfZTzLM^wKN!E!#}z~$|dH$?d90bs`&Q9ym<jXediwe2KFa${*MILXy`7}bC_`OQ3E zGBbu8DaBrEH*9)~g{IfD?viIks5}$WhkUdYuyj69Md*|n)1*v7|F-4bCA&s`9X&pd ze64TrzGP*2Q)utMk4(g!zhZo}34Z-izNTo4;wy@G9!f2GA$1`sLjg)xf2IBasU}<u zlqM58vOdS4h8$)v!U(&UZYbwyu;ci?u0P(S|MV%H@5x{`Gk6)4W=(K<cn49Cg3W_F zr=gRc4VGY~J1_p`v0y66p3JGKa(Dq5!-m&{SHSk=A$FIa3{C9-B>nh+exSNJi?^fG zBI3W3rRLkamh{8pXwyhX*u_SJy9)&)#Wqh$2lyD0%%K|MwNTuMEo=uKJz&6$aR5oI zi{gU_;s*M>1;o!cCxxs7v<3>a<=*94_AE8#v?Op`Q6)v;j*!golEE6O-78}k{L*x_ z>1L^ZbJdg0D&DE5@yp(WI7yw2^#8yTN9;D~*w{-;TjG$Flg(`t4_R7#0sG1}<ZJ)C zbR-rj;mtj!CXJKBbhz0=_}M(1C70)O{`OP*0PvG9Q{!E_HuYQ2amtkft^G#RvTAq} z?&$lm{}Wqb?g3=#7Jmr}v=4#O$0oqqHNu_stzXy1ckuYm@X-!dW=|@S71)#16Lgcu z(AmAmkCQ1g#~bwy`!)E_?i9pJgg1_*j+{Yl-FsyD*=JYT*9d`I*7)5S$vBhVJ8I`0 z*(l$j+RLI*YsA;Y8}MG5{ccwVnM67#cLS*0+Co=`P!q=^uTwx@b<G>igmo@nTVm}5 z;J4-DKN>C6MXd>q+jTO|KaKHe8-JG-s+B%kIvNYsRBB)PKO1^;(Zdh;$#6+)>%$E_ zm~Ud}OoAY+%g5Hk)vL{V9@j7|Ina;3c@Ydp7Iyj))WGmd^+moXt$yYu0&uC3deZQO zC+vRdNyiG36Ck~<s;x}Ui+kwlBIKL}2NrNoY;zlgyJx^weS^N-sNRmAqP+>ks?kFf zJlHCX5da>ID76oQx`yJ#+*b+Y1p<<G6Rc0~=v8rfzfwf`5q!xR{gf~2tT?{M0*RZ7 z&$Y;ybBY0}s@UB`;Mm=WU4P<yj!uA_gdN>L1KQVYe)C_$DwE|?f%TNu%qur;XuBRI zwJ7Nj6-;xt*|Jt&zKCghFRUEMCp{>H&LN8K21LQ|`Kn*}7_rPyg^4>YASR&b5t)S2 zpmVYg;!ve21Q}%Imos<yN%7QXb&<&NtL1xPr9+LY=hZnh6%)(^bF1YT9Xb(g8q_tN zoKA4;j$d_z$#dP;g1$a<=_mtvIlQcNOCM23GWc7tUD{0A8y_cP3=>KydzlKH<n2I* z@mNC*<pa$ad+HJ1G5YI_eP+jC%XB@@ROkmmsM2&(2%mk=`D9bzo3p<ur#i$lC2Zc6 zV~;A8N)9R!<;H|>ROu!gIF81v2Hc)vs)W*;G{?SH*b7BW-EJkD3T<9~9y3j$ZWKKj zN!WJ9ZqG`L`Oq6D(d;8gw-01_PX9I1iGE+CH>Q*80tr=z79WDA^Btz?&*f#c(m)&i z>P4mS6Gsxq{R<4P=R;~qFoHSAicCPYIB2ewN3LgO*FZKOYfC0}EEz*)=%{5GE^yM! zur7hCoNHU0%Q)A&ph|YtUH_fdch$uKsWsCp4$Q#_GJx*0J=Mshlj6zl6Y`Sl%7+6u z&&9~&y!zRPsGE>thO@6T&%lYMsmZGQQpzUyYO%cP4!0I8V(!B(t=Bh$O+H!yr0x2c zaM7G$!A)<u!qy@2&83#`bfPVm)Qt^k<HydyqKz<=ux_~SHXuJ47;5Q0{ovAYKARO% zaUt?EAvD-2z`lNkb#-^+xqVpBIpgUdWm?a4v(w@{vr+jEBb75%t!;iF<+M)DVg@*@ zKEG+a3u1lxu@*kV%9lHLXU+W10ZrQ`%G+3U>)5ftiianPwq(haLehFv<E_giG@7w@ zp5WaU{_BUuP_}u%xL)yqn#kho!g)b~w1Oqe&u{d2ec}`5i*}}9l;_S7u|a_yy@0`4 z7q<Djy)bB^+X4bN0WU6K9GAJc%4txJU&e{(aiMx_x7D}))t$-k9!Z6l-c2NmbImgS zkbLZ{Jb+qX^iL{I6EKQFs(F69D(r+j_zHKXEmm9(6X?}+=GY)vukncQO-m*vXn8YV z03s-{9{NTnQb`a@8tly)XSS?Ahqg8WPHTTjiXC|nKqI-r1U>HP+>AQMgo{;of+@f; zj(cEf=$vIO;XDaG(nptm4S`An;JI$qgEdWZ`q2#=Y-tJrNZQZ>RN=umxD)NhuNn<@ z+@+8C(uiKhPQW03R%6|?(6>f1G=o?yk<P_Ff>vauWDlA|(jE^$^8P?i{OfeuB$IUG zl1+sjO_MQ;uPPf=Li7+IUMj@Frb_?J9SV+HE?}!z*U0hoo5?94*x3#DWqF*;v3=Gk z?(`4%4<@|}=mbg5ZW~aGe9IkZZA#-bWeWBdq6Y`OK5X5`7Z_umDJRrsEf{ORs<Z>k zsZ%XSu$<}2O$^HqLbf*nq(b9v-T94p9#CtMw_P7K;&u*^YoBoXq<6leKI=686q6zx zMHYESb~SWukrwtD<Y#g6zm99JL5w`SQAQAtJ$K6BGChaqfkpSC*AN<0SxVPv`AYY_ z3TRg4J1Yc>kW(&Vd~Fb5z7T>ltUiD-$JBfN8x}2qGpxfyuk2*G<XjPAkasvAC=#0J zgf`S@%RF9~MAR%NN_Dal<w1v)eE=`NaxO_PMzl#qj%y-OI`N=Vk4m>)$8~}O;~duI z-|zC78n{-E{k?$7<kVvJyJwMKIS_}ip__|FQ;ZYD!GQ+4Avk}f_V6fnidpf!$fF6m zA*2EXtl@#>Io$YQuf<v$6k;KID_eBJhOe3$^3IMUWr<)}<h9RvdC0YGX*|54nTtze zWp)xIrCZXKV})^>J#_$gAigerj@Q~&(ESR6RiTV8vETR2{ki&@NZN9fX?R<Zex`?D z;AZzWcFiIc0S!;1hrRX2559e=R(m|M>RNk3+E*88>_Eiud0##t9Y5*h*RF$KFNx^j zq$X0~6MOHlpPfe3p0ypM1To$T@!}oa<D261Mr=XveORfTin|XL(VhMSeH}D?5)NOr zNl>{&(W>H(4~s5a3QKKKG-^)^FATw1z{>>hCb^PrqOPWG?;p&cgR@$I0Ye&cSK<|u zNbjl~Gt9*O&>xlX>Ck$R=ku`WT+8E0w-}SP$uAh@CJD5>MrSk-knQ}^QY!A|Y&9+% zxlOQKKRAdWynr$jwP&?x8vbmnh+7S7%wmZ1eF@CiJ%G|ii;!8F3Dy1r+1IkzDq9*Q zF`1XP=9{J*#e2m(nV2w6nU3ufdtr}Nyn=Y>O<i3zB+qI9DQF;Gd-JrDfQJp{9+~KD zM7PZ>xfk^Rc$$0GNpsEU`u2%pm^C8UI;=`svP;}IJ=wJeUby=owq}$Zp^JnkNgk-L zIuZE?S5m|1D+46t>}kTa?;Hbpxa8n#57e<QCk9^~>}`=q%gyvV`o0%yKR=k%3(ibT z6I9aD|A@r9Gv^Ra?Rp9)x4pxDF!Vxh>2Lj8_uHZ-_VP{*-t`E-=R7caSeX!qv!BYZ z3B0eLSHE_g?;fTir4G*_gK_h&RUcLtN7W{tD6B?g#(!r>^4jlpv^95ssKnCe;!CKS zp^(}$=GI<1>N9fWXGQ!Vn-ggB&|`%lAdh7f`i>lZkFI&$<U$m}g*T97hGD?Wn}+tq z;CirQ6uI>r_hKpVrE|;>YONgJ?4!Gij&oYTdKN21o9h==4mYmy?UKNJec*slJbXH% zJVm4oB4#0!@fN!{#v_4A$GJfTbUthbNmis4yzY0pn@hFcU)dpJlvzu+Q#m&^@3o9P zVi10-OD2~I2#(wDLY=Zska^#G=bFq5*P)LCM*+KeUn1VpPm&oQThiPxI;r|j6Gz+F zjZ%I-B_(wkW1d7hI3Uc&q2XhpmJbSzwd|^o&%9#RvAZPlrE{-!I&-9Dte;jMyLX@w zP-drU!ESx%wKXd+&*1Zl4m|QM7_i@zB^BtzYc%$v%cn`$I!&OcBpG!&+oFTfUN&%K z2uA=$_b%)OM;+*9dC_$OtvH(zvw+(+e~I{e(8$`%>Nbwlx~AyFyBVSrgGs@r1=ya) zB2{}3JQf5r7l}J%&iW<iX8W0lUiEk5@;gGi?|nMkD-}h#LS7M1VX$7J=l4A+$qd)Y zqLYJ_Qo;K;%PSo3yp3JN$wMHPim6sCt^d8lX?sY`8gi2=sChSNkf#5GeSmL`ny^NE z^qA_f1<%>EmHu`_e1y>G*d-m5&QVS=S(C}VKi`}&o~Q<q(X!g+AQ|P`U_ZAyDILOm z|IWGxf^7V>!s-5Xxa&C`T5-`I>@RI;L-~jExPQ`lSD_)a%^8s^J)uxHfPBpv@ukt? zjYXP`{H^H5P!H4zHCBYlKb0$B8jVDde0AqS*sWd>M{Z5TwEaeFV!${~qT3dic0FgB z$%qNr_s=pGq$2Q%y3718s6`j8^0n1!B#SX<m~y(P6+o0PYu;)h)1^}CfQnkH+GO~m zmx|i_#G0k=Kx6r3O6pISl9fx)@gj=I4b_0u=Qz;9LKe#*w&u$e7MGbL1iN$RI1XYv z%_aJfz1nmH$=zyqNfwC5Lsl`mk7uwBtF@X;aEc<8h74FYt)t|9Lo{1PQPP#oC*pao ze6!%JfczS%Hln{16ROA2BB=obmtxLS`7bRJsf`;`l<<iXz{K#MWPjgbPX(~@W9k)f zvRG92O3C7Y$-@4!qV+Pc*+ule1SVK75{DU1KMN6)YojZzc1Q#&5`zTE3iEe6b`-&t zib8CR=_$|lo4GU{&IDKzPC<oT?A3U{{+MDkTSAjWQy@vZG66-#bQoZeEjd#yn0L}7 zFBu!RxQadOS+K1An_BN1rX_$|n*?RG?ID&Jsxy7qlVDtq%|->v+7=Q|%pE3*{Tvyq z0);fn<1^`rqcf-$p|wg*RTV|4;o_q<O?6z4dD-1nSaF)d%e=Dhh#%`^u;Yq2(g~dn zG8%I|owhHCVdV02a3!^UG<~(!u&>TBZbDxmrNiH8C)PWRItIXgV*F7rhBa)M+-sUM z?QqC*5d@1P6OGl!?42}_75jYmuWbI*ieAv9gRtts_C}2>KpLJ)+J<DE8vkYn5Ps+S z)1-mQhD2eE)_%_mJC1}WS}d+;MJ!#X2ny2h#xt_^W&c1#yh(-3boHo*rHvmfq!ubB zSL1XG>#dKg@Jfz^A@dCa8K5yYu)+Py*(jZkbYyKahCZz}59JB;e#1-`n;+>FqAbvB z&(|Ow4v=#1vF<aG;-0w!p1G5UIXs_CzM3)vvcp5Ep$I?oIA<!>*xo%F8po?eAG<%2 z)P&YLho$y*FAY3WR+%^qK{@dRjCcLSA)#Y<lIrEHV?dR1OLsE~Lh-5B5cX~5yEUCU z3X*9^?RGBpnsT$;`QBoP{afwU!L#`@Q4|Q9Em-unLniTV;*>072&wn;`(G)gl4+kO z+?X)#06jxqJg@6;7F#CC0l*MlubN*X2~emVut^H|v3Gt^#L=dip9P%V&JWqQ0#N_e z{pWW8cuUMK<%*qX@U8^4uHcOq^0O}I*vul8!0eV}7-F1^7z=gN8JVEHLM{5XPiGM5 ztGny3s2v}IK44w~g6XRrpFfC@_isDEA7_vp`3I^{#RJQFdK2in|BT?^2YfCdU2Z}| zunP|sTUDeRV8-YCZ>LVa`~0e$eouJv!?PZKJpbgXA)-U3_~ap3eF8*;U95f{0{`SK z!O$1p_~fmB1>XO_>3_d!e5xbaIUWw)C?1><LJ%{drlTSorm8brCJ^+@E2_VMj1?c% z{@M&uaoLQ&fM;Wiub&27V7GWM0{pRs0<a<%78C%Rhod<W=AW^MwY^I7uR-bqs|-0> z^Gg>}1!g)uxNgN*l{Mq~oMTRXPtqca`QiquPI;1=F_<+I=tk`Wn(f}ibel|FMpT>T zo@ed#ZR(aP3h|Cdg3r<xehgU3J^yFUT#T4B+u1vdc2T&@jhi^b5S=;5erEoKV$spn zh^5J~gClwziBE@rpH!xRbO--+uEIqGYDOUg-_QtosOkZ9;piDAhrYnOy@P#O&AisS zCxIo3QzppD?~5YmEfat6#|Y+H%J7t@(DRv7)}dZ<&gVG9$aAL3S2MWxzao#?QG}~! zjc}&$i!mLCa958A<t2bFY5J&q($3$SmolJZj&N&?__WoA3=4Mcm!|kbb9Oxc3GI^s zT#-e4uKx>Ari%>S5U@q6C>@WSa(fKjNX{|rx)zQdmoB+F;||5ehn{c{I8;aO@rvTv z{Dez>Dq|&ed-J6}!M2Nlcxj~F`M7#QST7;`_ONg(JZg@t*VKf(Z_RW1B?Ecy_@BUq zdg_yjaD4K=fGrOGw8ykhrqaM2*~G$I|J^X}c%?sqz3r9M5@OE{PiWH<JI)j?Z|YM6 z>w0`Y8${?~O3sZ=BKqhn+@5O2&xGIi<<xtFM}tI~IZxlB9bamTtV&R~jhTmEnJmkB zq;6cXMgQ+mOX)}^^ZVA3%w}ISQ)?rGUBHMSbU&u;PLxdM;F3oxWhiX_r0tHt$S9M# zZO!AV+qtOF=s8Evt<vc2)+duGVdxIez&zPheybYrGk&9?V$VHdruCOh@Pni3f57+7 zRA(Zbo%}EGy)%m*)76;@fe-C5IM%V%1ZK@8D2s7m;(zk=csFeC<boa^?Ode@R{Q$k zMyd_CBsU%AQr&a(JQB}vBhOm6@{0uB|8LOl`>$xZn3JeX@V(=|q3TBo!pTW==6}Pc z0pf|9k?7RjZ<rG`XSd+Y1OKb(I`SJ%{8<BpMdA)f=#w52_iCTa$fFb2|ALy}(|^wi zJOuEk=5BcY59rbTKLYquZ|=Kp{OD7#BB$+QyKeb+h2lIiv#HnLKl)q-JE0MejLYV{ zUdN*;{^Fb-@Bah?nbJOYuJWS)21>k&|DOL>G;XrwU(=-!?LZ|}20Xs<BQ7J=DR{I# zci(@ue=`YX@jIK1vDjPlb1MTP5g9DU#?_e${=B8qP+qg@h(lrOM|<}V&wG%Oe6H#t ztO`&MuIi%ygryW&$VW$Ang0a>=8n5Jn|(X#)LKjZ+y@xQ;*WwUsN#!cGflo7iZfAn zZ+YISqj@z3Zv@0%X3K=b9-nVv4m1D4*p5@8Zh0^>3Bm@G!gI&}x^qTn0JeE17||Wq z1NY^yK4Bl>%GxG$L`SgMdvJ?oxE48stCS+hu`^Zsmx*tLbrJhau<OlGS$Z91)~?I& zmJG({8bDo(@&`0jRcx6QMwciihx%O{6RQ@(HDJr`FXJzvbf8W>)K&t8U#7}7$=P4N znH)04giW@ro2F{0-R!eX+uKlXpgZrO|Nm@hJC=(@??2hnw|}yw{QvkS-<`4YFJv%& zifwtJ7!lSa7upQzrFq}|DZWvD@#{j4X}OZrT7x5J8t6jiKamFQyE8<7K30hMd4Z2q zIZ!K)^4240yU#A5PZ&Bs0Y?oU^5^BDg{4?(*ZBFxg&L*BV)Jv0e?2v!y#XSzDe(g1 zcJWpd-OU0gmi(C7_OJM^yZWwqXc_sXC<>;Fy)$5hpb#aA#VgV2hl!}BSj}@@VzV;2 z-9`>MePUhV6;UYet|V(8sKk1Wq9)+8A*?N}JMijyV}L5rj*+@>K%Wy?6_6Uq(iImb z>|h?4Xeq<opIh$zX@C*#Opc+aVns!E-70!lX9Y=ly(>eY2@oHLs0c9^R;101QrlgP zBt_0k=x2pjsNLvdp4%!Rqc6wC(cE2CMJ7jC8VoD;>t`kZWB2`qe>4+&=*=j7?e(wZ zVW%p_H*E>ofeA&_s_)VztLmMp<`&}8^mL{T162b%*1L?!t&uyw$Z~CDCS+G35{WU$ zjUuDe0m?}h>Vn(?p#xW71p`;9wl&2DA5kg*^A81B%|}?8k2z=n;l6%Dp|1^CSA}Yq z4z#8XoPQRSrv7yql%`k|*oFQAii*VgZ-5>AQ1D6f;5>qrn$Q7l-Fw*^MR|_DdZL23 z=9o%+^B!13{XrF-Hys9Sjj4yikiCFv^;SBL_O?X-dXm+fjWtb8$WN4%<KABBMEN>; zT#Zkb?I`@*%Bd9${F-A?5E+xD6BBW7H`Z~0R;JeP<}&3(>qLhUQ@|!t?$;-*2P_NZ zu6@p)0}zsbQd0?A!N~}o@c=%NP78^Pt_vq8r_~gZ+lcICbh1|}_hm5m=(^YxW6%)- zC7`8`b)i|1qK(yM9oA(T-NnZo8_fuk-ozHpv$pv;4xCSo?5O_m9|1<uE`kTy3V*Zz zFar2x^z!7t7sBc=iOfz=H>Tzml|xJC&cD$8*GjJFE)oBPOI%bNV>fq3cL%;d9>_h~ z9A@%2I|1dAu_BgR5^@|rb~x;x#Up1S&pGqb0R>&(;*Rw#z0vf?RNg^-#B~pBI_D9R zB|Cek44v^&g3UW|nFJv-T8isxetmUd`r5%PJn8DPKCm~GK6Hk2yIO6!+_nzT@$9&R z!$Z)zF*lv_E3A+;@emE^(B=bv<R|j+D7y`ASJ%_^+G0{@a@LYPEN6cFq5GWqnEWI8 z(_yajEzm2WEVcWXkQE9q&8GaQGv5=^nNeylG5{Npm#rumP$l{>57G);39R1rn`4|e zsf4W>={(5Vt5>Zd!T@qCy`rpaK_?1aiAfrg=-Bdr%nquy?fHuw2A#>$#?R_v(>gta z4rIciTU|8rf`c1TF^o*mY@B^d{z1R>{n=9ZW)mcW?O{=bZEpME@hS0^KG|Ia%T&Z3 zf^?xmwiVC%i9v0fIJ&O2>}EaJD_W{Lv11r6aoP}nF2VBb0qKZi=FSRfHYM5o@p+lW z=F|43J-;zcG{>HcU{%{W`PgGNS;p6#pN|OabR|Lzste6e`1BIjxv-Zsbj_?05o}%s z;4VF|){!0Cz#h0x<nFdxXLM(Gf=g>YXNj3c5qTQ+hUU2Pga{?rk)S1XV{Amx>WhNs z#Ni70^W@Tq%8KBD6CT`IvAp|Fk+2BzmhjQj<qF<li(uHMiK}kb@cG?#wT{kwQ!Q(r z&3AalJZLCKd<SiG4ybeBDs#)hTvPDH6AOY@O5osB7!@8%!;&ivk&e(A*LsS~$rNY7 zno)DM5>Sez86GON0?8|I@=&K75j)-f$NtNAK##2MdA=|xRuID(iauPi0>{ZjbZd$^ zG%6!2$cl*h?Wr)6##v{?8w*4}Co3>;y4(i7G-t^IM$KWcTLhuNnn+6U(P65L-KyEC zNLFk<ZbhdM&rsQZ?=-5)eo;UMWZY{p8_$|PFzoeOoe-V0#Yin-FNl	)K1asiT~1 zKeU@xLJv4ue!gFzm6f{nB3u<jTtIwFJ8+D%W(T(ENmhCVy+GejxT}QjwLl<IIclB8 z(3nv4OQ~S_`L5_+&f+EBV<As24#bgrX%ki{&~onrv_*c-uaXn)W2016a}68jeT_<p z`P)5EH;A!Py;MIg)#bIMH)a)*l^e;)Cn8+ia&0|BR^5<!%?y>*NG^o5F=8yiNoFoF zA;hSCkwSOw6v$DegNaKVLENK+May;@om(dm0_sIGQ4ZO{=M}0e;ZE!|R9HV_q0|xz zI4<^gw4lV?L7J1Jn}HKe1ffQ*FZi?tGOhSzd(=?w_OIV3c4qb$j5$eBlN7B?#+-^z z8Bwj(6d!8l#@PHQ<B-0kRU)l=Nu?l<o+(CVkLHd2;Hz>3d*`z!ZWwe+u=i^$3_qcL z!t2t=zUV{0JH2R8)|v8Gwynwf=xkPEi~vTq=rLX1IVbBlMiG~S-Q45G|EN+t+qaW@ zKbyT*NwrVvY!3eL)Y9=x!-Q^}v8OPIs#95jxx}x>D1TFY(zTRSw&2rKW3%=T#h~c^ z_!B)acq?h$qB!lLFOg`7JhdfU#=#w0TV|+MkI#7h#hVhs2fg+2#M0r0K5-j=ma-v# z_Hg4evhd*15B%MA!fTzoT2=b+a?`Z~>;RMdlYL8+eq{{?P19Xhw*%Ol(P)FW6wDxW zkVPcc6xBod50l7xEE+HyQ&R_sLsAYq6B9e3MUY(_PdS)@0D%~|RUFTs5iH<%Cd14m zNC_ruJH#J-$w<R;MA1fQ?*?kRpTGyYQCS9nMO})2aSXF@s1zzj2N+;AEd``q6T*c) z6<=Z2H2oLf&TSeZ{pd{&*x^@0${?rm%2G)fS0=eeW_&&D;wJY721<;QFLy4$NOWK> zM3m9wNb9kYIIoflLPUV*DN&+m<#M?8UvKrjT22UF@Zq%c(?||v{*!6g3!n@7FQ(zu zh{%rE@v3gvjFfn#QD;kN;$6czvV95TG2c$>D&E0N+C7XJiOO?0YCn94hUgN_J2xfH zNH6;M(vfPL=B|V<ZRh5nh4p(`-d<ua6+BOEFfvL=Pu*&aT$>$HgN9RAQ5<CUne12D z>_Q~5{?`wsz+?zOe!xJYfM$wli=C&_tOtJ+QXfk6Dp8%9C3`gg%ar2YDJZjq;3~SI zY%TDD@2k%^SM#ec9C`;F9=W#8EM)aCYTOA<gO@-bSZz=OI&ZU@7<Xm%Ib&r75l^Gm z@Jr1v2=KoaLP7rJXou$)kql#jWxY19Z;Pl0ZAeW#)2QgXcSAi7;lxhy%=Q}COopGy zr6Y%8^{d>=j@ZRGFMa0dCi(nCT-nySYhU6?H?K02sCQHECY$+L7E@#rmp>TgVd-nE zHH@@y`k*56i7J7vs~x7vSRaY|ORgMciYs6M=Vhbz7AgEb+zT;5hKq5bCLw-oo<)nw z+M}r@G%WHJ6iQ~fqvly9i#$#e6LwrmDtG>?Wo#l*vpMc#7@+lfR+11FJ*%$yGH(m! zep>2P%rAxM$&H%uo=e?LVz_Ww=2lc@A2#YfH4#B&ATK40mJK3GW_e1wECDmR3s)?7 zC!&JRb;yao$Odlny$g@#K2xHXgMZ<Hkc!W4l1z|B+@rsQ8%7rwiEgmgTl|c{VW7T8 zIjPxRcsUZyTMeVVR6PjeMlc;{dyLe+K~`>W71~S?`HQZy&N_<jqGom4O1sI5`4ARW zy}R(SY`wPBcoznF5av<7ZR9f0Hdv>9!>|1Qk3?}Mmaw%$l$PEU@;G@cd@jbawzl4b zZdekHO8BQpIK27~2u%{^jdBd8MgK>Hb=R(onp5Fq4K^vTMV&Z`O0C&`BPWgXS)u51 zrRn`g;1Rnair?J*6XcLLWU?5(ZYWrV2H|)vh+>f<^Nk|WjUHJNNKwVS0b;6JK&@cN z``ig&X27iUV(P$AsOO{^^&|w94AqF{nMk>i?raFI(eFH2Gn8ex$4KW`y3ziDRDA|Z zH{>u>5@A!#oVQX}Ik=2-d2QN)P_m7~v-z?&rEMB~Qfb&)C(sFKRN65jX^P|b=b68t z$In4%wAq~3KE@nB9{s~&+!y?4fCP*fEwJ4M$mKiFWTBl6@Jk=7zuE9;{alK<fEgS` zE$C%Pniy?`Ujt>C`T`3GS&sqYG?g&LKD5h^&G!M~@#)&ZFwK4!6LW|(GJ_Y-R!HhE zlRg6TadvG}bQM<tWkGBHoe@=@Ntka20<7Z%hKg@>Dzf|L<g~}kq%piXu^Il)RxtJE zpj)UkE1asc;t&Z_^p9823B{{^_S~{zT;t*+nX)6&CWde$*|80cx?$12Y~R-K#B<KN z*ILGev6<Tv<k_@J)=E9>!Jt2*sUeb;_;Dxjr}cGNC{0n7N^Pw}M=#Gt&7x*mOOihz z+Ny|4Y<ES?W+nm^rpBzZKp^8%4rf@DJf+F0&lY%9q-mP1vITx66gAo&LnlySs070l zn>Idq{wx-F*#s@64pd_uKZG?(s{(@+Eth^Ym#H=k6Nko-rMptpy9bjnufcrGlq{p| z#u4#`F-jF5xt7&$P-`GmrO0a|)u@W=QA*$Gvu&p?|I9yvXAo>?f*G*PUkK{Th+VRW zZHzu6I%GStX^T}g*F%*oTARs%&P4-J0pst^HGdmFbv%{z?}ifqhQi{<hSE-2LgP0T zb7zA}Zz%QGy#NA%?1O-6!~^qyL=sw8_1hliw{-^c_16OhLl|4+w{`jVTn53f2^1<< z>ZGOIpq}>ddIDvNLiOxn+WSe+a|z}{f6J0ml&R^Serz~L1{4^f$%^6UwYU%6Rxg&S zbfE9SGZ38f3M?NG=w#wXCJXwARaQB$8G;N`^%^ul63!K*;LjzGci34424oj4U%R$; ztYH_K7Qy@F7vz6-<y;%hxk38wj$5V+1cdoN+dUcBSR0#}C>S|1{?qKKLQBJjl)d)P zmJTu0ovn1W*kEQ#IyB>rKw^0W0-1*F*pFWru>O~YWR)xVy~b;cpRWqS&Q0_7cO(bx zmORd0?TYAUgZfuV-tC9&Pm)SK`Og*JH*;@)zPqg%OO|_|CAmNB9ew_+{CqT`8VIXE zEv@=oJo9StcxRV#x>_S}zJZPrln&cX+`n)7(|a5H<K|w$|C|)98?<1!l3m5#f;yOa zOPoKD{<Y)48n)|2Txig&i(Q`+eF5&LXXW+V$%QvX-qvf<M{@&NY@c#)pD`7d<z`t3 zi<~?3kH@ObulvujsXJ+$mIksUgs>iin)r5aVR5=P>cR5_<IqA4!WkjP2`I#viQzM= zl&R!jy}8~Gdx3G6(ng98ReVmU?=kf3VHmh0KejxH#{3EkjHm9S^nBy!so38-T)+AT z4vq+Q(I?UCd!XE|bayAplnrS)XNYFZcL>|W^xmQrH)b*E280xhh&Y-Zu=z99ts$2G zRHr~}C)epAf86*BRz#>z8bX96bocBziiJ@=_w*3(6L1Ei=NHJ^T3c&Ri02>cj4X^& zw}jyY)APhTGyRI5i9)cdA$xWJTltDr<YOi=R<tpMIGY~z{uK+qGRtX7sx(!fLs$di z!n?hm)1x?&6DvGJbP3CqK#fOI%6dJUlMHX&y(G`nG4iI;Bp)4NDc2mSFu8Ouhny%~ zu)YYVQCd3<+X}(|{9NPn*K91}b0Hb6HO-YCHV8JEHfU^BX{ejJ5%}5xgsbG<&$Lxh zNb`;|D_N`)oEOv}s1)w#FLd?vlkRJo_sqCa>Nwe$MOoDryQ1u}vJEVcAyE$Kd{S0L zs59;*VoZ>S5KGFs6YeFll$vz;CwC+f7TUM1Hfjx>UeedR_f^7|eTs>%Gp4KQ!`s3; ziEe=}4po`A^PIHWB#X5HJ$5TslVNu&-fYXnzGCdTsmUaNOk;;;lrhg7FD6L9aXaS% zy3c`}zXbTLA1QoWK;1Txp#_#5&5{L2+YJ>_J8i>3;29Q(lx<3IU0W~?c^wgadJ>(f z$B$f@`z=*Dl*vy)-#DhV>Y9*neSW8sewUKWFgh{XPFJa)_TWPmiaLo1Y<uk<To?Iu z3YXL_(xVuCbWD)ioF`A|P5o*ykji#V4HWwPD!S|ESGI%*UADh~Ao}zGt(=;iB1`t? zAghfumefB*)Wz40CqE6&_13frhBgv@Ph7K09rNa=bA#IafRkTN@jffU1>rkU7ncsD zf*4?(qZM(3;1R9`vPSsHV5+9*iCfGHXGdQfs*?xtt4b$r5__Ux6~0~!Xw-`356R?^ zihS;|ASV@A>LKwv9(ZR$w4mif2(QkSEiutAcy;~VNGOheVQ5t{h}cmgXK)t>xVPK7 znFNH5jzeZI_33iSGS@jhcbbG>8h_mnC<3-g4LC4%JWW8=%sth1>WZ^Z9Hr4lycXde zp#l2EgWKHJCDP67IKfKhC{Rhj+=sEpY9kie!R|sT`TMWhze1Gf%Qvog<BYiJ&1D?P z;HG$-_fT&n(ZJ>tByMW5m4A>nj^O84g_ZNpHq)!nM#%0MwuD;u2Zh8NFOhlS^!e6p zPNld;JA$HhIlPF<&Qb3ZQ9sbF#){C9&oHj4+aR#cvYt<zVE_Uag4}2RT=24(X8Ky- zNb)dRD=VLp2iPD==s-XQk#1bBk5zmB6dm`rBkRcsLX#J(@S!cp<yE@l#qnl58!!sV zA#Gj2McpQOFi`=6X-Ssr_afSb(Ih*9gtaY5!m0qeBgVQ9g`Cn$Hjmb?H43U9YeP2D z&cLLd((wCk8~tigx;~QMSJCWpc0<mGJA9vfrcYEmL&}hd^84m|>f(pzZ{r4i>O28l z4Oi%JJb_Le&}3vNW@}`*im@8_B*J?mW=n92xbD^zTNByt?t5zAm^T&Fnw)6<CuQ+N z-tDv11fFv#gv?0`wXg`Psh5Cc*beADMSKx0Z8{0+V8%;1jQdu@;&rQ4TfAp#HiN>b zg3ze8xWfT^1QB1~rW|pxU@ikAA9NhJA?xOxlQ^bS0T>k}Fn@@?Mv|cQ)~Zm|4HRUV zE+Ty?gJH~g!zD*@^bdsDqB?zi4HV{kfAsX>yBLl)=x$~Hk!>D*Y^sUtbmUKrM}c@- z3<M_Rx5@j$$oHabDq)^+A<gJBS`OtJRnii&5^==EdYt$(*#`e&7?q52WGhRI<CjES zl%%Tw2kR5!pgGHYA~ZCMJ#UzZA0J^+W!9sm$IB;WL7)cXw>uQ+axzOm;qpES*-X#k zOJ>AwKYF2srRpYH?VtZDCEQonm&&uPPB1bZ4*H*O8Ra<CKL<Xsbe4Pt$9sx|QKo*x zL}IDIs+lH2B>n(qc0%c0G&rJRpM|l^z9nJNz(9>DW*H~sFe=GSp2Q*xiw>1fL@pXE z24I~29svv&r(!5jE4CP78e9J@u^8a*|5VR~xBD@^{v&%ubUUkoUIYubaWLRm1P!VA zGJHNJ(O9Hjzp8mTHqKZeOHqo&1=78G_m-Ro7Kl%iz5qJJXJ<-J$bj|tt#Cfl&p_1; zAoa2^V63$jqV+awAl+H{I3gJ%<eWr!Yc&CoK8|a41XFz(hbg4Ce%{=HK&<XHsTMh7 z&Jnv&0x)P8YD?fAVv>7=GMEIKX1T3ybTK1zv=J*L%=syk>pv?T=z_hR-9n<+G_#@0 z(nPLfrUxEy<AoWZlaK>{uZq*;0dD!8gJJ2%j;MyBG%=Jo_|6w=?J#ye9JawVNFlr= zZ~}hiKF@fbSqlr%5Yz_6WMLS4hwQS5OIP4;b@|2c$v=Y7j#~kizqa)4b-7`wrH+Xc zw5NYc6q^2!1mdK+9=z;F%AFjx+|aehyuG5c-_!Z^#exxLeX|=x>PshzC8!m@c=o!X zXfaK5VdjV;LxfSMj|uJ(61*8s3H*qY@j*dNs(<#VSq#1KA@pMf`r0t*r+B0{C#2OX zr8RjbW;rs(pCN4>Cw-Kb7lgWJ2S$%RlT&os*je>tItgUkYv&N|Ouf{8YHHJCS3Mj? zWQwl(B_HHDpA4x7Cv+=p2lj%gcy8+uUnFm=?FR2Jm=#8(6+dfe2LSXlY;q}Bn<AQX zJUq;E!qfH|*STK6>CVHmc6{K2cy)4`iDis{>Gb6W>}xA)B8o+QHXMaoqihyU1g(of zL~{z8umOkfJ>D$=n!x;h)9mtTYo(6Tkkq*8AM~1NUZ!LoM}sDzq%hl%Up}xgk{qgi zf7%TNnO|nBNjXFzf);J%#bWiIo&E40>kuSY&Bu@@5`NEPE%N$JKwOkYZc6S_QN<Eb zmOZmEt>5kY?6l4?#5fgI2^lf+UC?v;dQ4QNWGb+-xX4AS-(&(-e7eqbwBAuj(skcP zA%B;+%djP=vWDf=)lcSn2wKGYCiDM3B%v}EoqPBF;NzR6USx*lon|&MBR}~>XJ$iD zpj&?*f=}7@_0ZPUvZ20MC`x;Va7=?@#Q7+ro=a7DgJs`tQ%tFtdwou_Toz|ob_Z1! zMXZ(@)8c1dEAMB&TZ)ajKYK#<GB#5>u(1bLkq<xEgM#NHgFC(^E>Q_bg#K{%lssA5 z7d-W$CyWiMe~E6KG5P8)GIxY5UG1(YqW4W!Kr2lpmo5O@%%t?NI2>4))Fu1pIWUA_ z@xo={OF&}ZVBDr+yA6a_2LvXR|80)?m2MYNip6cqXY*M<|N9o&qx>uMUiD(TWzA;8 z=7(*Em3SK<deIPE`qi4XH(PljsWQNSHLO7p+N!41pqXOxiNh&v(10n(VRS7oS%Z8_ z*o1w&f5;^_?CTKaPN>N10#A=kRT^?>875FU!YxV{*G=QlsZ<q?BZ-0KOeY0ywggS1 z7Q)z@w6t@_Kj-{oGmrZEDf#$-Lu~y0@DVrGV$IpU!{T$hCB?=jBNSL?4}DzAJgxi# z9$^9kfrc(nj`&CAQE$z<{;PL9ZS8vLWHq20#Can#XlnFm84}H){r>#V|5w;IfJeHl z>&CWiI}_WsZQHhO8xwOfaWb)OO^k^((ZsnuYoBxWT66ZjxBB_}@A|vzeX72yE_@US z3aE;4gXCbFo+5ga>-f2Wu&=BAvnZp#4Vv!WyYjR+B1g*3Tk$5iC34dwhs9!3xWU_y zL=DYB6e_@Tu!qyBM}>JzsgPBq8ro|fx7JAt;kLtBr`e5dUW=|L#1>)j*``F3{@O6@ z=mAFG7m5v5UUYmS);|mxZJG}`(F_!^SbHVV<Z%%6icncHRQ<+vvAt1Cw|_>wZdz>X z0KlXQ!U$890C%cQy${_!*=PC8NNIF!I!T409nG>DZ5imaN=1;tBA(d*a<kXNKMfyg zp&R{(F<w;pi!9~D_Y)gi-Xp@esfMMt);aUQqgU;nLUwt)q!o8l+=L-c2el#UXb?}I z$Cd=R!s>G-D)2O0L;x?<+aBJmGiHUldDx{SkzcT3DFl`joT<s^sZKYgOSR;>vJ3 zD`XKt9Vq90;+pk*$h02mM1K<!cDE|7yYB2fiCT>{?62E?8nqq00oCWayS`!dJb|rv zzkV=9?Wt=qq)}u=1Otjs_}LUh0%MB76D@K@1T;QjJKLL549oMMLlTNwM5E}`r0FXY zE@{cJOOAv(#?ham&P)8WseM$-R3-&<md1mrYZDx$)TY7a=A~LgAMxOjL7Rsx3?3h; zhu%*JGD#Gd36PP1L`310yq6c)8mh0SWY12cYpYR;{L&zRo2STi!-niRE^RhQ4UIX3 zzH-=4mSc{%uV%Ov3bWF4J%E90XKaHo9T^U$@*U3^Y?!dRWUWXwvnfb3$y-Ob^MFKS zC)3DjVjnYu*|T;9^l=ZR63xxh?w@^q9PbscaBa+493FG*e7cXd^@HCWQPQEaQ`F!l zZ9+ZKD4!Ey#Q?4-u7n!rU{)nNlp911x*e49SMf8>p(UYde8)I~Gqsf?+kZ$eu}<i6 zsp0}NZo^dJniadB-1%bn_Vz=`=w=cTQMW}Uo1^`9=w*~{B2;4Cj&|WxSJSq|?dim_ z<T7@Gby#g{(!D9C$AcVdi#WY$R_B(6jlhxs7S|+bZaJ#0{h$+!aM_4RLLrL-d;gw% z^teRJ4&Ej=Iz_SBcP7ipbiAL)ZFW;^jAtu=i*jgw4qI?xzzw3#zldo}5J~g98l~XR zH55x1`>T}CL21+3=8>W!3Z9{jh|%3ijgY;do(%4>3L(=F<@isQc#CMzA0PyUpw0Z4 zep3Y$9u|!}+wb5;Q<7EOr@~G<K2zM$^!juq%+}Ne6}|DO$TJP#Z>T)9+=PDaXh@Tc zHb)%kG|h-a#Gj15u_rj_Im0$165=@Tmep0DbPZT~IKH;WW7Mt>JsxpB&<4Q^3VI_& z$#-0GY2UHjaF3N8h8cdG4us`=dH)_sFX0Jrl2}V1rZ|Vp-z+#L-o4>yKF|I7i1_M2 zAiim*q^k@cn%EJaCk!Vnq*j^$m3DlsM?A=x-||CYK&F1(VP7=n?YP;Nuh{J=_<gB! zsB_(;(Xym#6>M~G^ZZz^9MSx|r*B9B9Ira#m%T3x44wOj^od7GN*T*Aj#C0+xzph4 z3F<HN$=k6>iB4MzoDSlV22~0ALa_ie=&;cQ(mJF!rDI&xkLf^;o5yUey~z%~6gO&m z>-19}6*qBAP%m71;n8S2rn@%iJ*ee)G&xjcEFt|iW*-3@&6HXWhMK48YmdB6&TeOx zo?HD+wUzqXoYt6_(UR+5Ltpzo1WLm&ovey#F9rMcF!4^PcS*Ly_HP{)xB>}kV-wCC zFl4Ib%92IFLdk#ba7Q;dgcw$2RoV^9zm3D3d)H4uZq8+R7{h5~zaKri<pkmxtSoWJ zJ%Z_|CrEq&ob#ojd(IqhqQBUX@QHceDl2tY<J8Cl7<0jf0xx%m1H{CuJ9E62tc)G< z1z-IIJP>ef-OO~awIshSVz6e+G;w=TwWB5-+Bh)e3XIlYLa8vDCA`s|lljlmz8gmG zBXS2kQ45@YKNkdLrPesi^N4h<n`~7A3ToxV&oHKktH^&7gqh1Z9YfY!Sno7*a9;0J zun&d}d4#Wl=>8IMZ25Rr-}RAA=J9bMBcZJ}aX3D770PUH=p6x4fe^EnA&?`K6MP}T zsJs-1T_|z5)v~fQas;-rd-9{)fEVEj{{AJQpevTc!e7_fp0NXj8skBndfiC5X^U0N zJcgbJH_9q!RFP`?vZuPXFhB?CThI}Rs#^d$xbWA`TJ|f!Vq%Bxuh>!N5B2`CQ$1C0 zC>zzPkOq=8ll$~86C*xiE4Q`#7yRr6+>Q9LmM_7)!ijP27m&NM5++P&ez=IC{o_N< zld44*98|w};Z37PRbz3*(NL`yRPlJH9g5>3r|{Zo1y;(O;VY5e;lAq*bxI37-e@em z?LK=O<~&@p;a^hVosmen0NK@tWkJ-GR&_hf>#*T70<!~IPJ%4}6Eum0^#0^S5ZnWs zj|VPJcR6_c%ydugVB9@;{5Y!aBTxp@1Z-h|brzgEz3t1{L{DN2qO{I|RnlUmlOh;f znjMEyy*%Z&(PvSofwR4%sS!gh9`ngC`m^z3;``K*d2I^{x(UNiI84zYc_1I_JDz#! zB_-#YZ5sooXAMMiFLB4$#3`Sp%`3=`irMI|u1ErO9h=iSAHBydF*pLOKCiWF(^_bQ z#Shb*vb>+`TQZ`$Pa{+hy^w&7)v8aC+`g^a0@Uifm<k5-=Au{cH+!dp=03#cvoUTu zHT7g6ZYLCV7eBomtJfC!zPR>OTRNrcG(l?z*itktU8yrFvP=mXO^b?<cIW5RHN5F8 z7l*9IvT1N7%e<g{4On`yxY}D$2)NSo{TBM+^?~jG`ug<sSG_)4uYYYK>%~U^<U8U& znTQ4f13O*-=3x=w!ugL(L@9f7hu?g}#)kUQDJ3cydYb9UnMSowi!6%Dl2bC%3S*Np zt!gy%QVY$BUt9OTI!({WOvob2)Bl{5nP}ZtRuqh+0wcpndn7+B`%ZI$X>pi-XnJUN zMmb;#e;0^BMa@Z(VVVxCmWq~EMzbb#mySW64rJFn7l8}jBuO|$0rbxbQ}sF$)dDKY z4h#fD`1c9}g4;V<TA3KxO4+-bIhz}qnEkG`+YBFUKNAwfPFD|!X)9ryrliWC5VxiX z`mb4C8zMq-xxoSlRmVhkZcc*Bt&By5+F8&Iy4p&|q(iKrliEb{8prDa^9Y;l#LxQ+ zdJnp6!y&kyh^#`9OpDI&==LF(HTQ8@HMcBfTw|*!oRB>fSRPKp`#u~H@WVYT$nTvY zODX`{6!pLkzYr7c5-}}%%x-^8NYFM-SoLB(qld|HO*!2I%eH5(WO}v$;D5IC*<r-K z6&na>%Mcg{<L@nXaW!%^Gq-i{_}#z@Js*{Q&X$ku0^uPH9rs8nQ%YWnP1`xvNkNeT zB<}}%CE0N@lArFz3oW3bI=?!%Nyn}vP>9IDQcn@$UG<aWO;5^K$^-b|o{!@>>#TGN zG_Jkfz>%x%JY=h1yv&X_D|Bc-z9;ds@ePo2_`Uc`2p=!>TK<xaA!@w!5*wjqg%h5c z^)M0SuW!N!8O%$|tE%&Fy;7}>=0MtdmaBhLUlCB7Rz4{6vDN1ZX8{Sft?{|V<ghoh zs2=CPkF>0}c;G>3cvOJ8hAWrhHOJhlsVADqU~W<e$<91Sa9WS|I%7UD7>i>*_o=W# z2=`lfj><mmo3&n$bnP3gi-;By537a=X!QvnKtI#YXRsa{pSEAe#Zfi=;W5(2(v?Iu z6goV5C0A{-U9eU+R@+%)g;RC5ezwjA=hYr(t=Thf(Zw?M*1*NYhq+n>wZgH?aTdvc ze683EhAjlO1UjG8tpx5I=U=;DYt8p;8$0La{kENkuSc7BMd1F<)Y%mfV!=rne(Pdp z!BX&5<om-8yX@oE&xFIFcQ2c(gw5L+UjzqNSgp<gXWsb8w3(na%I$~{o4uOz9gzDn z8{J=HyE`ooEpiSsj(im`*v_AhC3-#$ZTtw!F|8!?{M0=GqNhEj*y#0$j^{~EfW9!t zQ76@N!ZpbNGS+?hVf#iFFZTR3c{a;1=H?E?p(yUVH@?wxBFzHWOq`vU+%0l)XtObm zho=nQvT)5gYk==qx^VP!b_Xmys9&t2eifuZ_f>N?W+&#$P%1cqN^crXdnnlgIHPoi z+jrk()0*=Qu($#Lv%(mD(w@m5LfCHTQa2)u)$m{+5T%!DA~=-kuCg=k@o`Cfcj~kH z+m3pYS$tpyx@%m_g-wJ9+Ss)7KgjFqH0p7VzfOPHs)uZ!6PL5nS~=7*3CMuC!OdLb zGum=k;Y8=o+O0SF$_MD?zO`BUZFa3rop!mM>u{tP4>-jtakDaHJ>_KUK&9y(DlBRY zOX4BbTMWEZc+GOZzK^^=?GC-KEDr@tf89zl>~yoFwcbJ=e!9OK$=H7*VfQ3FSVd~) z-zoIF0ebH<y~xYY#lQMcFrDI@X>-!d0kMSycx!&Cy(;G-&rMlUdJ8P>GHgDXJw+b5 z^B0ke6b#4hK37H&P@_^v3a|xxXU^Qgv*=tj)W*DhBb~GaP4={O8yyI`z|$`C*jWt; zSf5t-wQQO4?fEfDmv)YyZK_VJQ{77{(u2^p+(ovgZUuBcZs^&DdBJznoyBoo%I-T^ zD|$DjuLI8ZE#AOh9?CXobEUWIN6zIu+k1W6iD_<wQE*FhJR5*bcBV6XGNNYJrC&{~ ztFygT!Pi-E#C@>`FciY~&S>&`Q{$cu{K)Rs->$J!p2Ee!_fx%nCdck8;I7lCh&Cs= z!yZWs7{{@W!r>?{``H8jVA>?%Hg%r6MwDmXz$g<UTWe<<H>P%qyelai(tw5*rEaiY zMm}&Gwx&WzYCJyeJi>gLvlaP(o<rH*<<RQj9({%f=lorusN0XL>k*WDI>KlBMw*tE z<g}YV@gec>xpHAFzD_d_(ME*iwMU2}TLZbPB6?7q(a6aDwkL;iMu2~HmFMl<FW_qL zy8dk$IhKb3L7~SY8F>|#aMjE(5(d}q&=9owly$ZDCtK3$k)IK0vvtrb9eZGm_>l_; zB#dHgRv_s04N*8Csxi-J3|`MJ_4O8CFnJ<~r$r-j`6oqrB}Q=LomD75@qJ#Q_xX;- ziAcDYK`U(aRs~(L<VOX_n<?;jiM`djnv90|#LP+4MAvl|Vk!pVvR(ZI!E#RYBB8<B zoT8P=ToY%xqF8oG^Ka5o{2<NB;&oPIg%Z?r5vn!g1i_N>1yIs+_2i**i4fWb28cIo zWdg|=<pPm<uxVlshbM@~ONyF;1+xkQ)`Q{!=}M<5iAZzc1#o=QnVCjy){;VF^TJfb zr|5CyeM$Ymm~7ttnP=CXfl0}>#^3IP8~BHVu7-42c0>9hkB&mtkz+4qt>3|7^Nn<* zw{_sy83QSRS*MUJaX5xi1Q+OrD_nrGTcU#~FqX;EZFm@X)$Zz#Jw^hBB-f8`)g$^8 z+nm4pIDLBo2cIz9!p3Q4W5ZFKDbK~kD#ffQ0LK!WWN3(mT(E;*FI3-Acv@82+{#vM z%>W9(QA(xMy1r3NA{+ZAG~7&!XjVh@aqa`Js#mXGoe5nQ)H@=AgVMmw>`kAbPg}Nf zdwdV~me?;ZSz3jAmjDrfwW(%;u9u&s->D(~!F)M!ym9%fK9TIg2#yy`#z;Kv5w*fb zFf~20SWynER3vpAaQ-Y-;^GC07=(_Z3FxO*%2w~iLa7ytb-HEc>%+o<QSwf$05Msf z$7z?<qcwz!T5J+8P*PwTjx91n7mkF8tEgL%`DFTvQ{o5DsU~|uCJc+HTpElH4`!uE zoU;pTLvwJcCbn#hrAw6AaY$}Ogz>uz`#P-q3>~Nh!^LVcvae?Ob%{Ap_PrZ;5u%9O zu!3hiq4>*ksKa*}kIQ=Ak-q5{nAeW@yCAYj)JZ^G*?8(PVzF*#)r~z{R2o$ocuslh zABD#0uqZPX7OXIJJwy+<UZXIx&XgmZ`Ht^9OS?jc9|q{Pj!wZBSBn%*nvH}5%U849 ziPt_<Y*N}|=fTUy_~Rm)6^1MElvfT{1ab|Gs{3Cn@<yq`N;ONBcuQ6(kkrlz?b19; z+aE9Y8J$gva<qg*&Rr6}gvUQ}qLwtwc&DplW)a-jy2>eLTu{3Pj(<@^9|Q_OUmRUq z)L?4TpqZcqS4)&_q<P%j$>rP|RM=l6k-xCY^&YHLn9|A}Z{P(#!JSY^{0jJBMRT}| z00hoe$S)X!_btzT_Y$guoi`Gzh^O-kTQAri&!@Kw)H-;ORy^hqVj>lVGk_Foh!>4g zgpHtzT*Qr_>ZPcO`&kLi8)`9CiHO^GzMs<1>%lp!O|*<3CU*~X7j44{6I^}A`9cKq zIY)$ckG8ab)3+%K1NV85Bm?eBN6#>fgLH+BV6cpTH^Akgr}p@syF8r5VuKD(gR?HP z2#E#FCBFzOq9qDDTB|UvUO=RQc?oU^S`1<92i}l)A0B{T)i2I}@{IyBI-O|R*x5)B zR#TSoKqUg*eV<R35lh`;l_NKO&OU|TNfTV60QnXuD@621;&J?)onw^}b{^vR@jCwN z2lxk%nJbj41j1A4Adp}9;wK?{<_g>hrzg^!jL5z=|B5m)LtOz?4HTw2LL7OzK_@c- zWGYFpJYz$OPeiF96C9zgb#V_0C;8Z^@*FG|`C4gF^O~vYn5B(We2n9*snsb(j9<bx z4B{zGN{Y2ld=;PFHJ%@;?`l<&ccJ|Ww*=vMA=b*Mq{U)T*)us`d7at>a{<vYwSzd{ zy!P&Nolba53*Y#L&aS9c0~C~=eIRBjc}cFrL$@h;gP#SfO?-$DHB3)8WN#V6rcfW{ zt10$-nQ;6HB7rgTQJ!?l`)QylpL9&7S%n}O7K13ydUYe%g(B1|L~?3G_POt%x$lJW zpH1<(mw*d`mrv&zY19w<LNIulChBnR$Xj$-SXGSfjJ1bbZL`YFNGAC<v!muQIcGuS z2PbSShfH@z9EZbZ1jAnrW{%wQEvF^roAPD$zc`fM4=(jO^=wX!IW^LMcGTT%n-Rb} zTCeBgvUkrG<*akupya8;;I@~LZG#<|y6)B*Spps5%LTiRbd&b7?SIkV^CKRVBvx-2 zRB5vh|0UO6r&&p+PBZ0LI^P!M)1Z7}_QX-2CY`gsP@~G7P^+3;^2;;y{qSLtHvKMm z;o+#+xYDw3kxreC%XnxW4V~i$9hX@L7;QR3Pt!T@368IKK|a~^;jcINVdt$$wJn%3 z#@Y~uH}kJ;xu1%wvw6FV$4>ZW>yh8Q4`On5UVuRo#F0Gj9wk?}!B15nFY1SFWefUx zq90b5&0Iq-ciyad=8^UKdqqX6`?~kaCl`pyK2hdM@bk0R?FHwl&%l}12S3?5&6UDX zThF4+)sIv|BoxDjF}RpCMM}wyoDgg9(nzG>440sZA!G9?scOd&qS7<(M;+L-9s{IL zZaPU9nR*MwxI^oq4<^U``9ZrK^UVtY4_M@}OQB3}LJ|@9hJ`VakI9H9i3G76B(KXM zOd*}ahK7&hdQorIdYMVO=nJuXyBmmA-k&gvmR!0&)xmVH3320exMpRa6l3XVMmi~- z&vF}}rJ+If%O<j`D<(-Pv{Z}|-B)6Wtrch&SfFrl!xQNyvdxHjQFo%)#D7hHQsb+C zf~Lch*wf*TA8hr+lbXM|1_HOX&mqz#CpuQT$V9kW8);d*4Hc|D{-XPS_;j`!eAPRF zn+qYq%K0ikXNeq#;a_ff7b%X|Ly99Q>%u8Gu<mNS@w4(LE`%lU@x_cFWH9eK%d<a= zQX=6b#h1~UaJGZ;rGVLBNWQ$OveK;w_($OV2nH9QV+Dlu5>V|t1Ce0E*vSBcguN&D zy?0wT%kXMe&>lBu7ru%w@C5|r#|z|0ixYwRGIQlJq;mDY^QdbnbcFc>sJA3E=+nT$ z6gR8iYAjErCdJjI>8_T8Wwl_H&jd`RqcD96Hu`A$93g^iKfIkU`H}THMvto#xD4yI zU)Q(`hgQQmx@a3S?719COZ)bnNC+}OuVD6?MZc*d<T6CApaPVV>lZxbcaFw{5-A~t z^6|jDoO^G`(#dCKT03fJz%Dj`q*rdjLw@GRWDf7ox>$Wcy^nSW8THW2#Gx}$STZj- z2^lB+G#%55I7)VkH<fLi<Iv8b<JRG5v$PAg^!s{j%eGg1-~T#VZ8}5GVPAGdH4^k0 z4>H~vk8|9q?8dR{+qE8hF#;<#1F54>Yk;jn8FwQMLH+EH;Big!v>r~k8vOE5205u& zD6lPjtb!Ik>pO$1uH7E?N7`aogd_`)v-}&KZex6WYWCPf$WoCX4q8JnE`&6i@Ya6E zVj(D<@NllB8!>K<=-|{;3#gIUi5J#VW55&0(K^=_mO>Rrk(<0j{!~VED%0BJb^cPz zIu4?(%3)qa@=k9^jX1Cdr&#pZKEu&E4UariEvfR4=H_7ytD%YJsQ#mIndOA1OUGfp zvw!Wc{kvP!PGMoLP`6qG7qCNq7Gi}*?qegPcu-laiQW#zX--<dcwJ0Pn18$0*=?OM zxO}yn$5peXqBlm3p8$NzkkoGHfPyO>wm;qLG>{a#-~%{@EqGs+UF+_)v+zcZoXGWe zS^Q|{(nx`xLC=3VAGpff+Rx?Xu;6R|{gWAf_5g@=rLYg^51*=!Fi3fPzRBuV8g~)c z8Nc=;>s{5SIZOR6H7B6x>kVvA`?l5NW2fKw!_;eCCy+4CAmg8uim~gF^zwzCTJKY5 zU@*Ev3wS~eGIgZ~ltvPZiwq~gXo>LPFkdMZ=^n>(r$Fu-IRi;FKgoHlH9=8bHh*t% zgQUkQp{AC^lTE6ev7#KOJ}2kQ3jVzz=1TPCXc6LBAuY~R&4rG98B`;qrY3cA9JEUy zU`8spz@6wK2-0_>3AU%qC_E|Rxpl&BFCz!-RK9_eF^7}JZWeN-Ve;<=t4d!h2%JQu zhkPo85Z>h)z#LSg^3XP-OC;z8qN_Aj85npo1NZ`Q8oCa5PhJ{4-L-&|O@BF!cP!&M z>^EMk(`<=Re5Y9OWTF2K39JjXBMgKI?X$(|$lUUoAu%Q^*7XorPu9)*5O5s$RPZZY zUltG?arsv22;9IH9k6-z?Mop08Bu9FNHZHlS%`UcpeyH3V*U%J56d@KV)P}Jbt{ej zbI^@z<lgesY-0*W(T}20vHlw<Rw`zqK6qm250&XsGfB~K_F@Yri1JbaR7r8D98uOH zd$v#o5cnUu&qVI@C5U8$$D{zC7pOGK&nqb7ZQppGiPYt&WacP=u}`5A-<pu5BQe-u z&u&2DJJN(qq;@hLg$}woB?M!eF<jHfaj~wB;?+Z8yIn9h{QIeC>cb^rR$dgTESf~{ zo?$`2G37HTckbQCy6-eWcHLz5-9S_^3!h(rmxi2sF@sMXjQEHMK&u+RP&DXzGeQWb z@qI_jzLT^Wz%Bx9MBI9lM|Rf@{PKGbDp-W3c#&blq7TDmv>*5kUe7`&c`Y0G?7rdD zwhiUWU%+imaE-EmTV44h3{T1$KmWCm$}gU0^c?JDx%Q;l$IRbGZldAkjZA<0G#;-r z)*jz^MH*JUL}O9PVM=(UyxgKTW+256NrQ3sbh}F4Aw4)?l88Sp(FQk1;d(6CD$G|{ z4qEg<);pbKAwS#B(5PFI!j89S7;)+7P;I5PbrtxjXv{`RtyJ^V2|D7^Jx!N7$#|Zk zjW`aXp3FL0N+$B?O*ioyT+IkPn1CkUTj>pyH$5=NhXs-H^c1qWQ*Qw)H<MQl7`;KT zLuu;I>X~DdbL(p~1Ge-Zmw}E$7Ia?5WxH?n&#_Dq73Pu7n7sr2%lHy<C&h*<GPSXd z@TWTNLkVEXhjjwx_11H?QRXr`r67!QtG6vb=biSwf-<JTkg`DatL)?wGK71=Lq4bd zf=;#ukMX&ko$?0kA!p@u{lq*`tJ3Bo`Y|%i`Q22*nsZe|GQbyNm+>0sZn>Db6-ms# z<K7q4&sv~82IFmn3u97luid?*Ugf>dpQa=CxPGmctp2cE$Db!pC&RX_tqLeNca@^B z_>2r=UAQ!umicqNOGt2%!JE1~NVQ6?(iQu&f}O}n3g_t06I1gB5~+qzCXr12VM!Cs z5$-84?x-cLY#tUHg>RMOu_V3|>DYJQF*If(jZ91jg=gzL2k0=cU@~FRdv)JsG@6u) z)3ir7ZH;@9uD^+G=-}XbN3QHgIQE70xP0b0KT*_e@*(Uy*^=(WwByWP+=%KT1njb& z26fF5$}=Z&*L4p$@eC%-x|u+a*fX?nT`*W-W2Veb4d$-moz_{_#S1uiU)xGkHe>cT z8IOBg5AvoQm&*hwyysAJ!PBQrgHtl~jIj~R)^S>d>NAff%j2s&=+~LGy1k~6H{}!Q zyu2zTlTEjX_P?h^d{R#hc<6%ATQI0KrpSc&ng`5U(pL^C@{fZierJjD68y77h(PRR zRYNqx%;S6f2i7k$SNmTt8j{HmOy)kqzMrLEp%>YRq-8|sP$T=P@QYOmiW`vP#&>}^ z$>b$fpHSta=9@r<6D{eDV{^(+poeD_Bj-PhqGL6tFOQm?Y6F`{mXxtQ$9e}do5Rsp zJ1&F?kyf4EC&OX)Kv)@o%A>1rN9ARKS1R{KLj<!{Bu-rivY|Wwsv@yz2q^;TTV!LD zYWit>VqO>l;^g_EGPC=-U7|A$R)wwkFbyopjDWd+trb5oa?div=}Uos?-e^x@TH8? ziDkhD*G{1)-?J}*yd-;YExu)_R+bUhrze7KxWPy3HSciW!MvE|m_ESGp34PD_>y>J zw-3w<5<emWneN0-*1zm0Pu5;mV=N}i&;{oHFe0nHEZ1E>yVRL+${jAQr2GaM-<qDN zN|HJ184Or{(g5{!?9(o`v0fkS&)C*4b%otOLs`h<{B!Eai6W;K`k2ZG%un`OInZV8 z80n{#7zG*ie>#p8U(DS0%S783WrOR_lM~$L=~avHNf40%cnG9QGwxdHh{Wx5oLx!w z{qkO+0kbAh38I7a-i}2iQlKH1UM;p3i6x~#qavOJMkLb1(%`E&^A$w;xBG;!du{^y z(d3~hN<>2|T2296`RBBcIwCg5%${W`yVW9RTg>(jQj`aW#Lm1fnmGHE*!oJ#CG)97 z@vow52RWr<lJ{}c6AZ3tW=pLS)XXx3Ch6mC!PRP|cSu^Xg4QKtn7K`ybg7<EAUgf& zC2%bpCMOs`WWGYNi~L9xEN?|Q##(}gYmlNYW&Fh|o>Jj<)Iqsnom=M1_p8;K-}3l_ zU!d`nb|SAJB=9);(K+{IiGsOyB607H@thE=h`$vnx*T|$UQf3Y+o9Pqc#HLZvE-Ti z1~l-U79<?4gXy_8=!xjEC~E_)B$u(=F$0JmZ#Dnod@Ur%$W3?9eO8p8=oge{kHm_~ z9DAt(w;8MStGDDZ_OFKRXtFSY+;qM>`-uDrcQUg<c9dWoX!5vJP1mKwJ@HRbZE%by zI|4e4VV}BWq|uN_ay3=c3YGjioLH0StmB)aZ|H=rV$@lR_rf8cZz>hXtBkdnJCjRu z=yX+u*Y>o!tF=FMlZl&M5wgHZ9FQtq8*>uiG$5^V&ke&!Dg&)R{QzA-EUrbdQ?nct zo<@~@C<#M_p+tLZ?yX0C_-6O&jdw_LeU=rdULR~g`B^{>LcG&Ln~qc<3nTWfmfdKz zg+RA6KbXQ}eJhc$=DyQpLudeN{Q%dCDgy=`%z`wF4GCTKQXx&yX*v4)AsKCay_9wJ z&y<=9wel~;`V+0eW>*KKqmIOnAFL{^WlV0Ldl#t&9&&u%a|drHD^|*xOk8Y|u_;}f z9!Nyk%b3A5s#EB=610-nTHncH*jvlLS{iSWwaoVP5&-s5SfP|SXzE|JR$0|3tiaI) z^nN_-wU&|k+dad=52|2m(q30L1r2G`@J-R!Wq(hI`949dQ?<sbI+ulRVpqFT-pKYL z7)7bgs&<LamXBTTGoPMVu7xvglhEwi*gH>6nO9)0Y%lUs*?)Ly|NQV4fA{fEQBPz{ zJFFr=pw$Bg1cV9@_2`H=0EAfft_G@Jj%F@;zvVp5sT1-8Oh{q@<Tn`P2y{roa-BQG zZlGyYgiO*DQEEM=3I+i)CG^ya=xHD_Gr3tV`=Z#f>f)5Ja7tV{krQ;7(BJ3P#@WL> z^Z3g+NTR@6KrZMojN_EZKJOZKJYb;`v@{^mC-tO#N~gz(%(}H~SLrkie8j>zDasWJ zxuKb<H#?y#DoyRcH|A^`!8y!M?z98=e1|gQ-dYzYL!@PJ0Cl(UG6ngzQUzwL$Y6U< zF5VH72)>9*(K0>)3&9WFhO5ASz2y#YiEOTv)voTIo+V9qem?!}Caa#S0%k^9uOqM$ zaRa`@F~bKWD8Kg_!z!^51Y|8JC4a*IU`t>|;^F|TTI;>MwP#`h^p5n1;$)jDptjjs zKM~>JD)Kz(^~%;nrxP_6|G~xzwYPN=;Ds^_N1E53-*jdf6>0f9eY<+gxIgLUXP%6W z*MM+`e|A9K=uyCLi6R-G17HCiVBl<K>%z$J`@M8wTY7*A4dPk@5V>>#13Ag9Q_0Aq z_#Sxrdn0SplSp#=#f2PttJ{?6;>2~*)$1tn?GJtT1JqhnZFE){WobpV4vc8byU)H^ ze2RO#6*%0rUkV{zQ|T~oInH|{08to+lN5_}g>bK?NKNXj6@z7(gwT`YT2OpBwWr}! z=^ahIvbR`#wuB<`Ow}-(Y+Iab1zl594Y{6!rSB9&AP)l?2dM~dLi#>{SKG3`LRoK~ zRQaLw(vPN0K(}9nTCaKNehf-s`G;W$PRXw?lc%Mhd-5nW-UYK|VuGq^+kpj0^eE%v zBg5ZFm2|?+I~s48&S~N=b8qPubcMs!VjjN($>|zw3$Tm;D;4N1X@ydFaO{WIyE&UZ z9XCwl)?3}+vd;J<RDD#aXzt^SSNjm+`d$uU{*$~975QaL0J0AMCh^}zng61*v8{uN zjj5FpK!j`ed#wLO_u9lhz<`GfHz2>sD-(etZnEbn!FSIZ2Gy+05tYlOLcsO$AwdX< zCgA$s^ZHisZ8KoFkU@2jlE84`zA#b_hi@HtYsLYQv9N?B0SjdThyz9OW%EH4*rpTt zsIdaV2)lPF+n^a^pQ_lE8nx9_n%vmVq=EZ$)?Bjx`HO{~Ka1g*YJ?Mz4ik?96JDEg z)+}H#z>smHKhxHjaL9VkZ1VSzGfST?sTdkb*zw{oOA=OD<E2--ldjjFvk9nV4Rd{K z=%{~JIE?2lcFONjyW4x~Wc(*t^4qUsngHa$2atvQf0N~Z?0EiL1pgOZ%o6&n|Dwy# zaW@tI=UC+O*1kHM7ocG!{1i?0^p#o%gFNYh_~)>0g%8I^nd)}sw9K{sy0bo{7hW+0 zjOlVfC{3n$JO%qHSqytJLxlZnxoR74QWrX7w0>hF`&wV3=mKi46KCS(De{$r?07aq zCx54)>*lLpng!Tj%(Cmpf@gfAb|vL{xZ80m_$>0ivh|=pTc~fp=A4n_%|Mfv6|mhD zFK@0dM<e3xaPE{Xc>)ZVfI)zO0Jcg%P(WP3%F>gOt3ONtjqU_I#RWY5odDVYN_J+h zMy5utMvNv7&Sr|v4vuEdu2yC)zemQOK#9{ek;8yu5`fb9|5f~7K)Hb1{{Y!}{Qsf) z7REnk0wCrA7sWrI@&L8`ze0(50w!t~D+l}kR6QHEAU_vqAfQbcpua@;{{;)Ud4c{7 z)78?=&e-0_%9g>=-r~<DrqjMjwpjrIwI6{20ki@BO8;si5j+r(i<O<5t(CnE<DdVb zKVkl~7W<9!FBn9Rzrp;^nET6i>`#zCwMG67q8js`K>mB+{)zLa634%Bz+?Z0^Pg2Z z{sj9|PvYNTSAPflht|ZO7=JFn|Hk-U_8*tyKLP$+K>iJ&Q}K`G<j;bCPL2OA*ird6 wQv5$A%0ChRoK^mfI9K(*5dWvY|GTUHnqw4Yz#)DYg9p6607mL)_3zyO0lYvafB*mh diff --git a/controls/model/weights_modern.mat b/controls/model/weights_modern.mat new file mode 100644 index 0000000000000000000000000000000000000000..bfe32c8a1f2fe48728727b545f23d9d571889c69 GIT binary patch literal 405 zcmeZu4DoSvQZUssQ1EpO(M`+DN!3vZ$Vn_o%P-2cQV4Jk_w+L}(NS<NN=+<DO;O0t zvr=#?%2aSHC{i#qRxmKOGBL0+F;y@!Ftku05-`93qo*%FkR1TT6>}aZCnR_<B$+8Z zYq+Fvfa|F-lOgw%XY7xj{JC@I$et-bK3zHUrDswSo8N*NOakg>qqBDxoEQA9u6Ehy z)qQWP1238<Ueo52w@>3|s8tZx2bpUEH}?awxk`z83Vym;r}VqdpVmLsy5e!ms>wg< zwNirHw=*-Woy~C-q_+~TH-h0vj>8$orH&1vr_x!H<TTE5A33Vpsk-vx)0Hz{N~#`p zuu~UMXZR?#`S?+3u4^|BznF8jGsipZ?WXl6XUfk1*edC#{&8Q#_Lp&+|1LWDZTX>` n>4#sQwlUSrjpTkKd~>nuqc3I$Uv91SDq1FO{D$$%Lc^H=9Uz!$ literal 0 HcmV?d00001 diff --git a/controls/model/weights_old_quad.mat b/controls/model/weights_old_quad.mat new file mode 100644 index 0000000000000000000000000000000000000000..2c6b3c2ba627676b72966bf6caba2c299981a90e GIT binary patch literal 404 zcmeZu4DoSvQZUssQ1EpO(M`+DN!3vZ$Vn_o%P-2cQV4Jk_w+L}(NS<NN=+<DO;O0t zvr_QQ&r@(LC{j?cR4_8IGByPwAj8l?fk?mr1B{-&{6MxJ5Le83oScy0!H{I8@T}pI z!U3+Q#!QCXQ=YLudh+Maog;gu{P=X`%$J@?No;-#W-tlJYoAEA6tlY@x8A#UJ=cFz zi?fo4QsQ;D-<4x<G#8o=GSvib>IY;~l@j$7{B*TW>35w!t$(U@#p9M$-Sr>TEp9rU zXJlBro1+M%w+gN|g5gMx!x_e<jt!!x(pi$^G|qA#IjY*Jy7J@Gl`~&TsvdQ)Qx{NY z*m&&Up4j!X-rqR<B7glIx%z0+vvGfqJ?oCM*E{f%|Jd4V`z`ryoUgcAb$e@t(VVb( jni2P8u4Tq2i%ffdW+S_wcIuM<aX+-L%P}Orv&aAdv)GkK literal 0 HcmV?d00001 diff --git a/controls/model/weights_rich.mat b/controls/model/weights_rich.mat new file mode 100644 index 0000000000000000000000000000000000000000..f0d4f575a2f0a580a918891f9521bb5158525a93 GIT binary patch literal 336 zcmeZu4DoSvQZUssQ1EpO(M`+DN!3vZ$Vn_o%P-2cQV4Jk_w+L}(NS<NN=+<DO;O0t zvr_QQ&r@(LC{i%6R4}x#GPSfaHdZh)Ftku05-`93qo*%FkZlIU6>}aZCnOXwB$+8Z zYq+Fvfa|F-lOgw%XY7xj{JC@I$et-bK3zHUrDswSo7#dkg4){R44qQ!Tp-;haNQq} zbt@(6DfsDXozm|*e_H=k>x#!MtD?8X8*P5PZ6Pzmn$;ZBKzjY)dLtN)<T#vRT<X{$ zdMceINlxP|_mQKjovJH8K3zHUrKIXn2Rn5Eb%O&9UCbLx0>0?3=8*TZ;1!;Jp_KFI R+8>wX+zuaM6weav1pt>&ZiD~; literal 0 HcmV?d00001 diff --git a/documentation/images/simulink_lqr_control.png b/documentation/images/simulink_lqr_control.png new file mode 100644 index 0000000000000000000000000000000000000000..b9773c67678079ae49e3ba58aa3b4a9507c01c34 GIT binary patch literal 94296 zcmeFZcT|(v7dDCth+v6IQ4oloB4DAY)PM-0NCyc76hwOO9fMe41Z<!nMLN<uBosv{ zf=cfMlp;Myjr4E7s57I^Z+-WV``2BUwPp=SNX~oCKD#{6v-dsa%W~W3S?Q^$sJ2~@ zKc`AXMT@7R+H{(Z7XD>;$JgWVzYX@Pa?(`kANP&G57fpOMGO^HRuIGTH5&MNi;cXt zJr&jVH^_e*s;rZ)Q&FwOUpR+RchMUsZGO(EQA%0c%*jOap8mjBEluj(ZYo=OkG#EG z7`+E0Tah^ymY$@wlO`vf%YUyjqm$y-yEZhN?%qt1e~89>de}sBsQPeXuXm~O%glt4 zNOI)J=m>eSSU+PXj6AB`B1B^PSn%=8S{1D0`<HSs9W4LH7d;~e_49kFn+NDN{``SU znHnD9#}|!1n(pWK(Na69H~jp8kqeLh`Mu9ZSrqlpAC#m2{|{N;i~p}}S8z<4PC@5j zsJ>OGo?CLB6{&N@vgPHIJd2Kp(l1<O%kEv|FM3NZ8sb>$U0c!b%Dm=l*;Cw+Z{15? zdAPnIQo@M+NY6;F%}5HHHXdS=^eVp3F4}tjKC6-B>bKaHHt&_tm9KAh%r_}XcErdA zOebW!G$km`d#~25Ww8pGwQm#YzB<vFXFs?&mXWB;rPp9xz7}D^mT5Prpi^KK!JxWs zo>KGcpVJh7kwt62F4lD@!WrJ_N-f2EZE`JdZMkl3Hi7Ey(C0gx`LRI~ovTY_YhBC& zdKM{K8BQ31^`%xzfOSimaCpwDq-dmQc2iXgWE4*;^r$muXy@EU)5*V<*&%*?8>?XE zmfc6%Q?+v}7N!T&W!eAz$7dZ!uis}C@@J!37%Uo!tPQU*$iu=td+7e@=H^tr61Q}= zYHqcJ!e}j$q~@VK;Y+O=@f^mw2a)%Xda)la<gEn5s=y1r=seb%_?o^(t|a8IiIb&E zsa7Pyd<Bbsd!cQ=MNhG7x_O2FK+u#1_RK)A%$~OO8>?)C+`|_t6y<mL=<V!h2h@#h zP1P}%P}GMglWVJ!^J^>KYf&p@Ym_zJ`V=x}OJl+T)2?0CY>da|#@c?a<MsMFzDTb2 zOOE%hPW1L^7A_82doSr+)?f}rHbRk~7PGoXe=1+b>)MaC??;@;ts^{``h3f-RL`Y( z+uG%YnG)j-4G#h^!IG6)#S_8$c9!2?O?C1nco<Yz5;aCA-@-O(@ZQnLOf5av_;V^L z8_{NVC+McDzWI}AX)dPUH(z%$Qb$mT8STzPo4m%;^f013kr#QFWpzbgeV1p1xMnK! z?)8U<#mC(H?!bJyG2o-<6r1tUJQ^>rw7k@Ce%v1@`q7;h#rMPC4QyXO^y&R{jm2FB z*48=3b@K^_LXOcjQq81jrgf^crfT<#Z@SC;!}Hl~1`moBTtHEKeto^!>WovDWkK9c z<!tob^v^y9zr86p-SkCM<d-Jo?jo{NrbTZl$(<R+{@csoNiG&kacQF%GiJ%8uK#$& z8F<BUlma95;iep8C3pB_(vo_H9*N*IF)F^1@yM@>^FvWD$lg>A7q+Znq;@2Ccf8a{ zxuF;?oHrEZ-BY@{Xg;|!`uGpG9xS@PX%~d({6)mu6rS*CbZ3VM(RCVy;w%Php7bzA zXa4$1?pw?ldY`in!&fhc^7GlZ+0f&+i;f?k<WT<hBL-9>&*xJ=V2@(l>f<rE1s^E6 z>hd4IH$*WCP))<TCnNTT9H8_1AwN>WD4T8w7U0B3cjOqm7u0-d(bCW3^!oOi7<$EZ z$hZ9b_rN1XMz7l(ybj|_dw83VM-d10eGc(X@EQXo-f(q%^riQk{qFy23lh|r5iWBS zqxs_Oh_Gd+;ACV6TxErBie+c+yW3m$8f@CUJ+~r&#a%5RS@!bU>Wby^x2Yb+95RWh zQ{pyfG2Wg<Uafv`(DFl=5ZU$3ogD=eT?NFEY}@|xOML+X-NxE^W=}*~EJmA?MWs)a z=+&uR5q20>?kaZ83Fi>yL^J=0z(u~u6=20je`CxXFX;6Ww(b$r$-aKCB~`nrbZymr zvcUk{Ti))=r(atUMvkm|0JphOQS9jKaKoF?whZeXVqbkCoH|XN+HlSt$gKmX<pgd9 z8_JLCo|*43=A;zrd4G9kj2z~d1Offh?!eQ1bmk;NUY>Pt4=ga}pt4y<cKjR|9jSE; z?8U5r<P@$GGE*lhN%ru$@~fTF;diMy+p_4|+!V6z>E>`BKVdz}$+&BxY;ASE%et&+ z$?U-l;>1T=QgBi^S6^=w!QE_#TAe-0CSvv6bLNA{VM27%j3Dj9B%vUlBBmoG+bVW` zvFVb9FX2wGT4Glgre2QIbHHkBExXH#SmcQMukCu9Z_!~;#qRu^*UV_QQdhpEWsvy1 z&CLhptR?5u?g>u78T6<$W98Fs_0eF=R{Dv3{=D6Lq!hyhxu^DidH>ANeIhTE$j(On z;pvGtq>xS9Prv%|G2$ZXR@|@Vi=sZ9kma)d%m7NO@~^%9ilk>)+PU$LCNQq+BE23t zY@u=)4Ns+CXWI?d6k>u2ku%(aZV+|GpWA=5?WbMHJ?57FmKH;Q&x0QC5QV0DhuAiJ z{kU-Z>HMuB%<;FoQb^8e`ej~D0}tdn7w5)EhP#hkvLTfvrxX|lo~abJ>K;xgTbb{& z`YUo9n{eR?ztZLDiz1#C{!Ho9*bNPLcOFay>$f6sRlAPFhjv@$4Rkp7dg3x?o7I$x zl;ue^@5CwHhDh`#Mkt^d|7%OXk;~S+M1+Ggz<{i}Ig(XkD+4KQgk-hEz_A*|ekurP zHHvF+#%U0OoTlF$)k(wVb-T#KSbbvL)sl|uB54ITrD~rt?=H-8*UQi=>2~nDtflXn z=dR?ZXdK}f!lzf<E*|nfK7H17Yt&SKl{@8qTF}DGP!+qJJgGF<Pr3ffhj8aq8Odsu zl>KEDD)pUt=9V4VMm;67)I*!z{>WW_xC|N8<I+%luQOJ|YRp-DZax;jdK4LydKO%F z8ChW->ff#(8Xflgxo>DV_ltvph<Eol4@-@a68zOI{uy<)VNfW=-*1qQ$?prNKDYb- zl_jZc!GjOD0nR8$=SyAGq&UM}B(x!4KVla03X6_DiQ3&tV%Lz&=3chPg59LHl*6y4 zc@K-qh1+XQkFxx~E&tIDOnpY#su>bB$xryTQR?vuOexsB(LlRy+bY*Osu;gNyf3H6 z*P9dhT~@87o=fYI)1>AxcfMK6OLil0sXeEBOnyDQM*^7OvSaTyzPOG-;ofYh`1QC3 zbWj7K=l<_8RtO@f1^V$ZI)5!U3fWTJeLi<Hr$>E>*4$`Int5A#5AV(LUyuDruP?gn z+s*pnhS+{u%sYqw9Y>`)EJ=ixBZ^_y`>TQqvJ9&_lT>2It2n(Kx)PAE<+V6+lv0?l z!X|8y`5|1SY2#ivl=$xnQwy4_XIA%^`(%mpGv8>OQ%8kny6%YL26{HIipQh`#qd6> zSo~nH%y!!@A$FZqoq~^ka`5L;2iAiuqe8%XYIA2hyT$atJEQIY3dYLv`JTkae8(_L z9nrdczMzlUiV-(DEAJS$-wtfz-YLMw$+OtynV+VeQ|Wht-sa@a>fw?;%UFE8*UF-m zXr9ZI0R+4}b0#DKJ0!iHNR@8Jcv0m#jHps{%MKJB!_-ezaZZvp(d*~q(IwtC`!X6) z)Gt!=ONs5{&+p|=6uIWlbrj_fK0A|c;pHZLxKFk>AT4yofPsZScd#~;C?$VQ*>%M8 zp=AcEpvhJ6dzsofH;P=14NBo7xpdc`Z~$U8WYctb<s=81CGN!MeO`AYG<eK9AqJOl zC)aAC2G+b*Y>O2bZoz9b!+W(&x~#*=q)i(a`SZ4kT*@|WO6VwdozX?dwu%kLlY8LP zAVLl0Yp5k$vQ5JaY9bYJFdb|+q;<^Hhv|Jhs4-mXNMc%c^OLjA6aTRJg`p^SHPz4w zbhSV{jWql^<$lSRu6!NuIr4@Lo}rzcW0hTS=DK_0LNI0@)b!{dBcIZmX0Gos<#(S= z<fEVRGrDN_9OXj9d|$i^MRRFW4b;w|<(ZTR_a6N8YlhRU#)S#i@B98qbK+liQSUD; zy=bY}Wh-paew?K`339nF+yePp@Q&4jKNDD0S=(%?YOPi@m(EMgG&9Ivr^)dGE$F1; z84Q^_7uNn->aM@W;}$}}7u5H6Y-x$LeC4x2*x)T)8;^XNYfZoe6TIh1Bxgc}dC=h- zA0(qq8sjeHUw^l2GO~!Qi^M__Z^D%Jk5tLQb8U07D$#pwRoH9U#ady?-OTf4qh3Z! zA^&LP`8qZUk3vf%>%DP8JiQ76?U>?;a43=jl`jQZcNaF$ZezVJb7woLVI!B51lQIn zd~}|98~K}lBCi%6UB-nnYf9M0l*09B&C@W%vcxFNc?aDvvDu4g5LZI!aZeA=hf=K2 z&~JL(t4bvxK3Q4@#i(Bu$UafYW<5)ORx;PBlm4(X@#d1!>Ce=}k%aK^(j{^Zn82h- za#O6_juic}Qt_{^HbEwp*nx8<4JMR*>kF{*?6IrmOV9f#u{7S#(Kc2mHgkzMo?Y8L z!$_BB)>3m>d`_J>^HCHh+X$)I7>D`)$fJ4{gCcg&`<AjSmU(^qd<POqeeabPMP4OT zT-%Ve3MHtsRXNK)8%-w-W`!K*?scn2QCEl<R&Hg<O&a4<xjF*{IH4;B6GiFu_FkGO z=<W8*t6msMjIsdlMRsIhK4#Ozv}a{R$=j}f*WK1c&X2>cW_<h2KE%==^t)h26Swvb zVneqfV)1nvV?picVJL#_3g#qL0_e-^cu#XO2Es{P31H^yUUP>aOP=S4hdoF)+EYRt zyTPY7RhCk!Yr2zh-&z0|5EBNqOW`P8SXqO`1v5U=4n0V0&`s-xy`N5De6~rc09;7N z`)8-pG}Ex6_`Ui+(zHwl{=!#19y5w<j-dqerrZF5QWrTD^Zj|dcBR!_MKSJ6{N&G@ zZevI#zWnt~x`Ehmz03~BYpNEgxK}mKuQqHRA3o2Ito60;W+GL#YP>@J5}DYgrX)UC z8t#Rf?J$n&;LRxRtGT(E!^9Z^P~g(&?c+%?zR_2y24W4EjAT)_ZZ&Sf-)5N*sf)Tk zzl@K&iR$8oUBAwXQKnHgic0_3`s5Sjv&0mWrYAiFRh`Y#*B*mIC-7Elfm{BP%v&bp z%_nCuc#!HkJx1BUx@;vM0YwN7BYmxEVrF}rp*%BhPI^G{nE7C(<5j)?PT}h$U)e6F zhQ+P4nAf&<8CgrfYUaQ72NCI)(S8?Lt+|Bh!cG|n68Y%y%S*2pqBBjpkKSjBZ#9lT z1G|8`n0Jncht8jcY9Z;0toBao{VyDRqwS9{haURZ+L@CXI5jep8ZT>IPq9<SrN0%; z+>z1@l?2WxJ^iLSCaFdyLeQir*Mlnf0yXB|h&_+bnJ-Tbbt{NT8!s?@HH(NHfh66b ziHX(pFAkb-oq<cF>a;6a<r>u7=v{o_oU6ZQmvM8tM5hUMoU7;JNTSslhig(VG0HX) zcN26O@Cpn*9_pzvsk>+~y!lW0xH>Oa@vfEhj7ygA@16`d5_ZK+O<cm_1lQujOGIVy zlmZr}56)(1hKT9I%b)aR%Tl_G!*Ck88H-(8b0pT(1jP@qJlv*zZNBEf<mG)v+wc#m zr7bex(1J~=G1}1^o@%^KSe>6Nq3EUP7G(=rwAUjDj&u2OK%2rPy-Urrc5AAn!~%ly z(UHO7vmXm#cR<d^v$Yz1$FRB8G}2?OY4)|rgET&u&~!XFc&hQZN0+C`&svgH46EGD zOPZ6_s=@?K`zkj;>i;-=6|NtaL~xuKc%<Y+aze^$#ZWlXI*q$Z&rdhdoPi`Jr}91< zaR}~at$Rp^eVzCamf5sNZlCQf9m+#96yx(9G2B{z7p=%v;W71xLv<gjW*LQl@WM^% z_46#RjZyl#o;h?d<~+Db+1AsGbr8!~pygBwm3ZS=7M91oIL>+O)RL9sRBvs-7kk*M zyq$%2Q>zSe%IapxZ&iB0-JkfEg;X!2OdthzTAr%vdLYL!ve=$6oGDuyOE0N0P_nu> zmTsqnd2$&|=eus$BUVL&%p$8nO4mvVCNrkEVd<MLIG2~Qfmk{k(=PUL*2`T^d92v7 zo|M0~)<2aYprVhFd})V#O=_N?x!92>GVqPQ(i!+tXsFze0av>g5gF^hdK@2ZfAq;# zH$3IkPU>XYhHYhGY4^5xH1~~^$GDd4z8UhO1MUEXy;^VWxAO=9zgHH;c+!uDl}?xR z)#Mo6{SS|L)gQE_>4*U8LK+7!%;6~NtZl=ETOn*zH34WYi9BlLdQBjHBkhEzK-scg zWu;|+Wy7ZHyD+GjL)xggtGLgF*v}~`brF$G-bEcrLN|7N6gC&?NL_KrvEF!X@ghS2 z@d0tHEP$vVuIx}6ZJsTt$Y(tpR`x-VZRZ~1SY*r)&uJ4%N(XT*XJ*9(Q~!zSh6u|C zVm!qw-tXLuFmsti;d4yb>cvmRH#{1w2Ya+D(jMk+9ldO&^Qru#A2<CQM*fkRZfyr| zGHs54Rv1oyc9}OoqJVI9MnA^L(=)4MNp>=p`GOXscn@*dKCRoJ)zxasV|Fhd*PE<U zY&;Z>!_De?R_gdmjA>OE4xh0SXDOKsVDQ%w!l})cS_>=~M#g9=6)>mGTnymwP8crH z<9Ab}#{}zW?LF3|vuuz!p|v=*d)@8D`J%bbvD(XN8AQ4C-D?H(^)C&wQKxxE$qjdM zQKBap3;B>VpRf9fcTX|jHy9_h`u<d1Ve7MNBTb1ro=DR{nX|sHt<P#h1)Te{6eGo4 zhlY{@3NM&{pk28kY#GsEKl9;Z_-vJn#M)}_4VE>7`Eq<8%GkBR!H*+M*u}3Sbz4RM zv|#v^ed^V3V<=6YH2n0I29s5^m^JI74q4erigv@&2Y$CQuiE$gT-e)JpYEPrsOf84 zi!5Jw)gIG(4|_0q?!7ll2_;jb0&|Jt*R$JyxCE=jz1>St$?qDy_o}DnRQ8TzSP{1! zk}i#I_0tk3t1J{6&MqaHxXy93F|TmaGKy=BseKN`9=lh*k49nbM3;qI!(ywk`lndR z)^y{N#EnO2<mrcJBUjI|mn3{!2n%g>%{W{!CK%3#&-JiAmTz>5Ij00bEUEK5sr^h4 z{2D30PjGmxmFy#(d}|9qI~2R&QF=-`p(ap#{)&iHQ98QqDF*9BbvNGX@Y4K5xat*v zX%Q&z+yzriFga0myg<r)X^pSb`(<OV_2*b0X+Cd{@O+ld8|e?>Bg3@1W2#uj=`Z6c zzL;R?U3oUH0!O0jp9=1HKTm%9Ez_jOtxTQk{m7oCjgDXa``R*kR6X=-V{B?E_gKom z?Z2ONI1oF07ms$7EZA?eKcYO|`#pusxbR{)hdZf5b#_DEWu|j9y-K*wg)ynz$jQ4~ z90lvzSeSY>?=~A*O<6{jCs<Hp^r)_<__wkA9YW=s7v&5E#vvghzeTGxN9aHrMtTig zm&YeXK1p1JUXh&<i|&ZRc|PLhBX)UAyM6qdqA{Bawl(%%zlr)@FLNEr0yG7$CQ`%d z{lQP{L|@=uM$wOf@PyBI(lDAG9tbZgJ-tu4HY9pKufOk(vf4a#-)Pxze`|9I`bW#t zZF?(l=@qddGH!~;?_L;q`0fU0)h*3cG4FXV83OzG4RXMf3XD=Pp;B$n0dO|05)zJs z^O&m={r){Vlf)jK^J&a^qYd_qb|k@)Z?@hZM?6<qHl;m2hih5j3vDLpT6{~;#9X7r zoY)W?^fOoHI&}8Tcth+Rc9%~#_l_AT;^=TTuW88Qjt0T+(DM8xv#O#KxlI-W)ep$m zrPJ{Ao~h`(W>!%ri%K1f4Sw%;;FndgXed4rB!K<`WIKk}nH&@M3DEhA-U!B~Qgi3- z9lfs~>(i%^q2ZsTbIOl;kuA=ug^}9zjB*X8-az1S!yd8G?R;07jdaE6U(B*Pb}<JL z>}GVnCB+94%o$W`_mz0zDQu0FlEFJ^Fdw|9$SwxH==)Q<<Ir4tnyG!G@5{<&w0)CN zde6(DQ|&Fbhnl7>hl{T9v{X#p3&&k?>GS0P{!vRw{H!>lgOf78LT;xG;j)-}FtMhQ zH@(n6ZY<)`W{jI;$>gWkz9gwH7ekKOM#ZAiaKu(C;)HODdh$cj2aWoqHV3NsfNl8Y zT>>b`+Yzwd?+_$G5UZg&uDeke$u5FCy7E~t>}@m>^j>&9Ubo9#eS<cFAC-^O(f912 z#h76nyc!Hg1Nr1J_j-A_L&_7J%9w*1cAHx^7#EqD*`^#&aW;R=-*xVDz?ZW3#H3?; zs^t@Wqci+_lnR*K7MR^OT*+i8ZNx{521v+d8ik1A93&rMlpj)6SFJ~$XXjCjyJ+a; z*c~62%r;)^c|5H~*<E@ZkB*QUj_dm%(wnOid%kFQxAeC2jEiq0FC{O}Wq8j;Za_ac z2c;YS-_~6Jm|IQvRV+gyvgcXJR-X~x>6G!uTtK}NIjJwS(Nw&y0w4I|{ZpZe*B3I) za{~g%lm*TlCcPw7G3QqNxyfEP|BhzI3d&q5A;X4yCk-EcFh`VDH!gxuuoOSsE%iDG z+mo~;qVhCu$g_;#qRnD;jNGbdNd8v79WQ82itO{0xUU$uU>>${&jn^`ZkMK^Z^<UO zG5e(OGo(6oRBoJ!=ix0r9)G7*`&G0I5lEu)4XgehOfddPgu2-3w|=Bfbe_iE#U+fK zTHw2B5RlNMxKEjI9iDi$n3)d?IMU8@s9Vyz*r+Q)K0U?I-<-v%neX?L9mQX%yC6!Z zni4KI#9XkI5ItOEb|GfUY<cQtTvvHtbbqh$gomUso$8h8f#N<&ll#bI&ddkl%{>Af zetfJK<tGPOO3LtY(FFk^iiWEu+H*Y-0U;}tSH`Vl<y-Nyu0l#5mZrHYNX6WOOI??8 z+Da&wn5pj(h)u@IRB=;}BHvvNh!)ITchFEH`kh<3J(*J{;mSmvJQsAC=d3fixal6P zpY)4whoM}y?XPrN7!2M0^I^8)4Y&uk1n$i>X*j^L(bNL%CnbuH&Q`4rab*i21_a36 zYzUEhy4zhc1Uomp(n=#8ratb1!w;hPVk2XRG#T>>8%{pX-~O<{_|lyCI(ij+lnyVQ zZBRkqCe#fz(6HjWRIsc(s>Tbl1y&@BZ(l!?sWp%0`Q2v5NG%*<z%x=UV737E1;FGj z>4(SY=mYl(8dm<r&Uf=9Km!HqNF-Vb1rN4Cp*Dms&9W=M=ka^`gLG~yb8V!h)tRWZ zT<g+>N<fn|gE7I!&!d!`?%|QD=-|)$2jtVfQ^P<I@$cNYlbY%DI&?U&1rIk}<6W&l znFU0!s4)?-Ch!DdLgqJ)M!LkzP4<>WSJCZq^i8a<vfdk4M#vbUQec6@hYH|3MEW8a zmaoeFLtcOsxBFG1qtn56%>j!M9(Ly0c6@?TlogRoNFjMrNWwOsq}U+M9_x##_uWZ@ zJNqC;^fcPh3#E>w8VFE8<yv+LoA;J_cE|Ah`XueAlittGM<@OEpB=dV=JqxOtQc$0 zie>ls`r7J!v~Hf~l9OovU#G_J9t_Ns@LX&MY<iH8Uq3x&&v-UMeuF$IuT3x9F5oHf zk!B0Yb<=NmE44!*sTy+(IFs*m9M_?-o-jkFkLPl#hE%u?Uu>Wlyg4k{<+EXvZV>$_ zR&@80=MU#-_DUw(b>@ahY2anr%K$mFO<?!n-Wrv|(+y$wIF2+{M7;fL-<igUOC}3* zXXqm?$5GunXojiB(=ZfsOXcpQei6JpSudNPUz?FnXu7Vm%Gqx@RT6926Cv6DzN_@b zx#D5><7xc`2o!`cD^PFn9yCnN{%+kWn>cnk?vC@Fk_})kN_k_}mTt+S=kfvo`x^K2 z6>1lw%hpyV$%kZ^vH+QUfv_@GnL2z0A^K6V^&{u#rB2h~5sX@TKOk}U`E(2Gai8MJ zk2FRy0ur0q_Z;q&?cL<bIa^Xsk?Gy-ssA@##QGJ5@MpN4!p0x>v7L2DLh3MJnEET{ zlZSm|kMaVCkPSpc6S;WivisT!g>-Utd8W?FHLn}H%2j`l(Z}W-AKgpUcz=yFtfSl+ za$$e5F;#;!*n74W>1-P*w6ad!s0`~hEG=+<i_ATz28vYgW>10Hm3qp#-q2|ScTnE= zT#BU?I|r<p<I#<94eU1$joM8lgj?A$`JJ^X1E>JuS?1sDkZgyVj<n_671^U)QJ(Y9 z5VXN*JgW*Dukb_{wN9LbNP+L#$CntQRhu>#v=NMiP7avEFlWfrEa%5NdLF-hNP|J} z6h6t7hxbzOH$9NM850njE3S384C|4!B*3n(^z``6T~jfWH%oUc>J2Zwn7nX=Kf&<t zrCw(>l-oRb_G#M&0=C-&3TY=ejxH5Bb|d%kEV=GYOUL~$A2DlAx(3&>6e%<p=O@Mp zr<9#-u>5>cA!@a3epxp?up(6D4|ZUJv8HB!u+dzH2&WaEED@9ym{!crWGHxhCUQ0K zFLDeoMNj&baxO+*?=v`CBJw?f+a>gAf759(F90!xN1YT6za}}>!%Z;)Le$~r`;?4Q zGZN9c0GOnA1jn(EscFz-5EqgdPUlHCdH^bNCq%9`ez3{T49-;L#cpn@&((?F@lvmf zOEEtw@N=f_^axQLJ>LEuHcHx1w^4FyqlN*&z@i~WmVDI{;6|%djyXPYk8d_@;^F1b zpo}|d#o27c2dPCykN!-<vY`G4{n{6U4R)prG0Yq9tzRKdfa~8f+=647Qkd*1L8J!= z`)~9!o^NwuULYw9qj9fmA0EEg9UXJ(#(Nt>>XqqQ0b$#|w}mT8p#{U9bE{!NUlJG0 zR<YaploALhs^!i;*oX@B*beE+)?2%1Fz;r81my7eilIofq-YhS<A`oSRDOuypeFD~ zLdg1+J`?;@+w={@897a0msTjfICN}!M+iS|bo=rt+-#|v_XoL|rtkZ9w8r584SL@% zw7sb=LWyWYB{2cua{-Vno$l0JmjE18cKQ*fn|%&Wum52(EoLfV2%8MIN2fKL76Z^- z07L&xE}+MKvi~->eGd|mL*e?#-)F{F+|c%oezRTlJ#jN5qJ7~K{o94v`w)zq_DDR7 zvGoCOAJY0{2vjL^R<c3sTOGBIr~!uQ02QJ;#iv~E*Nxs@I9<bwGcruL6e-qm`OF}r zPL_e6NW23)1t9_|&7P9s2IR^Q{2~GP*ILCkC(T_x;v4NCKJ^v>M5Q16KhXsI>!@ix zrYcyRMw1geH*DT_718YQ;|T2lf)>ktIRDq4Yrsmj23AG6lh1UOdJ^5oBi+eafGBsF zwWgYe>e}54PiPh6^j^*qGHrajUF@rr=+bzOWpk1W`9y<xF94XLpKtB%c8_#uyfFXn zXp~D3x%+^8frhCo0xu15!u3t>Qv<lg5YX&=P+t&+_^xEWYE9EIMhJGcy1r=N?RFVU zaI&Nsh6mrx_isSxf2tV%WngyLVwWt9blna;_X(k;xi<YYK;Ze+8$4BvIw04+0i<#i z+h+M7-dR`hE2RFg1SvVvn-zc^t-`jCGi^sG{~Pb0UIXC)5m?_3euC502ZIWifERPf z@P<>h48=LwPVya;3v`&wf_UnzU%)gBmz_od(PGuc8AXX$N0J<x6gA7dJeR(NTU)Fw z&N%`9-3j|K9w`do8zMB&`NF4@Ur6B<#7eGvDdn>@tke~a`C2SnsB1xYQ7pHXY1(vz z?d0{l+xDHVx6JWvJ|Ne%g7Cp=?+MP6Rsf=PogjzLZ#HjDwMFQJZ-D`*>;0AY$<nl* zA+U5;wScN;Gcx}uEkqI`-hSMC7u1RB$2@x-_hoqA%5OQF-d1$Gw5tf4>w(bgOMJMe z37((eKuVMt`To97p^wUUv)>Kcd#W;ARcrzXW!nM)sNULQjwV_6mhvB)=5010-fmh# z=z<<``?LV{&k0l}$R!_&bngV!#H2Vj6_PI}z@Ce`fXukV;Z{uw>GfVCDXLY(ymi`^ z*m@Cb<-HIhpl`K_cB{>kn||_R8<C*f*EFQTm0{O^U!;=^^>dRG?ukA@S?XE||B)oU zlEuJ~v*K>EHXBOknGz$M!bpy7I4k{zmm0in57qh9j3A2H293=bN4h2eg=l0&$R9)C zMutU1(&RYW+_94jBzujxyJ$C0a49%m6~0<9K2B!|sbhF_w1Mf;zDd!@F@$E!@?&5j ztUTVh-w&hm9fW&!ew)h~?tP}f?u+ixGBSpu{-SO~npIn%*t9%L^S5}{nJ?sprbH#@ zx_d0tBRmu6lFPWNk&-!=agBD6%w&VAsL20~3nsXi>ABKTW-o>qARr(N=K|Z(GEZ{W zM>HC`6kDKS=Q#Mp5L3aR9zT~TD-XRI8WW=_vou+TNFc1qrPzUGpcnGp=FC{?zonha zBds+>ts>@N&vJm82=bEUiL!D}4OZ?;1Q2@Zx(ui}$F9mU{G%+1X^q2f&YIa^04XEW zSc4pA9yZUc$WykI5$6zXm7Ay-{$>6qy>IhLF8_Z56qQCgf^(Ax1`%NK<|RndyA267 zi!lNGb`--}z|FetL2c6ONr`aIXos^I+IYxuD!OWgS*{dlsyfFViT-cl`LVOqBX46M z2_ZXKpbm}3$Q$l8?Qn=El&7j!)>X@We{l7)md1H2is}vV0aWwthC7I#@C>?FV)@VJ z-EaFBW8%+3oqXU!qK&>GmFZT(C*!BUAxuCXi@bFlzk(;Lu@#8Us4?;&=1sa1an`Zs z+ZC%t#bIgu?QLuX`+ai<qV0p*8TQsF3>`W<q%7iuJhVKZ6Mp%8W_~H@xJTE1CMw0x z8LNw@D%rr~`vr!nFOXR8;u*_$Iij!|OO~f=MX?>v0WK7!0ZpKcgyWJEq<6#`X&Q;M zBlHBg7~M>tA6lVi0WS}s!wb#_FAmL*(2L*qjZ>(Uj+@(r-Up0Ca{PTBTZ5|Ad+{kT zc{okK9;mR#vA4`PV->QmY6EQ4jjrxxxhoy(+~ZpH@yyV3_B3hP{*5C=P-=1?n&zf! z^u(hN$sl)rP8C62(o`K^`w-Y#ih|~^Ek=y(!+bt}go{qKAQ5h>eVVT0wXk_hKWRRP zya<)CP5_^NU|2$*2IDqa=TS||F!_nTG-+b81G!67VHHz%(h>*mnP=r*<3fKGeIUwo zr#915c8qJBNNii~=UlTny7lGoZVl>}gAH%*?Z$nbMJT%ycOpIKwJ9zHjB;B#4%fC5 zNf=jbqTnH{7FNi25iK5NulkhM-CQrKTL8wE?mT$DP*d!6Jt@(2bXD=m)vA5=?*peg zdc2k_Ma~CR`lo2;By`Q!`ZMu%OUP_^(4$2f{l+*@3<w1|A3L2?t3-2ANqp{cmzF8# zLBdlh!#5XrFv{cWQZA{A#&6Nj=<$q|CQ*(bgxU)2gV2uq(|QBT!>3hI4nR&4XP769 z9mu;aTEZrmzo%}0yGG+zr|QHEHD0P`Az3_orn%I_RjspTwz1LYwcaNS1rY{R{GMlk zm$bUX5wSI?i<7-QMHF3fo|FwdO6<AdSbAxVcJAj5?q)q_J7#!i8@EAKYr2nKd=jK% zjz<qJZgunK^OXp_{GR@agouv~5TI?jrfLPAE%Ug~{{HyA4T5Vcc~;FUf%9x;bID}8 zb6um5hOS2&{PM>LQR2wU<7)D8QzPdvf!GAIW1`|p{qNp^plV_?CBtblIrGBjvfh*2 zz)v{+aC!?%y_b|3&=GImn!kQ|HOZYq7PkL#$y%Xf#G^m+&31d1dedTc+@2S`mM`vp zN2~s+GGrY5^2<3LW0`|Ev>2k!9X<8(@eI+w>1GL@ZSG#0)qo(airCA$P3|`gP#QGK z^iT1OhelTNEc`Bwu_4~RG4X^)We`XwP8CRiSclVjE3IW>p7)kUi8uOpyn<sjWv226 zJ139n<i96|Mt=Hnel^!o4p7i{WmR#Ekr<TJA>pOowEv%+EqMF5q0U#d7`AuaflA!p zADVo#z))wFssrR3>ZzA#F#xbR8`k>qjRIr?M7C+u?e96OKkL_halWfJH*I#KpoEcf zXER2*qOpCO`qmc*0M=njIfe=5mmaQvA#*QgN`^@xDWKtcv#9jfywyF9$<w~kE@dCM zm>ieV3=e)^&mpr{J6(~~8AM2k#LCBCBLpqqf8Xp9;i^hO4Df7@hPSOi0pNb)0$hj0 zl`;Lb>=TBSk6qFTXD-S$>riu3sruxD)a3j7o&K-)<9bkJKZL|fD}mB)F(QLIAW6-G zXro;hDPF>D!~)`)JyZ*S`*FE}e^s~}c{GpsqFtfv>z+&mDXXyiyai}Jo*|@%W{M`C z=v=d!B{++oQ?>kN80F%BfWd924=5c~MYebyu~p7G$xi(aDUTr8>zQ)z0RN9@4-kcm zdmUF4fC}+6e?zB#JO<Nw)FFt{1&1$&wEwmDlm&$6p62&lvuKn0Xv~F8XwJVq(_OLe z=dvy<ld5nVesRYFLJk~a!l0sQSAH5h{FCt2S5#~#3~q&oB)6Vl_;I@TS#8cmB3UMA zP7x_vw1MMz`w6nMSldO&uPoa$uYt_)bT}mXX}U#?OXnKOe_)`0JSu>E*8zFTLeQj% z96<?1Q2T)<$?A+wt_LK5IS44)Duw8Kgv?uAqPVdCYx7&-^6D0t&3yS_|H2>Jo<tP7 zU-BqLwl;CFdD^TfZ+UUwKiS9c`wg<)0c;c3C6!uM$D9Noqw-r@kk7|n=F14tsm-X{ zDf_qE`cWbM(Caao1KG=eP9=bqhKJQ$?z6wwW+Ws0*B@dzzyIllzl*CMe=60H^%GzT ztZqVz7q}JcLcxEkj$hXqtl!KBs^6Jn_Ysgkz~;8TM}%O`WzLg5PJpHnyNt2`C!%=4 zeoiG^*94oLfR=$7@*v0GSNhj0w5$r*l-)!ZqT=(CS#=jfaErcsM+xvw*WS=lyrR5U zi$o6FBcd9}A&Ddqr}sSWe)HR50$A`b(Ow|v`GLa=)~_L2*WN*!fJoj6ss|9@PTbhM z&xUGUoOr<Rrv)7Zwe=2(Z?81yK|?HIihj&RhlS!U!mfr}*me54vwoB;1=6EYatcG( zSUT||i8jUuP512$la}r^xb$;mrX|1)(!gfZ8FJOPa!PcA!p1@r66%R|!=Su^9=BTe zw-$hDIe}?w`_gXf?q|{W$O8H9JNM>pFU`6#(DO`u^4*ayvqQX@Mrib-;zy9?P*&Q; zM4ibNkO}4>A``dS;cG%>&6$8)c8e>O-Gl4d32>AlNO!Vztcofo)(|e(YG@W)5~Y`d zx&haqC$?g#VJxGphp!ibU{;nW&Xb{+QR<!3_vR^};c_Cijm&%p8WoZ@{O~2yhv}w6 z4{NV)1BkcXS3s3U@)S>Bdbww}Mk+g0Qe<Hi4K?N!C!;^t^LD5;MJmQ$rle<s4ZBbj zM4ZO2bRqs?b!oET-tMEF0J;wmgqv0`P9~#=5V&%`%<aM<J=eh}`H)CXwueI9s;vnk zOCtP;qiX~zoZ>mzmJ#K?3@4t0=m#Uc7EM87^%BAM$SY%Q8Iv24#*?CzZp>!(>kt46 zkV}eAx%TFEYm&;rf(%|hI@M3HUoU(P&_jTVuBf$TW6`zc8B+h^R@isjx;ATTaQys_ z8<*l)sSoQ&sPG=-TsMoD+kcxyFUYkH(Srofrx`AW_tP`>2}@qwS05m?&wRJN(h|Td zq?PNP`IhF1QC<W{lNkhxKWz*H1x;%S<>?8-V!8KuC(n*&z8Oy^lI<u=z*1~cm5S+2 z7AUlCvKtlOynWv=8T>S^`!piim`Ql57$rf1wvOvj9@7_+G4%*YjcB{giv|$chx=-f z<m&Kz1Yx4!B~zYHV=mBy*K1h<*7c|=GCw`rgA9m-2AlRnloEogeu3UDSMmW=#a)iL zFU}uA{vs$Kojb+uhm#$Hq(iQ>>A9yx*jDZ(=i{T>>tg{VbpkEA3#D%}#(wCdBPHIb zHUxNdhRGgI1bPjE3Mm;A9AX6Ji~UW_OcTx&{xPIv2aW7Y_w;oI_*>|`P{{YlT4x4O zLVr7+1rF+kiXFGk2XO!$wup$nW&pYPOa@+jhxlx8gva!|@3sYt_D0nHU4^!>Y-2;O zH*?N%T)2!;PP`le>vo*%A#FeXi3(O^RXlZ`h3ejF4?xl6d?ieM@7k*Kq~7xSr6-r_ zLgff<*&JR8(#0`;CoVp^#yzg1gv&29EL23S%ud7svP|x47RQ0uCwnkpy#dfC=>_c% zXi0v(iG(GfQui(tCmSzadr)Z^+zwG+NZ0P&;h&3L<WFv?1!Em6y;HWjm_m`a^IoXc z*R9_fhZ_7SI++Whyxh}y=tKCBxay^)o^UI|JJRLDu#$7}G#L7H5bkNkFf~mN){;sy zl%gc!X)#J-Q@0??eB-D+q=udcSea-wQ@S|HOX<AIaA;*!kPq^Jj_C@X$B5RJiv@Hg zhbkL(9SC|vix%^1JRt9D;XGXb`o2C&0JseMnMBEzcQ}%mNj;i!_P$26jXaaeWbsTO z<x=!lxc;J0rADwj)MK1#xD#E}R8L*6Mo~yBP?h2?K0{i&uFCdPbNi?SyZ}6)H-t~; zOL>TKlxHh!F3S?MpLLI^ZNVcAIbfcJW21t4sJLDk=(NFoia{BJ8{&W7XgBO+y3Pma z(ya%Il^B9&)3ix10SKsq_hu)Wi(Tz0daN=RNW~*7svwBs(?5o#X5vWO{mY{v2DG8R zG5#XSe#QS8l%F9wq+YJsDPHSY%BxK~auMjVjwc-I{gA?kXK^6IROG(PGwDGEmpk*6 z<W*MyBZ|3`-Jt@qtP`i?iqE&d@eFEVt+qxm)3QR_VZnqzg4%jXQm~-91;4u3Rz@&V zD{!2`qes9eF=*ySsnr8&b};<-HN1OjE?Qm?*FR^{k@wdfcBiLZA`3uB-GHtJhoBV4 z#<YT-Q9{5)A-ac+Ap*=8<<AXgL02ecu#a#5^l4M7@<$mMWechS@K)1+<M$vkLW)Gr zjSmX0$G<iXD~z_&7dgbSQa^E)@CicGwReCg#s#ajPNZU+E=8Ob`b<$Jy-7|HD${9n zNFKbD9k3zaiev_;MFBJ&fVelY^%A!9jQy9lB$3f6=sW7_s|YCJ9^tK<9^93$HPZCk zVyrRBF;vx|3aCSFx|5+vC&`H1TZ?~;emI(mSF_M+@b(VQ(*C?hM-=TQp{8w#2;|w- zma1)tgq1qA3hiKyHpACh%*}HjA?fS36i>IZ7v!Wl=M}FH)!H;5x2w^fHAp3C9*)GM zaQZ`)^E{r|qj19Vf5jd?$8mI<lnX>31!k%RFag>f9OIFRypIeKWXK5`GO=*`*Be7J zE%u7L<&N>l1?fAsXdsX%p;Z=1mvxj1y6pmp{<^rq=SUY3#M_Q%#*syaRJJtIz!%wN zsD)x)q8p<JVlWj#!hXYZ&_d>j>w9ifzQsy+%e{yl${a{wLr95IeL%XB*aVKs<DQuk zpC_4k?{tL5(LkaVUY6xF<9}@+FcyRt7rw7vL9M_FC$fr9S_*?((N3}g3gF%ec88Wi z+Knt}M<t)D_=T>C<$Y0+4W^~m;zg&Kml4^w9Z4So6Lw1cA!f}>7Ye~kghF%3W9ZTQ zy4f-`FXKhtVbzNN*f)@=${oQ+gE#-cqm^!PG{WJbIPlw$Se<MOlj}d96#o&#W#ctS zA^^OWZAOC|JuL<iI28<nLNya;k(O=m(=-(^ghh|;LR-K-yhLp6{+6gli~XQD;+4h_ z`TRZG+*{TCaU1A%V3a-Rb!ML-up+dcMuz9Z8agtsz3DE*cxe~fyl}rX#=VD{Pdoc9 ziP`Tw;&&LH02#L3+AIq^U)Q&(erI~TpmKo{CfHl@G$-;wKK}8O#7eIwiL20?CT!Ns zB_a{=57gQJ2@c|8UbKH(g&AXJi9%HC7Ff`(ev>T^sxE9oap0pL!ebjCiP5uD#)Kuf zQFi^ilVdLSFNw|8%UBTzJI#8Eix3e6x%A7(9Z7n-<q@-YIiRQPgzUC^F$G7=UkB&1 zlq6T0X)vP_{NQhYF0Cd0VrXISl&-*?eRg+=bkcnKOms}D&Tfe7A3JcI$s(gM(Gi4G zK5tKBr3Y*qscu0IYHU^#>z@w2WF#bKLon&4p}Ht*1o>n~u=OXw_!rQxO00r-A;z*t z@fY2ta<W#29{J34w|!j^MYF(uU3Z!IU3ZCCEL2Xj4RRz2185}O%e#o{wt2G+X}%(O zen?J?9Gw>+?AhNl)5M1$^+G1~uk!A;xbtjPt&Ns`F|{JduMZ61BU(_P{<&^03Ebz@ zPsT{m_*gPkx5zG$+#z^dIn(?!jR>!1YWq$`n&cMXxB_%jVjO6`+o^KakCx$S@{?Yu zu5m00gsY$Li}Yj$Ni0^cd=&Z;fxmwVIFqBg)p1ti%Vd=no+M>1y6FO;cN?Mh|J^Y` zCzLDF0i_FiBK6cjcF`Nq%1T2&YBn2Yo^H#sm3nTZscOYZuoCCWP4^O{@9r6(cPJvO z2~A4x+=^d*$b~X+e<JZ)D51tYOH>fyNqjK2Zf+-rPJ(oTrXED%1_3Mr^9jqC*UA(! z$@wo&Ee_}hm0Y%AJAT#Y{+<)%dGx9j8@~g3(52HZb$3EzG50c<U+^Bei+9B?v-*7f zQAMdA^Ii+z(x&fS!dAv_@x7%Ka$(9i$Rm(;>p}owARU<w;G}~N&#(!Nu;1QC?As?_ zvj4!<3R#OHs5^8sV@_;n9@OUFu~iX89S1F3Nmrh2#fOPlTMa$84|Em~^FlFB7VOQ- zhCDi_MB&kIx8lAEDmC}6R<q}aub<yo_PxDlb#)jl&OPI!I9QO`4?M#J3cJ=9GIw?v zLDk-xpvZ=Fz)@1)0<)shmj`$JAw}NIWaq4RDu5DJB#=fv`*Y<UfV?@iXlQjnm*x#V zY;GnZCSEU!Kr}Y~*Qt-0H$H@Q=vbE+A%!=nE{XI}P>#6$wiL*TTjMS~+9k_k>@d;U z0y%fxt)(H+$>OF}P$m_5x_-?Y?K{S<0z@X2$w*^7x#&+5mV2`6<$GlsKOP5l?H4ud z8oE$pUqox{Q;ay<0x*>|uU5K)7UvMpk7T)`=6ahAq`i40=U$SY$CRvf4QFK_yE!xw zXGe;=yQ$Ui`>)4r!#^zwdZBDSe}ouo2@Tf5Mm3Cxlp!Uz{;AaH_RD-X88-rN^j^cj zq9eP)-H{9(VX6qYi$GY@P$w4kDnTV+0Yto2)C%+<Aq|P+pty8gTAKD(MLp)Cn$G&u z)!kn><u+@Apd*lTyoZo!0UXTwJ=4(RQdW_z0|~}@Pya3%T+_hcPucj*9kc@(5dHWJ z2SGcX<-0?|rD{^P?5N|)Vt<firKcAm9$|d|kRkL_vx}I71#YAF!$)67G=hIvJT#IO zor{+(ZiL<w7V3rrbX)*{OI3`vXBl=+x}=AKn<p~JHM?EmyVvrvP&w(a26XjQ{Taj% zm3y1zrOdtq`NcrDrf-xXRi){bbV4KXc*$7`Tr8xong>z!cJJ{3((-<nak7xYuYip` zuIi;wFqR1>98|93K7ZsGKim_KitSDvU`fxki9b(Y)?hgvE^Ili7vcV+;9~-^&(SLC zEHp8*yiD@DPta*<7yS)e`44-;HGw>+*-ZY)9t0Ur!=F6y$>GY+x4g)rktB4#oG~x8 zp@NzIio<8wbmn#0L&{+5^w4z0{%il?saR9bLSc`2<ajtUePb)rt0Ip%0YEoc5zq_i z((~i$Oyp5+xFSlgH7i=(67xf_fc5eW<Z4{J>i*>SEP8E<bM4yNy!D!94D9ssgtd2V zxc}BN18^x^>`0FudsoV=X#_Ym^ohU_l<RXrs?YcSB~&`;z3TC!#}dJieviMA|1kqW zOGFAOq8DVBcpU4nngnzV)S1Y9jH0CycS=40<|Gn-095is3frk0e~BE<aho4Eg%tg{ zvjFAK5FeRDgMk*IuL)EQ&^bSV7+7dZmzuZaa9I_wa2AM^i-==JZsa6oz0>WaF<_7D zy)_`S|DyO#{LiDi^BqY9$wgN|JOT;<725%Rz>+wTAI@&`Y6CTf=KQa@kJ5jSVR*%f zw336Pny~<CnOsT`Cqk|<0cETMMePJ=KoIVI0x4JwgTz~V+{XAOcjf?^)(%yyF);f! zLC|DZfy@?}RIy*u7GG=CvCe}l+P+<UR+*(aNmS&_%==R$ihjmqcTo<~jK^R2Y2z5^ zb&;BpA6f(`Vk<||OBc;jpy3(duUe$}0Z}ZtANvy{`qDE5_?2_5bF+$^HcST~EyeGq zev<Do4ePxE=o60OxCq)eKiS`&{lCRSTKkq{pV&(=LS5-y?>q^rfNW86;TsaPAT5zr z5DC}PyT4#siWA9Ei$eGZAX3ZB0!<ssz&_izJB5(~v>W7Vjq`vIu`lHz%`Lbj8;G6+ zR2*Ql<fWbreM!nUXbU$+q#@!^tO`4hsw1p@_flJielLuXFhhu1z@Q6_tRUM%I=&Hd z%Dg@E1;A+46PqrA3h^74hw8VOHZS1!=7%KLIzCFSc~A-^WT43Do|)@HWM2&NvtA%a zc^9J8TvIKFQg`_+Ob^JQ;`{~q?hyPhFw-4ozz?%-=K`aA9A|6Fm@fwBM0S6A`C=#t zH9DcajZEU5FJ}-a^!b92M7<>72V8;}3r_zJm`Dv3N7;AUCYmUKBRJUh(;<m(xPh?e zq5~p5_JleXzyc5xWg|T4VgA6UKVc#hMCMR%R4H;?9NWE7p-B~|^zOfFP)NJ=q0<yZ zMhM(f;47<jc9RN3rtwR!eM^nao;}*`_+%bz6|g<kF%G|DS?MM7SVVi+ZApX4dLakd zwNtM0Lny}QO-lhBzygz4?CzZeIkY$^Fhu8lp?2o0^;()3+L(5=VO0~?S~A~ho-W!F z4e_T4b@V%wae$6T?DtymKc|Si`iL#Cnkc`IjOht~$V!6&A{a8w<`Q>j(N8{`;G+wH z*u_yDT671{m)IpigYjNl>Me1f@<lt^j;?n+PFKCuDM)A2O3FnK6UNf*ac$hW{(PgA zihQ@%hfL^3@y94r9M+HhKMVId*fji2<rp;AGe`>vnAdX>qlEK@{8WB_ffF48uaQ^t zgtrTDK{Lqi?;ryqdJeu@85Hog#mEIqKSq+6(r<kX6jB6;PAKvxCfu!IB!;u-6STY` z>IpNoDW_(Jo;ZTCi&P*1+={a!Q7KB*HyT`9ISA-J6H;d^foqENUUdxzWYTl4MT?yG znpu8v#T5G!%lgAs8KqGJEE-1;e&rG-IQ@LOW?Gn#WoNU7hbhWDIvBaL%CE8@e<V)b z9N=90c4v&<653<QUMFR4Z?)~k`N^AcpMuPWCDr6Pn&!CK35V5%p{{JBTHW^P@tius z)LrNZ-Aq|j$D=1=IlPx`Vf@F1ZnS*aW*TjJUB*5@Z9Dzcu-i%efWv)rT`We#I&5#` zNTsH(FV&L`z;x_tQ<-HT5I9fHfkuL8)$`-_{pT@2=b5!zI+Ml~Q|($->SR@`f9AVX zG)v23{*rzGH-=!kh#)@17^=feN)iik2q%#)^q{oLY}-JA7wDq($3aEpO!}BCng`M_ zLcl(cWNM5z@OLEZPw-fQY}6OZyjCCqXE>O<-V3St^!RIWO)TnASo)M(?l`s*k(}M$ z&ORz`h74dqe2lwp+9RuyIn6el?n_MY<8?HYKIqq+JW|?ZXB<@$z*N8rHnKCFGTMSy zAE7x%1L57(Oz{-RTyFJV1gS-OtLnB;1HgDPm-1a04G@?Z8Hk{GAp(2KbOA<ysKqdd zL~&?|q^{R4aT#K@p%>frelOLPBsODSLqByST3*Y1lgbY*;UD?Y^ojN6%pXZhvWnJ? z(T#j6XDHqFCC2BqAS>@r55L+_DCKwS&s1<gZC%$4B5WkPMWl*<zWshW=#5uyqylfc zUdJFZ!#{FLaI234LHU;@7(AD2+Ena*0~`&HEoZeel3F%W5KSf0pUo!fl#2LvujMH@ z3h5)HKL|31OaMT%X^_%og9W&)({{ga2ZCIHo6Ln$zYZpI7(;VM7My=4v?Nc8(+^0l zvx*~)hY?n>cK@Ayzcl$X{+ajy@bI=7*G<Esdld}0po+u&eK<WME%G+vi^H)91*?;J z71Q$=n5Yl11)s3hqtaXaFlKuhf!_O%;yVi}hISY!GgO1f{F0@vRck^#07XK{he+|R z@P~VtQtm#y9C21V_Wb=~_h&D9-?BS*UxP{@7gF4IZQ}?dq=&R}{u%-&v%3yFNM{p8 zJ}yoZ<A<NnDEuvw!F(7bh_=xL)*$RfvQ$O=>3xaM?fjS67n=`1N=W8?<6y)~w+K{K zx6^e16E0$3D^&2r!~sXWcN-q;-wa_ZkO4mPz!tY7lW)9+p73fpm6cplMyZ3W4l=T* zNWOAEssM(aO*Slpedzw?_CYzOMnmKo2239ZTu&5nqZ{zBJ+V^r$$nv8L9Zw0LGII? zTPL~J9sZDD0rMNU)9_FHHO{>Q{_JrUTK?K40G%fQ9LR#vAu#mlJ3heJ^EebA4cTEg z?bbb451#+aCJo;#uKVJuI}`sO*uWIYdu_$a0<8}t2Xvi9rDVAugL-6&=SuPw*~j13 zRTk@$EuimZTyen{{{m(ybwPJHQ1k%aAyNy{2T#yz3STRyrV#lUEi%gEf5(LAs(1J? zQ!gC8vc8Fj9%1T1^k@xMlM1!G3dl3c=U;mKaYP#y_UoZ?L4hm67X@mGBzzu3QT5aV zCr|DL{9+7rMExM7Xog>9mhiCs@nBM3%9P8C;=eWSGcKoTT}Q;WT}bPG64%A`u7t65 zX~c;MMg>8u?sj)g1CSSUO?4u2Y4<}y-_eG6Sfs^&EHV}*_#mtig-sU}2*fm745-N> zM4j`2w{xX9h4Av>)nB}%9|0__v1QkRco@6^_ciUpqa%lFK;eSSFIiV0LfdhPafkz= z!Yo^z6M*92(!I8q;W-ZHN@P)8Dbv3p>fmz*f}oea3)n|%q-aO#_(-==ZWw>pdKnY! zmFPIunupY*3Vkj-XX)rQlNO-~{qbXfov%X`YZd+#rY*UttsVy&v*5#UM^2(h{CEs2 zbyi8uR@lrW6GRdKS<d<ZLGUd37X?b1L2oyhpb~>~ctAqx1<-Y7!N(M7wh`zyS0DLV zLP6;|9dKDb;c|o-;H2{j<Kw`cI6Vnrfxkn<tKnExSx|cOsC&Y3D!_5RgX-Xmmn39< zS%BUXHGL8JE<*sQq12JFgp~K$0a(=Ad7d2D|L7P~$>fO!K-o-0x@~+xxAE}_pzM)| zR$mtUqs8ZPzkHaD!$LRG&G5^b=mRQI$q3*He9t^=TNg5rL|j!h-#5DP=UTq2K}Nk` z-kuSR=5l1hy?kGN3+g<u>la|xOcRLg5E<-6+`NpbIs+Q7zrZX%fL9#~jA}kf_v<It z2Je>{Pl^q+D`?qx714WuIF`7CfmUhY`5)&>x5$B4IrJA=9;Pl@Azpd!sT<dqd0M4+ z;M?{5E<zo`vrYy8>)Rv#X~)@*XCTo;w9NbfYNGS#H)h}a$tOS%D~~Dt==da-=adG5 z;t_#tFOgddPFwHlKA^ziHoTvu`DM(0eFez2kT&bQ4V!4&VF*=s?xj588j&BKnJEpt z95v?dMT|0-!0!SRcgE`N|2k*-J3Q9`S+anUME-1h^aeq2mkZkW2?rsVfuo$IzLN>j zrpCkYGxcD`Yu}-yBohJ(#4J<Lq$um4`xWp1_9vkS0q?U5IFkuzQ=TQSe1=IE2*&<_ zs0GPp5;Ecfkr}na2(SKmZPus+0E^)+6+Gv|mcr1A1|x-?-$7L$e`d|L)M{_P9vc4X zP5*)`{bCX39KajkN%dSl(};pdv&0?75&;hX`i|q1WZHw8NiodAghh3x9X}ut>*mcW zH@>f&P6p}Fg0PhDIHqZ>VBoip8bNK=r+R%M0fJ`%JKJ;6ZxF!fY@}HSDg0g4PQud` z`TXmkkU>&BfH{WinzQ<Gn`y^dwKBp4i2YgtAxbdLpvBG{x{G3dAg<`GNTJ-dXGM{j zZV<o;XgwnWrge(BRSYb-6@+$eLb<K4`3kxXpt5$roo5L{>Uq<|h#P=7%qLu@#h~mq z$X#TTV(UW~{YA>;<l<y0lnxV(7X|X56SRnTTRE2&&hZICK(#`75q`q(Hq!YCZAw?e zMXdST86`CkYy>Vg((##e<z<}e-56#edUe6pz;dRQ?RI%43%Sp+deDp{`6MNS;X&(W zKvqm5sHFD%5F-}tqW<vgR2APCxRhdu9b}!BQ&Qs<dl4oz&$6qPsCDJz*)b3_Gad>I z$(9%0g8Q5>P>evYuLd6}Np#Q%ApkSncK%$u3MQ@gy~fY4ZRT)^236xbnDAhLr0qv_ z&YIqxzQ>HvYcad1xs~ChJiGr3#JRO!czteTQYy><c<q}8i7CIwH^_}i6@B#EXM2Dk zNk_!k^N<vWJPpOBi$PjL?wf{0y%&ju2`Q0EbAi}OfVtaBCP4@Bg#(do5apMlWhomO z)wn+UZSzn@dM{GMNk;+zjks#g0(TSKt10--ow7@y4w@=Pdx&a@myraIxHy_J0ZQot z&>?idzL+3WHAyfHHJwRKJ5oS$Z8>Kt_3T<Hh@&lF>{idgFZ_4gmQ1_ff^@txt+qYn z68%TP9iC*k)#HrRBi=S3A|cMbr0~}6xlN6!rrF15^m=}x3s=i#c@8155nasY39~1U zEMKPXJ7X8uWy6Ea?79CTLbPpy%V97A=~6n}d1fP>9F#dY)A+g=Ur}~-+JNoBH=%tG z`cu@5w6Z5!Ufkgr4U~hSu!B6AF=rzmBD7g~Fwh(@_L9dO6{qKmj93Yj)o@Na;SwmZ zXhMV;J-GH5sW@aRYKHept+@UMMZhppK@vb-g>$xquJcS$O0!*3k5X;IVkr#+bD`<( zqnC4Gibp$u0DYq?f@Ss}&s3F2oL)nsG|hR~U+32WJ#zntulEk5x_|%2C8VPwkrFvg zE0m<Nk0_D74~I%+g_2{BI=BlNl~H8xUAAN0bw}IY94g5^vNyl$dFsC3>-YWqb^p^{ zuk(66$8}wgHE9^#9C_i&le*pAVBSHIY2_S0)nRIZcq<k8ZnVDiKv2qxr#9X9_+<F^ zC|*0{A2iF&kyu1ufVWx`R9rXYSAY5fXTzKN&9%w0!`%%=4yJ$3z{CX!QeGTlZZ5yK z&WgW}m!!0p{V@W9JJByzg4ev60diyQf`Ql-SP;(j3?fq288DS%Nh><kSf|aoUz^3Z zNOv<^2#oZk-Z3eFVL%qx)3}#@IBz&E2@Er$b}mb+Q-zH038Z4Ex?gWDu3obNzoPUF z=i9C%x4NG5j6r#g`@xneyHhuRSC(IpINa3C=L(==b2o$25iCOk$d`4EzUs;*;nNmd zG3VcQPQys8{IUQ@t?}PgD)YW_q#@9(uj<=RBs6hZVQ*T6wdU$#QpBfsD``QyOegx< z$7HP9<UnbPc4M;J3gz?2Vg+14)Dn1Y#pkCtL;>LZ+{5}=N%ll$ZJ4G=UTbk|C9GZ1 zgssh9^33j_qv_qKog6v0(hGc#ik=ZLNTR(VDZ!>XJ&}7K?mXVLJ9P$Konw+3`<(6k zie9n~ToW?19->Eta+*D#{}9xOV%j+U-LN-_HK*1}R=q68<xcS;o}33OquR5SK{R*l z^~hEf?9qFbf{`YgC#x!pd;}+<38wsZx0u&r#Eo3+C;9s`6$=4EYx#5>``1clQil(Y z0Ry7a6e#`VMGl?}F24BsTnEs&yTGYBSpugrxu+UzG}=Fdix&>#h9;boW-q&oZ7Z-! zSBJ!&@M}6xKFMLcR4}Ohq7aP`dXg5T!N<4Kqju#Eqjj}Ye7=D$s&2=s)juW~6uzSN zb1+oFng<U4idL?swxQe0k9l6Xd<^jV$mzOlsUxrM3WD(}+M@m{pPAYoIzsJHj0nBD zCkH_6d}m+5C9SO7m%dKKdqT26^(U}cEhQ_cD{M-k0y|FCZ6ypK`DH9jXi8l2o!*nM z!5apE3iA$@4TQ|ZZBk-^%h*-#-cEn$hk3K5d5G4@3waN)Dq|OVj@jMU(@wE_EEHVi z)x6x?)`Pj%DjQNi*!tOJ9NVXzyuo?*^%ItwiEAQA%Df`Jv08eJ;|;^uQc-`~8QJQ~ zY$*yuV7lX2>IFDX_mpcTv?cfJs9U>XWH|w&+*_p<Lt>*MDv7E<qpuS5c?wKbF930= z&b0T}Ah%N1lXN*9uA#oFMVwYvL&v(N#S2^c5naPu;3gp#FSdsvvrT8bV9fO`E6LL) zH+w-(A$7Ob-}_Ffdyn<GeZ99VNgC&ONDU{j@2j2Gi6V~r=<-{3Ur`#lrWhc1w{_&M z+7ai=pInhw@V!akNB&sm)Syi<B?MBVlUGuY`Kr+S1KUwMVbgtI!_mNy#EsP<`HJeb zR46j?9B~v^WbR7P9*v(JQ#CFwn96kA2-nrP9kC*(uOS0`<G!lq%%CV(LJh>vNp2%T zror34w5*Kvra<juFTV~oXH;jXZC`f{!S$<uo`WaBc+7A|W`hsmR8A1jtW5FUwsn)W z;nSd5Bc5J^(}#>X^joPmT<8Ns9jYv_9+5?r%TE9HD6@SPHTtOmV8o?-Q|gb7yPw@d zX&gEJQ5)nzZLeir<)X}hTb5ZCwf5YsUo^6K6{rsOJt@?xHs0rWdO?QiiiI5p^U9Cb z4e2nNqN^pv4XuuEB0*LTu6!wZ2Kx7hLN8<+BxdpJDIDx}vEF-%P_;`?#SMl?YNm~e zYk`Wv(9w`rVC324KY=-3WImng(E(*}#gyOSu4%u$3?qvd-Y$;TX%yvmF!I8Hk$XcW z*K2j)WG?IWiLYC5QfAGyT-Aslv)_C1%B0ySGbxPa3?36887QTdua~Lw!7w^~6jV9| z@?eezU3XC>cc=P3iBoH)MOKfb6B}n0)6<f>5`LtN8WMc&dG3~BYoBPQPxRbMTD|`7 z18P5kpXY+1u6EV^)aN>|o$KlF9{kD$LSh!1a;|3aq?Yh5pIZaqw_VowF1>xpUA`ts zk#nz2`8q(86)W#E9uI)Qxr;AfHoY<>fS1^+ZExHfZP@QK5v4!%v%zP*WqY_Mq7mkc z=H1jy4Sp@?zdh@4lehMjH^8tMrzx0)F)Df^Nw-;A*NWvdhw5Vq@k>B1d=LY=zAOIA z{rvzQ=YRyzem{`pvM%X-?A|ZyUN)uH#$VGO?;V;HxR+3#GsEd6r{6e^L_)GO+F1Oe z#l+%fJ3}R)!jjw0`H~;#rbchbH#%SBny?1uQJU)6Ts8eN<*${w63gbB1Z2v8_Uwq; z$a(|%elX&i^(M37uG|mV%uy`?a_{20CU0XAha$}m?>>j%q?%E2J+6n~hI{siC{NP~ zKT-F_vNNN2y%qfl7YCU2xl|@-DRQ0LwqK@GR{qQea>h|-S%x)^Dt9NY=K>5(9;31( zc9Bp~D=ijYUftoRS73OT7o^L0L25@+!N^m^6(<lPQ)iTCn*EQ%VB2x%08CMeR#t5W zR}lN7A+;fWg{*Sn-oy5Ea`-OZx5Imepf+-OyBB|&Ki;#zM9jUqPmPOiL~$o?g|+;1 zQ4;n$eMqEYlCO&$)|cPqS%Q+un!C;B7|;_H`D!sf&~SHpoVY7U;34NMunav)U%!OW zf=k;Uia1`0;e4vCR9GnY8y@CtD?HeF|7OGjR6w4_15&W%D?;@SVDzT)CLap1dS=lz zeW@3}{O8?R@(ykJ+4Z(EXzpTHG?q8>WYa6=no1mfIE*o4Jdo+hs(&$Q@`cZ-oQ&cJ zU{AC+>qR--1XULT1-CV=u4TK-x%+e}bBS3;_tzE+9VZ#GXS1K@JS69TA}b|8wxqr7 zleb}J012C`Ry+;Be~?F<=E^rjPNWzxKCIiq92cKa8{T&)0xJ+P$ddIAtMYb-R9ds8 zzSwrWGvhhD!*ccu)vuxZTijchgO;cM_<OUj&Ga|ZW6eQAT+r;T_?B*J-q-z7F8KeP zZ?9ImqGl|LZLDREHc#5`r)m=SB6ElC(ByRrpN*__*Fe)yTlqcF4+3K=yBH2|-74Z> zx0`LXBWY-eD--C4h0dh*lj%iUaA9>Po9opLd9$QhVrTW<)JgY1$NQavxv$8V+tE4Q zQM2CW!GwG=aoz#j{igrT;<c#C;Cc^S9K(HTgy}b97JCH_LpO>cxMdm4B~3mQUDQqu z(iBlHX4Q&c9aU5|%pXk>ZK~FxJb@ChfuNFLuOhJ{gKXVo;Xc{<^XN{3V9w-={^%o- z_4}?a$l}eae!!XIyg=-k#MGzvKkUaJHDh!7Yx`-}g}{p2O&%GHo?&?@ZSGB$;Ml(O zF=;{X_yE^uO-k>3V8Op^S=LhHuM&;86R8&|mT}M*o1(cPOy|$f<=r#-;S_QOb!PKh z#j*LB{@J9X(%OAaot1d?(N@*?;*;83TiMUErBHVlJwfv_f(x4}Il0kBnLzYYHso0R z+mU5j8w{k(R~3fA2l3q)6n5TN2_VFm;k3lbcvC`?)lDWsz_=lKlRsz!wZCrJ19YqQ zW9f13Sql%!?_OA8onyNNXmXk8w<0mXfy$}mv0e${{WN<`4l4mR9p=Qfbj1`sXuV%v ze^GoXtgd(Ke1w=(dq+Wb_UR_O;;Wcuhx760&}WG{mc;UYc0bulM1^zzsJFV|etrze z>3V^EwucNcVAnD376q_JYL2ZF1riKUV}V4fV_c0TC9EdVY6gcIJCOB(3k2<5=)KC% z+oJa@Y%4iXi}Qi^t~X$svT^N_m*tokc(=R}1{}g$yT20t19JGQP5Rw%M(Mrh;JLg@ z;2L~>_PJ;I7IQQZ8MvbkS>-2W+ZsHzZl1n|F_uVc1Pj&)vfLA>l{<<BIu_da{ye*P zdoz6a*E{0zTQcv{7yD@|5P=ix9?GHXv*8|04%>yG8F#o?)wYvbuRoh7W_@ASVNN3+ zfZYbCp~7b{OmJzK8Cl|PP-zvbsXNciBuO6Dn0%zl7XD$HaVNtd7b+>^JXh>sBkcV9 z`1w!`6X_IBPIGG~_Vg!_heFQ0j{TH5d`+4E26<wkhhWxCXUz|wcmr8@GYD392dJvy z88(ev1TDgfX8l6m*VUv~*{3oVzQ2F+k%wU<f%O3fT*U%J8=<uEHC5a1Q_0taZ2+13 z`w#;uj4_9^mHem)*nPyLvAk;?)pI(QH)(?~-8H@8t0!W)o`XKC1SSSt1;Z{z$>+Co z-340E*kP}lxn8&uJAn~njVwkMcDx77P$YdnYb&AHT^J;D-=W=c-fV(w5kFt>6*tVq zw|O1C2>nH!X7h9wF=ANO$s8A)@liHcctUp$KR1wn=U~-^EQ&F|$^UZ=IMJs)d3m4D zyE8_|S;|e%aL218IaT88j2@}I9~m~TUGVMR0h$sR8*&F=1$1%vgAaH5DeB_E`26k- zntSng^G6eghog=#W1JZoIHb^vspiM*$|H{oIjEipHopUOfAZ~na8Jlf!)%0LXo)!q zaO~+x;~%g0$Wlw4_5x99MJ`LY$w^?(S!4rHdp`Ppov4mWgIsKsKu#8zP*%JHr&v+p zmpsvyuoLUgw$?t6TY!43ZaWEp$_etV7I7=N?oc^s_N43j!NI1v$TqLMP9&!O&TJ`A zT1y~IV4(~M{`{iAd~8_}mTC3?YV(o*_iN!u=!H3gbMr-h7!?UW%=@a>m6^RN2Ld6L zVrJEa!_ow9%ZrJj{o*P<M0w1BSmN<o7Sh$tSo3NCjew@~O9Ygpbigm<BMb@d0F$fL z@w|vJZDhYSzHS}3q4go6slKgJDqJ2TNyP<PuF1!bJVP$dOIF?^%}e*qVloCR+cWXA z=><Fi;g(BbF-6<AXt_>Ll&Z7&Dg9lUX_z9avNL|v{Xh%o=0=3h5TD$Fv&;mz6n1YO z?4)MB7H}e@i5@J#jp_7nA^V=IW?{kwz(rHdi2eiIbVTM+x~Irc{J3eM3fli8b$Oe@ z2;F~d7LZw*?=cY86)D7T)fIS^H0h5w$et@6H6>0}iC)?SbI#PTjN<!wb-MBtL(|*- zr%$;cx5&I~W};zYUUO@(U!*)H*P#B)z_v+)#WOhE0WG%hV|3GlYPA0V;0uf@MUG=& z<>2Me8vLv-dTUTf196j)^>vWY^%W*te|mc2c8A&vz$a@xBr%V?gP<<1UMnHmy8+_d z1K6oOfK)}O!ga?H(^Zj;4Z`)QPt_@O4dCO$UUmFHDY_4dI}_Jaw!m$-{KCM+w%i7$ z?bPoozFjbT>6o*W1F}o$YUX@tY(th|K9z#u;};NMSjX09z616wu;M^B2p2OJ3q(aW zPEg|=GvvBXCw{Ky7ThzSZ9!fNZ<%Z+5?OM<*=IL)bjL&XiGQ=H38)rRki1>Q@feV~ zife`u%)sm|s?gCIpnm7}mqmnH-aDU8%mWdoV*3-O^S@?|7=k40F?eaMG%)fKoc^6u z-33K*^j-lDu<*Ehvsscy;p_X-{*wB!R!Wq6r#ABQ$=G-Nzx{mtUSb~EK^Lp!<(EBu z8ThhDSk^HZhG#-*b9<RM(}Z9xn9?Iv6HV=5poYmVs>Iui_;4&sHT<~8$S?2!1#3t- zk6WGYb4_+>7zc5I<L5W`6cLL1?x@{gn`now16URnPiy`5>(O8RAHSZzU&O(+gtn|3 z_0P}FL*3LPzdpr!`gkWy@h74g^S~z8<Ho$zGlXa_3sF!Z4!}%a{}dpj{puaR{BXLk z*Ju7D?cz|{4lpV*o*_6cQyk&|{7VcG+jI??y<`8`FS#r=`cY|-`?H1(DbYe}L>}5g z`N!|*upu`FD+O)NBk#uL+hT|(c{F3|7et?cmOqxoPj7FcXqUw0&Im&@YZ%GuTPY80 zSlwEHnR*v!t87qs1|Tn92zD$(Mn}IDkkUf?Qf}@yx<w+vWbS`#oF7@;3m8U$E7zWs ze5J#%*4WX#<0;8F(6UE5OG#_cSBRta+j&Ypc!Kq#X3Q4!s4Ujel6IpXV3@+IYTcgm ztk|mQHH<(k;e;!O_QVJ#tCXh-`28YLw2^i2>rRDg^Z;zWv<H9#vjj%-CP?$;PLJ98 zuXnU)w^`xG3+3%-JGl7aY^;;*J0zGIK=CmFql^L=dXR-*x1H*d-&oQdYe^3slN4=H zp3Gk8@RX4MY&g^5XysO9ikFjTXm-4yj8^Rf9F*oq(i)7b+=(6HPQW_v(@QuG96Y*$ zi)ho_@0X;zw!@_L*w4SP#L~2NESCuWyAT(${0B6-095;(z!N4c+{9Q)XuJWz;-i;f zWV$lCc8c$_=1kjaF%RumirE|py9VpPcMn<zBdw}4G^^oF{wND3Or3Uwt(I)U-sw!b z@krk4xezBu<uRC)A!LYYdq>-sn$_tb#CAV=>1o(h(n8yctz2~ckL)Gevqdu6`%{j^ zY}w882JL!PmyaT)oiPs8BjC<Yi!A!Jx_-a8Tsm$xQxOL=n+NQ$7>)E9#Ydy<pgqV- zI{2UOO3CZ)^gmxEP*X%4CT1GaaCH%EFC{eo&pXmnGW+L^)|TG-s^|d;G&jKu2So|} zpMUz7oc7o5-0$5(7k2ih_MJwc#a5YcYFc2BfR-pY#3I@cg}oIbSG$PGqg_RNo4>L) zejhSlOSjWK`)l{9x0T>*j1;o&3qpNR4Nbtb<t38mti1f_0u^p2@@A%d)a;UZ@de9- zcwDqFj^8`+_q+Oh0tf+08bIH2^ji9G@Sj)wE6U^FcEj^`H?@Z#U<Qrck@cJbh*}JB zG-YlloIf_G7%cSyl)V(;Q4}h`rDOE!EpUR{!;T1+R{w2G6p84Q?cj^rfxiJ_1L_Iw zF>ZY<Ku!MCvuGrUf~Tl2!N<-B_>#G>tEp}@2Y9uUAmX;|F3Lnr4Dx2l)=vI|09>cM zg1<^{eC7tt-AeB?515oX!-d-eP!pIT!J$SoJTf^Qy@Bvhq;UylG-0SUsqWm3%aUkX z9s8GT_WA|egMt$?hT;FLhhI@!|Gsn&zEsv{OS=3G4Z~sL+l5B)NbQBh$kZv=F-DM8 z(Q6k^&!T@>6$TkF@v{-V<p$I!%GiMVKF}(ma1c?aXJ>9BgTa2}$b_yR556Xiab%lB z$gwttQ)I}j5E3c?S^6IrqP}eQmKh|slZNt#V)uCgW(uVMEuf4fQ)VIxMA~_Q=L$l5 z237>vdZ2JZmTpv8ZpoX&^dkOpS&L@?s+mAm^r6Av)F(0nhGE}C<J&W9_RsNnmB4nK zG-_~n5CJ65r1y^M$|~oP|6^IG+|+J!zmWJD@RCZw8))`Sfq#<fEQAYt9SMXF@(Q~{ zcWRWG4afvx^oou}0!uWydRMvwWMQLGOI88wvG4x#-e$_0Q-zr>Hn~Ii`&8!KlSp;k zCjc47_VWP`cp;<wx;7gv4GNA;Lh6J5q>CKP+o2q$>|nyNS9rd{W`KY;kJt*@`(CeS za$aPFe90|+-{m6THI&aB?Nf5?j+ufeobt2;wg3LCM+T6$6Q#!(o}Ba~!L_B;E}Co! zC;dc7Qu~SS+k$L6DIpUW^$2zw*~7rj;wW0A^e(lE^nld&GVsF-fy($XX8ArEjH4pU zWhF$K+Nr%Xg*tivYu+x-BMdlHAc4z3Sq}~`h9+DUvEws_3?jP!$D{3H$gC(*f_@Xw zDAAn^G}U#9Sf2z@-la*ItNiDY66EwQdqMgoz*=QJa{8)P5BUVuAb}x!Um371Y4`d3 zqq=VaskiS+L_V5CTE2KgN}2WEHuA;htt8O7h$A<v3f`0x&x)!Kqn8C|#=9StcTE9< z`JY2W>1xn2FeC6#q&Pp+J%s2plrrRx7@U|Kc^t>x!%x9x0H<4Y+g2U51n`;aYR@B# zQEmBwB{vN|IcZQB%cfs?_D%f+vZU~6KqL*gRle@;Sd_zMJ#BN92SIU+?b#I3ZcqH~ zsvAH%1PR*9k6hbG$eIoq6J`NgHi!wiEddUSvX%F8KFW>a*VQD47{Am1a^#?+>q@aZ zbNBUM4*TfD`PohMVi&VLB!bnGzgVJhsZ*c8k^b9$!?46%KK@5Wuc{vit?Rsa8cc!D zjHXS1SK1wmNdX4!1=}o!IcxObNiW@7b7M%nBDUh*Y>4VuaUu+b=ivu=fIvf?!_<UG zjS4K3(H{(Eokh)S!veBm1pbO05U-pEj*Ki}ZX=-NblT%SVM*pd0s;mwPk<U)p<o5n zYMSfQLqWe5yNmNn!isRq6r2^qaw&l}xTNsk69@lQ<o&uv9(5&o15-6Gq5;4esv=u) zpZ4*C5Lx7WCBXT(`=zh7P?*O#vmLfMp<8UD&-Gxqs&%5bxBO1kg&>!!sf-6OM)Q!n zu~3P$>gvM5d<+zb1}OoR5jklPDxBzrZH4CEOSS5{Dya?mb8I~6mhZw2IHT-`NNK#i zEY;Al4!SJ#ag^fEy$bD9i#I2HMyyB=i6vM`__Ukv(Mn<iI%{HuToAdzb1=eCm4m=R z2W7%Pg(2-aQnCrkGLRb0Qs><C67fBtE9*TGsp*!X-vpkP1NHozSz5CujfV%e;B2<1 zED5%%Dv89+?)4>nUn;VP>FEI3H;C6kz@T7orsGbvDP#QS%`7{vvYpaqA?-e9^hJGB z5=6f!kZ1SBN?1P*=9BM3dLAfo90#6`E~p3^7nwP|jCH?d1i_nQnYf|L+G+nRq5C2> zanPy>#Qf*wpg;!XmVLqHVt{#T@?W$x01HONOebNpcfiEq_~)X3N;c|&1CTuu4Pb~3 zX{y0`CTv$Me_zcI{Fnhiex8R`4G$!H{7#7q%Y%7uYp`-wkdQzs7x6O%U7EaQ?p|6b zi040^P3WN5?<4x3sK-=d?uZ(Yhj~sFH_iem%9!*3%Y3&8e9}PD8lzKs9gUO+f)1Vy zzUYedfz%lerp)VFt)XXWjqUI9K>7Rc8blo^{(O*aWfB5cod`H%fbdSAOb0?x4&7|d zwUXJ>#@N=E78ghf9KV!zNQ4B8ElZ$k7Qi*&9=cnU*K(v&+^lKgm~%JU?p5px)y=Ry z!}i|P-s$%HRU|+8iSP-q42ORqTG}PAg7+90$SlO^cg~)L5i+5}ZUo?T8&oQwg(_HF zq#DJvQ!Es2o-SZ)-atZ+g-OV4^%%=7?X^SP4mud~)r9Y6Mz;+EPVko<6f(EH2`zb^ zei-?_u#;4~6?C})lX^)>6KjZcKzq8$z5n@iPeNhz2oVmDKkAwaPA7eZm?$|Pz?E<2 zSIrk7XbXlC=eTk*6k#{b7lNe0z2R656bTd!sIn%_y0-C3wXQj=PU2w#l>@jfRT5EO z?n0EFcK{dj(%Wq+8o0(Q_jzx?p%G_0Ck~v!(%>KxaCd6gG-@N^j(5+e3u~D5V4}Om zWb&_S6yhkqM_oon9ja-T4RQ0p%Oo#knpHuPM|Yb?%5j;c?@vnLoppl5wo0&8;#M)9 zDHaS{kn{H-7fy=`EL|+j^^oNfDWO&QEVF8=K3ncR_8?U?BFB!kv`uu+UhU?56!m*Y z{fC?9|8EHAqt#My2}P)H@5YJ!Yv%G$bntSrF7uf~&1R6U!3#9J$T2y4IE|?%&JKp_ z_AXcbe9ba(ck_;0xX0@kn$tD;koXoHbK7J!Ef^1Dx<GVJZ7)sBOqv4qMBnW}w*ssR zW&AmKhS;yWPaqnA#nP$We<9K>*a^NsR0ufxsA<WE!TuABrKf}9(j!wDaG3#)Y=__D z8JoBT<ai6wg*uO*toB|h(P@@V+CQwkMi+k~<_{Da6*W-86+k8Q<7U&e^}Za7%Y=7` zGtc|>GpBluHJ!qZ7s~(IB*3<>94R*d{`$AbVqng|)v6P=`D}J-c)KQyfT{!okoFls zSgh@D9SY-Ba+V?CU8bVqteJZV`EJV{RQ)NIK}ILC*P+2<o3Hr*QKbYHLD_*G<nFw# zxxAj~I1W}O>0?P$C^K%&fP9o2s>_&oa+z+F^Rg)-I^iB$RU@Yy6DEHR<gL@9tplv@ zsWe@I@LOs~%~NX)EJL8RI&ygoAEc`pu1*_D%GiQSEygrE$F(Z}g4=Jdi5luEQ0&YD zwWkMm7;>RuP~7`1-;!_~!2)F##)w`hXNjm;Ia6|{`kq$rTIMNN_{d22Zd*ylgUa7W z=C5p34)$ZfV!WX2XiUQDcXAwL<i~45hgNm^$V)IWE!!<cZf-pNZ=x0|fLNRVSkc2J zS|h981&fM5g18D|z2>`6o$s*_m^m1>?jlt#0&_<F7<aEQvWSjw3aT%$0%bA}LU-fn z4jTty85P#$+T?F&olfp<zftHk*8cf(Pfh-s-~1_ZY*5mEhKorCxFROiOI(ds@{928 z%Rl(=%JTvYpBGUWa%Zcb__?>`*Uy?~SmA%b(B&_JYwEz@mnnDU=1K1VIwBfyTF2?8 zBlwwh40-&mpmwqMf`_#PPvzD*KXU8?2x;5z_I;;|$>g95<4}v#f(Z|rR-P+Ce=7a< z(^*QhM|Q0ij8-ED!L`(h^P;yl%TZbL#0Viqq6Zq4Ej@sV=H0^>5@}OdgZzy$ICs>F zKD|HR<S9lTK3K{#DmMn5cLAEL6Hi750g1X4(<})eG{8E3w@gTzx5nGE7(b`+bJ*~` zc%R?D3WnUTkYNSP)12ZDaSfNoYW`mVd*Ob{{g2dH>tAfFxjpMKaOiyTis1K7a?i8# zxe~O?XvvvvbGV@#nD?TwW@CM8Y7Zon*+QJ@)6=Pk=T7C_z6-nR1{kqE8xxi_fC8E# z#lFT0gzPW&D@FCh!TdMyRyro2H*i4QNtgVmdG@UyD~9f4B^v~|in%LPBJPo;WKj8Q zb%8BBo5DB<NB|wO=LZCL{lq!t#uCE4Fb4#y9vKFfSky_w+AU!J9%RR<WSh`D(s`us zc24yqcg-UOfs?JORmX-{GF1n^WfwGx%foqTFY^hi*uhIt?aOvUPjV+kC8aHs>^$t_ z?7W=w?A&gI2*<?7sV5#jwj46-QFyb_r(&(#+ed2sUBpYW)|rfm^XTq8*uUfI-RTeM z*o-11a^UDky)qC_0zC%5n6FQB8J6b>=fK5^s@k}U3Ehre+)qH=BS)=X=K`=>3a7rC zA=Z5~(-}cC3xPDF&ML4AFt=fY1gw)>MvR$9Xy!mL=>X#LPTFmkfS^ldV8a{U@@`rr zVo0r{N}Pk`e%K777y4l(lSNEI6u6)aMsFXxr*&hvvjqL}>Ck|a>Kh9PeIUF^HNc@Q zTr=reuoUZGvQ{$ECyU)aq)~8|?~>CHmYdH7c=dVuY+)B$RS!)UxLtnau;qk;+u%7i z32=5xK{Iy&x!fouq1ej*{EOml!Yc_73!PTTtJ`SWFr3{0E4Bid<s~Ngn)r)yUotFJ z?hj~&z?P-7#*35rxSIpHJwD*<FKXKCsedJrI;NL+8@Ug^1*M*Z!J|my2-~cmjTe6c z$?;{f<72D<*c;J(hio5pw|L`6xUiBDXh;N`2+yguKA<qm?*ezIa9xYPb~3EJazJ1I zyN+zg5jLUtf;h1hp-+GcJCv8GH%&^%-yA>HUqVq82o^u%@>t!?BV}bRQ$Mc$9I=|^ z8hddw?KJz|gWINM1}WL8hjjU!N7F7D_AmzRn4j(%?<ypW@x>}FZ}dR*?|Fgwd&~Q5 z5+CC!_q@Ea_E&kDG&?G~l)U~~RBuaOd6y>4y#O|-Tr$>jnCDJMa>60m0neMMhTSN3 z@8#R|;MXr})_(->CerZ{?ju|!Ppvg@cN<patFIz6;Xv-xu2vmGL-p*zF6g#Kgg$fh zt--dTp743dND8_-vi~hRbA)<YJs0}{<_~sb9-oddD|S7Xet+JD???SPr~2%*n0X6@ zquRp3?>_#xr(DhZhHem|sp91vAOOWwo9hO;L}bA;t1o#;-D_{QaB(x<DD#^_gZ62= z>xrsoY8bVxi;e+DvlymNU>cO}YhNXa;k3O1t#(+R=?;>T1toK(5x5fksRnPZ1mf9J zUf}M9%#V?=10d=wMxZ77NbEhg2-lJ(%IXfmdmIW8&f?q#UN~~on;oL&&O|B*$Uc)Y zS4jb%odIJepIxaDa8r8Z3!P^R-wWvl=h*zjyZUY>dCh!MSlHKUL?F9LaJ>~&@=iA3 zMrBKor}TqOC`Ie6*E$?Lk$X;WLHZ%O=7=#|SjKA;P=H7c!<2bC?S?s!IsIA4i|076 zY=G%c4qUwUCSG8OR7Om|OrgwEyL_MZCCk$f)?pw!8j_7Hz~CB<MpRVl2b)~J;vf3h zl!b>^Z)x`p7||!T`rWPuEfm}ALd^yR#Su@Mxigc*2YmXUUN>=g_JgunCmn0`^AO)H zQIghweFi;bGF!i0<8y?ZfCTM%fyg!qtZCu^ll5vsV8&vIB3sH_*2|qv`m?~Qwt=a~ zZAx`k_H#XfpWvquYNEMpjw&nas7>*Ba|vORx47}3?%S6Pim4xGmlSi9aE;H;-Wf-A zSMHY&B&@(mlr#!lJ0_b{T3P<C)OSxpB}C+`0NdO&^-dNiw}Kq7Tf_1o{8=gDD-s#O z&_i;J%ZbCCEybW2!%-v)-?fS&B|0|sm_8ng{U+jH*;LoIQ@KD{_++zR+vZX1$X$|x zK=q~kAtMOuKt5RLR-80jh8F`RF-kMMnebnq4jITA!NEhhxLfN1v>qwKKts`{O9@lF z7ba9&m>TAbW!!?<*;*U(ItB$MAG-1y`6PYB2G2+U%3=ZzG-E;<Gl8l`I}H?YSUnx1 zu`Vt#W}QDXCrhha;GYcN3+boAq=c(vg>x1wXg~)j%dqITGSF=20%tsLtmF6xeM7=^ z7YZ>7d5<BNaX5L27EHD`Uny2x_QPA#CdAVdSSA56Kxv?Zwt@e#7>dy{Q64?f>cy** z+Sm<1+f>lyn1rz>?o3zhq%j%)($Bz!wWs2LTFFvjN{GxZCm%IuPJ5t?_Nq6~!d`~5 zt_Wm>DB^)Y>jFoPijKpJ%rNR4I}0=oaK7z?wJ|{v-bYIK1hi6PWm)ECImMMh<O@jL zVghEv(r~vCwC;e{stN3GMPURMBG)%(l&%gT5eVQxvTOLWsVjWLXK)`4ng8Q9`yFef zKt`mL%-W04NsdELRsh2-SKYs~(U0f>b0<3_=RoFQG10vsNU%Uz*}%O7@*Pnm7#S~s zt;ik98*3B3`Hf>-*T&9Bj^5LPp8;V>(4M0iGZixrW>Fuuk+9+V;0HUw+B%&ET^BGR zPa!W7lP!akv<QFv#;_~(gK)mny)aRpXV5aT__bn8KR%mW5&N$d{44uIJ2fWnd?kQw zxuDERbkTei&<yG%q!=L7W^0(vd{wRUWF=jLpwPUrmxx2H?|DBJ^cea%IpEBNOjeMk zTXUAxMSkYTsJGLX+zxG>|L)})>pp)T4V98mi)3zQ|Ef3(c;-+TNB*D)L#EEJ&v61i zhr-uD(WEXo_QnAPs(-fj8cc+HAqpxD6sTM-ISCsVs_*0e<6^bGpO-DQrrPeBike10 z3!o~36GmkYYuWRVoAC;pmw@Zyp91qw>Pn*A2Zyq+fACUNGGYQvMet@s`7BXM@MNb7 znQ<}=7AP{qrtOhh*B*QYljra1pK}zqk@Q}QyZ*df8r$y5pQ+WENjHpCuy13?xsP*V z&a8!kN^0meVPjF3^3i%P##ov6?RgP4jEC$N-vp4Gph-Q&XgAy$wEdGUz=Z3b6nfWQ zyY~w3$%y+QiJ@nI?CG$39->}EnEflkQ~BRZ#3-hPmWAq~X*gTRn`4p19QCaD?Ss1_ z1EuaUO~Zr;6ELsK|NIuoMeJnj_6QA6G4MC&aKEtm+l|L0`q;9pF=2hjF{P4&qD70~ zg{)&Apa=27|2iNq89EM~W1EEzr5kRQDv#8bW$hrIx%WO0vgoG!ME6T_yTY=F;I?MF z2tB4xtRd%8rbtEWPTQg#?kP!)opt5O?y;%bZ8DYC05ZUZ9%U}VcY2=qI&0=Wu^`VK zejmtjf3a;NiB|qp^nfO<$^%NEa3iS|akOUpw%}$?M~hrsOFFcchE%D@4fCX2-8cB` zRQ%eF*Q-l2lujIS2wsWLxE>Y)!7WF>bN{_+{eAafV_;hRJx{OYV!6g2a*JO!kAb~~ z^cBNWo~%FjfPhlE3$cZ>Gd>IoNB$-Eax(_>!kB<Mc56s!g%^fY$1a?uLO)x-saQl> zZ9EmkVDy@@>_yP5CrrqsFc-9Wd9xEer$@HlA>+d0kcXf9LIHm)n<i)f-v@g#&J?CU zQa^MXn^CGc=kT)qu&RmOePZv^Jg163b_H*K(eJ%d9>}|<0kyUT*gJUi>5r!r#`(T| zxm=0we`SI9KMp5A;aJ=d;%c{WTm!*-ko~?zs8T9E6i<J6tB{d1c6OULn*?NVWrM3j zU41NEIBJ&W=h^%UKCED^7KI9D_@BwvU{e)Tdh(!A!Gn;f3c}gE?)#i5DCv2YBszw! zVJ=bYjm#6ij#a5%2mjtdEKr(CW;UPu8j^S3KslV;-*_=d<2afo<SDk&rAxijwoL#Y z{*cqjo)?<qcL7F+teagQz>O!1p^dKSmGBhju?*qTOZtk!0vTW`Rne)qVn(=`_@w=& zZtb&;6;*?PNPD0J|5?;mAVOi&e5(jP<jfJJ%Kl>Jz~S<V&!H#0^%krAN#b>UcR)1Z zVicY!Gp5Xm0G4&s(p>DtT$0nLXa`EwuU7_~ZlQ+RZZQ8WoA^WX?F5LeLp}2FY@l7` zx9G|A#LyO90&vp@5tp>*?xpv&PzvU>m#-V7IL%*20p2+bxUs<M(v}Xcjn5K{xS>nO zL@&}Gm>8SeOO$zj%v3W%RG>*&3Yc+rx4<V_B%d6vzwi<9_PJ!nd~_o%A_Gw$rzt)2 zYj~TGeb`AneU~jEI44kmQBkVAafcIhwxWld1O5=oaI6Zj>*RM<NQC?5K$EK&SWzJ( zlaA{~VdjD+k?m|#0s?0Mts;~fX1!~xHeC63lf@uz>4^3bJglqh+o$xbvm-f|Yb=vi zo_Ml=OIHRxflxqGq72-+-h#Bl<dnS-qOk_N)V!<wQ56Cq{IPR9G9lZUaLe9(kkdgk zngdG0q-@30>W(a<mPuV)ELr7AQ}P9xh><)ygRm}jwFRLOPv*a0AR)q<aDBQ`5X8Ws zn<CpEEUs!Jw?l;AY+zV@b<QPRBjmJEWAtYasj|7Q-Lak;NN%?3s&EhLY7Qe!Y*pU4 z|90pZ!LUfStYo+l#ct}<t~wOht2LFVYy_Eabk1K_&A>JOVRu7JR6;oVK8ww);le3d zT@obmDX4G}dJ#<lS&hW#c>ApM^p7J<ZcYQHrS(>9he0=yFKyUbt+BDM&3tgch;|_q z?P`d;S<mv0QR-Fo_s42EP+CwK%n2D14t>3Imbuk$K??2ZGM&3?``l0-Rv;=ri+SbE z4n$EAIQ(pX#retfDM?b%r0$VkK!L{91>;S(V!r9aw<uv3=>gBe%}D6m+g#z|Fll@w z;`AHcLFB1nT9zUD<Aabnj8WehBxE}p4%|Y9f>duAo2leT`DZB$Ez`prxf{XjQJnfs zrUoN9Ltk#^Y*g_|ScS3NbMpB4<rUQpx9lbKv`JExg3ThSgMh+pSFffw04er(<G+eb zf1RWWFpxR$tlNCiQIJ_@c$WiVgO)q^h%hq#5u`hUm$Xye($Dt!(J``$@N>z_x%!_z z!5F1}k>^;%+nUJeSn2oUnQk}C^Nw}z;fN5u6XeTC5p#+OT<2Rhe^~G7Qjy4n!+5RU zI%-7bbZ9wA^KE;opt7=+a3<mQnUhCcuPE-J@p2u^dd%i*3a`C?Tv_3&go>Y$`_DzX zo^yq<v|bPN340Ey^YzkHC0~fJ`-)cmd#7K;{anC)HLp;947ND}%5?Kp)gqAKVUs~g zvp<_Nq;989N1@#I>1>M~`qxUqj?o_F*Hl?Xg$J-{&KPo;AosTH@1j9af2@8pOvqML z&Q%BZqme3iOYY4ogtF_8+iM~Rz_a3x$d%UIOUf>|h&-qELi`jAkP$h20?yt%{T^_4 zeD2r?WZLg6Oo}Mvk>zq*lJ<;_ZE_&9FS@Z3CK_Sl89x;?<OukZL!-l14iky0gWk#T zp1pm%Zgi0nP)zl4>mkt!Z-M2?)9PY*m-wCoJNL!W7F?s4ZP4a;T#ef<dcF5PQ(`wZ zVk(BF_dbH*c(v|w4WsYg8Y}lSasV<j4dP<XjVb;BIDSOa)Cph6*ITt<3XVw+3TQ1< zuO`UQ4(Zu*^}kj%`Sm$N*X1qmrl6dw{I<h!&mo$B7_41LdhCOEisxS`E51TIPZFC) zw=hms50&Hf4&=_|7;tC()HG-f)=$C?L$i8^;B8&GtI7rJjwX<&%atcW`&;$RjIRm3 zX;Bul;Y?}Aao?5i8xqdVV7vfs+%EY0OL*`Xaxk<`-p!A*5uy6r(DxkM$nANC91@J9 zH=vuZY!T<Y+T<RxorG9vq%*~h9bUn0;ep3}vHj3Dj`nFPQ<#=Z?^H2#6r%jaI|On> zslYANu2Z}P`v$HH;w7gbN+3Sqv3vP+N=;{43^bI{;*7YeNRHCgy(J%FhTR<FjQdk- zBZhseuqwvGKI=D}d$tuCDCaLh?&D4$)1Q|YR$ZoMde&^_^SFjZy7ioHY0a7$s-LPT z$f$hr=S_7iovZbgDY$-T@v;{vHMKe}w@zy;P~R9CIPKVoSN=FuV_9&$)zXa?#2lZi z-ZWH`WEEEx6iFQ1U08o7$V6h~lx~Ncn85Tx(#po1$L)@r?hVpG)CQ66zKkQybIS4h z@naFnwKMbE1*1dzE{qw>G)gtfT&r_0^a$!xOALwBZCF}JYLGwKI1wWkN~Ts+TDjQ^ zM89=Wj>nC)vyvp;33($Yt)6XIIKS^m$Ke`7{!IDv<NWTL&SzUrIS&!8Fdt%`4&94- z!H$UnQT)5opbMy}it~Qg_4u>frt$=sGuWFlZv1)1tV#bVdGyl2mJyp8rxnfyu>MCb z*R;igl1Vxyw8Mld=Xh6v$p@9f6HO5k_i6j_`RsLf1Fp+9Ymag==%t(1jeIG#+qM_; zJcZ6ddcSs9<BKcjI`GC^v7h4Q`>W*4F1CI)NjoPK%$0(ny2j@hC2dRqj{9f<)LyNb z!g9gVx)siL9h^pC^n4p9vl*YR-zVozsvNb7wLTl?_G9ltPmK8Wz_odk=fadbMp9$O zx!)l@{IZ%PV=Nl01cU!o%wr?agxw>hMSvAHAQru6Slz|e8rpPjf{7=U^wQLRCx?Tq zWi**0_wB(UMdK|+%&Ny?y^Nn#{Goffg@}7k{mLPp5%KwT(u{?E0_!{p%Xl<8Z>2EM z+rcZ4Dy*cXa$r|gr1WT=UEldaPLsfMf%k93sGC^M-)WjGfnabG%cpj8)oK`p**MID zqGKNiOrN{W=@n81osUG`+<PiCC=if&Mcu&2k>u;O@!Dfo6`GulEOrPs>MVY18ORNi zyHDaP)@ZiWTAZ0I43wYwGpQr<Nb6~{r)l<Mtsh3SlWJyy+I{gVf{jg<;aio*a1Dk* z!i<-q(-jX<xN^A}Eqp}qn$i7bNkhV>Esl#ozu+(a(d-^em_6I39!JmbQ<ZjrU4%3% z?_=>YH@dKwuuT`Q_GS9lN^#=J57KeceuRHIv=0@|%LgoJJOC27gB}Iqx{b;fDXArc z>;zM)rM|QetdX-Ip?(ZezFD{0T~4@8XEZ9da4=t2gi^#i^_duDE=NIu|J(IBK-0;Q zic^8))Ik1y2h4<~t8CBIyzZUk*8CcT50eL7JlubSYd&ugF{xArG9zx_00>7d!`K$w ztNw&K!^VXbB#j!F4!?m?Pv>4u#<nM?Ma&t=?V)P}XEKOp9Vd^sY$#jo8ngi~e)syr zgy1~8ti1EA=kgeEk2NhAYN;PTa54moNKv;rv!*MYd*zqG?gf$8dGGa}<$XD<Vlm&# zW0kvWoSRyev;exa%kN7sTij;;QrfHyqnHz^O`e>?ho5{9ADuBXDtfq&{$tASvl~w* zDS}D%Q$-KC`7ajj;5fb{XKW^8XN@h=DVv*r{H+J$(yA&r+@@UnDg<;8V{aKsT%yy{ zMtl<Ps+JBhlvoc`b--6@?@7M1VN};<5;#<Gc5Olr7rOI1qe4km*{ODv;Ijv3^Jw26 zAYuqUlF?sD7H*Tf1<XSbugW#Eo;9J78!~#HK)SBRbEnsdPj1f@X5A(^>Kma#5=EcF zm74OQ610KFQ0Y_XhPh9kkN8547cA#ts5OXQD&S>^P?l7z)cbDB#$j@W+OiA*i~a<k zwYk3VSpTVw_D%+GThS^PIfKz(Wi{yVv~97uPf#|2?l;}z$zK%um5Ia*whJQqvvDI# zV27mAKL$>uZEFs#r=FAh--8=j#N6|Xn0%06j)%WJq-H3}h~suS_nT>6lT<gLVrg!W z1}J2_piHO1EXCmRfD3DSyZBn=api~+UqcQT>9n2}3o@TBmlZ~Rc0W7B`O5Kb776wo zrLSi-;INY6V!rZCTP^A|mxqh$qYvUj%$Sn-N4A0OJzMVmR1vu~D>qj4LZx)AU2a;r zX&!$?Ck+2n;MUK~k5aj%rGaUg%6dWOpX{ez3&=C;1PR9D*R8rIO+L%5ea>-fn(^gW z96kvjDsreY>H6ZwYlUxr>@JnV{9$6ve2TeQTyVCjU~Fb2pBi=BcmM*oY9Ru9!WP*C zNspvFsT6z$;Vmf>Rb;OA&L>hg5|r7((*G$xy;C)QCY=4-FtX!?2DD8ufmM7wf>qIb zpO#H+tBR_Qg2`oG_V-WWrrSvD`q4|%Fn&J&ASw`Qe0Ke(E3IuUx|*_s<P|jux@vO3 zN2g9_81Z)_lOv(_w&`oYs&wn<_n|f6F#^o&YhtsV;FLF^9xw^Ti;KnW%*X3!YB}IN zN(A*Je7=D`q};Y=v-ek6ju*Jb3xMcK4ZuSJmZSuy_B(0AcRF%SI(Xx)OyiG#*J1nK zGO7Lbn(~HdOIH-5Zvwc;9Zvm5=FlD6r9D_l+E=WieT3Yv93#}WC11ch&wk7yjI5?R zSiLdB4CvFH3xvqp<}yjlHHgH<e+)l=<#AnWfF+@+#KeMmZIt*39i8U#VN-(eNe{y7 z6+Av8$Q-!ch6H7HqI8XwZ10Jd@#3V0w6GsbjM7_h8~cX2KeLir3x+mC#FqIr=J)@! z>Y9u5W;+~o`k9weQ7-^qp@Lrmx60}4w1H<|P>mPUrMzN<Cui6crdcxrG^&dJ)`xp9 z;*%n9X}(y(&xEyBWb|Ek^4dczHq`pBC%;NqF!P{=;BGy{%&vc9^t&M?=>{H__Ishv zo&aiG>_n#>fJp|htMu2oqb}Yfk<H#S>5uAV8+=9-XB6%?qkl$6TV%%vA!x+v07hG} zxtMxcLLWp7!JLT=$%DG3(#slFs{+BSDWWSyntAWA83#LN_Bm8uK_)j9ys20L!<0fX zNJ_sdINm;aKDW0u>GB1(qBr~a4GE!{5kYkoO?%GD>F2SUY4=veyyoy1!eOMkcQ<rs z3v<ddkCwj~Cnvon$@4PuVnjGXRD^Ji9od0HygkhqS{*NjiX7|Sol@|y3o_aAEiLe8 z87tC(4U?HIM_G^mb5C7R<y7=4R%PSK#tsHEn|mqLH96tvxHM>+lLlFRNePGHjjrJ5 znC|qs4VACq@;tzGsQ0!xipE<EL5!h~@eXgdDWV>EOTw?h1f<a@eTd`n3sS=IK~=4v z$l0Xy@y95v%Ij@YIw+S022f87VBwRLMC3H2CnPGsVx%hbs}A4BD7|{FksL@<XsMav z-=~ctrr_8TUOpq)MyHZ{mqRr3v3f35!t4?0sJ{#6PWp?=d6vPH6zYRk@$<~20x>8D zfDIv{)<)LelwLgq<HmmafnI?yh&uPBw}{M~_I?4tE<uYY`je1*tT#LN!1;SBFHDLd zjNMj-kLZ#1Q}L@G{efUYp|kC6;ly^`KnFD-LjGvG64{lioUeN~<%4%{Lvs6ZOa#a5 z;$smDNm9bR^5n+P=kj%vO}53)Cn`lpKn?0nAu2cMM>*m(ZIqJ@wB37INmMaBAKqnD zRl{4<UDN-v`=rF67hB5lleLjr-5tm(;qOGBF?$h1WUT=>INyQ^P>J(xbERlvkR|6& zSTxOX!bbn+5^i#JS@t%CIf|QZQ6&%*YHUXmsKQQdQ;?uhr5PRrL2R#wg^roiR2zsC zFgXN&YEmefUo&JRkpC~eohG39aye2!&+Oxg74eNs)zWXheN%3W!u3ZZb2&ufNNSY( z0yD{x0B@J`ZFhTyqj3+p40e25hH~g@=6IpWEgrZq#Q;ct-?9Va+KNf;cr0JHg`J3! z^C~(bV#pVDe<ov<@+*kv-$x#U`!A_oE}uhIbJN2<b7e|8Ocic_8Bi-hE44N0LSjT6 zqm6OVL-!n?rk7#u_ee2tL4FcmHW$#+G4xoDuPjSgoLL5HZD>zmd#YS|q;h<rgH7V? zoJv+wbAnfHT}P88%34N|7CA41JXDikTo~y8ThB6Sh08(i!UHEZ1ClAj8+PO0DU(_% zdfNY^<iT7kR(anBM#7gT!TG%q+|;{rj0+vT6?!~xy6J0UAYDhfX1U9-<K{Be?A9yB zt#2_O82l?ne`G`A9M$F;aVp8pc5l%!f1#eYFSP-ee`eYswL{w~lQ?n+z(|0&$?>We zpS{K~a$+pMY3~^*{bQ&9ahAZid?<WuZJRs<8MI5SQ`as%5wYl;U7CC5i!&k5F3lRN zd9W5&3JncC)L~2Us+5bte-mQUFO9L;I}7n0L!Z2jxOA*nvR@tmUYJ{l&BZGbw6JT| z8KWb|Xe;UR@0A3Xl1~4?DD?nmmmCb7Inn%7=*U|2s{WOnTgrwES?qHEVLIfv7pFCf ze)jbma!s>k<AOnM7c#4!Z2HvvrL~(&ApEB=kwej{kE|ol=X+o8I^Y^vo5IANj4c5= z=a}fthSRc#Q?Hd?JC~^_IEZWd4ev?jM;xgTAMztcRHxa0&uH8nGTiLh-~;{%b@4`R z;OtvtAu*8_n9Wf9&AX3Ef(Jq{OUmw#(Rs8$vAJGPCE8Jx@#`qU@{zEyVOgPzpdjJj z?pHvh-~L@19ZkrJ%-&SbI8&9o_(hXGDeKrr^lfP>9%K@23ScT(k%gqhnL0YE+1~-| z>mI`1RV3o~kT{uk>Dg6ise#cK-37hNSRGUIq|!`lB}=)<nXM}T-@wn*9W(BKznN90 zG5Er6CARRMtALyA$sVrQFZMk^`UcxUK^p+)m!u@y9L~k-uMD721yJosaWPv<XNh*T z>MTO%|FDPCF)h&B1=;VsWv-x-v%$;oHZ8&f?vJmc+}g}3zaP51*-?-{`<@AZf6w2U zRUGqMB_K(Fq^06i8!sfpnKm3qKzVA)oY#NbR-rhx_%TCKc81hEfOl&2!-S0VrcjD- z#ele1`z624Hb>H_Ur@?D@>7<MY@z!Jj8rGuFFqCKN90kX)6+?7pE(pN^Q~SDGFJyn zI<Z#kt4mbr{F#rg2Q+(6__AFD@~INn<>8Yy9?1>ayHDF>_SE?Jcz_}}7hKh;r<=f@ z$`B0k$F%}Q*{q?2MSg8ySv(rD3uTXl@D|DZ&O?uB;0n<KjJ{=)?Jv6cyHZd;2hb<J z&`7vPtG<#{Rs99X%bJ`~<O0J8$z_c}8z8NnEvBi*^32Os(ANc?u3?>RMFr>!xNbm@ zP<9D&7!k$mOw^rjhueJu@yQ~3k?1wMcP|(YuR#xEzdt(aN2VK>l-C7uH~8Hg=11EL z+grfx=gaGRMhv)e5lLnpH6=zF;5Bv&es8Karo6V6PSJ7)=#l}qb2kjASLh%J-C2{8 zH?kn^_+4cMz?$B5e2)zAbDF_xujSd>Z{?nex|>(k{77E1u8yvWJohnqu$lJwOO=yJ z00pOS?)Wv14$Ftx+SSd8mjL-fDsKfcGfBq~a7Q77)j;jy8@jFu*`zi?5ZOjMA^Afy zh`HMqg#eH)1>D8k8MH%X)Gtok(%DodbKR`WqAd?FvA-0jeNOVF982QGlt~YnU%x3( z<kbn^qO~UX_VP5Ln71LkV{yJ#fmhiMLykO4RMDgvIBl$qV>C~-r;?@H<&-Ifg3p&w z7?`t=uJUC1e`=WEJDOMDSNK&my!gFU`(foR-V4*P+Df|n9bwu)Q6TzrGXw}3aqPDG zw9V(I6Y*=BRyxQ5?M-rPc%__P0ABRg%bTFQ0XnyG3n^lHDz(3;Dj!0(2<{`P(#wk- zPZiw7s?z&RW*RG#*yu01ZN|_iv>wJcAa}6apJ4D2p+ftCdl+hU-X&wMbFNA1y~<%z zsp0ZhV8As2wdCDU>7N~z?G7*kJz_7PM7=t<uSw1dMMbQHkNlT5YpJn7PM@|3!y<lN z&)~oDO}(KuDO+_{tU^9$2)m1{Eg<qEWBXq5H~Io&ev>E$ZOaaYaL`Pt0RMCpbC&rr z?1%C%*v{*ZnXC=u5eb)!^gYgRc3$X2)G_dI?0&huV~+v?!I2I4#C?<;%cZrATjE`n z!DQk>v&U%FDb~-zLJ-5flP)zKFeQET9gW#IcuuNt)_bdAL0l`#JZ)W*6M33jUX4<* z4iJ>|>lWnHVyBxH)Mq%E4~pOD{2%#)0!0H1XrdsM@cGwt5~XQzvXH0swu}a7j3b|Q z)F|~@mVq969E1%e$a?R@TOJFT>z6JZ!*c)gIrlRJkT!38xU65F@lEf5FWFW*Be`9c z`;D=PmjpGm-G6z$V+~~k$)*hrm%FPUPiXWwpDJC3^^t#SqkyB+lN`w#azf|JHJsM1 zPuT4WeB16ZlMtJ|OM!Oqm;7rr$<sA+9(+9fMq|r_dv&C_#GaSSNnCSwHPDRdBtBFD z;s%!cdkq-B2@=yGh?*<_B?%jDz}o8AcH%%<L&l~UPN@ufecv+(?-U(hg6SEd$xgk+ z!aXD|yJNW6owX{e@5$YRC+HKVFA`;=IN?5n(mGX#P5p1uh}56I-`Enwp))B|EAcyX zd%D73w?O4A-9ZKkRIlBfN&bSK%V7mQSOH;B0haYgt{-KAh&>&y2<*Fbtyhyr&l5_H znOFA)=O*5@gl16mVWa-M5INV{{Zd2IojLBBATIjAH=7tYY27$%(tyzC9#t07-DWn1 z2nqx&qnO1WZIq#d#4U&clNWP(^&Xlf?r<tR5;H^Zi2J3wHc#4B0o%(M9HU)k`Sxui z(c;zmMxX3Q)&g{pe&;PH!gi2ZmC#DU#zQi@%eP?OpU{eyv*-Kx&<9=(2(j3DS6sNs zy`F=V&|5;yJzL8;5!#Tf)hw*sAL9_Wci0=;XY_iy;r?~&&)FvQCyWfH#`fsEeJsQ( z^Ybpnbs#v;I~{lzkGNTn@1-reFMq#6c7`KRHo<~(V$6~YVmcIgnXR?j%R?G`E-7|c zAy{K7H-Y@^dQVH42{$U91Bz?sc4Ny40doFGxj+_<?F0Y(nMgVTo`8BT@j)0&&)8pw z0J0mala0zHB_H!k$Sv1Q*7*kPrT`7>i<R&E)Ki_P#U9yJ>f>-{a#3uB8Y@O|doap{ z)bgTM@5<=Gk9Ii<OKi#adQN_*d;&dgx4^YuQ#Vg$(v60=SP5XjI$ur4B%@LQWs!j6 zUo`<Nf#)H|qzmbEK~s|Ydyl9j!9Dg$;T_O(qq4Y%j>Mz_0&L&+${J-iti%9;RcrUU z_fLrL>e@*MKy4_Uz+bA;=I;RM1f%2kpt=CEpEb&cLY~6g_Z<JzE?+QQX%L3?PIJsi zpHx!=OwRH=_0y28>QyK%ponV(1q`KHG$%5A=>b|2l9+!=rv#^Pc=TNZFbXPGQoe(j zshfD&V6qHEV(?6t&4=Uy>eH_<9~5m8=ijG1Q#G6vRGBK82Kp|6!=q9S8=p^sVGy$P zBN@>re9{@rZJ&Zz#Op|{+{Ym@1J5-sl*D;;_zu=<^n==%Mh#!?1>#gHG0X0h|Kkj+ zo)u^vyFkI%d-ef-GxE<QIz->z3Em=)&H+ECxAUF=4V~R0^ZS`qabXTf)x-w@ls)dc zcZXq<JDOMaD=0^R1OqAasUdrXNc4P+@;G=#iP6!YC{E^8s1Ogx6igP@4$yr#7OYFl z&9=iM2TusSxBucO?^<7*G$;)K^aPTazw*Z)LeFgTDiLzEvBle($$Hq72?==SOK~z? zz=ir+Qqvtjwveu+-P8Y2xDlHH)Hx7;0gP$#5vl7!P5|rCdD57Twq}n1UNgWKVdpu- z{NNxAXBS4K`AV++a#GXVc$x^g_oNvX!e5DvR`Dg*-m}L*5PbI2IFL_f&+^lK$nhNK zzVvUgx+?MBr!l^I0r|uXjF-P+_jz4`fWVR}a)Ms&-J;y~P6eCo93Ldh6nqm9JDTt? z+Yv=hgWhYb?$!-?14QtYiS_%{7LhWTz}zTQSd$GFngX@OMeZgr)xiHN8(f4$jyTO( z{lvHdRt#ZOeg#G~-c{M*?JmlkYcoR)E?-&UR2sDCxQv$*NvCxl9Yb_lcMrCn;&G;Z zJO1R~-wrk?8}aYI|0OMo*$~K{)i44zUd-hva?l;#b&Nsb*^^L$uk}9`qT#sFO?on< z1Qi;)G5E=4^MBL6-R(`E^z2;yO*sw+7m)B;qz>)emCr_ZJ*3^Tnz%jfUseAOI!2(G zHq$6x1BW}K5X$m<nDOg#AadWJ*HO5o;jp1oc*e${%uQp$K4(~=&2ixfM`6L=<-CUO zAm{CCz@^F`OM0N=-lXu3mYw&7VBujEoj1INj!r;-6BAB_m-ZLLF${HYJ<TThOS4CN zZqbp>mjfC#7gfJO9xxGY=zZva&M@KUI9j|&Mh>8wKFd$q@(4ZkXNP#kKpYf6?M1pk z59rk^J-&`nDoQEfY0_5}i>ARK(mRRVWGV%Z$O7?=I)yT4SCEtmow`&>I;;`{?$NJr zqVwyU{M(O@R|EddzcQgM^-uI>8;XJN{k|h<R#megMMkck_|4XLU4kd>y+(lu+2EZW z>p?B2Zmgrei3)mhpc+xe!BAl??z;0o!fcj)I0tC)G%gO7z`8E$sau6mh$)C08)z7Z zLX|p&@+7RGG=7Qf!zfI2e*b)@nZsu~G|KM103KmecrI3D5@fX=F<@?Z`p5||nLi94 zB7jN2aN!1up#J&?o}AHhGWgy(BylV9E{ZFvF6t{<*K!5#BT*op_i1cikVgrDpb*mQ z+>njH4x@4gw23{FH5*iQ5y@L$6i&zamf*aR!vy=^>+bWDFQ(F8nO>vdoh|yuQA{$` zWw?d2B3cqEd<WIh0tiy8y<2jKEG}h?g%uK>GU+MWBzYkh&ta3{A4HbcZA`R(DR3mH zJ*Yjj{YiUNdrUhYCX{RrVKwy{_ZlGHlaPJf$Ngqd0@8O8t7sfW5TH=*6l<Cz@u+Dj zQN{y}jiD8}j6`8Q>B}Je|57(0g)YcW!f2!hrNIt@wq)Z}!CY!TkVJes0tJVWCp-$! zu=D*^%-rmVIQG;Ess~8nOvet2M42UDZ}K)L9Cil%l<b8~BjBJvD5r@Mo0or9H0a)P zf5pgU6uMtF2fn{ESpHRv(6OEUy^zFW_+OPfzuxW#_1Qbttj?y%6N~>Jdv6+7^V+rn zhoYS+l(r1TMu|$ABn>N4(Og8SkZ2A~Dh(nel(~uKNh+yUnoSidjT%*m=7Gvet%mow zmSJP>`+lC^`+j)8JolG<|7^Sd!}Y(e^E}RDXxe4!8{-DLL-Vz2Q)xKAnxABc<>ZyT z!OX2E(;m;-X|=YlJV267YN#>#+B$t<eK~y%ePeyw6v1tpf38*!>Bu@$HPMM;H3Kkj zfA!;S9LHW0%{dL?ZL3f>S_%Z4FAM#6`n~@2{%f>U7%na{N*QyZG;+lbXUKI596dXF zIb=oIMd`vjzeFC5<JjEgOcHZQIQ=od*!j#v$7Pc@(l)>8Nhe(&BukPeVlW+srBIdc zJ^mNwFsY~?8o_0Ke@SB~P`n>bvz0PQ!>?S$tQ)FH{s@V`wjS!Juo>yk?w8GY2`gn= zQm$h_-jKV^P`wX@{4SXPb1jJvmSH-#^50g{Sp^6H=L@qBc;tV&-Oq)J-6wC5=~xSC z2qHiGx@QnXfVge2h!G8~O)K(zvm-xWA`Yv_J;C1WeuC|$m|7Fn=ka`Rc?uCQIUoYJ zNnM;3e<gXl{oG;D+!|E)ZoRj$bjMsM5K%dnK2am_EPnb-BSU#?XE@G`!n#YFYZ=RD zc+%Y2m1qGiz9U8R<KPtegY&TeDNO=DWB(gJljG25DDb{6^39%O;WjU;4TJO_EkSI3 z(se(YHD*6B12BbtD?Ph67z|f>Dd>~?^o~ThMd??5sm^^3(^V?~9cPI!PslS1n`n~> z1{)UfF*lUlhmYt}iAJZXW&@NzPg{yC?}qP-iyoFis5E?4k;mMdmBLV~SCRnTQBc48 zS-sj`-s(oO`-=0};5UvU*4uOa*U=lc>|fIZ_=&SI=$7nZ{U>7FP^;VQou40qeJp7M zaUf10C_r=Sc>|t~qcX+^jM0O(XR@^-aU%1^luvO5Ud!~Hv|KJe?ykJ6pZ?-DLaX)S z?{04;KJYsaS>C<QD|q<G9$k{Dl>P4f+Py6B)E7({a=){V=mLBFx6C=(nrfE!-00>x zeT5vbt(#@+njQnNEz8!+Lg!xV(CIxE^`<?gXqjD8c0uKCIYyQaR0DnP>yaNLnL;Ut z1xAyt?4Qh}0BoX}^Tel|-bz2}5FOK!?0$HY>_%*GRnQ{jPlEoR)iRE_x6VS)p0=1% zNV;R9cJy|e3oFOn-CT?Xclh77gSdVV@P0=D$U7V6F|)MHU|Ip!Eyg+NeRO_^^7j*0 zF7CcczLG=zI~_f-pk23l`M($>Ka2RpnU;t$Y=S(_`1yPK6BaUWnyy(vliz>N-GjI@ zl<5S7w~t(ZnUY+!o1fcY>&a4Z=B)`kx@@NQOqN{Z{^r~!%N_LGmv9B&shYr9K$QHo zT@(rq#?O0qM~Wz(xU&TI)<<0OSL`X<xhh*Ag;RUgeYk7s1tuO<=4dtxzC-!+YK216 zu90cAv8}k_qo<nb)iS&96fNi8*pmD}$-UBv1_RE4zH!Q<c2c53H+h6e?5dm$V4g|Z z>)~9)Q)_>@Q`F+zzO?`Hfl--ekXZX1H&M!oDU4aP<^W+KR&5<r=3tI*lpb$pc!=IH zvMUvD{tL=m7AnzrLB6FwHD2+mkQE*Z6XI5)h|ZyE%KjhD2LopX_KCH5qEo8eo$+c$ zKFog=RGRJ<tWDADY2Qv1eB8$JdL32bOUSMn*fwJm_gz`##5oR|kDw5EKu2v>S4+ZP zX8)Ni6k1(y%@#@ln|sI8@54Gy+bn9N+kxUjLQpLTBZ~MHs12Ut^;Sv|dziCq=5!?r zlGc4(H&Y8P>2EgA5_np?_Esx9y!wXW^On{B67KQu^b<-$q!?jM*+i;JQrkd$EtP=* zuQ^YWe+S8CBU*X4Sn-#an)&Lu`7nfUiPe9%85M|4)>L&CIhTuae)e9xOXZe;-)>XF z!y+x4YYg^B<4o_OQPlwy{+X?pN#0POJN`6ZMsN_Tzn#iCI_q%A(KGZW_!Ki8XZ2cf zk<rJpe(htYz&1>dbXjBqlAx^Rv>w3_*8tU8DzU$J;)zXYG<N=QeZC^65QTFoGs`sM zGsbv`H~7mhFSdE`=n@FpPSOw*5u2xFI*Lgef-Yk>q#$z!fik;@GzqrbRV=KdisZ(J zbe!_jc%LP!E<@C$WONh*w@CW5`vCDQ7UHcuM)H<dW!=}Qz1~$=8hgZW%601gM++$y zYT?6r-kHYFlRl6{M?*zd(pk}JJ#672-M!N}xhVaj&W_moX{rhZTE`=j%7*fXee<?( z3qK>)0xen&9&zKD`qd1dd4~qB^ENPB+}a}LkZ|XoO86D`{H}Lu{cF&IMbx-+oA4jc z2{R=*?Q1uciXOl0L+fO_A|`0WzOu_J1zfaUkU?-Q5jU?qSQG%ji|NgB*7IT((Q7@E z&ei8Qr%KD~$z>8BE4|DPHlCfEPixtGMIL%X0zwCM2hB>2i|1KwSf;p%x8y4@g!0|J zg7XuYNll%1oQc}pAh1$bmz_hHX#f@4s!r)pbDyb8cjnyz?`7E)b@nK0KLLkV(ZL!` zg(K5m^3C)b+T<X@X{E)nW4TYuhn;xy#bF}5bW`qnZmu{kx2Z_mlq!(&>Q*gzzmY6w zG`bZy-*Go8rwI+g6V5h&X}c-+u;TUM`FGz;qAh)G7wSH0o{_lAcMS`(%S(t0dO&}7 zJk>!j(_@c1V!Zq+;-Q>It=x;*-g8}aK+$^bmQdcg=y5%(KjS~@wn*QajP05{+%Nkk zG;UygQcgaL_Z<I<dv!B+FSP1ju~z5+g+t3~A6N061S3kaCyU|Yna}j)74L;V7SMaj zd3{CLUY2V{EJDgkTf0J6d>-@Ye=_T|{|m`QtL==+icFTRyn1kZ-qrPk&g~(Qt!wM0 zD7)he!>wu4gqh@*c=5(+U7zDGB&)km%Ohiy<>L9sO_yt*AJ>F+#Vb`vta^OHgwi-> zbw;Q(UhjIx|6(YQdDSzADf@{}iBiC+FkOb*U)|M9BYOv@Elt<VMA}-fJ?gW@nllim zrOA0-wSpgWHzq4u{mm~=zU3@Y&f-;Gey&hLMX{;OJh))4*E>GLjCjRMSq<A2DSk<x z#nk;L_0uCX6Lz#9J~BUn#s6`HXxZi}>Vc0%3fdXQ`e&YI44spit7XaNaG9&|1toFg zIHHj%vkt_s^5$__9%Mgj?bwhXAB*y)LXyMKKaFV#n3-aCDyL{xxsDHPbNk#CwU=*% zq$^q9PMmQ2Y`IkY=&t>%jIRo14b8ldg5j0X?vAMnT+_QOD12wwP7f7JSjSo#vUI## z$4^O`$vO?~)21=lYxrgveToIA;+1Qm4TXh*vT#oWBU-CRrRYS`$jO&Py5w=f5vuLF z6t!vrKB}pz1j66c?8l>QLbp!Qw7Pdyh_&+J2wS+e6mq#8XFuzoL1|d+kQ^=4TFr8U ztuxE!#hEOxDo=V>;SS1`7B*!;yD^)A>JPgBjrVTc<`P<cN10AXY-~f34%Dk>H+A1l z?djcWpX&r(iOaBKW!R{NmUl<x;cbQ~@s=4IOkdRP+P~@26_!LMrnBtKQWx*o-yT_B zjuB%|a<W)?CxMMxo-DN1z|hG`Bv#398MS*F%g!v%V}i3Py^S=z_HwaL$LD7cnoCx6 zMRM7=ieb^ynF6dY;QMfoZ|Pv>jU-b);b2~~f%ng8DUew;&`F3+Yx9>%7RsocfnRs_ z+IcL`1+FDXOQ;aqPvIsoyGj98SdoB=(x%|)cWT2vf2#fv>=gyIUqf>!c!Gv!-S0UO zT>7C(>+QJR$#2$3bZiI3Lw@@<N;x2}H%*Ny6wMy`*^bJ&GQ>4&SJK|j(kV<E{dk|5 z>qZZ%hM!l@v)_<xT-eEFv_JfwQvS9oVQ&&LZ17R@^3%De_J;f33uDd{;++MuMhB}& z?U8zjDQQtAvbESz;&)acgY5oV&&)SoGaYl)aVuR@4Qda#v;M^$ymQJ6B(7UMix6=m z&Ytw$5xmMn-05A;FxJYIa@Em0&ixmEMY=A!D5r~;S6a-grdk^`rU&0n?q52t+>dgg zA(B($1bfs`qp?AD!zaXm!Cj8dAwWQ_K1rNEOm)*J{#9|?+b<Wsu1L16zAg_Xm(%Qt zMG~W*gGbpXAmy>D*dlmpsC&6y;qR}h9GaKj-nun;t3*(2x^HT;OT^$NNvYZ)JxkLS zb!RDTg!dbC<9M7wbI#hPb@N(^$veE>3ELV=6TbXLWfs{kn?zu6haR8)gX$~kz1HPc zOmnVlW4j7w^c>~<vqn+f=SaB*0VL`@zhlaULgvchXK1J`^A~*1di&(8YnfOKJjrO> zB|MNFN3%r@$wXTZ7tElrU8-)n)okLH+$pYq!;8nz)uM^iE^b1<+_ZWj`LLt|Ix#HE z&7`XrYfe_cZq`R8vmbx*QonC6a87E%DI^&+`YyY;D5}@#q`M;5HQrj5_r6)zd#YkJ zw(UQ<oSCAZ!L|bZ`C!{hC3fbU@ydZ6qIXri>o87}|I!&ymL4&kG7(iCg|4BExKS*> zq+w`fnR9EmJNq@Wft$i?wj39p$|jlKf)<t9DCtI9wG$$g^{=v&O(Hv`MJ`|dOR0fp zYGG14;+5_%*Skxm6Ghc`iefEEYD{lR&llbfoEFq%odli=*N9=bR%p}Qbjl-nXvB^1 z>sw~^8rYiXF|<SU*0Y4<j)>9m;TCI=ombscXy~LGJXHiQ9;2Mf=+ZmJmL$fMKs7Az zyGK3nA{v1H@r(gsY|SGPLK?cB<@udc!=XIGNYgT7OVhy^g7kZqpbL2$Ym!$U=dH22 zNhc<Pr<O!dW$SasE4CuL!o;Bd{T2Oo_>MkVxA#GL@KtH<RDRlwlbg7z{=7GOdm0my z@_Bqv%oOK{1%m)ff}ojsALT1P9;8OOIN2?vCHE@JlhAJ^W6c=4Jx)nPWE+fWf(@F! zku4Se9<I2`IET)uPEgcInfpwCiki@4J0~kA=wTZ1Q^V~k<@pF3Ys}K7<Q9sB@lMmj zfsSilhDhW&%UO?cAD(o+Z(g;!F*bertWuWrN-eqi6r$7=esgBlqIachxH-3QO2o@q zdhh6}q|oO%Aoz@C^T9Z;Hr;*PrP1N^sCI2ixQB!B;K{u{VEwPr;?+Gz@t0f0c3PW- zLTpT0r^fjPfn8cij858+m|kbu!|{;i>mmW3=DCH{E2OaA<96IfcR1wM8=q}2#zgu6 ziFyc0AJu%ch3hnFofjb;adyyNR(8yqMf-P6d~h{PIn`XK-nC=Nv+H1)$Q4XiKwQ&^ zjur1U0an<#-EbcJRFvyl=x7+3H)_XOGtK)nFDt9u(m~w%5mxK~8|h^WyhYi}b@!E= zohvt1zVJ_RBh4f$M3EY?-|^^yKVG1eUE9Wr^ng*;x!YxHqw}w~%;$HnJdx$IB`FF* zAC<DIjfcFKF^^oG8jhxH^(-%v!yY<_MdoVfcn8ri<_I`+ntKEuk7TQu!o>839W}yH zS|}g4aqNMD^Ui;GWjXcR%v^-;`E%R*Gth#1eZ=PdI+FkK)2B~4q)m|pYCtU44stNB z3gV&0@69~sXt02VLed_~e0bPLuj~*?c{}e7Y<GFb>`Snw9^%tfZ|#xOz@}}Uea00w zBe_zF8HgkvB=I#zPgJkqudSY{%yk+Ctmu=ob0twK-aEOg8foXx)KN`L@#nd=HQaI| zi#)mv5qJ)2G>E^32zr00Yu)~{fq1liK|^j$04DqQcuM0t_*f+}7Y~(j0H#iE*7A&a zN74p!q!gXNI}5_sT5r=hK$&(c!E6K&P%vcB0kACIG>>`ql8xor*F8pzxJ;Orv!Y(F zL#F35Ml3yMauD#9<ZUy2vPO3}7J8Mky`(2gWpeuZ+5NnPBWk#a=cLq^H>XPRRbX37 zLf!)H0Lgti)KMPps+vDBnlOAff(Q$x@R9ar?dAR}4l%*aiDSjXS=G6r3OxCy{u8g< zN@pBfCCj=UQ7CL8jDLU?hAl56nV4=#9*za0HxTJX<=HbHK<EAYdg5$;l^*03hL73B zZkX83QuR_EhZ0v18Os(-^op<XYdzll@!>S;s~0fOEJdh&2rD~DkZO97A6661q){}z z>CtkYF<$<iOz+o5G5&!^vF2m#gCiszS@Q7V;&OmyL33rlJPe-pFV}Dt6SP1iOa+2H z6AX;@^`%7|yQCd^)+1$XJpq%PQOlGdx31*c8l4`RrCfwMeHnK5f&!U=4`&wJC@;pX zFJ~PE=v;~6Cq6BHWhBtYSgU2CH@5>A90-j3n!<(<fJLW6FFE5IJ_vmN5PVGblWmH) zb<_LFF?jYdYj;#HalP#AGz0&Nz`2fc=vKb&JEp}8>6S+>rbZ^6tnSqp$~sqk7C)yU z<s|V2HsHFrOr~L>T-tbpUtHCjKFS}*4EMhNYZfl;#kM;@$@uZcwX-!W{?G-UkaMwf z`e`J-fBVd?Xq}4~^u|gJBD(R{Ck9I$vpQpf6{OASX{E48y|f1j;($kPHO)mg%GiFa zTJo9}&b_g2&w-gIk*d8O3qA#ov+2VZ#x(>__JLMxz@fFAYMk$W2)0{?FtKyYPAAtk zb6~~BJKa;S99_dYAZVCXJ%%G-tcz70mQ;^5iZ)~7u)#v>YTu~jg|t%GYy~YHP}uKJ zo3`xhMxeAk<kg)v)QJ*Us^X-G?v+q()#~Z@R5W3F1-kDwL4%sH@qQ0U7&nAB75=ec zbzSc($LuQsGo0rwdF3$W`GY^1r=YlEJNflZR0qXqo(fAc%x*9W!pPHV_{VP=6@Q@J zZtOAsYT<(F4?%?&%01r;h?#BnAsz4uL`4y!LfT9L<0_bJmEwwQHraRVQ<oh%sB?F> z$YN$0fB@80{tCP@N{#X45(X@3yux0QSwg&vym%jCdQOgg?C8qd<mL-k^LAk1nd0y= z)2_W?-198XxsdVpz`{DMd6a?~obV%V16UxAa6bvYTlQBVoGvj^Ja<BEbcJsIZ9?90 zhQT`0f!%rn<h$mmH%9kXIa;_H{<-*B?C@%SEkiE<Srqm+L^Jbs*IOBB^NQ`$XvXnR z?`UT~a^Kk^cd6F>;TAM1FDC|7TR(o;@2}qw*C>ARQDhAT_>~CUn9@#`pd_|1avw1r zBq?RERT6C10V>|(Qq2;gzuY`mKcBj#F|xOkHnQBG+Q>;UVpei6l;6Ni@eKa4@A<3V z={CN2GKuF#f4?~xCd~_bL8-6(3r1nr1F>iPSYk|L>y?`l<E7pa%=_qmB)mD^UAC$k zJ8%Z!-7MOC{NDKe7q6l|m}lze)kJ>&>DOm2oT}o__2^%2`)b#y-tr4CSAi&yGcK|7 z?(T}}J3EUTBbvZO;AMPgQz`?bf&NkzSy+TI8x@_oaNT<ND^g9E)oyKiMJAu_Dj!@b zkENeTRO+sBNq4tCOI2$8@FGC|lUEMwrLHW`gP5C1{-_&x1MNZJ3>aTiF98P`dBzhS zJ_WjK;|)oK6mLM#tt9a+K6xSQkU`#w%yF+5pQAoljOhE-#D2CIZ<u54SNtD-ux@QW zGlhlJL?Po(od5l4&!T8D&qJq`>akJyneUspq?yWRcv+7u`1{)j7y_P5tdt#X5<YT4 z#P2FwFQD2RRN0HD#Y}RfM!=(&v;*D~Y;sAe(EX9cc$bk-1ywb0LxH0>R~iX+B+--2 zxjii3J~A9RHt>!3{y~EiwiP#i_~iud7DnaftxaoHG4)U9vZ8SEipOZC94IJ}8Gda- z1_-M)Zd-vNXO(*F!;4(1qTh9XtpoWSs%dHh68#DP{so=k<@dtAw2fU?-fNB*@wKWQ zCVXr=N8gqk#JHCZ8#u*(F2!#TCvo4)2~M$&CvLF03?LXbOtYW&)TKO;#r`U>czQ=f zQ-<^4A!%ETI%w`E*sobQw-)(H5@vfRjF00%#UfO`TcI!Ut5xB$QR2gQ+YHs|!E9Yu zJT_~y6{zT9n$E!TtS+f$j?56lk0Y3%iLycqR;%7KOxhW*T@V6Wjy81DRC;)g6aY?L z`tq)ZUYL7rfJj&ZsfIBlu$1YQxzYe?C<EK9ja|`)G)VJP%dK~u@Z~K{hJ{{kvcoLY z2|^~u&8-Lu3?QSTmkBTj%*6jIfk#u1NrX@*iN>|7)>5i33U%$10tFtu_3wMc7IqF0 z2-Me}OPwS(IM>$gsZ2vOr6VQA<^>LmLtB_sIQ;pqRpgMtP_y4`uS!7;<CWknY=GQ2 zXSVf*r5<entTNt~p+zl0NU|E)EN+&e9@xjD7oeTASIQ2<ydbnLK_q(B|2^>s@*^(r zy7)3*V`6&<J471_#0)=6Ih1v2weB&Eb2&F~Fm=k5(>4#5h*A?W;&ozyKkUJ`;|vqX zp3$_Wq(Tc1>a&zK$uPwvtPPY1>Tv#-cQaFwX5i-H$N7bP_0zWkeiz3}NJMtBT@U?( zCCbm)&(m^1dk!S&zI_WQ<<0;7xxhX-7!irUI=W!KBZW$(6s7I`IbR=zOJd9YRXS{9 z98(Ll6SzHc*}Sler7F$jauXqERWl|(vDQ1ddj0wl*pl9O1%8ehJo=$GVr#a_vhcH6 zYzTj-+)X$TxuNS=uY5^*OZy<>j=8t0HydXOoJMk_3Q4CV+Yh8LBQa;_LGyyp<{hPf zu{Id^<A??J{`#k)132<I>=i6WX~tl|H#X^`=yX(53ldA=5(eP%ViSJ*X1S;UjK|#E zC92bdr(VQRs*Fs9Vz&CsZ$kplJ-;;pT3qHS6QBG%0!R#La~|e9RvBg~ge{!0N{juP zjhtA#;${8jxa>^g1hmd5r!G%of#M%txc0oaXBL+{n!%G(WGNPJT0!I?F&d#Z#)DY& zF3EMBn4pVNG^YaP`VX5F=hJ!*l!c|R^F2_M?GuXn<H~wgeXubQSMv4pccTb#bB`HX z6<Mx$vIwp#hcepJs?-}1Q#rny%?qM56I;uWkT39+>Nhi(&qC>>ZGpv%X|^FFZ}frU zjHUMey~hN<UGlD*$590CeOw!tu#vF*;~H~zgQ>ilbvrNG-RHk-bVo`uEH8BCJPR-l z&Rz5zb3=BtO>FOaj1%`H<qT}^Z&tV18F53B?Sx}b-G1SNa0_miu_ys4`e6GiHmn$1 z_($Z=6up?RV27XyF^+PTHbjsA_L2;3H%x&YU5#Ca`>bz59ff5w`k29UP;#VR*@OyR z4QExZRJ<wtqxVJ7-5(t^ZZ^r~B3?v>MI-K$<4#qXc89ZP>r=g`giz{QT{pa45w1bG zEP$PUEl4gc%5ypV=aIM9(lE4UoF0k1FDKxUw}4bOg8&hNz}*Z4z#4$YzwTXxhGCL8 zCc;MdELE2@)y$A1tH7B)pV@qoejBmN?qB;5O~on0mxfMFrtQ%)z0#Vv``d5?r!6lb zzO3sbOyhQBeEGPl$(@W&XrH^Z)ksr4b4kM`)q@L|@w{I)^WeO9Yr!JgRTnLCx(}AG zsr#QymtO6!uY=vuMsH>;sa=;~EFqy=DZ#(F>KLmRZQ=XhkK>Jnr0rG&J>l!#7LYng z;$qJ*gA+>SF=LTVX)PuUQ{AM!a3Hl1k6<T(g@2slRY}ir`@<^=sK4XpVC?O6@=D<a zB=j3@Ifr>PxR5luyJ|3fE=ac$Fxfxdw9w7G;H>Z!3ptK$hUmm-GHZ<Ua>fUCaUEsb zv*EHDdm7pU9oXtiCu19OY|hIm(!Z^*Wp40!*%IgXmq{De99ekRAmb%*d&t}67Yaat zwj-3+%=RDOho{Lqf@83=V$Jza)EwDGxiy|(nTkZCmE%kaEI!MOk%%P8mu_F&$i*gb zzy8c_fsLwx1Cx2jO@`olg(mBOUti_B=*GF$zRQeZ1SQEQSFIRYxUw=o&&}EIvx~O| zf^-I#HN7vW92oPw6ZfwL$;Q<n%xQ?6)I@>j6*e_GUnHcU-s4={+6VVdiyLfewl;;| za&8NZ0r8P0JMh=PRU@7z05>P>-*TjW>a1@Im}Uu0ufVRmW|K|EIuW;Tp62Ce8Ml7B z?&XANIZ6`xhZ`2~xeplbaf`jN9wm8buTc`J66%f&U!kmLjs-U?xuy9l+`m-8B=(Jr z=;*&*c5J~}9#!bYVuEHHPL}Debv1k3-2yM)ARuw|3#I6m+N}2Q`f)W#TTIbp8*O~N zCuIDrf8j^1jKd>+FJ?=BuX#8W*wM<!1%gcHJgkj&W&<)9zBYUzZ3nbA8~TRrh~XY= z&^Fm+D_BP!5yz0^nbeK+vxDES3(Z;=bWqkl&h*}l*x5gUX6W8yGk0@nEM(|5y~0>4 zTex4o>*0C%y`5TfjrUp04SPZ}@yF-<wakAb#^w9&6GhXDVMa;L^46dK6U_BOudpbf z6FKy~Jol`EfuA;{q4*Um81?WGqi>b8D(o~SIC!werUc?-`C8kl+okYNj5nk)EFeh@ zR#-0=!u4M9h;A**N}UeiOd}`Dffiw6a}Y$Uul@hVixJ1Sqb7VR(vNoIZO*r%E>QJU z*w(=(8<*ObQ~uC6tp_}Y)PbVb4PvgwiU*rosMf)`lbFv2;ozufo=)uQzdhe=TANql zir)n|0ipZ*igopwiM>jic~#+b86Wl2H(@~<N<cwZW54c+nndZ~Mq>ThhVvmcV+z*~ zpd?m{Lj%KquZ?ZDe!m|cCb0Tn%SzV!tS2Lfzn}E^cWcOwUz7u&?58&>&U${X=ZRk* zG5`5kvi&R>{QY(CBQbA><BBm1`RZ%^xW!*I`_1(t5=;^W?z;F0Ccj@h_9NVipRSSf z+@$%J+TR=M7SM;EtDollLdvxq9N?s4B~Ebx#X{L7|C^@<Kn%dc4&WNvw^%bQUcDfj z>LJv_ZJ-0C(y7>X7tdL<(gnp<&f%#QK(qh*Tfon&S9Vx&x0htBTX(c_1%I{$yI&Pq zI5~%>*q|Bzww5CKZ_mepbF@VI=XRwqn)g`-_R2w!jT+s8F^{RwbITrPeKY5OdiW3` zZ}qcm858khs{NndZL0<GGUcV`;AnHUW6Jnn{C(yJm;Q$p{mZ%f(43<{X9b$AOU{5a z=eB>}H-0H0)c^e%{L-@hr<eb8o9$Wk?~Ba5HtCkkLd2k4JyK}`yfTH)jI=VO$p!iH zqtR0MBK*7?;HRV^F3&YjGhBhi4#D3GOQNj%aF{O=x3~tpHwNwcZ(m7OhOMz(lS6GF z>h%DK#{!X)5&&XyFu^3p;P4~PwfD$L5}a#Y;Q*rlAq4dt!bqt(;mKJr=zvrFw8lwg zmIN^JbnW2&TWM~0M02o)XhkuABGc(p=Kl7z0n0p0KpYQmQ811~t?Jf`!c~z`v4EN! z2=}vk<IcEDs(Sg*j$5D`xhBtnc8*u{I~K!uMcW-@cxqG{V|%M<76h{T#|=i>G;{RD z6-(Ya-N_}z=3dSD8q}Clbjk!Fw0g8N@g!KNCRD5Xce$HDkpDjSAX_;0l{K$EpV-Z3 z9ZJ<{Oz5qloz0|=Jp66NA3{#pA@rIAIcxJ3&Rb8oD!oE|&@)MZp_w-V(OM}s)qMuj zV8U23oq|^S^S`~isOC-8LEB)#TGNqbIK|gxh~SF^7)ozym{>o&Y5vCF*5c+*PZ!X3 ztBS+y@)iWnfBy1?;masJ!*8J#DX(bK%fGk6+2N=Au#|iA_SfC_f>#(yqsCT|`XQ+N z>b%w(KABR1IEx>f#ge4o{)-Y)t%KfY=~r|Rb=EDb1vc;|Pj-6z+A8?Bm2vdJncucP zASxP*k&NwsK8fJZiC%Dic>gaipzOR$f5+?0R4L4=OGtK(`lim6aFZVn@Se%#QYPQ= z+sh!cL-SK%_-O&jd802bAV-3P=FwUg!!`BSPv!838wNHa*xK&Pwe{c}C-U0THL)QF z=E#j5p+~B7F#Yzp$AGe%l@Ce3iiRV@>=46ijg^M5&Cu^*)13=6{aBM?HP+TheG zJXJM_SFAUlp8D|D6Z9YZjVSfR$T8QxkI<-L#KNF!&gID?<XSQuphlN#DJ?Zko;@b? z#tAKnk;k}$PO_1V9l=2e>4Bs+(nOq5{qzp<c#Iv@0Y_UWVV7XzhcPlXIQ(b!U1A_D zl#Q813~cfVB-$LQ?DN~J`F&$L9F4vt2GFC#@lHrB14-=2GaJyXML`}FBd`i%dgViM zpX?9=S6{^W@tUx4^K@Bw)=8jWN;5n(IWgYbsv$cPwPw%#D0A3@8cw`<bV?1xkrGVg z_wn3ZoAluE5+wT_Di5QO*>MciIBoZy%n?Ok;HTRsqkh}9P^&%g`FT6vMKF4UL6Z3_ zkyDYm75O)+NNg{~n4s5=<0F5E*3F}N1o+qt%O~n84H$^3Ap$B_$x-{EeOG*JLnE8l zoXsEQQ_1#e3}8b>Cq{LV^zD0(|4MXv|Lk&eq_n}JrQkKT!QgAKjd#s&YvcE0A+L<= zg&2+O)2CXQ7tQIyCVVTon@*&0&6gyPzT4_LAp&n2+n2=s|9-J%c@%F4;m!{~Q@3j? zNlDfjwsT3cN$8ehQJ#pB@4{(1Z1g`rhC(oe7dH;@%}b|A;YNF{4O;*hWzrmTfI-&{ z`T=}#v2%1m@ohcxuXF*VZGiRc>enOY)VG(OMPQ?$zNSXmVK`HWVSv_XQt7<8^3AV1 zg(@lpeUd3^L&D)oRdB5SdJJ619j7%C3_{|X&oBlpK}62cyi1-$+@v~m?{YN;FWVHY zfLXS$&bi1pd^IFi?UL-MnX3UD-k8t3<-ROSx4Aea%CvLIws7sc8O<)mXLc%|`fZ^i z=YkM`ZO%@QQsw%s(8Y%+0!xH@ZE)!qBQudeSaJ5==_S~b$yA4)x(Z~OzvdLsT@S=b z6bP~e2xMXy=-tjFg27e--D7p$HyJmx3I(gXQRF0I&{*gXAl{Blvu$a%0&9J`1`$DJ z0w(EcwGh`ucc=sUGzkZj)~Fp~3#i_?^q&t89n&=d_7|&JD^*CmO$i1R9i`7h)B_xj z-8J4^up@2nIQRC!llOipw62c~wg-cP{MtyA-d=`1YXknX2eZviU~|Z{ex-9qcg^DR zj?vF>yiND(<OcrP=BOG5hJG+$+4^$j)@jHOVNrLvXq4PeoGlOGu4zXDp-GSeD%U#- zIKuK2U;0*s>A!twI^X8q_x~U}^ue2hcz`Z;8zimj?nO<rDiqeskJ1)(W~*Uc@blqA z-<o);dW9KMD^)!F<Mt_)RY)CQv3A$p^#tlGJ|E57!KmS1ahoA1isrb&VqTO32^wo& z5>@c)9vP@G$7^hj1Us7ms|9i$$9L{r@u~PTT{&jo#r1!;HIe+wHl<M52RwgUAzE;> zQ#q-LySobc9sLXVGaHDSLkiMRRk9~_k3HO`_9686yFaR;R2DQw8TA*F02}&tq8)a- z)DNYF1j$Cvy=9S!qDK^P0d@G5nERWDCu!mjC!nqPaXxOgXMnW82wjK$?SAVPo{O<= z7n8HPIx18{UCrht_AGjOLiHaBY|qGCj2P&;-Qr=ELDL?Cy_rOOQ>R&2ILnQFJVhd~ zRk1}levZG})(b55p7r)no6Ii0J;jyd!g*gFBeA1eXj)y%-#sD!`6uGP{eB+>aCGqk z(^A|P@O5+B5NJHpBD{66?1=}rVjpf>UIq{Tg9NYQA%cw(`1~BUO|U&EqtQB5CD|xf z6+G*nUi)IstTS8w{4p#+fppgL_XYD~z>TV;iA4TE>jOJvE7(pQnzq=1CDv3OlL*<E z8j3}IYr^i72vBtraueB=_xnc~Bq65$!hgM!HBWi@wa|AhWJY@T4v7+<XqzTHGt+5{ zdvD(8^`kFX%uM|CCF;mIXzg^QYvD^CQU0c5-n^{)f1s-&+qC{s&ZsVDp~NGa;Xbb! z$<SJ4G15Btgoj0<i#rLV)HdRw?N>0J0>zKWsvS4P5XF(!Py9D~PN-z;t+2EY^%8&l zgM)#ddE?$Ezb|E0FVH(u(R~Z=VNb(+Sh`IEl6(U4m!NG_!vgD_7&)m{c3Y;`GTWj1 z&@vq2^f4TpPpMxj+?;z-ih8JDHtgwpaJ02&9Gg-w^p=gzzb?anxi8YtEo6QUM4wUK z@Ca)~oX$jfZ~d%wh6LEY$pLJf0zC~*G82zy3fJ{DzXy-yUZUrLXoEg90%|x1dI!kR zx_t^AX|X@b{eKp9uqld=Kir(-Oqzt|klZy7w78BELO0><N;<_pzseVkjTP|wj*PuB zd3dabC+FYG|F7$*RiFJ@e4U7wC;yKL6}qlDwMTw!J26vAf!-ky*5${C85+wUUFyI5 z-Jd3EXwUw6BfpnG|M;GM!Rr5QHT^QbeIs`M-I3Y9bw9t19sli1`n|^a$AbDt{rHyq zf2d0Sher`~{++67lG>4lKcO<e+z7Zu)Bb<{cQIjJyn>UMQ%U|{=Yc>AA_5bW<dI+d z^tZ#Pnt}<=oSmTq6^Zr3`^jEx44PZM()Jtc0wtguC%jEUw((rNk=`<w1lvIqYe^=X z4H>q!#G|_kk{!DOPCe2ce=yC0tfdqqE?Y8K7j>msrGhG!3X)kWKIm*2q3;MEIh>NQ zySD*l9PaClD(gcSac@(xQ8`eyXf^^C$}k88OmC*YoS245odhWy>@dCvz?mIL&TdjH zP8XMKvcF2G(t{GjaUlk6F*zh+cBdSOL7U9zI58T!uXqV9GKyWTzenlp?pka(J++9s z@27{v<GEDYvF?T><i1pba!a*d5Vg8YNj&BiQzI9t<R?+P*Y4u%)1+`El&@*wpeog& zzs_3uHwes{4`J{G$6``;xmGe5QV(Yn4g}9s;*o;Zx)7D5v>2rrL?AT`fvneyJ9Oy| z;%IB|I%~OK^XIF?@D%0ywiT=cd@Ks1pCF^S7fkpbOiVU!dgRJD?vO|*Dl<2dMkOUT z@4CBtKbZ?<UkpY~CwOdhzyI3rkSsYmT#>p<M!FqMjh!%<EmmQ_)*+fNx7y)(LO+OP z`y?48Ii}YS>phm4m)t^&-b{E)WC|Oc-A}*(5(Q}o4PgL`ZZ{nEeuh@FA?4J>#BhFN z#93kwz7f>fJD4Lot(}a>5_({Y17neg+&4&h)so$^^B|17tpAEb*y!~vq@X%3Pq4cI zSiNr^GZA7?eZ@U+W!WVFpsllSs;yi{G}TBhD}<#&NYY!+jSM;+(}R;BoHbzYltN{o z#vq;1)dlT!{o|2G<V@(efcPx4gNOlI&S8#=S$B0R4r3BQ7&lat>E?99uo_K@PgmBP z8)Qzdj<ZW;F)Jq`NfeGnocyqWM9Ozg(n($EzD(Tx4QYO{>hqQ002aOf$r+kmGJca$ z4EVe;fY<+!OQlQ0C65544{tN*c#QqPIl{R5&bctJ?J@ac8m4IAXth~8Zmj#%_9x-w z1!D4vaHMUGXr79KNS26dutaH+Qo-C(zpSq$&*bvjbjMzO;?+qPejUyJOgIP}R5q9e zWvnv9;yuk@H93y1NM)mXm;$Gp#DPv{lIu&nTymwddy^Rz0U-RJKIO6n>2E6Ji-~75 z_@z{vCJSHD6b$JmLU2ayQ(^HZ=Hu_q>a%37-=#?!L4y&!xNb6<?47RsDCYe1QMiHg z^!dO}Va*<1T{FV^oOv2m@X&aDoYr5A5vbh-!fF{A44t%s>u_GJNgiPg*vK!a82r3x zGJDUYI_M|O(+Ac-Xv8zUV{pAm;Vj#iHk28p&Vb5?P~gcTCoA!`6*Nzd@exx3?9>W; zFpz(}P=*leN(DDvJRCJs;o`LQkT0jgmO7h9YZzOJbH+fjW^HsiA62tWgW+j1>%mGb zOmse-)cgkhW4hQ$*D3yJutPOS?D;i;oiFnEM)Pt%*BGe5kf1a|(YL2Hk7Qn+0E@CY zSH^sge#~Uk2@+HCPSW3Y(@O!pBr9TtC*7Hvl+r;qy#7V5sKhHLLCXEd9mGYScK?(p zJ7lLeMF+Wjj2d!=br~n8mOTZD0>VKlCPhJ@IBcwVw`E$vjA-`SXqz`<H{?HEZL3lX zaRsAx;{6N-1n(;236cMc^7jcc@eochxXi>U-as%{gWI<t19{Rqc_*C7Jkj>$ZH&^= z=d55=V7Cu3gpTSEb_NCzhizA*;g}ls`};t#e%k#)`2;RuvQV>d!GL1H7EV4pk?EJ? z=u(F4cha@2v`+i@_?R2V5)_}oNiFO|@bh+VW<+9DUP^U@GgR<Z^-a&o94-&DNrHI{ zzP2l?Z_Fb?NJq~0Dof&H+|*cqz5_Yb>k;^qviyp^u~{G+BOf<ghWqa1{bHd(qbcvt zf)SeZmg7#xgA<SegZ}@c!eN|c3>q!YoHqES47I(#?JknEa8ag(L)26sAy#A3j9RvU zXxcD-Zj(N9^fq7Kr^Qi<<*?!2|Ky57KljT}WLkjXa$`NKcK2;euN!yGZ}1D>a<<PU zl!LkR)4KxSVA$A~xfY;qa@e4><mhRqvH*OL!GvDdXc4_9UVGJIA(Hu?L;86IZ#GBV zgqVaTx)H14BV87Ap2cD=Pl7M(kWLeX78R(~4`SfAdl)r+kaYyc^{4O|8aaR9G|;_} z4yy>)DX}XK30(jQQm7x{-|Goa?37$K`*+f;ca~5gtHNDfia!qsn=-8Dc|4niR~BJm z499w{2+dOx*PxW6I_<S)k>=Jb2<7N83*ilQmwzMN3L#L&@(S=edfX}=*y+zPe6rjO z-ESt0Kp4ToO^uL#f1|d3{r33fojbzMmVnaN2~N281~Oc3V(Yy5!NU6}ktYeA#A9if zNifrWU-4ku_~>W5JBojA8kM`X;9Gx#f*r%~&n;}OJ2;pNX2|C$z-DP0X(!@fwnsJH zdY2r}W#_%Z0L<2ZaKwp*g8Xo8l*qL?(mm_xCs^b`%)FQJ0n~kon?^42PPTj(XU2X& zL)7!VAp-rGoUuM$K?ED0dAC0Gu&bRfp&F)}XmoJBU$y<(da~oqK6i|w_<{^XBO(jq z{si_fsGU{bdo$|*+xGC}9Yv=unP;7{Gq7U6wvK6l69qQ@v1+E55e%wi^l9f5=#bm? za{twV-CLZ5Z1q@&x~~r#R)TBFeI;LC!lJ>tbRKpb1-qcfasIztqW*RQyUrO+G<Ilz z0T8Y<$9d4I)-H1hGR#1tEHX|=*pY%Ap`q6)yx{EgeRH>S)F@Ukfmp$UXZHu=A7JOU zX!AMV<>>Wo8=+{DUg^4?k-05hET$Z;bNg+LVQR>rU}Z!jg}E)j<WfotUH0N1v8J$L zG=k^t`rkh(fl7kGpMZ-cjq7cfjo@9~2i3y$!bsT$49#Ou9s)r^lY4&MpQi2^s+4n& zv-r99fmYX?ID~1h_Ji9(j3*^_sf={UPi_MNt=nY>PI5ZEeFg>AtLsT`$N*)$QL@=K zB()B?+aQ0@Q82^hvju%GfuY7HNt(GBVbmpx!FbCoTNS58cR2y!TzOb$en(QiR@=@I z5n+Y3AeOd{Uc<I^DSLqgo2zclT@dgI94n}6QEq3QL6vj#ABbZETbHdn!pzeOwaB%L zcz$Mk({<FP3S^V|K%pE|UwofV@wbQG{tP9knyr)Ym<BoLjE|IgP%}*2fFDzLNU<nz z^Yx*H&gc*1VP2C{o0YcNTTy;D5KhI|T@hU?(ohbx-APEgZ+OP&XaT3Ak<jX;gFbCs zrj>pRmK}dHMfyy<`}?p@14FH#%Q7+1xj36PYw5`fEL%t7Rhg2KTy>vSZJfV9^UunS z@_?4bi8DkeFn;UwsC(NPW0oRE6^@-*taGp?IN!^Leaz%w_9<l1o*9WR)5VS!vv3P{ z3u3U<(v?BWzU*YHArL{dDKrNkB5?4r*{ro2-%LbzT}q^kkS%I>JNU{41l#7-tD~CM zG2^pNP7)@gCsIpJTRtu~9T&Q9G9n^aDXT*(A&5Zksz}Km!`UuI*nEU0(w|4Sd08~_ z{4~`ZH5QG_6@CqppSx=_TBo|<TyV@|%!nL6M5uAyrT9F~@_IdkL$($kRnn-D6^EZL z&<FrG#d(<R3DJr-R(a|_x5&}*rdTXu{_)!_Mj~g1eq}MkFTz$9f?hj>OE$<W7qA-g zi`%@eBa?tO<nfg@Mt$-Sd*BKH&010+_O{C%bKqmnnE6@l;PsYokhPAb>NWOmmz*Oo z#=MHHo9!5n=9h0hry^1f{l3;^Z1B@vps~5)0<7-O;8LP?QOHZ92@7O7$A~!UZq@um zVPQ#sfVA~-`f!GcVj3pQXT(ro=G`J>j+^lyY*Nc?9QZ1tcW_mu9@dbio`$B2W|p1i z)}U^kJkw;_i0+p^zQ0L43PLqKpM>v~Wf3#U_dSGcXPVL>G9#3kO@4V@eq2XeV4?5F zC%oxtS{atyrw)_x8j9>gz}*~qcRQ5Qh|+?bUXF`zcB>S>8c1K3sL}muG<|8qGV7bv zvbiVInvyi%^6_i!*7K)(KE~9W%nSJ8-Ppi+klnsSq^OQ3*nG2gI-B<Jk?(gr1;5cD zBgXhC2?AcoMM!elYUPTR7#La)Td^G`DsE!R7^0?s`$obCOBwypnuO1m(rGxwtV1oA z`^SA;aE<@&+GlR^Z*dM1HXp~WNe{E-TI}}lE@|M2=-hO$GD?M(O1=!T-WKy-%uEGY z)j(JC<9!r&(&xJ1LtJ`ck!T50<VxY1(95Ee#3!g%T<el1o2b`a>uBbhW|(y04-O6Q z(6Fuh4Jm!o*icInvUperu>fLXde6q$G`^2c>!p4uMFCKPv%eGtjWus%Qaz%^Y=mzd zllhf}-MWF(-D|$L154&yeiZi%{&xiK06)xst*-ss&HrEi^|XN>L}e}^OjS}0pJs0V zuNUuG4gY;Y1IgxEMrKGj*N$YBhd<WPjJTJ?J3Pf35xayFt!WQ=IR1Cc`@D_(V{T>) zeO@e-W%cr!_aARXH0t4d#KVZ5U2^Q4)Z5bwR57?LK^j4iNh8%-6oGhDLGCXEu52d) z4MOP97PN&=W?O`>&;}V-ni$!zz-+xYSfwTM8F+g}_Z`Sb7D*k8s!ub&N(S~)n98bw zR$Bs7A#373OJ*K~7DKWq48Cjx;9mOh<h0&ngfs`YwN2T5m=OlUIHefU+CtgYS#k8L z(1|q5M(A41fJpSo=pRp;{IR8clOt5%Q^LJJ;}pnRgzbk%6=slXxCv`L3w)`PFc=WU zm^8#~Z}|E1Gg7=MEbD`Y0p2&z;bWEc;o_enk4Z<c1Rr1wqUi`D+|hj#+l?1Dg>9iO zo-+vOI|w^mFxV|kXXK!75rx017({RD$-YNCn)YNnCK6&mucJE}2!i=Ze2j-QZFWTA zrKOg6@Fl=Bt~~&p!t$goWorzx(mI=Svqz8*-b3X9Fidj~ubi0i``(046}QE!7uRtp z3}cKK^r1kI!8|aT=8v=c;8NyjgWF!bxiz-oSJ$vm;3F{zc!gJGx#nG{s~u{oPn~8D zLy{Q?P%{8i#CrPuBX1SxA?WknYpKLR7PGul31kvB%;rb?#})xcF8qF`Oa(>BX`~`E zOu!t-qP80I0fY4jblX)!p5Ms+VxpBD6vZq9W8_bLy%LCnU;L58Mzx_K5GS=5u@7`x zC(D}kgGfs?*Pa<eIQwMULG*(6k}JH;@u`*~ld;!w=5^Yt-?yxvuZP>V9f~*+GMTf~ zzkg8WF|Qe_QAeW)UjC+mF<vt~4BAK_)R8kb%W@v5E)DUD!QonB(`p`j>xLL>7T6f2 zC|qtHX{_EE68EYS&Oa7KbF?Lop&v~3;}Yog_%C1BbXW@={LYNcjNB#hl^N?h1D7zk zOx$s7NhwO-Xal1p@M3plkfB|0>Q()fP4KFuQQ4NdTr%z`FEGHuw61H_SsV89mNYz! z+UkVfz}!T<f1b&(q2R?!8{e_os=uxH=eoF=%xeb7k6;_k;+;y?DUg7hwOekku=@HT zyxocyMyMCopCe}eOnL1&y5I5fAAAAW3LCs0L2YSa%Oz~Ic|W1OX0myu?M-a=<}$iB z%-KN-BO!xC=Y!Cj(#U|ica(?|iv&o_YYB+sJ>C&F_J9Z9sITHZPmq8B)MULQ#D~1W z;a{KL2*T#dJI)%9ZjLK9b1+}JLvFOP{gGTt85HnXWbEp?_M$_uXsPpz0@q#Qjn=&d z(r3!TD5q2jWk5M1sg8u@V37a$G{rwk-$*F?3}FK;ZHXliAZf{Fg~RQ+u{uGoOg71Q zjPTTx7!1|hY#|onQNCMxeTCX!9Ad$9l{~oVTcDjwFRQo@AIM&^t@Qt6Tluh-b$)sm zd|@M`K(+(E(u5U58w@Lxr!tNg&m$<4SjP2jz#dQ$K2+_p%?|>)!r-g=Ssy;U0NA5# zb5n>}57Y0-&z;mPFP#i_*uV|9^~G50eTiJS)mxn_>z}_=lr;!cF_|{otj^WINJcN; zREVgvJf-^M-EzIGQatjH)mhI>8GTd>6Af+k(TbpCB8v>@uSpD+Jj^GfBr{bEs`%im zOBr7@Z%ACnLMFqoPCe&%vZ*+iZKK-HTk`vPZ3xeWtfT7oszvH4f+OQcw<uj&(pg$> zjx)e9PxcAji<cEIj+IX!>&R^($5Y=AP0XUrn;>J)4wSULEy*YKji*!r42Jld-QAtC z;sZxx(_r*XBMZL~l#^r(kFLLWOxA7mxZQn#{rIt`7jPPG)Zohg{(SPjtFj|u^=m$D z`A<L96mXz^3<l{iA`;3UJ4W9V0AhwDpETo0l;5aT;XP=dviSS$L2UUfRGUSCJTM2x zzvs@E3e7dc)mvqs?nvu_kit2`a~y{&f7S_v_vI%68Nl94>Y(<UU}jo@QWPBg_v3u* z{8McSLFqv3){~kNlyZD&J;(CK26ou0JBra7i9K6Wqt4iU*P)L6>T=`uu8WB+Mp(xH z3P3n;#X#FGahJ#u37%$Nb2o4eCR9=wl@YmXDNg5{!-v5#`0?D?<o<p@-^Rlm7~|ou zqG;Fi##A<2W(t`}Gkyt9fl@%RCu&nXa8Lykn@hj4Q?fJaQHkP*KK3~;6cRhL>3cb4 z%;ClBq0L(jz&46f4x_zNHOZ!fgcW254R_$gIK8oUWPfRTt&t@minzMMt%1f>OQyBC za_(ctUF95GFtj^32)=oJWBiRoQ;U$Z#A{W^1XM9HHztLlq3kK%JqSG}9=>ocvV)-b z>(Tdh5&T^s8OKmGBS!WIiyiW!iUUgQv+IH^%iu$t=Vtp3O*?FDb+scD|31R`rcuuq z!-4lIM96jYuG>na$C)GhWuNr6Em@|-caHedwc!lRDAsz$+=GWCU-3bj^~H=IpU5xo zG@^Wk@)S+z-bxVJ;KX^Q^%U_OYHU{rf*Wj7g1Weu(CpFHm=b-g?cw`Y7!cQyR`Ks+ z{Fk2yD`^5CLk!*5l--zAf55sqr=DZ&E~`+)ddst&T6q;;%yKKzz5R#!)B8`fGmM`A zl;k;49%W}-&9Yy+^G<cry=^8Faq_D_QOe2Y?dH%O)Ay!YFhs6KV|DRrR)zn1VQW~o zb25!U4-NffN->euNEX$(Rcw~KOVIaHc&u930)HX}5Ye3ECJu+=^Po`=-tU1V0hG^h z1-w<Lbg`m5_l8HzY>)rD8(4dqw*y!`Vd>&G7*MT5h*sIWGRg<uw--qvWey#2+EXhJ zH2s@Zwo-JP<mB#>5w;r86048sx&-I}3b)aNzO0VZdh!~vnlxuW8CpQoGUL_7eU;I^ z@z9I~%DQFsO3Y!90siCjV`nz~YY+QMQq2)Xu3HXK3lVvTVb;k0i<@C68w30&`+UV{ z2F@fR36q2lFr$nyCX(k^+jO6kX(#j+LU!OqIWD^=hduf~z3#oRfif8`fmIx#DFmlV zUYsHZ96P&T;2N3IH~%HA28`UQDeF~shC!BTx44A}^J(y=f2!>9Y5raKm!<Ra>oh3! zX3K43C$7KpKUKj;ZvVY6fDr$*dUnW-K~(6jcAjRK#-0DVgUBaoVrTr9j`aWizh*OG z2kZ9y=@v?g4q6baPsCXN5aQtup=xeUIQi!9O8wVsgsyo1EHCWi*FQ@0J8ptmU=K|_ zRJMscD>4so6=&c4qZ;LUsq<?;yXFF=9LFso5SeYe@aKNHC+MlgQ7UXeeJD!YDZIOh zr_STguv5048Np!CPWJ*UPMSXX9=n&p`m59o%o-0p^qg`CtLhK}f@!JW!HAjdonGSK zi_zE>yU@|}9KC7<BSN)D_669%4z9j{Oi2S>|C-?o=c`6vYK7~!$Pvc{lfnxkq|a-- zQzH-ho(PuvC!^WS8v8%MobE6~NH1=Ah}bOwD!0PQ%UPj;8hZmI{K{W;Ypu3624SZZ zBE+7<s^NF^TS=QkFac~NTYt0*WIF2?s9Oc_LTkOD2p)0ZA13TkH8Mz$TyF++n<}3u zuPo?^v*-|t9qTPC++OZ{u<HmJwD!M}|7f4nwfogk&>D6xPKt}ZsGrPf+J&!ZJin)K zv90Qt<G76Pq+d%pTmVy#F{2TV_;KW8#HG^6d6jLOcO~alsz&HZG#o2?=AXp?p*^bX zIfQdd?$o%mISh?Q^lI+c-|r_|#pdol{#g%F+3k&N$|tW+HBX=3kYaLn*n;<XynYI& zX%;Z*p2I_MTuhmi<a2qMr~VDcN$hQD33Vfvfi)lYXxlejELz|I=K(!cfhB;9K09~D zob_2FP-Q$hs>hgKVqtNrTFUWW&`v+lSZj{K93kb=PN-K!`pE`;bf#~DVZf~hBcO+& zDOCJyoc%ZnxxA08zI-B)fnxaT>!~)}JYiq;<S9pVJnR9eb$844LO&~*_0Bl0b!V3q ze#Y3cTg4;91FQsQ-wR}&jQ@UeRRt^XWA9CpV#I5f#JBEU*uqdG+TtxNK+^04p4PZ~ z&IF=-7z26pvJVGh^^BYgTnQfM85e;~lx30CSCoTYB3^%^h=@pU2wO@z&l@k&m)<Ta z&;SQU5_7%m;dS_Ln6$PkqEck}UMaE$f4%nfcy<H&6s?<g#r@?f1V|-uPJ&Uvxqo|| z_!IuDgNY}{d>8<jd>W&E`t+@S!oQWTh_amhUL%c-R16WmjEbS<TgBkHFVQf&M$Dqx ztk#~4jftFzgq^j)pknBDx(>Lq!~EP`?mgW?neXS@VOI}E5#d^<tk!fU7epLdI$8dF zp(pNVwqBC9nj%_@$wqrqgCr3f)8mE8-eWO|+2(vYlRKMf|J9_wZ$gN16DPjkgje*Z zOGAtD#|DZ^Jtl`e8sjl*pyjn?U?T4tBjV6iEkc5eoow630YUm@8^s>ky5HX@mUqpo zFY5tEiv!3O2Pg7gH#Ypx*}Dk2n^X^?&I1Sg0~Ko{mFC(p_-(XONSb@y&BqpFP2_<} ze34w({e6$7(wp=#CAhF!!5WW=H;8<+l<A8ZC>#?n%#o@gH$Z())L(1#l3phn`@$)Z zI34#l+Yqw6Va$XY3~g_V!1qpM0iXI%TTdDWeT^GB&{ThJ<7gt-DfYxK9vfq);a9wV z^i9FUm>!%<!oVoYn#3U-L`sL(6+GOs?2K5j&4UREb*$IcW3a8KlRTVKB7`>-JU`J7 zFX+8aO%5@bX;2sc<-mhIaXURA#En+pCO0|amx<wJDJ;DXoLcGO!C(eMk4q+A4ebDe zp5*}NZv)hmZpgRPv2H&BQ)roF8)RUlPNefh_sFQ7Wp4<vqKUrNWSnT6+*=)AmDI~4 z=bqDRlYF@Bb`0oHWYX>^%fx)qZWHe9;nMF$0s9R(W_xyQhf~U3^X8n)*;Xe|#}nD2 zwc53Fg-n&3L>KKa1Esl*Ol%+#79mn;><Q^oAFk<GaUJV2Qcqhaqh$E7Q;IuQ`BaoJ z4j9MF_QdT3J#6y@fI$Q}-;9PY=ETT=#1Mhw4cmx~3bAg^en2d7txKbXx~c`XV^B*< zUBl3<2Rb($8<KI|^}H%+%_th`tu;H)iV92fFnJY9EyX>&ne$yTc2DU1bb0#`O1bgG z0N3I$GvXFrN&-0uF|erb6Y9QPEL_J-pXtltyIVx?BU|-jpsJ(^+E<%~*n*ki*eDBK ztE+MG`K85Xps+eN6CiCIQfm%oPH-)Vy=}0GDvsS!G+JFSdJ{a$F{e{zJ0}wUs=7^( z(q2SWXt-}mlI=2PFwwZ&xX9`9H>+tkm*O<uEco@A3=pJS9VkWu=_;&m9!kOVpV5s+ zZ2hCZ`8GLJYDX|^bhW#JQ!bDca89<84#P3l9D-}}6t7NQl3$>O%wsT+hx&STVVYoQ z_;jRt)vX(e3%A63@md#yr1GG9yeev;s!N{2S~=DrqUDxl>Jc6lBD)MB27Q&=eSLPT zy19ie!yz&Kiq^2T4>Y*I00M#hzX(p{yO<Gq)RP=8b|0?m1rbYf*Mk|6mo~kazA2)Y zXZ=3U++H2_Aw)AaHiB(ar7m3xP82YPQj+D2=hXDVyq@hCUM+Wa$IlSc^Q3R664Sl> zj%>1V5~9>s#T*%qF;!gm<23^m;8+skF)<hl)?brz`>hzX1cy+DG>0&n)4{WHV~;NB z48eRZ2&$2qW}10$`WV6Qn`>#YY+lIX4NRkyhfWOfHO?2PA+XfV+#_!vU!!QERkhm3 zxkK<Irjx4(*9sqhcz8cKR|q@ktE7_5yqLD?X`SMAXpHgST7@g&X<W4zP*W+wx|EQN zwyi(Vl@9n*6+11V)Am@38<h=pR+Yj!_CV3(Na*AU4}G&k*{&>m^Tn*@IpJioSFYGy zZe2kx5DtS1e1h0JO8+<&2AA@dGduMA(U@8dJ9PE+g4{s$!`~9yb(uPXrcWF&Y-+#x zsp+$OTzS!tKlb|9?^(ctJ*sw82NN7MtmWQ18F%HYFUXv<I~2qDe*Hpx9jR-X2iBBp zeT)p-hU7jwj6esLHH|F2F2JhI6qVF6lmj;gSaU^zX@)j^gT(Pl7mke>*W1!kuocF= zs(=l^gYI;f*E|c(A&Y7EzrMp~v4r83RE^<4Uuk`?enW>;SB$l>+1?1%$7`&8v#16P zk+B^b!TZTOE%}&O|9aU;UVsx}+|6S)JsW|qNd9eW$Q=CPkr|)}E~98VVs$VvamfDP zU;V!)@PAL>|DM4A?g{X&18>EY*p&AhtzYKSvAhaZXTQ-Qf-w;Wrt9$iVRDQR8}4SA zu=S|ApAmnr=G<IU*S&zP9~0t9_D%PZz;niJ6I9{Q&n+I4O=Qm1MuHn9ivoz8XPEER z5O|Nr%gz-4R7fhZUt4;9I;$@(0W!CS<HKG@VWl59W7%>1#K1|EiV|c*=p^h4gSxOz zAn{IfVQHFw03Gz#3*bQs$fz2fgvSR&=jE4-TN}%E6Q(W94et|878%L*5Yw9a{-qw3 ztsY~oJi`IdZ41!%KKQq~k9{H1#xrT490!Bb6og{i+0OHI)g-6lY>NX+k35_r1y|&o zi&mq?m4x_F9FZZkww18?j;-Hyp70iknUSQE22q(1PoW&whc+Qqr0VJW`S|p_r_9CN zS^Ehmktk6$#p}jjk%Ildb?pv9RPpnJk`gEU2$lWr0SgF_O2ljT66aj=WzO&Cf$t}7 zN9dho=p$>)!Q2E>Itk^9K@2NWi&_Ur-C^9){fRgMyarLum6<|}d`M-jMh<CGU1#iv zX1zJm)z^9zTL0+=<ub?!v7X5!co=d(oMuBtaUbMya+5h{ulod!xI;K*9UCX0%B)3q zLtMZHxA`sWEmcu(vgpkG)cBE%FegWoCkOgg(Fg$%XtL|@1%kMZV8D8?*<;ep_L2zv zxZ^Xs?j+>6K96Tg`YeMe0#d%v>NJ-(O&T0NfazQtW|q{V=R|+%$0-;ILRYh>cGV|) z#1I6+4Y48L8v2+VrTJB^dJuqBWjop0UP^gX7&<w27y`z1C}YdyCUa!wn8aT%f_sq( zj_P-%Dykkl<4x~kRZqQAZMGdZ{zMXK_8xn_infv19FYFRw!flBKc6Jeq!jCfg<IdW zFXpmtCpP&8PeV{Mxt^Bwxe?fVSk!2B{|@9Klpr=E%`*5(E+0I!FZT|BwRns`d#Ya~ z#|g}gV!#X!;V>cM(cP}GQrNG&{rk*jSVxco__SgcZwDT5hT=E|C4q!wXk3b!*=vUH z?<WE-FPy@5k|ePWf{Gdla5xx!P2I<Bt$w7%5+%b=z#}QifUC<q3)z76T)}wQ*RT+y zt)5o>OMOm=Ga>G5)3wOxQPFWEf08c8kg<uu7q5x>QtQtnua6eh7cJ0w@P_NCcuhH` z2&TSO0<+ex)Y^A_-A4k@T3?Qepwf0wih$JTC|z{BMdPE&CzUG?ew{s7xJ(jT9$1Oj z>H#Lk*k8Ii<Y}6^xAtVq<nUxYeR5E4(xkQ#UZ1YUNqM6dL|1%#_=?VQ<6;YFRINLs zM6`$U4pzDB@L21>8I%8k@G?+D+Dz_pncNWGs#2!+$*9P?@XYphl=AnALMGI)4(`A8 z^g5+FYw4!yJY!hV(LjR+U#C7lRUuIqVKHVc9%_Uj<~EsjH_wgkQl>0;b=aUdK{MQ| zY4y_NjMv9}$JdRR3_M*{+ljA8l9oy*1k?PBQ3iR14X}RPX9JEa)j<sp)XDqyr{dQ) z%MRt(_xoNtI)3qUeWg<+w7@3$JZWz8CvOv5v{{IC+)IdBEgVK`cn9SAVVhi^wB7+< zI&F95VCy{Q<%`@dVLu>z^RK>h{C9mLraWE&JEH?R3Sqk~mcGf~=Iy$)Y;<RCKlDOr zZ!fdmi+FeEc4S00Kdbi9jWq<=BZ5xb1pmb?^S2flAoBir)Wb){c|?@#xYV6@zA$y; z-OrLR$05qe=GuM37K#y5S{G=|(-*v|yLnf4=<!TeLP1=$IP6PtZI*7BUU#%^+A_{A z&WAqwGH`o%NNujXpXLYfy*z1HmXq_%s|^bMXJPl*Oic1svX{O~UQ7M#H$iK-fhH-} z79NO0ZBenq#zklJ!x>Hn=)-Lu=j*IsbDj8jR<6!%I9~knrDQ99Wo^wrvqS7RIOl&h z+Wfg%henO_6)mm$B!n*eN}T0`gT=M3k*#@XszDuCvm_7s61lFfLUzWo!JjH~g<ZyA z;=F<3!5Sw*xEFu`(lc~&`PkTAaceb3mW4ci0)=bc7~vj>UYH#+<i>#^+w+d&|LpQu zec?YCSG<8!jb!u~9IQ?58aHmId(%G@-)y8uC?uR8$omqum7;pWcebE${s5OlZA^`P z%Fqcp)+^wmHQwM7U^6Bb*NZnK{#C!5H>Kb$L?ZQWn)2Z_8w563IzNx=Ugw|{t)h4| z-}I_57vPcrogL?ikgyq6fANA34l5*jRF7_l+4hZaQxYsA@wCc)G?7QU!ZqIJ!+}x+ zp7fo~vf5GPVPmCbSS`MrO7UkKs@ME~ntSg+toQeST%sHjl~Ee*wg?#+$+$@rvMDp8 zvdPX)=@^A`v}BKrgp`q8%BYmRLz2BB`wrjhy4C5N^Esc-zrWx4=e$q7@7H*~p3m!f zJ+JFA6qx+hTgc`B*2322A~GmCJmbtnE%g69m1i$Oy}5FS!_EBV#gSss@HbzUnysC} zwko^~>Yg#=@r}jtjjNowV%_wpDPstLe0e=7yk6mLUP8SO-3_PnR0oqxiV$b!{u;0+ z?lp?vqdD%YDahogG+Z*&?|C?~$h!+dSzXp|Fo_W&yDG1URg+M9W(&<xZLV!jCP~eQ zhx_HfO;2DCw$QAecbr)&<-*BP-YNA{tW@TYH!|x%nZuZ_pL71v_Gj}1j@+s=@c#G$ zpoS$N{Xfa`9Jc?!;5$v{d27w)5r})8V4%hLcv4QINc-LyP#buJV3@h~;IotEJtz!% z`Gkgi^RoGd#MUER(X+(f(0Ss09q~h^b)-mGHGF#C`00I5c<bKMPB>2-@!#pd!F($u zfgqi()_6?5cgv7?^Sm${uWUI<F@++t_Q2h)gJZu-KXhd38q6Q&=e}Fe^;U@Ht)Sr7 zLj)BUW4CTNgZI9Ff0NyH(1~{Ovy8t6;v-@*`TVBa-km%!k!O>ZqjQ*=7ahy;95zwy z*DWdK9zLxaQ`vgzWje2OIBBZw=Djzh_{))v*0H{N)KL}zNm&8=X2n(0_D};?G$m9e zX1(8OY=FNRY{f3YKkE}!Hv$`uT~t#7xaD0K2Scl?8l49(v>(+%Ia{vp7b@%L4=uY2 zk-&A7q1GGPU#-RkDV999G&hfcE^jL{RVTD2ovSxd?~<TDlIdi&vL%3f<4FE++1upt zc){_23gVmVz8kG&pv*O9&$Q0G)581<39&>)u-b14B>3jij<wxPji*rP&4wa>^LVn^ zM<%DRq`udA^YSODU2~@Wt;G{3&oX5o$|@o(vS71%T4Zal?8GhUN6_x3Jx`XFXiySv z)6$^bt(Nok^a*_i3E&{~LmnZ7D&4}uN5?WLi8*DbnfDwBdqYZ}+jEZ?dN<0PF>!*? zFOk;XI5mP;D*NZ_ze2<ESyPFnrKZzwR?Y-?DmRwvLeRCYjU40KL=FJ+Sm*xtFs^%* z3G^Oun?IE@i>3mt+hQ;CYaE`bEIlPh4E55?{A@ES2%1PFOE;&m86<2DSZs*exbs-+ z%mQ_tC%v!6d95`%<&I7lk_abzKUYC_#e|(5!e<6glw&u8Z=*D^Gdor6XdPjaP2j}H zS@3C#V#U}@9L%9#9ywa_$E-T(&s!*Bf#9hQ&dq6J!Z~l%f_8OkiS(`~T4cpj=2cXm zI_c-a{GzFhcx{5DK^0<s^$&k(L27l2C4xm~yl+W`=49o?Q+f1miW6}KJq?oyT3am+ zJ!JfF&qfy!aocYy!X`f+GAr|L`Wm75l1>dG9hY1Kf|DIbG&rsRo~<L6SXolANBzm* z2w)f6`N(#{9sA?Dc)dG^a%Yf^+bc3OuWFfsVBIqyiSs06;PX;*Z}>XmP_8z@*rGwO zQ9mZk5u!^Pi-Z>!7q{+Q)6)vp!fHi{h@s`^p)S^(jg3NsTelQ<XZ0R0FFDxe%y*v_ zBgrJ~e?$_eH(EgPcmKFAqVavWPI8LbBZ`BwtP80i@RwZ##M9Qw96hJ}hs0jZX)T2) zgypPLe+q8c1zc$W5u|s`_MleGLQe1YjYF6H_5uv7Hv`s&YqqDGBDE3ogQEumbT+)s zW%6g%-4P8il1?u_NsE{96#Glk3ak!gtF<`mB;_iUTQI*~B2?Kj$5|`){UNt2YmM6I z{ey0qjgJm6`#I^9R5)z*J3@QgcxB^IF451?DX!1uUb3gEi&GZyWP!D+wz-90PbmX! ziiXr2sL(xTl{E9eH|Tmg=ZxQ79c`=oalMM~zP@5#+F5@qFY$?DrEf*{<iifFTj~jw zy$79$2l8D@XBI*F%dvxNadcP|3P;&<4cvwkK@}49e5o}7%S{8iaZezggnI}z?395q zPA8$A-#2Dyb9d&8Y5NmjmmJIoPM4|UcP!xlv-D~zQ+gA``9K$@;&xr;mnKe*j>*$% zs%iH?9M2TYv4o~AS2W%=xn24Y8GfWuO=0&^yJ32)qq|{>pKo*K*FCJ+QK_?X)WfFf zGHR-!Ng40#cQ*+^_?(P6an(3}`~!a{i<5dv=`D^IL1S!Z(y#wX?Hs`5v;zGj_YSv% z%$^2JpI*BFqA|CEYnT+3u9zzv!E#L^C$~N;%F59AUikR4@bQW8AyT}PMMUFf+SZt9 z?<4RMzo@5vPO5@ZLNH_R3DMMxNDfOYb*iSO?OSP?q*<TiShrP(B;C7Yddy3eb0~Lr zE=5driIsvCW8z&2*t}~jitfgbuV8{%>2&%;%oe}ol^Mg83%Z#pY0}*#R+f+Tin`l4 zhG*C9@9Y+6nV<``U6kAkcVFeMYCNvvRVM*))tlQJ#J+$x6cK^4DuQqV;SDResp`GJ zCURwVv@N$a-f+{1_LHpgy{sr}wff8&CsxSPHW6fL8)3288#>fO_vV+MAAu+LZEd-$ z(3aaJf1pzcGbHEQC5_n&x=d#VSIiA_-*F5tC%Y9F@HY&|bw<<gI^G&lsH@r>6*MQN zE9;r*8)~!t+hhsF0z^q1EF^VGvCT=D95f>gqCN%RK2%KG-Z*$KZ@5sxFl;f_wl?<a zPA(bGhP3Aoi65FS1O{ddv&eT0#H08eR>P|RKo=@`ELpxeik%`cVdWYgXpt{TF{quh z$UFqyLF@JFC6L)#=iu#lHJ;3D?K*n)GW3?Mz2|AKH@?4_>tN`;pih=Z#9B6CJ7TA< zhb=Sw49nlD8LkSRISCL9#fh$BnJw7}lW%-{u3?=zC>|Zfl#lyG0n55yqlgeWnuAO1 z8{lzP39-_5Y&r|t?n*&de6s&WC3HI!fp2A%cNs)n`LR`(aiof@y}g>QKzW;@?9|Ho zpKIevBA-hMOiy*_ItYN%r!BfP7EV-yIA=~v;&@k}aZj0_^Jpw~vvO(D?h=O&e7M7R z4O|h2L3Do=j4lGs?)!Qt$RMA8Tss?}=MJC%69KK_D-MDE5Kj1z2!_Yu+53UeLMwR8 zrJMVB+cC!!Y;}y?C$@XBrX1Dy0mSQZMD$Ura*PBSoc6CLkGDH1`yQ2$P-78zO0Zc8 zGKf!yy71;@7bEE-A5`nB0q0$fn&Esxth?1)b8I@>!82hMwr{6K^W}GuAxgl#{rl2< z&h5F@mS{3-d!{Z`Ap<Qg5K{|1yrW$oKdM$uW6J^gWh^F5oK=2VzQ<g~M}Lh7C^;<O zK8*Zt3PR+sMI3VwMZU4da|Kw$0LcOgVm0@yq>O&S{!p71Kv^P{(*0ze`SHEnbI?ZT z2cQEVOsQw!9s<rY;m8OkW7K<Ya{wN0UJ9!26h3zKD=%R}tg_7>8<uuyWEyl%4>!Gw zP#45D-64ab=Lj9A_d_{tJV;e;c&j-Qi%CCS84B~_#KXeYxLhMLUBK8Oh|Dm#uKoys zecz?zO(FmSv5;p{xpDgo3y)F|VQtqc2F@%W2*%~DB&T&~FO@FCst8BTh??-|<be?< zH}TmhFU4mFk2a`KF3NjZ>z>ZekBq;Ypy9e}Zn1E1<?a(Q2EofC2TB3@F_p1{E9dc5 za1kpbRsJnV#{@;>#|OPS3$r<B=Qa7x^1d>tGK^98Ky$G~?vJ~`sXXNTb{~uf1ja2? zYp%p!{@&=9rZe#&MzR~I9k2Af7W(?1_XZ2B-(e?JR-=ne8bB3W&*dO5P?F~y^dHdB zKtK5IK-s)cKDa=Iw9P^PXyPb}y-y@drYaax#(i(NV*h>8fTIDE9;Eh!+?)Tl<WXPn zGdLWt<Gl>MI`b}%Z%VdjywLtrbo(>emw&DjDg}&R(+D{9D+0w<E+}@ib`MQB6%nod zfFHFi(_$yJiz7uf>n!(`75IY(SeFr+uM>TVEhId+qBc(Z-AxwEAOU+^0NL)q+`NzO zM|^9b5N0CjEywPejmjHiD<q3Mu`6>+cYmXj4o7yRrzC*6&cbBcMpgg-`L4R$GSu_= z?K)*_ua@_<76bS9hjp@3&L8lOaC*$Kq27y1cI2-(b)qz*X)BR)!xw4LIY5;U?CDVx za%k8@>|%j=33V}RUYc&Gs*<>RU@sNfMAbLE^zH;1M?#2%zMmJx7XaMZ%dPR%8BI}W z1rF$gR~yBuQQWp4*af*UF;<1Q>j#uNUq12+tza*Lp1qZ@rp12X>FTh*ly$REO3&Kf zRImu`ubitYP@8y9FZ}WRS`qvz?rBnjvn#REvDVE4=Oka~6uD+~hWuk9X-L)a+SDBX zrU<JUiB~M<&=TCHE26R~1qz=1z@5sL{aw!tfCf8TQUHc>CWq#&X3!(WRcJ^VFszw? zCkm*+k1BSt86Ax~A4{+ElUn@4-}iyuR^Vo!D+;;#1))=dWWt!kq@|swW1G7>%yRlw z44|k$lf*esfxvV)>RG=4&EofOHO0F553QRQiYvYWGTA0}pzGIOTeF4v3}`8v@;+(Q z_Ta&ySZ>EXD1vnao%B;2p4!i<;hzFLh<p&JQ392r_h|C>G>2WarNGG&%zb3Ztevt$ zLNupY$PXQ_Dj%ytTww>Lp-yLLl<pMkf7s;HJTu|F(h<!N2_=+%Sh+d++NpP*>8v*w zqv75R9t54ch@l};93sP7+%d#jpo~L!ONYi`2SF7ccGKP2y&Qjg<S?ub1bqi!Nd!8j zMd&(mG7Yx)f{YDtiz{?(i!YF}5jj1!sG$GKjD$}cOI-WwX~8nBVAZZpjC!rbWWsnn z(g7-WY0&j}=mK;X-OjAi5}=|*X3yPVS+uIx)H7bpfaCK5&Gji|?p9i`_|05d<oyP; z!*GxlZd;-W{M%l8qBF&;wy#ElRE@+G=R6iIFl!eE-D*Mf`2x$_kZt^?{;(GVL32#5 zF}0TY2e?_});58P!aLA%>_-WvZ?Fxx&rKx*qebX@O(U9M(6!RsWv5IH%0;w8aPJn= zt7orX2h7?Z{uR7+m()$RY+kn?uo+XEX!^kYboTH20q377A-2qCz@JsL<4#aT=WpBn z#1Xp*{1Gz$avSv4w~4!DciLE&&h8yXA&Q^5L^y<@Z=+|e7o0&AFC6*dh4%~qwvCc^ zpE_k!n6@I&uMy1Ba}R5YJdrGd^2qFZZfq8e@oRyl2c0G9iEa}4E6>edV$22*`1O_2 z{SPb}Q+kRmK+P5dF%bhX>XrnB7aWNM3^@0AYUmUYVA_HfkEj@aK~Zs8e;`|QXerR9 zWf!;q$AiAx2gxe;@GcFL+}BephHcL;Cs_9ldAo2`Ya5B?nt{(CCr?^L9U=%rMw2MB z3)VK+gH4l8>9SV)t}oGDF4SvKn7((-@I--R4jjHwk2}~irL@qOc4_RDy~LJvZR>~< zlyM*1VgNI!4nlKA69&$!bTukexlp^Tly0G+s2;Pt@_j(kdbe!pc$2KR$8KJl_9Wn} zKY)F`jZWF=Xu{>Ia3q%zGbFpT9OT@1lB{=vRqGT|l_K2>Dq^?-)Md_ogtbQUu0m^v z!V!zEqJ@mICl%K9=Vws=3!59(eVEa75LcRJ2C%RXhsA>=J!&GtcDRqTL)=4|mE7&> zF$FZ@V7)YEf>th~0FQM6bHYDf0F33HzT_U2o&rb(XZgO|SWX(gJA*(i=x99aT{~vG zSY!wtf?VoJ-~?T&+2Xh{VQgPytGVGd0{c~!I*_f9kNI6@qv&fO2bBF}DUd&Bh+|fU zVf8SjLHT>|sfz#!#YS{j$i1H&q{%#jpvjE<em2y1?YFL<mt^}`44@sd=zpWSa!%=2 z&tEK1R_~$hpzplOt==hk=!pEBIFa#oz6P-tH%XZs^GW)hB=0h)KVWO>)6D5txg z6OC?P(3vibHgIwKQK-GLu*nit^6mRZ&)U@kgi9UtWxqj8YKwoSley@pu~ZrxpUqCy zY5$J99}2`Dn?4VAuPo<zdU!kOvdCJL&w!v{>q^?QZ6RFUm^6^Z{z~`(SN6=TZjV@v zACIYkY9paaj*vYutIbG8CZPyM;XUzRv%E%wplWo6)rr&YQTeR`!;$XN(jnM7$L!^H z-|~t|PeoEkI7X!hLe>`Gm430|2PIYab<=$*GBH#crj1kTlP$l7#Bqn&X%r8<z@r~T z$Z2HCVN_L#HH;lu*<9C6)DKylUU>_KP+vL)a;scHCbtcABAEtXt6ep`8d`C!j)BS8 z+=C5@-BpRDA-QtB<z`l*OZ3cp;s(FlTo`FeyVoRghN#+NhpcdH$)E<W_@!C~IlaM? zLQyc=U`>pU0fGj=O=R#ExqD{{#UWVPQjB2YCZHclG79DS*yMS=;u8j%F#~f{pDR<- ze^$J*OzMaF_cPYz{OD{wZo`qf#cYFg!;ZMII%jjzcgCuR@zN-?gUjRf&y4r29#-Ud znZBfGCU<knbmlGiodPYHR8kEf5bFysjoLRI(*O;F6*v9PQs@#i;eoFo#4Nt{k0&-K zcrhlf@J{RHa2$gs)tJzb?ek3iJx0pIe`=<ePP-U@uLo%KING4^b1QoW=B>fneQMfI zQ@<R;0DHm4n~DfBg~eCE6rjkR1i<+pugc)VzHUhS8Rvboo7Bu=P23^0hXDM;j~U=k z2chDv)&Hl15WXiEuzx=!0hvAdJ$uVj+-q9xq)Mf`TL^=}V&hoGbw2aX4RW)wttYY? z?VF&ao7Xtf#4nHL7ArTXh(L2cYM~h$i#)2Xk6*V5+e9AHdVJrSKIxl35YX#62Up%` zGk)32c$#;RAYWNpaX}Y!V}vht1MdOeg@*Fd%9{G}e6OQvdy;+c0pY5RZXTo>A|UU& zkM1X4b55J?{}0x(_IKU|{Y^h7Cg8)or>+Ia?YaUg`ZBb>C`8rKr!|_mCqaiIHApC? zz^=hPSu6TaYrs68SX`09{<zHkoMUQh)Y4TOl_CdM=yR4Quf<{#=LkxCUCj*ZZGc== zxRZ9RilCchlfCvtY2cz!()h)rkaoDt3ZyywW?lMjYA0^jf6^VJDFCk!MQAF*NBV({ zhxypeFr9XeSrN4$={z_~QvKuUT$kE)S$+OF0ecoRU9XY1!fd?*dC7|KHjnfRg@`IQ zKvl)fTchziGFBl_T2E?+1(u>iC%OrGTIUjLAyinQUkzyL*sN$;s>W1YRXw8d?4pvG zK7`XkDE9IupC5!scNC@Nu7H$-wMe2?G6&mI%wwA*fS32Y|1A@;?g+qRx0dDT$PONt z>6my5x?${BYr7nGtYfA^7ASJ3L`BDcg9AIDs(*IAz;Vgu%|046;ftIVbw~BaIiAM| z+ZueJ9p~I^c_kq5wZ;BpP<y&=QaboMm0MI=y8Jhy_u3_u1OPueE0#V%pcJ<OGI1_~ zYJ_tnk(wdH`P2arw1I`*>AS&~DJkv3MV?<1<)`}n$3Hn~rpVskdJjz&vG*Ex?igpi zH@sc0e|qRc#z@$o$fCWVGM!5&W9`ydM$CB}wDa5HJFNtHKM$v<<j})+eec8e)|%U| zUOOxXipjIjOL^njXfAvcMb)0O5f+=mIXJpmS6S1(AUi~(gvmCe{Y;uI^A3%aN%PoC zqb#d_0C}*GK)?jJ<$4b<-*xo3claE?^=@72KJ*7ff_B6fuVFV8eY!`k;vi=$c19zE zw%4e~yJe``@u~{cv{=;K^haId%kIHh5PUx0-iIFe#}5szy3lNj_l&9_A**uqd%V96 z;r9Ch4u69DL>pp5NxKH11`8j>hhR6$E)B@G9M+5ZoHvGjHQ(LdCGOU0IBA@>YC`aQ z|IZxy6KAQ<m~tv@+je1_Y{~ZLP$MZ8?Mco`)NovZ@_jX^kXhHpF46c_9BT~GnYNWE z|Gf(wL;)jLwsvXkXh}2D4UVh6+f41_mf=N_XtPGZ-1Bxo3YB!5M=&@g2<~c!RO0@# z(y(9OZujjG0!K3$kQ^(r>gQz_6d1QEjikqH_+mEsgrC*UZ;N^uMS=X1Q-CBl7uyw- z#qW#(^XQ{bYBDO4Q435F@S&pxGnwO-UJ|cC=H@mBBjSBc^T%>K$Ob~_k;^_eG=qZ6 zo?|~V7O@rh;76cfF}v$!`(RzdSdo>kKC>HnM7xQ#aNsm8oNOqCf-9L-O#|{VFY#2a zJ+}*6)vRApeS2<(s}_;cJM61==f>7TjM8WQG)WBYx0Gs!xY9Nd16YGu*5_F_7}#yF zIstC9#%GY>23!f(kWrgWiG~lFftG}FpU%3DSqsUMOK(bqv_M!3welu9gGzpWFt3k6 z8Z^G29+^^Gc?WWva(zNfjJmV%Lx&r!HU@Kfn2#*gGAN!5-eE3t(__6Rt>@=%Ii&@Q zQ+EzS0ijij126@bW0)w1a&=V78%Eq_N6j(&Ma4d3yA2#%B-Y+D^fDg+GuxK|l)IyX zhQCk4;5{2rt76JM!VyuUT5^rBbW0h8tw?ik_y5W-7*MYH^lc6!Z}TB{sEWNu0zdDQ z83kqi=b%s5jCciu@7ifv?~x=mn?FfSL9GBK8ev4(crK%u8!y|;G1WN^otSlm=H7x@ zUd>0hi(OgtzmDX3Ev5Rt1{{oS(5c0TsTF$xuKmz6dhoMW>1j=)vcH+{*=ZI~=1LBE zNXcHgwKJiH$ZtgF%XHX`1nGk+(wREg3piA&Se@1m<WU922uiYdzJ5ryYXv9DAp@cc zbeK?YoQ$i1PUnNmReyr9^}u>*7}@N1pfWHr+IpLI7U`M?J%b%3wzE^2A3xwUq}6yT z-3PGT7gm%Nrsqo(m(QyHiW9pA_mEJHn{3iq*=p=VxdVad*2P;CN;xzYqJWq`s!CBy z?G4>IYp$rXp#Q}W$mHRS4p`$EfIXh$2k6ezyd{GC=fWEe4%r5!y38}488fMbPl5k1 z6bZktcVE!vrp_kd1vKuAq$DVzLVNlqM-qTnzD8%QKprzm`qG}5!LOTbmZi;@=<pJ> zt?!dN*vd^ahL53_H@xml=Rzv=1F+^2T+FM5_nh`VRiZ<+MCx7<g43IxfiJ%#bZrcY ziWvRL0&HYqaQ4fpK|A%ofWv%>yAZu#8bxIc@|1Wh;QWyzw?;~q(AmsyeCS0T@A;<m zDnQ$qBK&FMkK%{$w8BL^(aa~_fSi>Xm>{^hlPwk3=kqL4ZmU{PU9mX+hKd_zz9aXx zX>Z#fq)KZ#W50E9ObnhIj%sXrptHtYjiwRIa@=(X){!D|l}MAY(Y1YJq286n9p}J( zliSz0@^piXz6T?d*xhQ#{Va7YD`RT*gBh9H$foxlErcotAIHd{^^)59PIvT^bnH_V z3Z$(!F_A>yYPZ<YiaQ-n@$-@xtzm&uH@rEV1rEabC5JTy3u&bvi{ThwBzJQxxEHN= zsiWr20dD2aM4@rE&YGL|Zoy2gUqXRBK*^y3cO_($Ta$4gtv64}yfMnLbsUptjpwN& zZ3n~ECafN?gz9qon+LKV76(DZ=bY!(h~?Uisr$s&Xn2ftpEUv@VvvY-_HKN80X1Nb zUjQsnSHi-kyL`UJAe{xO2D75W!P=6P$3WU?G{jD=uJx9irxhVKYtK>M4rtI*hw4Ou zMnhE*R9gDUGFVj179jWNa2pO+YtnV5D%ZLH75c!5I#K#1f@6@%`wdQNt`4_~X-Yu> zx7b}Qb$=*Nb(1WJVkO$0Wc8n1D=!I$KIiJ)`B0*t(}|XTh!yr(XZZUu@PgK`Q|TTq zcApc1a%#;2;ki-r+%XPfMjG@?ySNE?#z6_>vh{P$5}&9PyRnAWV;Hxw_6Is|4I!t? zYByIUXFSz#Y#EUB=kq-=ApcWCY-!xufqT`Xw;r?#o28b|3Z-(~ugj0|DoU8p^0OMg ztN5;35NWiIyHcRm<71(kAtl2tcJ$)I50W!`6G1#n%`+IB=!e8bhf@+pSCrXW4zm9| zYZEv^(3F`pjST;#{V5aR3zt<+=O<S1qJ`J2$xWtQEns5v32IMz6)`xTxnGrV{d&H` zo-C0Nk~VQge}1?n%1y6)s}o)SoGklxDyO0P@*CoA!8|synW6~U%aZcj&@x!O@pS0O z>6v%-u^gM1PD`9a4N~m|>QN0p%b0?5>Mcgziw!YFutoFOg@EQmL#Cmmfc+QwZ}1hN zF63KqwZT0iWc-uyLbnsDG9Ms@lFi2WmgWyI-{Lw4-4OQ@S9Cr=z8DBEqKFwespm_z zu4nM^0`WVNFhqzy=)X=EZ|^5?gw?15D-_G9xu02AgTCKQ7!7EBTqx{O(LONgsG4y^ zj&-Pj0xI++;mE}R?T-3PK|mJT1g&u^;knU~W0@!SQuCd9%!E!1k8cxOm2DdcP9LIp z1mI5n5?bLBJVJc{S&Jm$%AM^Ku~hjPSkNk@{-PBRb^6ap;eUR*`{fXAiv%PF-Z}$o z7j|4ac(0Lr%#YRJdACI2;&@fwcAMwBdsTJ=yn{Jv1*}S5-4GixWur)C4!xUtnak;M zYQ(W(t?o7>x~uzOH_L$C%wIt=daBZCmCvqH1zu`<mmaCJ_J$jLP3;Sf&K&=|xz0m8 zI)gERXsfB`KLhp62;d`k6b{@a1fD7(v^+Fiq+AGv9Q2?hqZ?=yK`B*G!w$R9OL15o z?0Zko%iK59dmA!}MwCj$gWWp1tn`>~O5Hn+V2k0{qDt>GE1PjG7W);;jPF(%;IX0L zXL_ddo(Fhjp@=B8s>j>k2|=f_%54uMNk{Sj=KDPrM45or$Ts|^CDe`kQ2-CRIN$nj zXoENpIrqVCUQi2Lp?t@Li|BSLPnYYbYKe?%YP;;WQ4Ou^c6#=BG8}Y^Frv|JBZl_c z0K;EbQFV?dOaFcTKCALXy*OFMsr_MuDt7g2pszYTy)ps3{xR2m!=I0)WI4}j!tPX! za7{6ZTK`RZt@56>FB59^PIqoPK%^#8NxkXghy3{rY;!>6S<R(ZUrct5lU(o9C(L2? zvYj&&ID&!f8eqmEuk3e)d3c~Y96VV2w|4aDob?1yOs=lTE$(>$tvui}sc3C3hnuWj zhi?NJ31#fGJ<yc=)72gZqA)*5So}3hX+F^D@*UD9x3DPfx&EqlSDSr&fo9kUhR)Tj zh2n3qT$v2fS7L=t{VM|F&<hx;xPF$_-l6z5AV@;v!+$T0FbKIw9(O;W|M1MpVM;}` zGiVJwm0yoFYKYsQ67-Z@?=`&$?X8P&RLj*2Eij<#b$MQ~`7r1+T!9Q}?9wd29G=CT zLjgMZ#c`T2z4b6!ZSQ0m6X(7Hjg=2dxO4rZppy?b!4Z3T#fa-b-)W%66zNLY0Oy{S zTmi2}gKF>;c!?EJpygDq;{nyrTXTcUd0@!Vp|1s%fYI57^sD6h<?5?|b_<QqtUln! zAUS&g2|qCX{>PA^wj#a`+m?OmFvt2)+DW&iI!dhNBVZPVT<hk=NF8uMA^Wo;D)2s@ zF!%;h!6*+se>OfS5i3hff!U@~x1Y`zO0QWhD`Ke!{2~HYPXgqji{@EO;CMvxD+3Jx z(+{@HiPB%;EtEhQ0-G^UyCt^(RgkP3fMt(rOv{nqMs7AmkrIxE4i@fJoIOgjhvIFN zDNzMv@K?WzMqp17POkkwuPtXX_87RP&<U!_EkLCyB)VCwy=SEeUAr5!lMPr~7T+sQ zy#a(&{mE`C&@@>91+Hp1;Z!5cX4YKn+AeUKo(MkjMhNftqr@g3e3~zkHP=`z<AhV` zlNEC-M&{iDpq*+eSH1+q&~ShRwcGS)?2rI?D66U`&^4SmH<WHr+z#|X<IGcQR1Y+E zc7Q4TMJStIAWKL=e=Zzl>Y<3)0XEa-VsqMC<M6hEcw6vtf=NN~uiHl1mHp;i?=wl> zJ_+uNda2Z*loXx^(AcB_atg884k)J%h;w;s_)82WhM_^Jl`hpGDz!frp<<X#HnhIL zMl)~?zS};1#uF5`q2Po!3f*zXScDgYLBOz=(Te(Cz2)=WC_v!Fg4$?6fj21(u!Q8? zIu6x~!BQ|kspc}6pD99e@*WL%&<CVrXQU40A*y<3Gxz39L)$!C?|K)x`}^o%M*6Nw zxlp`OJ#^z+nU><)J1OI=v!$&+-TPjYs7@O8PJm^%#P;F4N<CzmFiwq>^R~7?!E`S# zX((VijT#TPLG6*;7zL`n02U8-Zjt{fao4iE@gOeeNt~Bop=RR=tFbHn<LU;$NX1#c zx|%mPEtM^U*XoZ>bgN62QK&TKt@p_2C2zMdG1^0WaHXQ-iJ`}&-_B<T)pcgUVu0+- zqq~CI*a-Yjf|k>)z;S>ed;{;7cCvxD4yE62s?89<0zfJ9HL821f+{wo;~Unf_`p;3 zfs{9lybnR;A7cThZZH}QtzZRNhS@0THBPUR_^veW{0NG~=sRq!ec2+;4w_-%c=+V$ zZG1phy+S5v`W2=x*dGL{Te$}mEoT>Cdwq;>1w}X}j1DNL`|uP`t92B}o2(gnCSqE} zSooLmx7=B2T5I?F#{tpj9DymIIw(0c#LLp5RoxZ}YBTu2v$nNhyy`y6^7fZ+T5;wQ zP9Gn=1howVe(CpbbG7pxNb*pG-te*pNV<V2&w3`Nl=2#AZd(UkMdYW?0EWevN~K;) zqpd{HH8=tt?Wdi8lzTTfPJP0I6e@4z_dl?-nunBdqO}FRg`Guz$qJ6-P0`VfDc?U1 z6b$ExaggpLNjz%0tK-T@L465=vHOk*Kf%<d`vvD42hNZ%SWx6clpPqN+#%Huo9YLV z-VM4G4=qIqE=*ffEQNADsAjps?m8=w@Ci#(sF5t>p^|5Vs*dSXHictCq-~>}g?Ys* zP?>B0Bo`wpu3XbHGVR7K_pSl$(+?ije_7rDvwV=GkS^MID|%V;o*U;V44mA=7-~?2 zTv}R5xC@59WC04gG4w8bG!q>h0hry6pF>Ew5r>fKx<0@bR-G2dtuge2X@oW*8=&F( zYhHsCnsuJd;_=k|ry&neg2IR*SYn_cL^TwSt##7|FT=CVt=*7A0VOl2djG}+Q}7L{ z0lO#9sg!?5z4ouaQ*ekJvuR3y(B-fbY<(L$AC!Gq#WH{{X8Kr*7mk@!hU%K%ag|b* z@%*)`epgjVU=bTGP$FKdm{PUe#e93_+~R=bO8$t0Gt&E^KJozCkr6-~c_WcAFtp$n zWsuotcExC;k4Jm*k;!YKp58;nH=`gH#Fbv{vh_Pe+uQj50p(rjdHOkH9L!nm!mY(e zu)jqsf?;<vqw`;TE|tvgYh~-0|7bdP0Y(6k5gjw4>S+Wg$(esZI9QG4<2-4%_+4^i z-=ah%1^A7z_4c$HjnWD|fjZ`XPOJCwQaC<FmSX+F#%zZXa35h5gxbJ)5_H^`<0gGR zOIqS-an7u#VHqEZ!l&AfnSMZ3k@9H*u}?sjk%~&0n|8BPPl^^1vWdxP&DLzPCI$sT zKu`A76{aws@3548@1=k;f$T%g&{=BoWlV3RnTdoLZw{4&t@p{FIqRm9Q?hC6Oa6I} zDew`b(E_cIWhOr@Vmkx*Z$r0b#P=KzJSDXZ0?6zV%kw4;K-0k0y4?aDcFBZ>=w<YP z0g#1<NytOoq98xJ4`ISJGdRN$v>Xo6ru$~Ildt#p2bGp^9Bt+6$zl>iE%bgU7V$w> zmLD7ypX@%>c%h!HDu%WgUV^-;DE|HuRlfr@stg(KJ(FLQ5uPg^eV0ey0=hRQy414z zu->b`)kv1MB+l*iGC*lb0O1vDv+Nq%LVk*>4cc{fyI}miX?#N&P`)P>$W>*%Z(^7n z5m<zI33LPFV`W0(>q(oAs(w63{@s+{uYs)k9psdg>3th5<SQ{%vQ8u1V*bKe%&xkn z+!F}}6a>TPfj7Q!99Xje3dkO2Ao$WwNP*$$hgLZM5C6y~y;S+9C*&GWT#i|NGS;8t zopL_2<}4u8HlJY{&Elom`Yd5?uSNWGW%B>+3*FBbSezZRMDa@eB;-#6`iKqBFPk_Z zVXky}CKEeGN1$G0|Do{fA|PYXZm}Ac_Iun~pd9;tuG`zTMcuyvyQ2VJHvxBW<F)j~ za;T03%9mefTe-oxrtUw70TeX^f>?QlK*T89h@9DgGj%ltT}u!<y@c2dsP5nSMqGjm zJ?CQduSebKwopq<WBVE*Un~-LrUQ!dwATqGra7byQ22QCaI$?!xKH&Zq>R>2Y<Nn^ zD73&^{cA$TCoFsF=BM-p)6Q7XXM_HHNBzT;XfTaJhdpRu##bpWX1D?I-hSDDd5>@G z=-`t71CH_4Z@y5bDHtio_gfWv&bVqC0rh?pwIl(5NNLudZGI8(m_qyBI&s}Yp+>0u zv=p+^0}9Fq$c5@3bd~>)%lRFn<pO6rMzz)i3YnKRC~Sy)Jl)(cZXY9Hj>z%Ts3{zz z-k!fhIh7F_oO1v5xu>%&TX^h=Dj=8xGsM~|&u!RPnLCx~NxnaUL(EMw{y-oJb9V}< zk{=-<zLJ49{sfV+r{c{2@_87=sfd1;&=VtsK^7R5|1~x1!ju>V!4IJU%oN0&KzA{s zutR+AqX|eA4tKsoj^HI85ao6NGpYyZ_>J-uA6kxmpMiMz?!&tijn`uTW@+)iz8%_; z0|wBG0b5{r1ntr@K|6O;4`Lqy(??-p0a|zP2RB6k7ZUdz;PCqZVY3oRPG<T#<G8a8 zTqyH{?nFQm8aDs;q&ZPjLPdm%`V<`Y)CN#27L@<_5YDDWtOZ@1F-w?~U*7Yf&Qd>E z3h=+X$D22o!;>CHFw6TZH~i1p&L}QR@5{7D56oXK!e>eXQ7+(5q6aKMdh)nEJy3QW zwHK^?5}PHw=U=e{6LBw1yYA15!++05|LAz=2)jybW~X`sB1%Sxm`A%8L+yO~3mvy2 z%@pGlc=BH(N-@&)a{yVM1kRclF-y9<8!o>JJRAhf=x&;~zFi?H0iPwvAv2Ws$EGlN z$byjxPOI4<fa?IAtO#&NZT-o_8qa9v#6IwtT82Tf8`;JNVRZ<Otp*c=tPxRJaN9W6 zvWgkJK>W|y`$ddqvmYJsb7NB>Z0=;ON+!t1-72{A4M~I<CRkOJ;P#!pdn$<FXHMHZ z$j0;EbNZk^!3;#Zk^o_YI10>=V5Xp&IWBR~rhzv<N*3S&C-^+bU&&~*r~erm-5~J= zr?oecj`gSd(QyuCAw>bQ_#R@@m<eEC;^_UgG7YRJ-r<^UiOcwW9c<!3mSY|d-2dBp znIH@Tut^x<E9Y`7?jVa*^t1ooY81j}?|5Q#ZQ&LB@_8grBk@Nj0eVUw$c~zDe4iDi zBD#a-$)D6{6;2LM((Pnb9PCM>-@`<(WoB{n&z&_1t}Ysr{jtNQ@I9Ixdcf&o*8Maw zrzB{4XW|(7D?j(cyrrCS8{-7-pooJ7y&ge0@(Q5(43Msix&QQr&T_8hGk`y|8s{4x z{)l2%!)0ML1T&COM+>8i$ei9`B16Y*f~ba)3aVpc*$q}Mc5X|ck#B|SUF=(YV~c-Q z3dloFYZQZyF4*#sTxst@wl;+Ow#%;p^wD3W1jLGj{4akhRKwBRxKtQjOb{%LB2zNE zJz1~>06Rdx^&yOFgy9sQS65UIhpw4KkF$^&jRpk6t=-E^+w|yRXwdci4ZeY&0Th&5 z-r|a*xbxDXoj=C#$V8a*H1_vv<&1zRCuw!@Lu9^T*$iOT?gK6O0bo&DwQd5IGmCy{ zX<|W|VTn9);c<`!%VtTfdyQ5_iXhtS!u)0nneD@UpDfMe((huT<v+Wh=D`u8vR%E4 zUxJ$BoXn%Bhya&ZjmnQni7K*jHQ1p798&3h<i&-I8ln&ueIg#fL50a!#^RQKQVq2c z8Fhbx9h1L6YJNi3598j#H2G*V;F5-g13fn!T9Ql5`2`y}HGuVK5n%sf&HC0MaM+pa z?+<D2$yDx~z7R+-6aMk)PsSSn@c2Hfa+f9eL~VO}WGTv}i)@SsMe*Dix*W=xR|Fhi zDM!q(<IfV-em1ZD3gku|`c$)wN$W;Vc@t{pM^?VE(wk<;mV4V=<m7+M{?`&0925hi zk(rBeqk~0677c<r(vvGl=+BAPt`3`9&BD<S5w*9MtWqwh#JQ|T+75+0IitpznF)mW z|8N6lSx3iAROvze@6pC&<(O=0^B=E8m^~C>qK0aEx{Iln&*RlX6HWBObS8>GtO)g? zumj&EFdH@7ml$@2ABxH8V@YbAug$AtrERGHb@Q5>vV7l6_!e!xRvHJEZpAY-m#e?* zlw@gO?*7e}Jdu4{ldXc^pgI-0ZlgZ|0K##;pjftbdM_gVM|1J88}V#nx~+DqbpA6P zN{K%M3l-9~I`SEYBL4TED-my5P^OR_;wK@SN-A;9l6CPut>tl$=4~*<=iiKDo{ApO zh8*GA9VpAVI|QEWsU}U7P5@T8Co`9*-^_fcL=5rV*whk0lG!%MSSrYpXFg`}Fl$p& zC{ILL`Z+8WEMc)l|L78&i}?PgJIGa)Di^Y=A4PCbG92`3_(9nJD0qMRYiOSd2pnH# zGW_TB%!mWEAt3T5{q3955!W^zs|wzEn~u#r1r!p5&Z==G!1|Kq)I+2*#pp@u9Us(* z>-~?l&<+gqD-i>{h?zD`jd$7sVQZCV;U_}RF7Xja+7&F8GkL0(vC#57G2B8*h1-5% z?bc+3fr$KTAPj*7Pmb<)^5^i(d$~-|KqX^PKn*;Vk!gXZ<Rs60kQ|y&#k))0R)LwU zQMD$Xr-8sx=W!tEi4y259Qd*Mt+-E23?V87WY#8gdGfH!vQgv{MMI9Iw(S|4<FEk; zRSg4Xjs7i^g~OgTpTvv$*kLe8^;rwU%I({zA6B5G{w@}ocUioR(t{9L4^^F7TVc6j za}H&Fw``|y>d{)j2N#L+c!Xz{h#<d(RnL+B9wb>+211pII#fF^zuwfv<zRxc1;~;! zVMvu#$>;=(Pp+&A98j!;A6ST|PMjvc(zMDpAMz^&mx-3~Xx4S|=8{CBA?07&_OAc_ zcR)^9r9}akz|A3W9O@K;<X)`PR1YRNNd4L!RuB`(XR@khO>u(h&KePA>YapPj>x^E zo0&U%gT^F+2VlREnuVDM2omGBw-1?+GoeFlz+9fe%nz9Ijv=SGse(>ly^}i!(3fOc za=;Stc}o$QEKSGg#Png4bC&F!X}L3dr32*b1oyTbVQjhsNGO3$^He|6d#F3+T6Ru0 zz%iic(pVwFkU<pS0kk6i;3Fe^UaZkr_vtvZrcX+OUGNk2I&uB1&dSNiALI4~JrY1m zObHUK_i#`t%I_g3Eg(S<j*w{-c^KOz=KT2Flk-<Q$wyQv^4M{NzNE&-Lw1kN!@pe+ zcCKo8f@&<!qK=-BRqH45%@T{>5gL0OJOBV~CV`$7LPhnns|u48but$yJ|sx3V^tB6 zyKQ&;lHA1lDNESCojsz!I<uo0M0bT5E~L~KySu1^PL%`LzCFN(ma~8`d9l|0pBI7& zF}qdwsc8VRc|@V3iiSt#A;m{(b2~x#0Og~SV6pYX6Y~T4LSXO7n@2$G^I1pwfZ6J4 z|L@P&n(F=t)CI51sr9;k2<~F|(hd8o^{REsP4Hnr>FwKx&(*Ixf;L`Wznx>@(K9pf zn3Q#BHTpdq#rV8<n8?N{LQi0q^X)_#O7dBqQ3<~kt*PA_KZom4>-xbWNui!vdPfap z$5+2MTu#fnib7}Z)we*B1d`$MU1^Y$3ShpC=0{^f<79gjN3e5`fWvtA4ltgZwKYVE z64XXxHE@0DygvD^6z$bjhmu^e1_BGN1{K$o4KJ=RRehqQ9iS2OlUmNY&%^kc{B~3_ zCZmIAQ9x|;ax#nXu-6#q0YB}X(gQDL<TYgzZym^CdpncZCuCm#IwK86rXQ?|_`oqD zJLb@>-xA4yOcdL!SchkHAF~90iUC!^H9A}=#z4e8%|dgT{Kb926e(CA(BJJT9Y=4y z#4y~k)B|(#Jw#lq!i(<c`-kVFE?Cl$$~qZ$GiS^^buybX$7;#0D_%5-W8`pof)$oy z2<0|Csh%B1Ka0S<qL2YI?vUJ|=3>d_ehIq!vs=;hXd6uKoswqrUwd-hh5Q7rt!EH2 z^qkTBaDZF+f7q*pFd}A?;-l2B>Dmeai0^M0uH()TJa8CR{8uJD8_;&%<xXn=x-}Qk z>;fh8AhkA1Ium7qL?_tvZh!l?dkd=xC1y!JVn05HFOW@7d<(x{Ce)OnA3@-tbCZ0s zg6*Q*B6Qq12hhuNpr1@{+IX}BQj#$d@qa=Q<9?>A5KZK+Zs3WPWh~<fWBH5M^J+43 ze=&LDQM}M!op~G@aLQB=3H928OB<k=k`z;`9|vEX!tTeo(%vx?nX6Pf#Z03rBG<Zq z6)v|LpynWG40OJ|g(oOfS1i2O1;oG6*41^CxVp}7NHZIXD6jsyd{@mIu+&@qb)MS~ zq4Ws@8x()x0}R~E_(K<1IS;=_lAqzz>im(3JKg9jtsXDs5Apj<r8Q7Ae#D@36cz$$ zpr=ld$gQ@MDEOtxAMA$o4=5G>$Y#~uYBlJ)x5GICMS`l~RA;_Xd|Jf;1=D}qa=<l& z4NXqJL7E$ZvVtJlUM^_e-Uz>bB{7SQ9!PfYL-VN?bu%x5&N<rF36lA%NO{JMRy|FN zyP?F>9sN*9Y;~6rPaO{C$L#|UW_Ml$&=Sc1<kHknL0!ZI^H*%07T&@`;sUfBMtj{d zmNOQky+KiAtjINWmN>ob3P|WHL9iMVy0t@;zo!U_f2~&_p<eZOL8ldH$baU(Fpw(& zg>=-i&P%_Y{T_!9c3$!lgdt?5S_q3yrX=_|oS-J3@6RiHuaLUmqvQ-W0#N`zqhOd5 zZ4LEbzGv3fGg^BeE!ccgV5b)Pau&{FJMRtTcGw8O8ZFw{a0yO9LO03XH_(v*DX9mj zY_H!1<8%IA9{Buh?-#^4fp(}u*b0C$;CO};loH#g!O^~}c?!DImw1Z4N^h^&u=U7` z8%I#L)$==Kh<uRg3xiJ0$6Y;V9&3;YXjzXYuJno7CGb}VBa`hEzA?=sR_!>Do}4?e z!2ho9+w?rJ9c-b4Y&AzVSz_dYxn4B?dG{9eI7Q&h58I@H_$bWxZSWrf{e{PjlxdGY z0OUiiRh#hy>T2EKCZ8_ErlSw}Or~m9WA1;AHDH46jFG<%jk%~q&JIrXq?^{Bjaepg z+sg)XQLz)xc!fGGfM|3}XK(k{*>Ol@>ftaOPnc(|d#sj3*5`p#O;rSqz1WflOqG5} zpmOqZ(rIrXEMtOPATRs<EyxI_I1*JxUAeMjrCNc_Y8rAmU9HFUq$<*;u|uWtNaGDw zNQAO6Ab36o^3Uwn0&K8+>QNrvc&78&DUjk+_FfEgu}wzTk-nR-djK`MI=A{}@&zCi zz#}dOhdgwO2D(*OaU)UX04cV10K8qY@;oQMp>WSVG$^(Ga7L#@`mpE4ob+L1aw5QJ z0R2Uk*gvU>0qZ^{LvqnD`S=Zc3nz2%r7vY5y{&{O2IyZarm8(eUs^NlGosbH?sFLb zpd_dOyDJ_`0`tzqj5=fUg<~w<^F8ZvuWBD3_zd#O#af@QktI7pHZuyd%khUBefitg z`$>4UIF-y_85U9|9Ra!_JR0c3XXr0O@o$R_7fy159^igrrOMY610cG<eyTq@8Ht<P zNmcWr2<S&#nY(!oK{CdOql82Bg^=BTgsd*N5pFS|5KL3tsfk%88v=qQ0a`w118#LG zV|SHa1}Jw{nd|M&Ir*p6H3GL-n~T>0Qs^mofl;P;j`@HYbbJDKY<t%MvcrPUSKt=< zQ1*d_IaDBEcP*Shude=7%D;D;Y!eiXx4V6Zr8&Ed?VZA7+xd*I(_0F%D8s^j5159r zURpCIf3qFCp?~$4%spC))5|!1%z^SmuvlWVl!cMwD|+G9fsw5mwFy%4y^M!;sBy&s zkbInNJx2#21t>Bo<0S<76i5KyeIsGInd%hOk(FRkk3N@SyJYtD(@W>$iI^WqoFM}i zD0&dXLVcRL!f{P#2xiEu2CIyf0)ap&x{?HiE1~bIDXO_v=eB3h<M#FeIE?Oxhq4fR zZqw{R>x0z?c6K<T(#teTS4><y^G;LS4qB-*21eDmp<iRqp;RLz#2(1iR0Hrk9Gt9M zx}O-yfVFA;m<*7=d>=t#)!|t$bQc^rpjvCwGVlkPGeJ>?G?5+T&HWc}hhHKZN-v%c z;7K!XvG4~k=UtQoTGe801ez@?$-}AGZ%HoQ9Cu<U6%D>`3)5);6Z&_#p97M?k+u1F z7A)ws=8xk}Fh!ePAu|M-ZZ&7J$fqW@|8AASC04Ax;~CB_6<3&DFV>I)h5(<RH9-8G zD~PoqDQi5z<@)9zHLXraU|;xsflI-j%iwWUEXrY;9Z0T$T;B$rVG$n|B2A&94%I@h z(FKR&m)NM#c+HuWMQqm}6*80S=d{xTTWe2pOF&(FsIx<WM$P5?o95&Nizpyh*B3xj z`cffxTm3QU&V$zPA!icn;j^KaE%%#FfJ7QUsK^$$kXNXW9dxHCU>Dpyy2^BYcY$#l zxw!z&sR*91f4xcWKGcBk1A(ZmQqbUC{y?-PDs`i*o!IO<1>Ry)oBTc&2QUe3zifcJ zQ_Kk2m-d;b4Wa@d)63`bz^a@%gnP1b9^|}Z-%ypw4bsrDf*Fay95%WGVN&v)VZhvX zn$5wDqB8@%L@KkFXb*mnAX#+;4#T<;g5%JW5b_{VxWLBkvzEq}(RsBxc<&uy5VfYz zl(Wda0(8N|3)gjPhsL*ffvxoHGSu)cPPhy=zUg8Is^m^7!`|$9VyN_<oU*zBxsFWY zjO<zxmqz_rLGT&;da?$<vv=iDs||I=YnmM36J5e0*hKOakTC8`e(zzp2$Hw6AfZ<L z9??<m9o@?)@z)gt=s0=+@vxb$#%K!Rzn*lpi3v|C&+R1GT2gioq6{)28<593%SU|( za3r~T7tl}VoEI0nQ)LoK5;iJOLNN+LF|TK&{T9@#O2z!1i;iH7N*peG&#o&ELRzt9 zk%;s8pl|_L<K$v3CfZQK=uWT{vo4j6KTDg4Oqq#YI6W!sz)1oo8G*(q`NckciZA%t zp{m%*(}Z{n6c6a|j3~IUh5FF2&<9~4F%%w-k=R=x3AA~AfG8XYNeL3=)^5BNDWO|} z^w|ND{wwpF+nh!~<ni}#^fimLe|xAOvY(ughgdS`2t0MQ7R3zlpaUGmOfC5=*iTM1 zKy&PWJd^On>a7!6ZUAFyq?OZuibC*(l#yVI!g`1%aAynr(Zah&VCpdhTI|K#@Jw0o z!KM*BhE)=tZWowYU{Z`?zqzu1raV-GCi$3svQk8D%WRO&+SI1i{*&GM)j=>5c8Y4k zW*yquH)(3Od1pTVObe~MXSHYAOW?Tr02H>uQ3!bQym29g!+U6GxJ@v%&W9D)Mev#2 z@Ko%~euD+;GvYHE9n$hpove3jYKkauZFq|8SkgzNo}emWu9&Fb88!uZc-%%1?^Fl5 z^l$KuItGG4Rp2(Sp+v%qlbtn9Afs{Eu;gP`%rU1&)}D!%f6rdhsl@X3NEYUim^OEj z+tw5|gw^Fcmc%Ga0&xIM-J7MLx;_RbD8l51dPI}GZ2H;8DH&4FBk-g7oD3+^P96nr zQ>Fs5E5p$lP=X?>BR^@oN09f<gtgxKq7S$WADPF^HteAe(YaUP{cR-)6r2&xyDN+> zM!t8g_}3R}XS*GlXe^>2H5EX?3T!eA0ZH0Zu_H4ppiw-sY>$)r9O^bokWXBQr>3IV zNT6v~;<kX|k58gW9U?fAU}&8o)4dy&{8jeaBq$aw;8FV`C|f#v2}zJf1v;J%WO^^9 zp`<8eLqSn1P}v>RiLp7DVC@BL&T3z3y3tuP$#_$2tL53hotb<*=K#fuuHyKHr;um$ zc6NkO?p2y>3^W5hklg)sB`S7D-Dj<~i!6L6D7=dX3cIOf19?>tjsoz?j)GWgW1$qr zNrRpfR-Y2~6a-FL)WuyTZ5K2<-{nQJ?pTZmIL1XN*mQB#lOQlD!uI<f2G+W8O@k|+ z@JG9Ao{GJNX8IQN@y#4>%pwY%$1HSXILvCjP6X)mnhgW9q+P1&Veh$@F$Inaz!(EV zlm4#Hx`L~*O&E}e7~7oHpNH|#6u>ktcCVNo@9aPpihK5py657<{ajltZcU<+M-gc5 zfta}d&GH+kI9rqHP%?a*0GKUx6qp$524BA;O;|ar$V!v%cpTYRvu72AmH_11B`}xd zSqfQEkvsX_UuZ(E_KCtbwzHA`tPrsl_!PFN{5a8d2HLV&224|l3FCd!%jm)q@eK3* zSsE{ZVPnz_arp?OaZeFbpt^ZG)xv55vpS{@E8gxd-yW1Vt+U(uGVmdX)1gksy}o;V zX?fO``#Z&L4`Scmd9Fa6SgRK2Ewzc3+rQJ_-#4h0MfHT^?$f^VvP`=_N!M=O(;n-; z&tm+ZJ3m9f;=XXED^Ah*JR+gnE=^azZu%}FAk8SX*40kJ$j;7AYc~quXL+wI+gpAF z5=xM}kf5N(cz8SDj{;2&dKd0@a&jsMSrio;O**3c>}UW$F)N{f6f`opZ%kUnvS|DD z@7_3TQ_j#(no%%(I9M%2#cfz}+zXmL_Lh2vhK84GlH9?16tFHPfYa}5z7EuMA?NXr z=WKo>Hu%Lhn^DJYa9EbaEL~$S)fz#mCdNh^??Tl}&*+I)x)IU@&ju?hi1ZbxN%l33 za253(B*<s%Yo3pfkGDc0D_>KbN@-bK(CM<|B>EOp%A@@nOi{!x57HtnEfDgrwJi z6)?29H8M050Iye3RVAN)$)dQpxLn-bg}MgLO5L=IT2$|g_L#xJy?o+5tuQ>2&+v7E z&pJlm1MprK9>eaenSXQ~e4(-cRc3GL#%oaI50>SXpueIy9`L#ALxk`|x+o1%{r6Zc z3X4tTqT!=0z7%Xy(1qz>Z0zo42bR@2OjP-VgjiZK4MX6-R1SVv@AmG2#0sQFY9!yK z&%sxLYWLYqYuBzV=ZybO0+FDRtvh#ehcNoK`^CDfRS6>JmMT$<RJ9b+wb$Vd9Y4Pg zIQ!hr$O8`B<@um4%e`Xy5!hifU7}%25IM6zL1<4uHsP|MLAj@2@c@<5_1IL(e_v{4 zvu{20m3v_i;X8g@Z#>)%9%k;diWtML<Nk2jazL`b72k3__MyPKSeD&b#ECt&n<jS6 z_1NDurLnI38D3`+(g6F3X;`pKu#%MXkBTkO$9>P6(!8v+kqCp{rz`-&0{{FRov-tg zy`R~jz{3bf8Bg2821OzOqg20%?P>A;&PkL6=`_6XW#Zw?L|@HV@S8szmH~a-3*W8$ zZDLVy(&k^6gC^kGNhq`BdY<oMgNh}WRs@(a?j7$gHGHgLeh_8^^lK{MfMWuAd=>}` zwZiei(ZxkhTf60;n7!A+t+>5%!Azww9>sbFa_YYk@j;v5U-Wj6-sdvBI~W4R6lR9^ z6Cd-p;3pEk-2TR71Wb1?mFKzHYbwFC*DG@6b8~b13?P-5(W-^M;|?XF6OrBqatHGP z^jhS#RPgaZ^xr-r1G~gcFife$RcPBAdHf1LNC=0Bc+A_OB9W|BRc&Z@^qZyw3+-8d z{PD-sXkMSp?6G%u&Rp@#A3l_DI^)Tkmh?W06lJF`-|eGCyCYpbct2v+b;^O-rtuC* zFOLesJ~A9w;~=cD7mky?^$!)we_yoiEYLiDq^3#g)vH&0$ByYlFXehv8C=@--2SLi zSBT!ZupX|7QzxJN<FYE++S{(`Y`T>6?@Pjn)^&Fqo``?>^5y3afo;J_ZZt6rZ6k*> zxhCWcOuE8~x{7$OjKvK98jq%yl&118jE!vS)Vu#Smy&|mWn^R~0cmW^tRiu^#&&I= zMQm197WuuM=WAgRG`kAZ{P;3g9;|=y_=^nuc@iBly^dBI1k6~;(}8nJkiqAi`CM)1 zk>wZ@*c7F)D<CBc|N2^|d2SQna30LV;wWZA(}D9W*9jD#5+Zo0a{j(7C_Eg;q-zV; zq{yy@76^3|5(RH|gLGfxp1%f_f?fYcZ1}%^_wSkRqw^~!{Qu*Bi$cb^$sMW*UCv)( zpoz!}a!TyNHXr?A3@ZU0_4XO=v=8vrE&AYlWI?jr`t*VVfGtJg;J3B2v$L+Li5Y<Q zN{@B(c%Z1>VtlkVO3cOh{CNTp`OigTrKt8WjJOIHB$q+!8FszyEObf8%;e=UDB3D6 zE`AvVhDD(C5Gn31l%bcu8T5T`VxR$(nTe@s;_>Zpf!K5KX=1gej@oW>nYv@U?b_6g z?KZC|O*=TY1$K3HJ%@7Oq;;$wz2NcVI}#ES`r6<}6z}o#<oucDZm+3Q5v#ZDcA6JI zO&@J6c!|n+dwXvRShs$CFYHXRB5q5IPFIBBCsNO7h!j%krj2j5-oAS9no33VP3di3 zH*Vbc4BeA*&e(yP7}oA}Z=0k{OiccE6TF)v2YCj=!^*5qObUvfr^!=>f?`mGJoDiC zzpn-=3W{U5$;%%GCl1~X|MA(lpFExZKfRRN>lKOv%C{)y%+<-~^HZ{CPGm@*_x*om C6t2Ah literal 0 HcmV?d00001 diff --git a/documentation/images/simulink_lqr_sensor.png b/documentation/images/simulink_lqr_sensor.png new file mode 100644 index 0000000000000000000000000000000000000000..a1ab30ecc1774ab7014f806f0c57274287ff3e59 GIT binary patch literal 79787 zcmeEuc|4ST`?eO5q7=C!R9c2CEtVn_SsL3I``#+MWSNYuO-dn|2q83MCt1cev`Hnz zSTYP{i5ZzmS+c+9rJnnDcR%;@{N6v_KVP3uAJH^(UDx;gp678M=W%>*VhnY7d4zd5 zI5>EZ>mI{$aB!hHIF>JRuY%tUdmj^pZ_B)~IvO1LjawM-!^(3<4UTef6h^I?JIM(@ zuRgD9<;}st_X7E|tj;s@3<t*|@%XW$rWftM%yT_3HA`MxWQUxaQc+=61czJ~eeo`w zpG#0skaOSm<Cr5gH_iy`jpBQldE@^2m4X|u@I*dDU0Ka_?C41!eybIS_`KGy*8Agv z@W=1$DMp39u_={Y;bGQ6nVJYZ%u3(mV_|`_fFBD28s~SffUEiWb?N>#!t#Ipz;Q!V zL-NlbE`9j_|MYK9<IIWA@8T!l9cZ#-_fST&GLoO{PQG}hcBmy?XWi`glts5hCC^g3 zO23`K=|3Ojk?F0-13q)&<I~HNMvLP{?UVpq?Akbod8WnWd(Cy7;evbI>SJYY_M(3N z2aFmw5&pLMkG&@@(fx;#ZhF6dxnkYn6H`3_1@nV)A%zno9lK?bc!ICDT&V&a99vh+ z&rC=VVw;1e=;ube$Ye<q(uZuboDFfmmUi$e2Ez8vWg+{Emoe7bAwOP-=UNpxPEK?< zbQ!776UyLCkS~<@H3;iVYuBUeBa#0BUzapAQ1D@|IZ}(iEL|A#vK{~bW&f8CM0cNS zyY%d2m*>WzNgb4o3bMbr(--DvZN7hQ7$qfoJQ4A%YF_AFoDGqd=Bymvho2oKceUr) zjIu)(1Nw~Da&VxR7C?8bSx3B6eV(drm1kYT$4#2%CaU;-IWN**T<k%oB?qt$brqe9 zs$`{xiCqxCy5E;+Dzfj?u|8W5e)KYqBY!Yd<9kG&Jic~zx@mFFXtsB8-l3~H=(kV! z6pHmU-kT)ve790oJk<v-(2tpwLA%1a#*Nio?pG&@`>@gI@TYu}GizH?7RGmv&`MmF z-rqPgzk0@{ayac)u1j0C-=|O^+VoIL)AQ%p=V?PXHo0Hwh*S-jVi_Ecxis9Oi>2)T z(pi)-KNYg5v_|i!96nbpXuP@f%$p5l`(=<Cmm=@Zb_D|d)~WDQ4r&_CMD)E4L+@6t z6LX6?{OyJc{n7D_Q)4gIsTboXm{y63?q6m`3dr<ITxBz9jgYKQhpPZ{;7!b^XUJ?K zJ@9)&d$F@gj!8!3tpa%M1?mOHh_I4}K1%D0D1JEAIpw>wwDeB7nUEr{er*lOQ%6nW znO+6loB|b#-$NFnM15P0S?9NpbQBob!jAa47=`J)c8g=;i^hEyUT+KgLf-em#!#8D zLulq3KRRS0$DzF0eJD8~Uo`l~C&i!{ADrFb+k15G<f2C9`XEzo)xH}N-D6?$GTrau z5738vnXPYLMTnf+xZAK8He;)u;+fa$N80leCs_2ZnTe4hS(6<N=TNFc54>#&Gw{@= zifd-?Zkk`XY}?#FCRFnyG|#H&dT1z-phZ2zRIoB37uZwqy{%u55S+OVsIpcQxmSd? zEV3787r%ro425(Lhj4J5Kkw!R$)Pa)tKZ%%3ACUt7q9TZsWa829s@DsnFgia5Ao-c z8HRfZvi4OUm>mV|M!gAUo8DUD9*g{98;|nZ2r<gsxB5K2INA0mXZ2=3g^70$MQlE> zOF#mxH=DSu^L-<CxH<<qW6@})_eYzBL+6vT_1(8u9ckr9^Y22^$9_#DuN3wx5zI3& z&sOnm8Q%UV<FH0nTHl-9DPIf&B+v>irc_av6%(Gp-$iiZ3cLkr*{Iu61ZFj#sB){_ zWQ(3$=loQ!=Q_0?4|zot-`Ta-goMBX8cCp66ECUP%+lH2i@KuyGjbu*^}&l0mov8$ zw(BD~?96o}xt+==9#(X2d9-4A)^3N?)<itny2Qnth!!LtwH81RLT)5OfOqjKb)V1? z4=S!KNY{xfEoxHha(`Dj-lAuR3K~kneM!3|`($#otCBwhw&jI%eb?5^Pmy-`!Fv`P z(EI_{uus)BB>Qe)!uKM@^v-5v|KCV*OS4ha$a3f+d*Vbg1+f&~HevS)?;%4Rt;l!8 ze5(A7ys+<!>%2F;r;nnvQnwS9FThjNxrV*A8q)oxck7WI{pHwB0$#qs<Bv#wo&WM8 z8NzkWRDsZN49^dE*_OXOeNB`Mq<jG>4atw<sRCZdP+IqqH-EhrDJw7eQi}uEqm47U ziI+mIVPEp63Y<i8(bfaV`mI;F*7EJYTprXAC{F*+KbVlM6D2nJqd&@KibWrVuq)*f z54;n)v$dXTr0(w8kzdk~sMOV%q_Q!}hr>(bKi?m*<?WHCWK}E6?S(#!mReQPP*aNM z9`oGug#t(B{`19aWsQI4xe;D7KkDh%cXKyQsW-6y6r;j-WJ3qXjg1=4Q0~((ka8Ef zi8mxPB%fb{P&?wtO+*Q%3K;i=wiu~RzYLxm)3GVPaJEnQzhB`@&EnMJF2iM?GB7g^ zixUo$b?OVv3v)y2T@H&g9WNC)`mSND0WP3S{~^xMS|}|7EGGAVUPMATCL9HEx&D8- zY*_TI|9P>EA$ro_Hji)<0cV73XrVagBnaChxry8xk#LXSMo5DTJO;6Q>AyW!cwigg z_1g%s>og>J;BkG8!h|3E%bpF#LiFy0*t=`s1Nk^5>0;l_$({gq=i`$vzR+>KXUED- zvrXT?rah;=@FN}eqtuwlL>MOA_8)f8pI80lrbkN9WPDqeNnJi=(mKa1C)N(nAWEyn z*2`AD%eE+BX%94}sQ0!PIHdfDn9)RO$^NJ1MV?dVF>-{667Abyy?f(>LyG?2&WNb^ zN#BYZyd_utm|Z>F__-nR9E90p2-Drc=?m-8(R%-7^>h`R-RmMnWn*2^uSOP?pLn)> zlX(5}&^2_nUJcnGQLz(=^cv$3ZsO~m|FDUP@c7V>@^&N+m*Uv=WGK9Ke(auxyPx{z z7xqJh{MUP#zU{%T`W~s^+0$)Z>~s>>?G<K_qDHq{K<dMAb2^>z&}XE*fwTLJdsnG% zZ?BE^?LP|H0Y>-tJ~OzLbLo&ft@x$IkMHd^p5?p)(;EN$X~ctr1e2vS3W${!DrE08 zloAqbAD14bMnkG!Un8I)`t^5#5K~LHlG2=Kl3|FX|8mB;i3;y;Z+3UZ%Gh*!84Af* z6Mp2LFwMdaUgB-v{owrbV3UveHe`?9so?pE4tfv*#6}xc*!qFB&lnV4*#4t;H2J(7 z;^eMj2R8hB#98xD_>&KLJC@4`Pd5|wglwLixtV8Iso3A|&w2Uh-nkPPhK=YG5bYiB z_HOc3QFlHz^zqqMcK}cAxmE|rDD!G4lcjE*`$xLVi)ItxK_Q5x+nFAz*xHt3(Igf! z=Y{M1`sqcUV?zQ`N^>x&&zFhhP9(&=o$awlxp(9zCHc{uCkNvkDmq@d=9j+`mUlYg zSu<Zc8yI2Q_PQ0SR%ds)H$CXf`_vVw0?|kRegDO3cuK#G(RPDNR8>6tR)E}WDx&v2 z;?Fy1F)>nYYcTZsQdn2<P%@#S)F?%*J;y?Bq_?J~G8dp*dx@)s(zow`vv6^ekIW0~ z=}G2~#~tI|yGvCi`+trv4Vv{+!j69hP<G;K$?`kZWb*I`g`K3FX4=7+RP^W`CVe%# zWLM&HuLQs<y>6hZdZOKCHSxw;$Q{Q_s(UZ?N3a(4tRh$22}8X^DG>6lie6EK08ZZP zdL#O?;Q+)SqqXfCmNG4-9$W?cr^#KqLFrfWdFy&C%klbqCxfJ^Q$)qb^KdDw8L$3V zqVfc$tFWS*lR<)fVS1$UTj<|TLkorLxT%qu!cW{8ilyul^M1FF72sOl7rv)E$OJXP zN{6fgnQ^<6fZKS;QI*QWU!Sf3Sa#>7!ZY}7wxT<2;5k+~E7f#pw^6biU?QI|gSWMY ztB+VAXdB9BvB03{YC&|#vWctf)Xt})1^vJM>v4bMA+`YWCV!&cx|g7V8-Ab4s_3u} zXb5c~>c!CjDviogwLL?z?gQ_gjB3pzcBrz-`rQD1nM28#@)zdC&yCf^NfKN%dqr{G zpB(cuEerdqjdMJ!r%59FQZdQ^{c-XCx`A<8epZ{-qI!a&JJXQsCMG;{hLMrdeY(<v zUNH$tbEm9KtT4Jsc|>~3xY#@1&y9-*@WK+v&^wCSN!V_Uq>o+%A6eW|ESB`a7h+95 z+xxbevHo}{<Pcc6hA4dR{PbWP0+c>(Cu;k#XeITql^vln7O5m>Eob!A-Wu&Zmr?>3 zRu<ud589)Lnuq>?9@IK!s8GwgXJOCqDA2mKiB-KG&F>49q85R53NEeZP1yE0x-V<u zuoL|Do)DU%Rd;Rbit`0jTjW`qVcJl9Y>bgwXZ6C2>y-bIZAhaH2+LWLn+Pvo1La2G zln>R%lQx`-VKx_P#7J68<&s*)t2#Y0+fi79HdOc%5k<H28EfE<%K`hC9-jPgdU9cw zT}jo8mG&x>M?Tif1vRmW(`2-jMCBpk)%_X|4eh9Y+rq-EBJBQE-eRv{&?v29D7Lz( z+T_(6cYXNYq@Hpx?99)sV!ZFdfbK{O@s>)S)$$4)n`L-TQ>0VSPSqaO_Wkn>iO9zi zQHSq_?%Z&zG-wAG)^oZeWZpuB@hGO-*^_D4uskj4t$=~T=^K95_2x{Un!m)@H7rDb zD3snC9-m(Hu3fqZC!ccw9qG!CNar0&T+I3so=^=BCuGxK+<<#w-oSFU_>I!aMLDri z#xt-AU1#I$9AQ6@p<!vXi_L@bwA*l5=Mq|tKcbm6`KYVhJHz0?!RDFCQP*{czg~i% z37U<Cx-)A%UY_8GtY6{u_aUTJafi0WL-=4&R3MM?2Il<}*74&x>)}1HV*5^AyQQBi zAmIklbZvN(+FZjOD0{~uNZv-IiIGTAm5P2z7g59L?@-Tu>(b2i+ZZaWvKOnMD`~e- z@frTu=t@t<gqMBQ$Xf0^J2~pkXd&KoomAJ((uoQZEoe>mZBSuXQ9Wwr{Q`b`3Zw61 z#H83Lm(ID9>5eisrN!);#U8ckfsK_T`IX&g@nQhZ1(sHCwKRcQW{ywCEldw}5##Kc zq*;I1A$gDi&sry6>{|^F=F0URCl^k)h6DwcL1wi@^-4jsZ;GJmx<do&ms<O{*nGH4 z(*5b-^r&2inqUu3jwR@`ts-<?$N{9V7?XUBIgKb&lo@6YeYO`;efh{HY0DEUxcG|K zsn5Mn>KJlX4SaoPn+I1XY!lcAB9K%LZ@q(W32iau!6vBT#)q3dD)0O4H465S3};$? zS6(%Ld-H+rOi$IQV%{%64!~aByVO{1)J3(0cL3fPHop&hW8@|A*?X~z;rZv1d}AZT z)qBiyEl=8%x)rJhOzu#VAYb7jdJi?0#5n|aj>d~jVytt_Wys4@l_srkav<>aFTq7{ zmY7!Pu<h3_p!-k_JcNxSr0<=rk1f~z4*R?OyLCzjin{OgtFj~6o1>v=sKI0pMf=IW z_a?y&PrefI{4&+;LM27G_g2$Y&+RfuIAdYwdvDfOHEui_6aH|i^U!ZkH8uI<(o}|Y zTAc4}{TJt_0Li%^eYB9?#OM8}Eb4}xYorKx56VRQm9@n9IX)?~>@!Kqz85^dEq)DC z-yzHS{PN!}+i@3XyqGG!?6i~%<r`p(^CLbT4k46=_yctb^3HvYuI8xFt+m+EfgG!A zOBb%}(S2~r7C#WJlZ(D5C5s`dk&8u%z9a1{@05@Qe<g*2$UV6a0YG7v8p>TGnC#PG zF2xxn`osujs>j<?pk(;qqhRL(3(*?WJr|%a;dSHbffj{M_oz@>7p##Lc{)|8_|2`! zEmZ?|^>Qx^zHP6>v0t9s<bhIM_|cySsKwb+eFFE860KU|+Tm9hIpMVOYk!n_^1&e^ z=1|S|MioV%mT+#?qAyl(Lx^2kPk$a(v-tv&;;G6u%*I#NaZ~MCB`d~ZOVgc==UOKi z5LY_z(M}vkzm;aU4w*B(jl<&5J*4F;;ekP$@`R5l9x_*`05|W|C_Y-7?d&tL%7jXu zAxd5`RGU7dbj8d|BGZ@{ehvR3U^q3528o(ISvK)wHBkk}@~QJ{-XAdOCKOrHa^EoZ zI(GicjHr{uqsd_X1+}c2t5idkhS6nNl-s~t-7hP?Z_WYeI{Bc5@_e;ez?Z_8<)?Ut zX_Z*@%1Fktl{f#of<GIIx$D@6>;Dxb#SpUy2He?r&oF?R6tXbQ`hiN<j(GdSG98$z z2O`ngPf062ay?r^?76!|fBss_8D+<zXWFKl@TiH{ffLLj+*hDq%cDtTx?ds`G2@(B zX>0%X3C7{sFGZ|~MD08FK@)9$FL;&8?&R0i9U6LYdZ{GItT>9aOldYhzA9<{JA8&m zs9gR0eX8chAv8H~`hwE-v62q^qTa=YDUUO!b~PUUu8*5r<t|NCpNFi!e`GLaaXMw{ z*0r7s&sXn0Q*7+<^wKg9pS)A&F#_l&74~8B*sj+phkOqW+|g`V;4?flD4+uL(T1sA z6r`ERlfR*TMT+3^wi`Ooiuww_QRee=%8;nM3vHv##%wYKbv7G^+x~AC{I!bjh=Vzg zSNs;&@s65>k~Le7E)*Gw8fWkQ0V$1komV6<3WX4ZDwZ{oI{c5m2^-^EjdiSmXzFe< zp|MZAe|Quj#mlG(e4Rj~z;-XaFo@29eM`G{PV`nfz+P6dd8w*hg%9ATbH5dV-x-ql zT*#!)@*s=$*)m9mNiOsXU+)YupcRL$dm5ng$<qkskxfSMT`3f@mkOO@P!h5t<Fbx0 z$2OuB6mqpIWUY%)UdPXW6Gca<%{T=>I-gooO`PXbTb%P&8q9x}q=Iumi5|ZASY%)J z=}6Ld07SGz&uWIDMUHucmRb4OD-k=CS*EC3U|Ho_Zl1sHt-rA-F}|oa^=^dM+hzFR ze%Zjs;tjsgX;ez$3M!aVxCdBu`6TyIS_!>_;d<q;b`~qdWh=5<gqLMS=L;WV$n30r zra!ocAax{T71qePX2ra_fD()lJfO9s3!w#{moz&AU}XhLMQBg<4O=(_4OZtPQ0c=X z9-@R!q|Y+zF~R@s3e7AbqMLG0)rN1@I;?eEG^#~TE8^|FJzX}Ql)<#zzUw4^-YcX_ zGB;B&33}5!#G`Y3`zfAK%Jm*dl>#dzWD&#Izf~7%i-yk{@dd|!?=&H4`*h^nmEtE{ zlnj{1cPE_zuFTMO<81)xHb}cus1G%JL|eEK60TOMex$p#xz}nU*Tw<%$7mffFNxz2 z%&glQht?xS`G3mh?+gHvWSuP(vVEq%4SHxXs=haR?=ei+Zb5D80Z4MzTA+p5mNOI? z4}5?oPP)GEbR7+;ko%5a6*jOI)^I*wvqJRr<Yg|g^BJ>KY|qoLZhK{14g_xCzisBU z=p=+SE;QX{Lhbka@}b$f)Xf>$V0C%#e2llWx}zM2E$=ym%$KOhW^K=U?pCcWu>pN` zR`gwhLj6*6hyVKV*(4BE71SeY&>bKheaoZc9$}BWJSrP#WKU0W_k}gLnzZT;EDppN zb>H5WaBs)Pf9gkf-N8tO6M60@T*o!1X+aMnPu@0`Q&9b6tiSGDl|FRcL8Ii};E}$O zyF2xk(28Zk^n)k&Fv8vJBk57lA2=$_=aWnfRmCLltozBMh#WlsP!y7{N8R4ocd<x) z5(82^NTvGhm4D(*R&GLTZPQO*QT)jjMo!2c2OtrD>p{FM5W&6<l`d^kIGb>n3U`2j z+X<@{Rkq$qJN)aWA+h-ZW4fzx+s1?|4s}u;*L^89^(&X4_um+!)$#;w{?y{R5UwM4 zkoF^S7}yte4d=~_gX0PLmTc$Z1Gc;ViSp3bPW557X0bkCt>r_Rb>blp%68#k)e6~V zu?#2q=g^959J-?OtFL)Rn`d4q+LO_h>{#SJWl;2mZE)_%;~)0pA3FC2nZ-w1#OJxC zb*+)BI)ai(SD*W|j`d?gd2()PV%93IAqlni@A<$Opcm%WCK<P9S2z*Kl4G8i(DnYF z9_^wv1wZk!e1+tW$UpXN_maK%3%d*F+BL~21Qa;cy1wYOvfOX)*So)CVP^2K(v!Wt z)F&JN1B)8tg)->b`=Qj`MnpY0u&;Z;@!kEC2otVCIoBjs2^q|Ns4>Z7hYOU%TxTkY zYyR9kGHnF(b{Yy^S2af2?~7%Q4LKhnA+E38+_#<itHeDP++$wWv|2cofC+cnMp)%q zS9GgEt^UiwtC!9VC3(BO3R~>=d-`^2QRyFP!>8%NX`?dIq2z%8M};l6uTo7#)@PgN zxn!gSS0s78+RS<r+t@=1uzT6sTHgOEq6o0RHOx};JbSBIc)EF|-)J|(v^QufDPW`2 zjCCkht9@x~qMmod?!ud$$e2i*@Oc?P>a?NtsqzPH0_1>keOKD6R=+SCbs8uqXRExY zp0wgO4L)N4muSc&2$H*(2<P}*yKbA0$obX8L5bc}ADBpR9agMfTnNAoU%x9Ras%4A zzp~&LrOb1O7edTnI$?Nt>=@aAK%5hrH-H93wX4i4eZ(FWVikc3f)N>CMe0`o;J%lQ zQavGCd%U<G=`F>R3_Mn~N|MW;wGpBFQ%(1r=&-{jRq6xGKZD>Ee^lF5prvYL$Xe<} z+MgoDRB7{k69aF45*xy~4V2Ft(Z-H8%KBvErl|8G4`SsUlFQ`1V|E!_SS&CR8huFQ zU4fU24hJe2DxMr=yrnoQ0&2v)A0Lh&d+#qy^iz`}M}v+(FqY%heSk{5yPmfO$Pcd{ z+>?V*_8G<qjiJ-{Q+R@)6)0Ef1-=Wq<NGRk#_2#$<f$Yvp{vE2u-*dMWQS^ViiQ%x z4tVc0V;AxGOIuDHuee&bUF;fU@Kw1e{0!f$B~)IP*rat-$K(&!mDd!R?wwC|dNqCf z$xN)eg$Z|qMoN%=SK@vwU~DVk^XUQ6K1B{d66;iJIzw=*yXZE@w5Yj|j@HAwZB71t z4)L*^nVrK;<kV&Fk;j||vX$kVfU#b9dw3$hkJ$GKpu)xuQpWCnJvqvNVS#OVi<VAp z8xTt6S(7czD>Uom-FvFaRbsPnw_9MPdf;CMBfapjIOX-)kz1V4CHs@sWS2k8d~$K@ zl+xKQ;5tr17a43X6p>)Iqb)|e?xajqG^9}=w&g9aVb4fpVrGD(V+lPk9{$P!7^4(M z?Bzp2Qm{>4<52D&9)DUE6%jH^4)Ly|$T12pU;LexzBClRCx0tp(?b!DvS(uc1N>9U zdF~RxyT=)$c;5oPa|6EeruR-g@)+7%(bdQKiEU$lZodUg|6bJ!)S@}5fwBi2-<{uQ z9qj`Qz~F^D4olpau(XEc6Mj?FJb-}7H7Bioq$eQUC@&*cz<WotG1;AZSaA^^V#23u zygIttzq5x;Ko4l6WR4)+5*=X=p*83To-5uzV7@igbizhtZH!RF__#!3K|>f!V7p*9 z+wN@(YzBV5X(TN(-T9OJUDN2|!;`XGm+0GPKuC*RYxw~)fxk^jo&vk4f34-YiL3<r zg>E#~WSOfouzyH1<nhS)_%8kXA4$ITFCQMg+U-74mJ?nS3Ka@Cx}`u`kM7?slsXR7 z4S9D;;I~Vgb)a#r`CGhfBW&8G;rwYEVdfEk5;DMXN0PK>&taqpnq`}2y?i(g3@2Mf zF-KfH@att2zZ_BrvcC}q^rq`un2;H3pm;Z>3UqEIyfTv2V91cW`xZXa{vZhJuO@!I z^?NlC({Mhyov=wvBg=?~2v>EX&$bW{YiF2v@Ni^wc0?imlIu$bOe>}!$!+F*Pclff zhA!6DDF`G0^zGsD!mCs3p|3fI>-;g+PuH%|fN2{{bgn|zsmM(ni>b#jWoW4Jmm7`B zPM}et4!@5PzOF~F*_c`k--6IW=oJ6Yn*&(oL$>QjVfJ3Bzs^JTH3g&W)pu-moN7e( z)x5s85HNN*@6|Yad{$*H4B0&7vvl}}p0ANBW>7PB%Syrs@L!>R6(g(;`h%Xd2u&f| z^Us#WZA3@&{Z5}BhNV1)k~w@0n*tODLhwYVLKjd{FIUs8`cy>0<&3DZ&j%s2MZPUV z@gqYy$S_XUuDip<2cZk|v?GK)j%A}h*anW(vQ}etmu5rGkD=si=W8;wgzV0QiTd3~ z=IgRgV0QoD$#z1lonoqKNKtD|`X+a7^g@^Gp^@Aox0g5gZ=*sze}6P%`*AGWu1cII z)J<+;=uM3EMQ)-R@j8~$d=O|iglnCAEfMtriM7FS*%x8!dWFy>+k6qKRynCdzA}y1 z2RMl*m8^>TB!|LNp=MdwS}4Gu8iinj1+%cFEoYo8fi60VlBsmla6W!lhk(D_YIA%C z;kn#zW#;llW1k$`@+XNU`xWkgK0pYbqT@Wy-xmi0vJhz+C;M*6RbVoy)^SFpXHHkS z)|L8y|6D$*Vjp6xUJj`F3xFJ-p{w7Z6Ssj@iO#4Fnx!EfKf@Ms$<N@cnH!YLgZ$>v znn9`)RmB%qdH{m;s};1cM8Nq(f=9<1A~NX_X-1f7+#I&nxU=wdSO7I`_d}<vBVKi) zL)G@TgiO~Ub@wk@AYX%l$OQaM_3R}7@y@=t<C+c)ZJC8`Z7NSBZYP1&L+Of@wX5*l z^bS-~oygp#ZlFUTs0SG1?tr6mQuf{r3aoTDsNcRZcbzKVwq}{o87z8brRLB@_8wo9 zrh7-TTT)tnS{c(H=C2zvCWq)oydG5N<7zU{vUpFabi$UhD`=j#C~j@aigMAghMZOA za1b6&PS>m4f=<9peOM@pp<x)|t*VE{mq(+Gwy37wW$ZVo6<PIrke724*KCqTc_nPq zkevHHUEhcsfc<B`S4IzI_H=gcd($Y)xqPF&kU}&G)PdR5B4%-opm9lcp06vf7<E#p zR!xo&x#dtx?K`EOi!bm~tWjCLdt1-}lV6;TR3}=ijnkF$Qua_WGYBs+`vcz6CPgi% zTmK;}bG|AvfjIemC0Ry;oHsiUo3^r``3M<k*seR<G`lY;g|-3#+XadecYwQoJ^n-G zDRwn_wGIZpf&CFm6<zNyDF+3SmTudcPu|wnXfNgCwZE+=q_k)2(Vv7;i{0b}+b=C! zv0>;*dW0~;Dg70+p7#z8rA%(<7*PNK{VyfK%ggpLi~Z^gSBXvtZQT(xQu(I7uug1* z&nU(jHUBx$vs*ttVe@xDVt#RLxmMJmEe9NLt4?)$=eu5H_X=wE;zwj~v^7M4p}n|r z$4ltl3Ir()e9=W0Yx)3&mZr7Frs`s$iVVzY=<0IsTs|h0@-oz%r09??E24?v$@8;Q z<UIvdEkX7rE^U($$rG{&)xL&U!OK3^a@K^TUkCz$_nfB9>`dt{$eXb2zXr)I?-+k9 za|oV3yOaiAYeVlanxDpXx*5F?xuW;*=j{Z;<inkmcta(Vm7spRz>n??{BAIXGlX|I zlTdy9<Ze+7=g-Ca9n!UVaUbrqc6z_ns53(oxp8e~7FGcFH^lwOX#Py&xcu>d<QrZO zkK8zgZ%V9c%sG<He-9s(%(#IykO*K9<0`BY1(YfM*YSmzlSUE>6UNUl@;vei1m>)Z zvW<a-3Zf*k%5KF-MX4{8-AcQ=1+C)CEbd)A5g}lplWH1mA)qek<||%|be;egKDV!_ zwW)ir96?q~f3XLB0X5Msi4a75>6uYI9A&WeHlQV-hW?zY!^7ac)Z@g6z`E=OCRt>2 zXv?5VL%uZLJ81sPiYv|#8i)#p?Kgg1ecHfP4G2u{)U2~h;<M3020iSqw%xsZ=K59l zQf%wn_Ms=p+0a~oAQ5*{?-oBgT0ek)WZ!up*~QoEQ$w+%&AIo+w~Fm%Xe%-Ohg6$N zc0VzvDKwZ^IltYVH|M(U{Ag&BD}J=i_0#Dn)z5yGUlCT$Ji|~_$*v8C*z~aon1X&x zjso)h@$41~7gbxpZUJC)WqnI1Hey#B`*>k%*Hzn^-FEq1o-L1Vs;r7$Fc1F&M)Q6q z*BA;14iQ{V-^7U*3zhL*O^Xno37n6JiL$!Z@|T4=f|}=&BZ$G&+apQBfA=eW&8$+D z)_l9J>wKcjQmt;^4m*}AMVsUjc7YQeq)tg`U(~KOHK627ja!RPsTn=Pc5PHx(Qu&Y za7@`m$b0z;W$9Gy>r4cj(Uq^TD%)?4t2V(-2r?OyvX*jV4pA$P9ABZ#0*t97lP_ec z(7<vnpnTTIZFji7PMlRL=&amxpz+`fq|lI13-jy{Ph@-m(7C*c%04m@6`oxop5S58 zwPm~r<;Dzf>UyG`9((q>{1WB?2}a8a&hlmh@0<Y5`R{{(LUbQ|ld}+6KCw>PpT?=q zO^pApkwqRhXh+b7@1fO1<<=8XX*IWEGh*Xar(!zEBDV_a+efrK2_&xKeLg3~67#D% zi@V&;j+t()mXX4Hf0>sJ5So|O5maR_BrjM-HYTTyY;shWdR?#|l!fI-pZP?rA(gKs zz9DBQE#SW=L}9WiqLBGa$*B&Wui0h&kwGT)sQs&si&RV;ZVI!#j`eJQ8zThJO7}DJ z1|P4iacj*qW>xs4j)OW2XQB^<dXLxfPNE1sb0}$fPlAGLcX(BGlYtVQP^RcjtGC`m z!>igAI~n)2bQ?cv{jMvb=p!xOylSl$cJy+71fN{>kF?qH-3AE*`5jGFr)qhW=G#Gv zM|aH*uH$(F<6ViF34fZ`v2Er7zPA)VTolpwv1W%&%w$RyAFI)sm#yk8XNB1d`J{|5 zm;~G&aUD-K?bR%}JpCg`3)C*Z<W&4z*IGg_1A4rVk|BhKRVzwUVzpJax~P!-u==>n zwWIGdr{<0}&-zDT8|0;2GF}h#MzD%lHv2<+eGY^Z(>u)aRydF6UCC;<0L2D^s6e+P zoV!)2f>Bz<Sosaqky1BJ76x53ACf#i0Qc304S~hf;{|-CWOG`%N-z*br*wRIb;wa< z!M;jb7Jq>1nB3`bAf&%AWl+nZ*FU=RYJBa)hLV(&gVDR$xr(z=MRk=y<TqamiM7$j zHFd%2i4)ebW&0yKZ5r%RvxOQ5?wO$scu3!qA2`*_4J{V+_8%CAVhF^6Px_s2{OFS1 z={f-?@vxePHzx6|uR=yCSxTLFlY(XvK1RmcsyX=qo?bcqIgvhgP++gXx~gW28Rdw~ za4d{k=RL-i@8J)n%2#7Gv&g9X3(x>6Zzb46^Us=obSdNBh2u)fSe3lCY_s~&lXK6w z#LFa;$7j-q;`}yH-v%B}HD&7@#@k=4dwE=`5BtohDTE$L*2ovFThge0x-Qb)Z^w?3 zPcSXm3<PR%0GrYwtl%<0y7SFXmO64RS)8^^vq1c8>c@*9?JS$k)XFGHJ*HBmIy0Pp zvq_4iT0-ef8K!jXtJ~5a%qLUfN#mD;igjw_yU*+lWw<z)9G<T17(I;3OgcM0`<|^a zuD<gSfr(4)Fk#O!*x3=nc+n2miYt-@oFI()mrAPd5{7AH1(HCTm2nrz!GG}H%bh!^ zxk|LgJ{j8QXqmj29laz{Z3CBkS9`89&Dew;R<AL#6EHTYYO=VA&%RYQ%lOis_=wP} zFbS**m{D~`*s4O#q^~+aPgay?Ojd<#p&cX@P<<R%tXliH)V-^sU!Rc@_sGzM#A|>r zn*UZWmocAA+nUk!UONM-ab?#XeWjHyE3?gymGB#RQ}rr%FVAE=>NSAx4AO~>oGVmG z>r}q%Rhj$xg3drD*n?YdDT?j(#I%0{iE)!`MPTn3wfkC2;^$qBJ5c8vKb$J{CtIbY zg!e?ux8>IN^<5-Ug?DB($5!Zn_E4C;=sxBgr5z(B&n&Hqj;{=_HY9hr-|URhA{XTi zN4&{S8>!fo6jJ8oFR{;MJUy-Jo2<>_ydV4J2!?wq9M%ci<&V_pe(}oas;U{Tp7Syr zn`#+#^*^gMcEieU!KK+*%Z4r&VL1Qdc}VwAYgg+$^Q%x%K)9Mt9aA3{a<?V}3TWJJ zSA{0G)6Hz-Pvc{0DWLeN6`!cQNE-I`ohPIz<<8hiK4Gfy9j|EMkR&uxzU$2f(49+% z5;i;XI^L^lm9vIMCvm8&cxcgWac*&TXkILxhba8%(Y=f(hno~Cq^BpVv<lP{@VmrQ zO`B9HyId25DE9t!6Ym$-ac(ehPLIOdA+w$C>n;>A*JE)PRqp9OIOx^8?;t|YX-@z@ z@>32>b@frxWB^;Yad?D{h+9`I7%t8fEV{s;!CPe)vC=T4_lcUK<@3rdz~yos7AqbO zip<yJBYJ;+=f&1M#*UNsB@71{F^6@v4vtFZ{UA}wCl=nQyoyY|YQ0PrlqD}8k$hWD zo3Z&P#2Q47$1C??O|+ex&Ner$OYlImQ^)OfQ!=9O&IBjO+Sc*51jvnk*rrSeUjzAa zZ<m#U3YKt|>tM5PGfZ4}Gz!*~7JK&gP{K@K3s96=M<RM^{HJURtqY9t1;e9-dCh6G zcv%2Bst=};O~(%em|XI&+uy>*gow<$C8+6*(_*)v71msz3V1)&8ies_pEafkb+F&g z20Q}>_Ls7DJ0CZ3VPHQY?MrboNIs<@MWRLc`PbHn(B<upGK<eL6f68w<>|h(t-jDS zR7CjE)|1M6v;rtj5+$ZU@O^GdVfP#yVdrLX7az3~iK7~r?CM!n;?rv)@=2fxn<4kw zNAsa#w!cV|{KO;0>PKDcGmVc`B>9Lery4xlbsN?2U?I5Y)frB#`-!&GRu}e9<ZC!5 zZLV!Lsb>pqQvDb#%Xj+#`Tl$psjo@IW;{rc(?PPrgXUOd)SjS_XtPDx!Nz#5T+Bc+ zK(9H-Z0%gt@Q4oub&${CSP<uNdgSv|ZS%Je@70=2NNr-yy3W|tqK#1#9yr(L!3ukR zzxm!<ng!ZVndgkZj-PT|Ok?M;(~Xl7R$0(C1<mKCu`^~#e^|G;<3Z+qkV;P(U^9+` zlx8-a&E`BE6xrwW?FM$<!`I=_VAZ^*(pKO!DdodB`P5;Yl@IybzKMKuS$VVc0aqq{ zfS(x7iKhtEt{h#TChBk)vV`0|0@K%_Aa2GX{q!ZL88pQaZ;};I$M+`8HVS37(k!=` zPxpCirEaWp+IYoCzPHMi<IL7dAjkY9woNQ(vJ=NG@3uBagR;hcC)MzDg?`ha(U)zh znqeC>v(l1<1UxH86><K@C1fY=w_V4}@R;FQ%ygY5ch#X7%`88{M!Wpe)8p*k-qEk0 z$4KuQ2tDg$Z6>2O^Na_72aPa}%@`N6X!0Jtk)fN#dqBCdT(%>Cn^H%ee{bkLGhKW- zB{<_vs_7^B>2n(?d`#6d6_|?Pc|4h#)Wdf1DF_yNQ{x@vIo~smYYwoa^tO&&D?X5< zk*_2y2)fOG39`M8pg?45egDtUgX+8mBCo~3Ce|Z8Q3y@7%fK+*k9Babbl)=W)E}Fc zsht?E=y6db!$<nCyOWWULA-r21=4na%T?Qo6+Y)GwqZnm6sPJ@>k;>XhuAd4S&XJL z^ZHXClgGd|de6-IUp9@3I&)|ZF#&IpuH#$vPGyro-BGKlslLpN`_o}swa-kvOeFRz zY#%prZBVm2*Pb<8F_52e`hjAy-Imq9NrtWh*^wdH&53X18$7>tNaaesWdyhwm$gms z5OZ*Xy|FmEy0ot3n!JNPcmWO73h@=;tRjspAtT>_8LPq48bV;AJxYeLup`9Cr~-p` zZJx3;8CR8OnoDSx468A{V>B6MX%L2wh23eH!wX;Z7l<p<^;6{~@8B<NM#rqk`ZuZn zqKbfM@b|>tvW^S29G)v<?JXt}GH0`mEz=e^PxXe>sQ&nPRd!SO6|E1N&M-s;-R!$H z#5b2)W453tY?VigskU<)RhxY5Pww^g8L0CA-tFBMAfCZLl(4Hy<vOY7+*)z9s+XAT zDG9Mr45CFTV<&pNB>KgEwcq1wBP^N!AtPzqF?P`S10z0S&#by#{*)13)ntpn=q2-Z zej@R>Dl4i-lO!g4wBsC}JM=E<HJ&=gR6rzDxQrO0SfXx7ky~WE__;rY@>*NgqvsLM zF|Uaqy$0lHAjVxK5fkCT27$;jYAms9_;YBB59lL{w_%DiC_=kSE)Nq-483}LZ>2Ld zoGYB)zU+D!%L>@#c}Fky&GjSh=UcBIF&NERf4<wRuDnT)ylw9x0?C70Ux_nuJ^Db# z=>j4QksCFfzqM8hyJua@!erbSGVsi4ewa{go>K6mGst<YxELq1H$ZXc(_v+Lq|O+I zoZkGXXMWMEsIx=l9cxd8jOU}lS=VqeQ>~Pa1N&UGC8T}hQ3MtWFOfd`Iikw+WviE2 zOq4_RZ2IiZ7vbhu9f6?vXTWcfr#+fG7RrYg3}h-&cG6Q!0X(Olo=`n@((IY3fUN=+ zXSkiPkT*Qbz}KFM@R<+s4rg0D-Ood;Fp`8dyakh850e$Yj2IRLA^6dW$e>RY`;m}K z_C^Xjr(wJ@YG1F=R^fN0`PJcwk1eige$~yH`$CUVsz)vc;#J#*0}ak*8QY!YBPIl^ zD%`<y6Lm>-b`U8$!djqV{?L#gtxtW&{K~yEBC=I~E6q#)GS=8cC4}KUzNOtw6l5`C zbu`A&bWv(VS?fq-PZvWqtw)7PAvkVpzHuQa((gIdd*MW?sepG0HQ9ch&tlq<^e+l` zO;u=&3As#;TjPHU{=*M$C4f$RiOmMNI0DaJ`=lot?l$@}A;fJ#mv|YFiCyjLx}rL0 zJ{YT#GXym}6ZV(?=(|O~PVwnI;D6QjiN4}WsXJ0UPW=?<2;vljiCyb2KE@<?@F)WD zy+<z9)ZW(qu*-OT&Ai05Nz_c2<iWQlTH=&`C#n4aX?3Fa`I}~-5~MIp%cKOFdEIAI zH?#MxnQsGb<p)#@D=MJP_F*#=zG2fX1)XZw#3X#PaLD<PIh%SXZi|fI?g@&INciIf z>=fK}3;nZ_mU>Jdk<_93Vg5J?lii$!+ce)e9zboXfO4gE)Ko&-*TJXemB75{#CO*O z`WVEM>`b7R`Fyf(m;GTrjCShyR^U+90sLu|8=Xt*I3H^2safK;zuDFK3Fw_zN_WxY zHQRdkZ38C%1UK>P9$zN?DgySKR3a?(NmE;T8c&>!_IP==qO0}0U6YskxR|~Q`KBND z7+(X&8DKJgnFVgF(8yB%lYWL~DM1|SKhe-;7gyJ?Ic?P;0K@}lxBDjSKVEIr>9LZ~ z%6pl1F~viw7#?@5JZB<H4hD<R027;Ezj~N)xvfww#uJ-CesnmWEIu&nGH{kTw3`~o z2spEy?#|rb^o$kdz*F4w+AOMZWV=j!&(K<a^wo5w&d%yhLz=Q0StK{3dG*0<gy#kN z8qW6_6hiV<<-=FCpGn0okB4!{FQWv~0<23d-V3>6-BPaDejA-|B?7o)DAvwrFT<Pm z@3yEzwaJgpR6bf|0)%9^9*XnIk^kZ1mZic}`q$7w@|XYP>YxVW72P9Y2uxF7$io+J zBzRcgicB4j_{s?s{f{?hsEGv@4+%QqzUt16@YH{wV!Zt4_YB2`Hk<MYT1!&Z14V`6 zFyX*1{CMLF$|@lGdN@rC<Pz|rsRAH4`^)%oX<v8)Giim;nu~I=&#e$W6FKNuSfov{ zQ?$xj(YHcBZykjG&y+1u^iuakAll!8R1$8}x}1+FWakqt>i6NKABa3F?_~~XrI?ss zYk5+?i@@}Zox!!H@g98>65yGINxfos@lz<5tszQF`8W1|J72NvjTSn7B+ndpJH!{L za;($L!mbv}p$DyWF3h1PflRL)JqhD6AUa|Df-lASF@Squk19gOX*c%5=v?H`g-3`% z4;cpw>6Pfm@83Drd86pt7UP5lv>?!hPgWCm&NpCn2vT?Wwj6x#UUrUY_v3eO46@`+ zz|?imDj3wL;K!Ym?p%f$GbJh+q*e`x=Oo`w4<*B~)bTIPy7quBX$NI-Vb*RdqJSEO z3nf3h%GFiLu69L6R%--6=6*a-vF|oaXn<<jo#b<u7nrgd-pOm&fBJNo6u5&q(W8`{ zWs*^`cv^a}#);!*k4}MQ;q&<jaP)u&=NCbE!aubb926eebP&{*air-cpcj8ktUA$C z<=+nN<V)g>0~*eA1KSCc!_EDdjxZtMe;;)K5rPeY3D{ZCHu`pHPT(K9%faX6+EZxr z2F0RgArb_2jsJ<;&?TXAf3%BSNt60wcf<~ZQjj(%?JVe73oLgSh6nh2bs*@uH2*&P zLfV1p4EF#~AE}>c_N%_@<W~;rmt9_s-IFgiA8;(A!YH21C3f*?lG-0Z6cTSExuAOH ztp^BXMm`j#i~P9kB=IlLlDs9Tv|Hn77*hEJxQb3I(LMH4reU%hA!GIAC1u-of(Fdu zAkF{HrU$4{Mm*uUMLl@LnWU&T=Z3u&8{Eaev}VPqsDg9{nfdsR(%O<b{H#K$EmdHL zXwNW8d09U910cmH*a|PK(14-m2@6{<tv=yn;D`EU=6Uu_gMn!6`Ly#-M^7Rl2&^=2 z9%dwT5ztb1RIVpE<3hk<rXjfn7UbUyd<ZV7w}4RZRy5zN;+NZ&XVZZQr%HKuQ74}w z19B>G*H1t?_Zo3OHNsu@E1r7EjqvaaZXe#u2vf46bCe&&m5PFrxEb;2Xk<A)aRruj zHnXdFCK!g8-Oiy6KrmPE=OfzHu0Snv!Q!V1&zaz~SsRcS<5JXrd|ZL+gwgyN2+#B6 zERHG<x^m(nZ&Ib9i4Y7c<5}`)pb+?<&@&yQ+8}!^03<|iRFVN}Do^kLC%?Ncwdb_@ z+*dHZ7-CX=y34#~L-)$y59FaT_}}4AC;w7K6u_u%g%~pAF3osUx2o@V;SMCZ;z0jY zA5hHrwOgI*M8;<U&-G->UpDND(@!<MiW1m0VZ6<x&?MSqWT3;=JHjAIxh*JPJEeMl z5>#C7a6R-f6@|2=0W>m<00HEn8XG7T99z@(cGJ<TtIFB_H0O-+*&@GDYtThz&%zB? zlpo!aX8ahjaZlNWaZ!V&fz)M}@}eHWVs>!0054V6BxKi4G7t%vXtUTDw>A5hkq~BZ zv1^Fl<Xw$|Cem%K!aNRegn)Ozb>|&fLdRhg4Z@1LC~>x;tteQl{XoTB5wTo(5i&*> z;vEzD2<duh^sj0bBQBz|#p{~NB1p$#|4lK1r0iHZIRcaN&<`_-@`)5ykn+mEAE}u= z6@i#&hQK;!rSv)t?w3{7V}l>}M_RiscVyg*i`QVR-u>VN_?9C<{P4_<G<t;RF;5y# z4i8bry7+v@8#vuys3)E2s(>|<Fpg4YqNe=AbKl6TBnKyt6x8&{gj0muvR~X_jL2`; z)cluJY>P_5%<Za8$7EkE89Bi!I@eSRBWm`VN7t}BKpE~5rLNku%P9E^3DYbfgAaB! z(iAn?P9NJ3=?sKFrU6-`05_+hh=14oAXM$Q!BA|&u8jUjmjR;F84@YqV6s-oq3m>^ z)Sd9sHYcB9pt|}R9bhnB3WPDvI_x_h=IY%bsS28{s25Q2Emy;LZ3GHWa7wi!*Q%e7 z^602APe$6)tgH(YGZ|6BXS1UpAqwTnnhJK$JOvC1UtlQiL!AuQPGQc%<qzbPdTtl{ zZKYF2)qROQ>z$+aQ2ZsGo5ie;U{XyzuS|5ei?~t_C98*22Y8Ga6!xri&5r%Gw$`!# zDb7ukLBWoD*91fM@~`*N(cdg;X4<Nqy|pBc?KXTcY#0Ku<{^+lDqC_ZyfXqQUxyMj z=*`h&pdLuQEd>V`i!x;oelK#(d|qO{g|WGWc}aD_Mf~>$rOMIuJQXzA_u$1=8ZBTI z;3{W&W*mU{RkqKHbjN=<8CK4pV_nr;a3dewCFm-#O9?U7d-Q4Cq?7NnzgZVgT}shP z$th@iB^|Nyy=|MaQ@%%6&irfOdXTw#Zl3DmsrHc2&c0E{5c<hdKZ|CShpG#)?pn91 zBX^e8=ZiRgI42h}Ksq`xDJH#!qV(QA1fTLyl~b^8+*riJ*S}(l?`P=$hsX2SN!3P0 zBJQ5{d6&}1`k6w`{GnKbWx1%t!`_7UX(~Nm&8SYvfb^Z_c<CaKGz^hqu6)*9r+NlX z0ZB81Y$*C;@=3ky9%>r4;M4nxh)*xVD!D4JV@EFMvqR^O^FsbH3@}6OFT~z{j7aOg zKdddSWJq@f&q^yPpYNA3v9t`7Nu(K+B=Kf+D!tfUM&a>&JP%UJ*eLKBKK*+=%@yAs z?<jd%h4%@+F3PNIj#bJ2g4htby3F3My%Jt?{lthL%vJbs4^$!!8q+)MSG|sE#bo=x zP@fr=KrFQM;MviedY8{{C9Kj@c`a>Q_8!s0A#&mF?s;kH;7y||iB>!0&5Hc4x3o%4 zgP`Nz?c)4gx#G*YvEbX-XHsj=)c`tiY+uU>=V8AvKG82Q6fZ$auI1ak!%GjqI}q>& z%d;7_%S+;sgP><2idul9aP;$!6v+Pu$%o@ZYdg|Ja~+$K-4Ru(isj(!qVhkvn6<V% z4(8sfYZZnS{my`vzWDMAu3fT{Ns5srz>~w_5Q70k^mpx%OO;UGvk|k0L35oz)w6O2 zDG||4=s)Oka6z>_OMp4*0N;gN-sB@-f4@rXIL|378g?XIPtd^1a!%U%WXEakI)#qY zsNO|tkyTd9Z5|qCvem@MDoRY%a=)cOIw%f?dc21Zj>n(S`U6~8f0eWLU7FD3IQmwZ zz)WF*^JG{%b|%$WLU|!mV+aQ9x!?@B>59&HnqAQ5Qxz_9TZ*?4PViv%jCT|`^n$)6 z>?N@ltH}V}X3W8}ppJAGs=xdgoNjmA%(KUXkE!rDlR$22Z3$9B%Rp&Frd8tB*)nRY z6tWN~^!C8B@V$RislHq`62@_b;ERIFphLgGQzOt;#lI4Ul0{2^Xi~Forz$fuy?bn* zf}KNk)VWP(?O`fYixKt4z;!rhBsoH_<|h&cRm;h<YV3N@*JoTT<vf)7_<K#3Jm$ud zUiY39W%2z<F8LRsB!00a|Fc%zqc%c4*kZlIjNd!;=|A3n+xB-sh1b)WZI`y56-6UL z<$#eq@`j-~6WjR)&)}G`M16zVnYVii%8a9g?}eXu1fxOYy)vWXQIQ6gWDh%>wZt`b zaChN^QO6Kna|8MwAJ;?6><B*P#?Nqm2|O9(V2~QQ`5t*Ya^%sJ)#lg!X1m_bXQ{q& z{i9q>1{6Y%0&s%&**ePevcVewj+>^NyOW1W9@JZ@+R7l!i<Vv{9k%7d>)^|#$gvpi z06VyDqYN^B`5u%M_V0O%0{7p~D^Yr=b--@;L$-9hOb=VmB$rzv?l)!HpJChr+N(DZ zOK}G+DnPS43X1Z`eb$Aiv~aX2IN_o!3m3LdyzxfMrJYfziRD>!MoT6J1=sd>ASNZ0 ztwia=M`G>wn1R-%2tZ6FV+2tw0^CljJUr|?k^y!K3GLgu5B89FX)`@<Zk;NaqEMm| zuot^Z-B~`{PX6cMl?AY?#l<d5CpPO|N%W|A13KG&?QQtF(s4}@fe8f&zrH_+%S=#t zAb3`}ZYian3fAyEj}=tF>Ko%YKxD;p<gF_)8-|svgGsc<xu*ji5EJRQf|><d(AscC z`v4V^KOVF&K-T;SrhW>aqJRbNiyHJmT@5qFPL}-Izq@V151yD`f8-7rZV)pYq!UCv zw?9GKAo@Uzpj5;$RWNh9gZNevL~cS#^4kTUVfIRa$ARY>*gY>1&Y>o@4}j%%6!Nuq zMk2Vt)IdzrAu4XGa?kly<eQk?mC?z{)ftCDtHRn(iDeud15<`C`<Z~MZ?}>AOX@Zr zI7a4yB4Lu<tM0`TuVUw6vTx)}+4Q(=OE~lhAfMl8Ne7J}Y4Qc+rGDuro786AL_mBs z`ylYYJZQu{8?g)gFV$UlVsC{!)ePe+K~8&^{CIU;h2%+voexOa)M3*BdzcoIbgD;7 zySlY)-Ay?W*Di8XZ5QD9or=8&&VM|DD_2S|X*MY|RY|c6o*rZcMUh@lIJ&(Tn5xiM zi3kE)4C~1@&Ff{7L7;DR2R*-coa9~78ls?->G`^i9s5r_<-nCsQA~6QjraGxKw1RW ztsY!krtyo09clfwt}Z=+HS13Q=a_NnkJrAp07|7v1b8A)5ZB|MK|!2r!E-RV6DB@1 z-WX?l;bv0cw>L}nA?K4N%^tPkg12`yq(8aVf(T)QT3_{mUaX9|<nO)nZ7s3q26ohm zbUtfJ!TwRMY1Z9Y6i?F5(3X39ENF-xQ#(p3lNsU;c$mJg`|P{>`>J&au>xq{IWM|+ z&^j5sQK?h&cCxpv|6fvdHrNY1ftIzWb+-IGw&KsM9j-0lR6!oBk6RJ|gT11%>%QNs z&F3uPGDqRwnl2(b!!MAVd_-0v4I*w%S~Sj7WTT+t)R)efAFS6UPp)A-h1In(5jh`Z zNN&iGkJf8sDN2t}?%Ib{>1LgdWzG}iVH;~1i+0Q-V)ZylOXmJj0%^0-F={{aAS=QD zG)(qc`#GDRT*pSZw5<{xEhGJq!WU#{$~YZkfD~m&wqEIHQae@)2PWj1<(PZ4Uj`HC zhg#7Fp7lEbKcQD}jDKj4JcT#9S4EdpAOM(u%e!e9I$lJWB^n@x5&-ggsXPeiq6FQK zm^`(m;7df@AD#|3Opt$54d&Gq+P7w`5G`&sqFMJ%*DX0|D6&bRO(a^r=IsVF(hdlf zms~bWM_&fHD(BY0&FB(apJpvqKRC4+vQyiMk^I?`9utcuDv^@mF0s6#8%;%qWhvuW zT)ZRey*n~0j5ye)?G>@Vt;2;DFzROBj-i!%pPQOU)6HS$80YZ7<3ze)<K_$_@c`sl zhs-iSU(ahFJUj=o;_ca0phS4{O#To74y~d#sxJn1AyURD5`U(!^g~|*#6tKBvH-6+ z{uxszZML_Ku#<Lz45u`Zjb*53!CTC7Rgg*Y&<l9QETtM;zS1qFhZ59sU$95XBPsUv z9y8h>8B?k~h!oU|hKkcqiNT|m&-c<1`Gsxg&Ja0D!JccHVn3_gcB$f`+oY2rAcmsz z?WZw5s7Ry1H+loKTud4KJ6A4+By&_-sT3QtvM16JSf(ZAIQ57>9C`7xEFIC5Ov}nm z6<8{78?N8W1~&z*q4DympT*=xIH=Q`@#DjVa)e1{TRi~$>6ayE(<8pn;ye38v8tYt z2m82HzP*+}j=OQ{(z&p8A{IFeK~xN#A&6E;PtZ<u8IoUOxM-m0jGr)EkzlowdpU?$ zmZ~x*yv{I*NxDQ$qgeR{8ebDx5`uDW%{Beg;+$%AAMw)mHArSW=p#9Hob7yn(n~(6 zAdDZmQy3j)&_1020Kl~+-Lxp!7T7tDfSV*bB0QiEcE0zM-^%@G_+3P`y~X~`MiT^U zebbd+dr6@waOp8t@Lw+S1~_qpz7MUc?BNS%rHld+^f_rVGK!p-XM^kb<l!?Dsls}U zG~quwQ#HA8!F?}p!be>PgPm>)o+&A$s|r0%RWxx1W!(X`GL=yXZZasOK8PxBn=UT_ z13)E`XbXpH5OfSKtuOhNtP61rf88Ym@QoGi>z1vQ+zl<+T2(~k42G=TjiW|&dj0^8 z=+2^1dVAcJcg1R_DY~@2hLafHs*f)RLUZYOo;_y&vhKIu2JeS`z^DSwnqTLc2|EZ- ztIN~^8OSD<^61CIkkSz$E!{uJ9$YeR;1*Yeg9U)W1nG5Q>Znl`3{qqXXn=AXGs0`^ zsYA?Z9LNf3H~1wc1Hd#6C!sVNwB?MRMEo5AViOE%9h|&otRcA^=&PSl8c1*2YYZG4 zpaKfh(c1?ab!T^(0LSEtH1S>ahSXT6bsgZ|vFWW2qEA%F<UL9a{B<bLbF|qnM=bwY znr?7|LPuG%s}kKOMx`gy4;%Xzn|J~*I$gi+_U8WO3~(R<B^pi;K*uorAGurN8(Se2 z^}uN$^T{^g<tc>I3@e9jM{0(Eq_VuJ&HK1G9A^fO%%5R77<epe@|B)i3Ob-+35R}= zJaDejC!myh5E^bgs0}NrDD{62m`+fN+1_C^r-#}3b)H2|L<xYZnG46t_(70$Jviju z?PcJ*0NBrOn{J^gl|4Dq5ryFqKn$iFN1BK_V*W3|FVMH#jOndcSo~L8xHeJB37!b} z7=M)ze-sGaGZWF|9kj#=WCU&!sS8qfHzc1IlcdWhX|8l<!q5Je=ZIw%&o75%ng=*4 zJ$BeEjYd>T(;NfP$*a+0CLI~bYE7>u!hveBK}~y(2YC?H{ttWS9gp??|9=hXkR~Y- zCk-kzj3OCDWn`x8RI<q~GAdMxmI!6LghcjC^GJ#=dn+m<qhVzK9<Ph~RHySfpWh$9 z|9*dcZ{P3t<hri+c)p(F@wh+PGA--h3(PnTh{e>6yycvU0?4swRbb7O6DD8Bz`0|U zlQYUMf#9`wHQ{xIhW5R{t|3HCLe}xT9{=%;wfFb5+-(ORIjp9h?vE<$ES#_1XdV<^ z<-c9iA6&dsF)PnYjWbGG{qt%;=&TfVFUZLK`o#aeOj=vBAcl9@zyEO@XW#f%yG7RR z`_fjL3EW6Ia1lpHsfX6orKfEqfeG1mA_YF5TC|<7gWmM`AIc$Ix5+*~A6?PW7&EXs zt#;HVW;Q*)`X;iuo)q{5*@V9LN+6s5sdQN&{~xFns>Iv7In6nPTwb4I=tAStfujl) zU07BH*FTgVzx<?NnE(}S5u6xd={OQ8ib029C6w3goVV`LFaF!f!wdv~|G=KE$NwYg z^MCpL-y*}N9<1-Ph~HDgrjl}6^Gaw7(Wh>;dtcMnQJx6f0{p?9PlVqKR2!jqOkThv zm*x8`6rw@GQeD(`nfagSUz1NDzy@dspRp_E&#dwMW03_?yB;O;iSe;T)i)eKaI=iA z&pVMydg@-=O5ssU#61T*br!L2|IS4@ndwa4`G<Sv#-OatfMI>r-Hqn2!cXnHs~e;e zd>E(wZy9nwUi4XOw)#5);z%;&rZkc%;Ut#keL3TQ`aRd!<v~AU<^b+>Y<#dF6VAPE zrkG0-12^))?l_;cDMZX6p2Nnc3s$~=y)o=J(cUqMy#h(Iux+(Vggq=PRq^}QIR)i? ze!i{>mgpy2j{pYydsf?I#9Bc{A7!smW5=Ni>F=(uzBM4zf!Zk1@UgcedYyFy8AAqf zi5L>O&P@Tx@%MPR$skR8Elh`0h4c#CTw9i5VEOO=`F{b*{qQA;AL)O%x&Mrn`|-h| zk>&pNUQY(f-%<A_quvj1@xR_IGSU0@w}=>S=(%GOHTVxCKj6ni6=>dHAbX~14G`M* z^zU+4=datF01iuCj)S?y#Jp6}9{bN5d$~+AemgpUBToh03^7*~<G%5p$G@lM-s50V z>z)9V4fU}28N-lbQ!PQ-IfqpUfq~XCDCYkgl#g0=@9?g{;cIzBW+-C!UU6`+ksxI^ zw|bG57wtKkyhR`$G|8KoZFsqhw-N8?E$7a-9v4z=gKRa|1&X`|2cL`5W!^n^^>SC2 zyo1B;XKrMfNj7Yy1BoHd#ebe%cF4fB|2mnzC5r#GfHbpyjNU7OjXiCO>W{D?OB8q$ zL4#|#S&Iy@n~(-33w_d8L(5UZ955O^_p$yAmq9DhI(v9Vdz^h`ZsE*up~;gI(S;$V z12zLu5WhseekaEgTWy|-m{|qyprjXs2eZ|AZ*4s6jbT?wXH}v(S{TQ}qh4wzYQJ-2 zf00f?ASR>>+n(Qb>TMc1YD$f4F2vld8>x0}ukjFprxu<pv)BkPi&O8@biYrSIIO%| zv^+vcy9X)5Sd~ILFU>kc=1NtAE$4o@z9#R~)@iQd*Z!oax3tn0<DNRWdqV<Mh7%0N zo)hymG3EYDqpipzIG~Z+)#*HbTOL{7uA0TI^l&9QC@FxZ)jm1Ds2eZ<hd}0~o1PFa zi3mH+)KWdl?%+}tXCSb$;v!inWn(=G+I=GowohG3!eH&zM5~G<j#>u}$REg?IA7Oc z1e3MZE>7;wM+@aymHL`&&^8hfA|(odf>*LcT<W&Uh}XT-hH}*smbCMBMzQrnFg`Vo zRiyx)!sb^n(vv&p768Ie)}<l)ddtjOJn6;+^NBcF3s{;Z>2S5wb<LNLl1*hgG2xOg z`@x5F5bsR<rM+vWM|kqnKfWD|qq~7Lk*Wi#TXf-O1NGk3muL>9E|5#?Q3kOI>RZr; zS}{1MR(XH#D2U7??UO3_p);#<GTTOPY&<NpF_PukDzA~ZZQGcb6gn>W*(Ca=Hf>Bh z#ml6?+x;ryvD-aM9BMsd;l#J%NRr{f%gyc+`MHXluQj0Q?udN0mh^v7E?Di7$R8Xf zL^Kz<`~r<*6~lJ6x)moH_0P;=?m{=xF_5!s;4RoxwqZ$}^I{c)S_I0gO`bHc?$<R0 zPBi+$jl$(FcQ{zr1;2bph|)-IbNC7z3Rv7p%L&}UFZX*B9Y#ia3z}~Yw7Y%Su(${h zza^L%gZIN^!6;lyV-ynp?1V$Mo0Y7hZ(Vt51ZP}dy7a3NyZp@R=EA52cbi7WEEdQ= z-bMX_%brdc=K@0vGN#TrB7c0>xiBxEHB0ca^K%~mwQEDs+UZFXjns&uPqUHbIYCqS zsl+oYHF@(|zNUI_Y^;XZGp9JsMxNvH@{=E>iRC<3QQZwWv=e)J<l$|mIgj>STb)f^ z159%V+gKQNJ%cl6bCyl38^`de+l&gl`8e4c)6(NuxbSb=_pU25^`1xcA4EXmwb*h5 zkKlz6-<?;~CfJn4yM@^1vCd)LmY;QdFwDo<nfX=8LZ2Iqt_-;nW0xuodHRB3gB43q zjq=W&M`k+W_MTSi&B|Q)3u3hGxBNk!?da;;69~q~QRMJuG_S0FZ!K+_T^ChPbun&q z;vbf1Pggi4+IUVae}50$w&IC{R56k049@oXi#w)kYAJ!#(MYM<YR{E!q7mnIms_r5 zk^JK}w3v@2ZLHIexi#l1m$hdZ1Z6*kHp#S4GA?Or7}S*S%fyNHTfy$u@E1q7v|wEg z51Obs^|x&SE2<$%IhhVZ=WOb)yAkUvSN8xFZEp=R&7zuea``LMtn#@fce(d!&Rh+S z3MBaAmNToq?B%f9f9Jp(k-U`T<Y<GwWvW8diQN)T_<x^C_Ec+B?*4d9G4-5Dv^Gk= zMS(15rDYZKty%If^)($fn@MTfymt3$<$4#Wduk!R)YYwU?jsh7z2;OC71yvcjiGW@ zX1k<%%>}aGE@abk*z(7vqkE`xPwDgS6RJ3;CaXVY;cR_p<odQ$AHRo5wVHiRnn`<# z?8U*Rp0`+D*j8h6a{Fg8uw0N+=NNuCcvc7Ty$&js)450=kj#`Zo&RWwJnMa7)_com z3@>@I(d_XPfS*3sH;-3!zltvuiV%{J;q&1BPm0d10|T?0X{(ROPSaMu?LHzY(N-&Q zY$l8}9H~prN2&uU1|bT1Y``-{d~A*O*~>XoHFzW)ZqsuvQtu1>NW_}G^!Ycm)OaiB zx<n>XyN}zbE>KXXI!AG_TCj}Fb#!ShywvQ}+~=U5)xTYtrKm3-9zA!ti%Z@(4lLr- zZ-Kkoe((dS3IosMdiZ$+-xu9SiRi;ob&vEb%Ih>Yocww$vzvSCCI;zK2UN9qbR}Ge z`)qg)oSFZZO8l1KWz*GTRsC{ECy9~5e(x5XGyW=!+yD}Mqx(M7{L@SAlE~+o8<qCo z#lZy_yw@uKwQikRw-|lcz2fL@xBl_L78bgD+XZvGHgRk^a&Ba_OeSuHFXde2IV!p+ z)&*I&saC;3JKKamr=@*dE2ik_7Ra6+XKJ+yAc)fN`l{KQ^iNUCS901J#HvG>y-<Ut z&o4Llg*9(J(KF6j=aWCI<sd2Sysvy#+X{c5`vq?Ed>#$o?u}EuAIW=1b%dSsPU#nu zmGN$FO63WM)1B=lukraW2VGrYrD;eLE{E2~;)2oQf-bh{4%-{sWF4r@>xSB@Z81;Q zBF6FcQgPJ_!2PB>4R`!hDd%CqdWe^qiD3R_N8uU1<Y#@m<E=X1eZKX>Z|L{9y6q_s z?;JTIw&VPvgPn?NI*xCSZg*)vaC;T?1s|htt^D@Y(HR_X&DZQ4vnXoTVJT!e-ak_P zNl${YS!~pMMY^ALr|MUwzs{9?+_PM@lU~is#jvxH_R_ML@K!b*c0N@Vst<eoDe-f; zr*~>C=6s;%V$<>UV4Z@z^~t`!q?>09;k%L^(2)x&+KvdLbo1p5nPQ|5+&_8ZVL@Bv zIdx9)elRzbbr&+DKV^7gxUa)%riI3ixI=j@?SgKfm<Bic74niyt+BL+UTq$E$W7l@ z>_a$LFmKFBum2=dD7)8klN*~-fj(q61OPzH?P(mI`sjU5JV+b7<fj$xUgw+|nP1Ja z>Uqi?U^0|ABM#5u4JJ8K50}?{<t3DW3&hsGGf8mx>|S1a6(YFfp}iSChk0d(P&(Bu zABGRB2FPAB0;a8hFLv;O$1^WAW!=_5%D%nK(O@AsdzQU0=_{aYsIKU8=BK7LVg4)` zUi4KjZL@D=0)@Fct^IJJUrZx+#dI{Gbflsr)2lBu^KIJ{(aJ}#&iYVP=)h|qLfOHv zeV1Fbci9!5T{$y4*KO*^S|oL&J#1?Pixm95M!N`C-VizA_EkXht_Ex{--T-|R&uP! zs|@q_dJvO3x9^Y2BD80xx*fc}i}B^QX^yHZP}@g9&VRS^klENcntYChDU?R;I~Xvr z?*-e!I&+td09pVqm>H@UDJyT0EZpqjj`0ltMrVq*8s}Smm%AiK0)ld2a<Kj5eFe`+ z-IkZtx5gQf1i%MQ^MTHUqzs5M4?t{XfdOLA7w9p;+o2R5e#eDKXM`k2>1KUc-Ai~x z4`cDc?v|?!ucSm@G7dxaS8g?59&>NYw`I#`Fo-8Riw(y%5&76wcYPR|NdZg7-4a7f z|KeQs@{D`go;9@(PR*D%n}P@F%O!KOw`3-tU*|!v^v@Pg?e^flh`N1eu*l}da2)Ju z^X1E1?|q&p=Jv_(Eay?6KOancs4?x!ozxQB&8Lq>uJ4v>o`As{*T^5&2;iBkjd0VQ zw;Lx0WPzOa6$wZZS{Aws-Fl+Bi}RhxT|TR1W0_+t^7-x=m@(A|-oSNJI@1uRz9w^5 zh{*Bjgf4%XU&gd{GD;x@SdB}<7p)TCs!R}Hn)%KSgQ{&`Ugpj#`1(}vdG~e}b}zNw zdso;MA%1*#@r<!nz3<VP`}W`1VzZ)qRs^B5c|U^Lp2wynjL37Cj|6S6-5Ir?n9f5a zTpa(3I-r_DZ2ZoK<^Id#B7}yxKMix3UGj&DNgJK6Mt?4%RATs(ff4X~sf-_=E+_?} zVlK<XJv#DvEDMUvMb&SW|7<ub13yB(>_d(6<K{YJHTMoL3hPi7=_ZudW96Q>Ya&`_ ziLQ|pB#YWc%PSI%PNWdw2xf_0<2IdP<A`-d3m=fZ63afG9xgT*FSDFo#iYCGrDzk1 zI<}o?owN&>*QLdA7{!}PLV%{jme%$%r0wnuMpVPU`Hs;lb!1`2NEuzAeZ8~YJw(yb zVz<E^ZRM`|0)aAF^Sm<Jw}y?1e_EW*<~vT>@ry34o_JnoW$zB~-%*I`cAPI%qGwdC zihyE(D;?UjH6=s)1J;C4PFG3}BYpG!9On9`0ttd;7?kCHfasM{)<*E`P;7=iS#=b3 zO*5P7DY8oD@AubmXUF&wRp)Sw2+Rc7pRGi@G@0;_Z<XxSs(XpzqpRldC5H%q$1}-A zV*aGP;x?Gu93yf3>qGx{MHIt&jJnd%OiJD_^MC~%{r*x>hsQ>y5q%KFreZJ-3tIW} z$G)OXH?}aa%taP}EOv6e&7;Y^3~~w)oKYHvYK07yg`dUbOiwhQm1*@VLoX;>^I8{z z8YaZKFVF=K$$Ao&lE%S&v+U0i6VcgG1XZXF@t-f~4eI9=MvMB2C|eVip=lO%c7Rj) zg&k)ys@%Y=hbd_)@gMC6YK_;Fu(|;6(hWp{!p#|s*pTp>JBFt!cK-O@ZJOiK^}K2` z;&w%C6MkTden0t)v__M^iWphf9sqn1Um^yI1t={WW=x=4pNzv=(8e^m&$Fs&w)5e5 zI#Jr}JHxs;^y{3rYNl{6B<Hi~=FjfzeX7qx8z$94TLh&x9i8XodWUb(P&Ic5G@b6~ zYkNsSxJrOIV1+3%&O1;5<M`105AZK!gW+k8zY-&wfLbUzzQsw5;PR9OB(6ZxZHNY- zy>dJ1->l;~7&1RGUJ)qI6yyA<-2a)_@r+06Xj3(8R1jtmQ!zodn*w|D<c6Hd%?a$= z8I{nC*mJX<iyUonlKQzr7`Y}wLjYBPc(vwf6VcAiu)KG_Co&@>OjN7++6aphacRb< z^<NPYESA(H+``;h;4Wa<HjaR7`kQWjf8%f$;auv0@Hry44s@C-!cRkw_uwVZZJ#$s zvdl)>@V5uWyA=Cx4AHPm!$ZG(K8)!d3*^W4Sc!^RwUZ!yeeFKm`VpdENYneP)E0!y z>?CW1V)2zc-Lnh>9e7#0Im4-8&W}2Z!l^M_ZeJtv0csOLo7x5YLN@7>+0WqV36iZp zyTa2rOIYbs!kXaFhE?50X9z-q>^}JQelc@-sR^F${ODM>yvK56wLfJSZ+}v>W7L9h zBTLcXp=*w3c>h@G?-P2=d7%mKV5IB?pjAwJxF3-o3Shw7TV<6GOkx8=9}wmY)Fh-= zaXj+f(#a9u-(J{{IPjZV=*uzx9rO4A)^?d9)ym@x(|Ug&Z(H*wbBPWzO^0?Pjm&)3 z$Ww};vS_Tn3mt!B6=C^XGHi4g0nGi^+=sT`L};+jIedh@;<NR{fc1!%iZ!)41*ahq z@~`p_pzof=s}&x>LdEfp%;`+JUB}V-@iFcCQA;XERFZqj1ZRP#*VDns!WY9~7nVzg zh~|n`7*YWb%mqE5!Tj9f?ma~<*4bSt#dmNx^<)ibM_>)kY_w{DIu3S`ZZ1U_8s=z% zhE-ta#(pbWbqlPTa76(c*j2!h3{EEr_!Hp{)812nqEwQ=-K0Vj#xg(ho<vf8=*<tf zQ5kGlmDtY1q(CXYUf!K#P-6E`(S^(VDGC>h0xYNLx~d>>4{*U(Yxm!M(Q+7mUb`-2 z9T^y})sGH+Y1EI!sx3o|331Zc3GN5nNL(pBf#~WfZ2dSAJp!uND@vcVR(hOJ8y$)< zrpx;v;|52rmnEx+(O13is5z#gWL3(Vl4-S{I0-G}2sx!mBk?J{Wqa9%?yH1i;RwWX zJ%Q$&yA2+%_%p#rQ;4=n@*j_5xP@cW*21GFze@JxdxeG=-ovIOo%<)VUF;<Palgee zp7U7d^vHv@`R2X;t3h?~Ym`|eN6o)|R*m@pwBAQsblvDb<ulA#a!|s#@7UPx`e|v6 zZDhwlbtObUUKJLmAu>o;7qxkG9bu8*g{o<9LRA>D*j0YxubBG4oW8YXzv9EbwDP^F z#PMF2VQG%jK8mz!M8LBfTuC*Rkap~8=osJFzDa_w-{CVs>(s=%&&6!fCQt&_b;oig zQ7yEdx|Q9BujS5pIJsrwVO^aI*f>TRV*^?P&F;(4C{$vqWXx+~;0x&7ZZ4>h|Hhcl zRV(XQ#E5IhV1{Y=>cP-?Sj0AmrXDfvp?8&>=cv02iKQWPOx@xWXaF7f-pz?~F>%!* z3%fFRWU#F(PrphM+52i}p6NhtF_NRvk#j!SXI7@3%~RF^JP|p?;D1;VRJO2XUB$~e z@mE5d1~s#)CnQ~aalGUf#yOq@_#q;90$Hk4<`sDuLbG5X$a&T+L<-kj%jr3svgH7& zRB>Ki(^yJzj9#i#86bCQdH1ZI4i`O_?sPH&bs8CV?Qpu?5r+w@Jj_}UIHrTjl*3?$ zZt9}yWxK7H^}m&Oc+MA_wWgdfUJ1`o`3X5DKlHt=xNv6qD2U?rfzU6MpwL+E<l=nj zf<7;qlSantZ`rA=%~`{qJ;g9f&#pcx!}r`m;cSOU=g@+li99(IZ!gWcX+Lc!!3*#R zzAhxG@AbF$uEDdj!CNhH9`OfQ6`ETrt31)r=zA1>`{C{L#{*-`SJhGC22#wc1)NUA zU(G2Zn!VF^dd|*DGu=s<do5~j)UBXPTi-8n3L4C3-GDS*XOOh9(uvdIDV3xgdK5lq zg`9ag&9r`smbPj+Q%s95uhL*DX*V}2)9Z9=B%QLWb4x~(XwZ%~t<ybaP}oy#W{e__ z{JxQXy1|mzvNJVI;mak4SP%3ctX@vnA~7x6ePX<)C@TL?p&Sk6n+RrF5XLq*2o{W{ zjBKOgpq4Q&o!$K~e9hVE0=C$o^9^d}DeQkVKDsr}9kObxc}3h9Gr!Dllcx-74v#lQ z4q7)2hT`n4f2`h{&^P{ap3<$TR*y9FcE&8ESlY)tsvsslFe=#9cX|s3yjXmdO}M84 zUR7IJcq%2*Opde>c#fc=ycw@jwS1bAdg0jmJ$oA8lKh@a_LOS<YOAa_-cMG&mkU@8 zg{?C+HwoV$oy0t^{pp<a2Cnm5lk7)5%j_jXnhqo8H@h|=t4&mkkss-Kyed$)Wo~!- zSQld+?fOJ$5Y#O&b2!bzG;atACuJ6%YCo6{`0WLkWCOD1Aq8BQZ;g-QzLp5p*t&C0 z(1GR@Lkiq2hs9s*+s}n&VYC?`?mKxNmK_9I$Ttf+LC%)RpVpkym($AGrYHFY=iI_D z);amRhOy}mi19AZMSG7m*XyLMp$z8tHz^D%_15-4>G5R$vYV8b)aOO$#y2uvZHk>{ zIM_Qe-pgR&amdhc>(|J*CLvCVhb(aO(8BN~EPCK)^1WJNpRKQ3(X8@NMZLw$_^9f9 z#knyZ+UGM&u?nnOFJSMU#+^~SBp5FScMhPN?If;ae(+`nC!DBoyx2F3Fj*F>R8*!F z_=GvnyPXx(;C_{Jy?+%p5J^~-quJ1HGWzw?$Wh_SUPZ|-5D)fH8m?#CwP9z$jZNSS z$yzV$_vAhAZDW3kPU2&KblJu|!gunJVX`rFD@Cx)b`3kfXid%sVfTzs4d=*CTctM% z+3~C@tOwOEo%eYS^%J-uwClD7R2}2gx2<{RJ7WhfSNQBsJ^HdC@<5!HP+B0xZ`um& zpwE7#chS|{pd<;RK;-p5lxm|`&msAQg{XgOK~3c+X`%iSNJ={NIr>A_4c*{lkBiTj zz`hDi&%D+PW>4Q^j&2)!YJ+%J^5X`%HQkLb9zC-C__Tg^f`eOP>mrD;rVjqkCnVGF zz8~vV(r<E~a1FscrT&y~Git8bS+>ZJa!hV(#rAEN|IlW}0o;He_*aOXWiTH%t`zn+ z+eyh_Y9C;ga385}&MD68l`t(^N$9&FO7epWNo#xp*=ytKt3+mW&kQYjC=-|A(C&1( z$5_E?SLBC27gggj%g(`=lIW4!9cK~$e0o*1HMMQZX5ClhJ9^w@|9ZWg3d@-+%zsoT z+fbL)<hZ`YjOrT+@0>cXlG9Bm`oFfj4wJ0B;rZ3}<6L3`yFSZ%%ES-8H+Wd);vQYE zalF!BR67V<3~b36^-zhwVmsW_6qz)5-wA6u^a6Ws@DXM8;Krd0qP3Ds4oEvR)AM|& zH~{ezL0cGJ9~7bw7J1b<;URaOvUh0i&dG%RW&X(~W%>kUoi+4{L<W{9Y1XFgE7j+y z{Tzf|#|j}4i<-+gCqE1{%`NI!nYmDM)Nzp|+x&ix{6dA84RMytMQM86{o}@Khm85V zjmt$CEWhlgBuzW*zmK=_+D?v2wLm2B*c7qExy8ia>wRq1?0vm8`p@S52X(lha6yc- za#TK_L(_%pb>iykHRlGFNgUv<tTs7&4|^VJNd4brccQR&zL$z5HUxtAprq*Zf(6z4 zb|1OW&KsZVf|$=u2N^MpO}=2bbDb#6Zyeno$?(UL$Q4*R62~3WFXX$t()<;w>c(cx zs98WqYEh=iBO_is_vL5*x}!o8cMV7;v3Zwi)n(-TYi#1&>oP76kIi!&)d*LCT8Qrv z{EXk?>ywTCKDcj!nr4iRWC-zr<loSQaTDE@Q_ui6M0s*^eFrowDx1Jf#7=>tR;92g z=1OF6Ct+>^S-A0@wY=C-ADKA0x#thvoo;qQ@zcz=K63ht<fpllDmD9HA89;|e-12I z_R*c;+={6@b0{y2eNU{V7EzTvy}(Ax_cGRxS&}iM+}!t2*GW~txHq|3Z4%&G80VC3 zvLi$$mTjHzjzSn#-}y~*#-K1)CBDPbevTgz%gV}o?Mb8~6no-j6fO6j9;fL~vuL$? z%XxJ6C$5j^BVy!1)w5!|onH9A#Y4E$C$6b<vqjAYr>*mk{^XP;XKrj&VH!_D6+?RY zokwxoJ13F^s{4n)h@Fp9Z>qse1F$|><v$#ge=41-6;W}`S@DW}A;SWt(vWU%v&17V zg+U6q*WAyiRPU-eDg>L5d$?58s-fm3quTO&(|4am_HA>?9u<x%DuZvPTL3?2Mf6E6 zTCJFj@4ek-t`v3z(JaML6)MB9yW||s;fHGl<)Aqs?xN(c*JJR<bKgVj24gwScMl;> z3MfoGh%A-tr;BIthfL$m(V^Yf+2#AU9muwg5$9)Daz>Hf>$Frwf9kxPes1x1t<e;D zm5ykw37URtm6Fb>4y>$f5WIn7QsTYxmNzqro0+7r{9LYmS3<n^r=FpE=ZhamnBN}g z@lEZ+qhW)g#t2uL`cZ2I{hbwTHz;wc4u3G1s6*yzYF>56rWmJ+-iBKeE*ZJYA-yVV z;PGE5KaFfS`eq5GQFYbmfW)N%$u+<-wN^bQ_T|OqMpHrmCYYTE;0www|BP{B9X*@w zK~h%hPKWI5?-%L?hOz5xI;DU#{{G!C%j+C5J%j0{0Na@0M=)b-iBS?`YHaF^ut$PO zN+U8h0~4mytm;k&rKR5jx+@aNv4_?Z7Kx2Ee3!ZK<(Z1dUR;;?I@CHYN;e;D;wd55 z=4t{ET5xcDbm+XoIJT=<;G(cFA|x1`@Kh7=Ucp84Qm?f~|7p-8&PgKJc0X097X6_C z&P;oBTQp$=fz)?bi#GS*FE@{Wj`mg#A(P8k;PLEk!ML*v-WyBsl+K$og=h+3-$G9S zX7yUwGSTq-uog|Bj@>E*3(T*dx5b9g1YQtfktGY-j&3$m8(zBbj+vd&0v<0YK)?9K zc-C_Zb-L0sASUYTS`A21TRXfWFDYcKxyyUZy*YQH_wa6N@8QSNBAPvX!=qkaUsBQG zr2RI+6o%nYDOH?|dFJ-;@%dBAA#5HT{kR@wTH@Iz42ye4(N{GF@H-{pZq9S7oQ~Dx za3mflRBgt1IgW+Rz`gqE`6_$#3aaVcRzGoF#RG6F6BQZRv->37ODUq843h_4padja z-ZEtlXnq^~L#bs60qJ=KkV}r1V1yQVFupzUVDO-dm`P0SF7peAU*|-=YmB^pe@*Hr z$9S(ms*aDFAD3u|W&L3h%L`fwCys{fNalG|l7CdGjpb~Uk@ySHXB_RQr70h{I2;Bx zyO`U|7MSm;#^uN&vD!e-aA3siDVM`?sn?UiVP_>Wv3awB%9H6JEfs8eaft2B`5-`$ z_SmA4MZuY#LafENLWT8`c(0np>vJ}1h|A5uG4OslZT5wYW!ScvHp(|E)NQ!K>S<9_ zhih792gZ^_h^M4$CLpzTi^<z&)Q^_fQ;}gD=2~?(`#pOC<W8=rg?qlRXmOyb7pRuM zNtvGWE<mS?Oz1KrScQG7pxcbl0Xx6_eu3PX&Jj|Pb$^Oy<{|rUTnf#i6Q<YUrZf(I z<W1vKbSA6Ga>;z!l)eJu#2Uyl%+V*a2{a{KHHSNaI7%AyC<~&IRi`%|d&~?uYGAg? zFgl*K1as-?4EbO~X*C+SPKqz#Kgq6tReGDX40?`|#<?H?#YI%;uqcj*bcIf+1dom# zwb=N<f6L;_av|F@D!Lv%eaf?rb-U!AZHo<b3`I8DScJE^t(|*uxnAsp8x~bnEmz{l zfTp_q*@4<Uk!?cdt!gTM(IYs#eVtRVgN|BWo|?UQj+X2F5+{D`ruD<RLlN!w+rJ1O z+Ly`0<D+?iYwhqd{x2CpiH$~8sqK!!VrdH0Hoh7k;D7903`PNGyX5A#_$i0szzIrw z+emL@Z^Wzm*!I3f=j+uKD;<0usQdINclIVAnRHcImTx;Ox%d{t{4G;>WdA+9G!V8} zmN6D+SaCW*v`sU?IP9n9qz<ZnNRD){=GOTo8U{!{ReHL!lxze=$M=}}tLNyev_5(b zb?9MC5Hd*}M`->qJcYn&c%u1vfSg^YUHZl-lq~|@fcKV@=^5L4q6;59f$@&R0?h?j z(Hz&a$+x9~(Ez5VL0RR*x2BhLTrJ6nz=-ii-5HS}nGlL#nT>W@br-38+*T`Xj9wBi z;V8^%O?sSd>rOhCGvaT?^^AAk=k-}z)%m5*mBrCPJV!Y=;DEjM;25gaWKvt<X}FU! z5vdYi*hj`LP@!juyF${Fvh2uEWs+OE0e7VunS+S(1}=zUAB+1~eM0pUuehw7>Vt}k zlrmd=D%VKw(=Z;w`Ed@at%@wX{^;N)*=GeSt#(|oQ>2zg9UHEWEH@ZW{OUp=dvSbL ztOuRgTm@abPd}+1Fi>5#iFMbmRgXSAi!80rjy>)ldp}cd#{E${s%w+>GId#=!{Vbc zTXNPOG81d`l?`(-rn**@MumYK!=)ryIvnkLr9-CUV<hXF1?De~T5TK&Q+gWc%Rd~{ zH-a%~@bE}k=`~|)9P1q}8`pOa?#_1f)_Sb9KCZY@wg5zB?bP;@XCjNWTC&?WdfdeP zowoTn$Wtvb)l7uf)mQF<ng8v~Gk2>lr0cJP(quTH>TtS1lIe+4=<3^%@{E2yKP@%U z9v4bU1<l~R-P1q6kY&z`_HKE2Yk#yxUd8Pa^j;r=6MNU6RQ*_N_hGLBnzs!m6{urs zeYfn()3Crc%`+T^L5dvG+v?^=cDScc&ph@<#;F!>Y*!>jb6lWc)E2syb*FL?k1)m% z_Y{v({}5Rwm8<JgwYH}7LmF?mS<Gir{n+e}+Clv7#3SxDh&7J_Fq&i27F92{x1X#| z>+ls~+?Tc~WSRU@)!-m-*7Uji{jnzTxTVc*jrI>ALX0-L)G?KlC-d5^>r5PNcIH{D z+AOPR8;@wWNl^749zMbt*1YO;WJ`Oy!_mgT#f2)3-YY0_F3yJPVUm&ycGWK)8x6G< z4Q4)|y6t-JV>qlI49QW)#+q-*Hj6K?kYJ4KP1<vl&sGN<ubjrNxXAi}25tLVpU9E& ztajrQY3<`C9S7{in+5~y0Y%kewO~Cc9I0Ut+naPHwFqFn-gTu*R6A$zfb)BgW$U*M zq?`VTS^lyv`c|L>$#b!=W+hA!r93YyW@6viFQ-+wR194^HKeh5^u1_LAAlcSa=Omt zwXnl8>S0#-;{JxX*T+fkDefdIkF51gRs|Q>U96+q$zBG6KGB0C-^yq&!D>^I_W3UZ z*&?@#rr;kyQ=wKgQvHo;l;SnMv=f>9!*1*g#N9@ZJDpriovlW%H>O)xthw&I_PuQo zBsM%Z!k|Nu=aB3Iz?YqQ4Epo?Hbb}9*yK8>=M=PpAJfu4@yg!jk=!-w0!h>rO3~nv z5-w9WREyf^aI$1VH1>EOg_2oWkr#Y_pf>D9kG{&XP1jrt;*Lij{d|v0xU)PYWB*1? z8;vXb?CUsW<FCZ~+}^Z)<JB)AzE7KX47Og0Il4J>F+84PZ!drgbtP2)?Y?k}t<@G! zOIk+S^eADw2IF4lxnCRwDA2g_lNNEW6r6o8+t#ltT@ez$ztCad!H{dS!JoPR`Jzha znQ?*PdXOQu2Rv^6gC1>e?C++@^>43_5UK>O;?S2iwtNN#+l#;6l#kE=YQapZmt0nn z3WHq}+jLp=ngJL`ZtVqUtBUxPda|O#GTI1({2lwlT4;?$W0I_PMM=;WU^S@H@24+A zJ@wr8bA^7A*!Fhdb@lu!+B#A&naettee@-JF4?+j#6A>%IBBH<GkG~2t~i12+GCzp z7PlY{43)y8)Y9XGEijT8rp{yLV8C+0p=+NKm##K1G{yNNwL+WHk-u57!~=sC==`Gg z$h+n8`@4m5ZT8yS&^S^tTb{Eu)s;F{rja4Z#_wRfnBn0c?wfPR1kVd9MyOI4&oU;l zuZpi%QS{H&xezN=X}Q~$_tyQG<HH6@9}=hu!7H3P-?tQp>ge}*=pM>&RkpFOv|M-d z{{FPc_>i)}<0&T8-TRe%6GrOO+Ks6jWuaCY+~1cDdd1TC1+nLI-|+fZg{p2-N{Z~} zlr4Vyr2T*r$DLx9bKq+gusQ(q{FS-G-Qa{A?@PK<a~`#FV?7#e-@5Aj2$pATzhvl4 z#TcQKdnW)5?bv*-*xr7Qy6-DRiph-}!yTtoZ7QSUjya5~Tw+_*pB`r)<YYlrG+BGl z*RlV2;d-SQRm$+t*ejEL)?!WQqCKQ>Ac8?v$U9qhhWgl1{r#l^*S>!C#JB|kMfTfN zeW&y9$>~jKb+y`)t(ci$5^P~kJ<&VDr(w2M_m(oJ@a^3p&Mt24j%u+LmF*gO(W^q5 z_tVXeS;~D``uMW9bADO~L2EvKE2j8Qvhxk2vkk3p)r@)D4%)R*mMywRXUY;UchziX zoTiy@V=|^Y`&1%?*#250XGGas9l~VpbN{T<=&Kvt{zpBeX1%ew{OvKGoZ|kJ{Ly+d zAfz;H6eHlQ%~ITFK5luo^ry`WKb;n|ra&<aaJh{eZLn`NxtX>J;e`&rXv49`_v0>4 z!{lPd%uTZ|ow*6g1npFsYFm+Qvvkx+4lj)qm8TNFAy~ffNu_)(tT&dJ+j^=k^H2$% zHhrmQp>)Yqtv5O1{3!|&v9!<u2BsKfC#jff*TT9EjNOI*`JdwC#rxF_rKc0eg1`JY z%?aU{%#%<*v>l2I;8Ulp+|FV1w<m3?lLUzz8V}HYd}}=1LA1X@pf*mY`p~pW1BbDB z*1Y8wWFZ0ZTcNYG0o<QGEvXBPJ<I0If5yFSuC4cvYfyeutA3Ut3tSsDa*1u5xW8q~ zG*E(NV6Iw&9Gxg)&nx`j{XMcY>eFuYgG@07%I4S;OjhMs$?HE&M&}9(4G<Ro$0vX( zhBTz>RYZVK7{TbQ(LT2b<8v#N;rCW41k_-m-0YZR-=6U!#yy&;VOVL_1$Wq25Nei9 zYF7SUpieTJ4x;~UQ@EnLF*h?G^y{8s3~X}wPQVz{D{})@$WMi^xBcg@w~YxO-Cw%l zLwc777QFo6mil|q4mj8E2uZ17Zo@^EyD^dvCcH3DwJqOnQ%aPI^Sizl*@t}{?la5n zBka*~rq%E$g2-HKa=D_HCAOGX<(;t0Y#(nX>whp=e3BkSEGfQAHa@yP^qvEjcKa5! zCzuvb@y>tuUa2V=-Pn0gL%nzHNur=yEU4clch&g{l#1V9t1fiM{SP`1P+13=Vz9&K zJhA2pY%nVf1Jt7NZdQvAN>@T!s7f<c7k!s6;@4U8hDdaAHAO!y4N{#$M*S|g^a<|$ z-@Z@T9~=wYeE9sabud@NxMUf`Kp9wV?`pt}-3Lo)Z~D1Mq05=p8|ieu*s{Uj%yesM z-T3~fF&VOa#$JkLnXs9Eh}w9ac~UxtURlLNx}3S=)l1Q43nULIU^~^KO__-QNqh#P z{P`!Lo$2|2I-+%NF;?4tC^3H$KW;!Q%8h#gPta|z@P3IoU>(v$GmIlsQ7v}4B%XwS zv*ASJdr$-#jFx+qA@)N-l3!(2dx&gfK&Pg-`$4qt7~y_6^fc5yg=8=fa_OEF4(mKB z7T>*TNgh0biJT*FoO^_yj+4ZyC$>i&Uvj{AlPh+(Hk6)3Z<DqN#^~JY??~m}hSRV_ zWx|fgsCyj`qHrX0(t|1;V*=bc((E>p2s_XU8@@8Nx6>})!W5mqEyz{BPtu~aX$GZ< zz!(<AzQ{L#wNumrRE7-0$Fn{l#lCQbu-FJ|%hj(*2dg=&!51<k-UMRXd&;9%fQ@gt zqo0fQRMgTcx=o_vSH!Wc1%64^>0&R@bk(bSm{s4s<x<chtL!^xpJzqey4{`T)rmUB zWL;~ui+wZ9zgr+h%eat<nCg(pGdz({t*bh!k>(0OLxU>|{VR;(${GXR#)h+t`%Y-1 zUB>^RJoeH^1KBR_rFX09nU2>P0=;k@N6(kYPe3Pw9c_v?Id!xJfM=vxm2M;Dq9X~X zwH424&5!wL9$0-!Z@0sCoxLBR1t<N53?PP`a_g9K?x@Q}bU|QE@PZi<<81Zi$0?R4 z&F&_;T6ia({JLxLVuRv%D|Ox5H%13$I&I5OUN(}{Fkk*u7f5{X8eC!bWtU&4ar<>7 zrTqXvz?rlXcCFA_{mvT=rQ5z-9Jz_*6XmWNLOF1eG?;dPJ*OjDW@*wF6ZsD6jc&hp zV_5IHdV9hRIg`%g;gPRsj@iL=M70yhSGLy2Oe41ELS*dXrw6P(6L|gCYMXJ&|EW>^ zVPNN}@)0p#XUJ#vH_B<y)A2JN#5&D;q%X6SduJOYz;dZR(}U!i0mo=2ibSWN_Dwqh zcl;$roI>ksM+`F^*&M*ZkhU-}KPKJQAV79qJvPPOBMXCxGl>#aX5$D^%KQ6l-?qn@ zmpdg`^j|)aapVC@$k2;wk)eAV*RQ`H&>Q--;i#l2m7;vJMI^@>UB^$iWwbrjxLpja zw_u$%b_!4`Dm7A;cPF2CNY9p~vX=2w@Kr~WZW1n0<1Qtwgz~16TkJz|L5qpx)G4US zc(3G`eaIG@mit#C>r{8D512I?6ZdWkj=>V8goMF$O=GYA+WS-^(T?wkPt}Dy)!U&J z=+=KRMX#!%gEsQ>f8@-ChQPBAN*xIvAa8`_gf-_1Y6~La)t{rutv-4Squh`c2hy4# zC<c9SiVFHI(673z63^O4Fb5C^Z9_QM24Sf^1JT`79NM#PL=-#qFQ&acZ}TZvbWjcy z%Cn>ETAy|G()B~IfR!EW=sylAMbB4@U^$iY?t95!wOFR5ZFB|dKwy~(qrx)m;d~Yc z^I)qz={ORbpEkmfUPD(?el8OwvVRe$P6bE;C*Y}W^v@KlYS(jWd?!$@k>NvOyg{7y zxr&9KG`{9xC!g-9E}H2fk^9S=&HCc168hZU0Vw4d26cmj)2MZ?c{)`;EUESSYW#TT zg1ccm)CY;GuQB6MTx6U`sM%^RFJ;%4Fqw2ymR7k^+xImFqDV=>;+tWuB=qSruO&Dw z{muIaIo`lU(1z~RKd!4kc9}{0O*P|vktMtVDbm6R>XxWotx%y2Oic6a8&+6KO^4!# zeZA$9@(=gqUYYnv%BnA3EO|k*rvC=j{<8C&jXFE|X2(eFMJxSMm35!<^_**zN9bY| zgl%!+<}6U3;JDVIvO@c6hn-qAz=NvT?l9&fcd_$}n!%d%R5h)t^J(Lh-Ybf|m(;8c z!eTqzz#JFEDlw;6=ya`s^RbUzpacrR&$-tTPWkk*yB&_gYo7>qdz~cejdz%Q?A6s4 zgImKON+M2JmX%{4@UkjCp^{^L>Md8@cSB;bL*LNhuZv5o5D}-u$DVKmKa0C6V=5-r z(+*zb<-jd{WDD)#tBb|F41N77dFx3DcEG3oJA?N7)Am7S7@g8uvPT8$xf6Gq_jTOS zN^Pi64h}66l&x$YAIR+Sjcb_|1v@T|kQ~u5vSO?oftDufEklINX5Jb6`NKT-uUJRI zy$s?$84!TpYOIc6IR}Z~6u1A|Ap`j^r??~F=EE_qy}T)=LXm#T0Uftrk(LcKsPE;H zvBC@UgA}yNtv{Xa`24PT-t3qn8{~a;TW{Geoz0HCm3M*sshd9`rGzjCAi4Qf=zwoO z!iaBm$@Lx_(P?%iTMNl5B#Loaq2f(Ko4g_Fys?6|lKbi^k9U`M%&o;Jrg*9GO+(NT zceZ32bP<sej$a*6DRg-m@a!;h`;+Gbo%{*J@Nen7%|wC5Y)Q#pX1bYt*jG%AARa8N zvL=HNwwfa_g$X<{YPoUP&*q-+#fdH^t<H007^v4ko!uyJjsL|S3wZxbfDntrEB^Rg z7K{KrRPd{|{)CSG@lGLW)Pb3EVH;2$e7#?sx@rtjsyoJx-PmmGN350v-Z_F>Z-I2- zy!mB*LH|(uvOOXuufoSP9Tk{jv{gU)sf$C&m7o^mBhJi%A?1Jn$oK;!cGeJebD)0@ z{&EHpwIEzr_O(;bE6m#)r3{^!8adw4{Pa2OKdTD?U^~Ju#Ghne7rJa)ZA!YJQIfwo z9Vy_y+`L9OxQJ<r(1KwBkZma|Ly_>3-_6vynF#0*u`CgvBQJ0umr&NdVA0)_FOCUT zjF;Njn00=?rjz!x5P$^;kt+gpHd~+HW$Oz6(X@(2etfb>IgP-PsA19s_DV!jG&U$f zmSQuho%%=MG<w2q<~{smcd?9Y0wf~@bF38Im#8gl!>59kf|JiY%kS#o00b-S0k|$; zaKAzJ1<@D#!86JxiXYHRdCp&4mSUtp)C+{)i4=S@2ey@mG&$iFw|cuaYR{M0G?g6t z4mA#}C>Mtw(cT<miT~x+t!1yxhFXnHfprsM0J<P6C9mx<YATdaO9hAP2-<=qK!k5h zh$~jw`(@R<YLVowyf1E>h>s;3!Bb)0utrzh<{k^L#(%%6+z=frux=1$?wt~!ia?k# z0`r3fDvqUsVm&dFD4|adMORl@vFmeI`|l1maHBNQL;CgmcWiQu`p0^IAIh7`jS8%a zD4@OzPM-yJM0V)*r{n6`W~MuQ&~&PoUOvG>7B&$5?0>oc|Iw9BqXkdC-?j_3GRI8e z)krAlA}dEBi&}M88Zym)`-HtaOwnfU!j#%>oic&v=>dUu-hBS*N#ezS3t?YWa?mSt z(k@(<5AkY4hdr#oMr3Lvj2Su+K4JyALkl}b-!$+1Z)4Nsbt}TgVHzaNcODWwMO`~? z*)ph$>d+@3^@>#tlNYA15J^m*y-J4fvii@OfT<DNXOT#IBu$zTGW5ihBOVry<nz4x zQRQu)uqzM1g@3ygO)_zsp(R^dFD{IFa(%zPX>p*SQ*8e%e--U5w2b(_h9E)pUj1)S zsi3U)Qe?{?Su6@Fj~Eg95;nwnbCsrl|4XqELW>~GOu;S8E=RCRf#W;7oOg29>3<DN zgDS%io!3HJp56Qz4&oYEF1xY8H<`@&AiE6wYQX|Q3#g_4?IGs7fw-jm^X(5v!k|wJ z50^~lM$x-JoGrh|2fly3fFx2PW9n`SFOj_NX+m20r%uGTn3Q&swoV%(4ML(OHM9*M zBd}V(B<SB&9^W2@vd<vwEF<TWI94!naA2FGxbGp5bBF~as~oz5d*fpxItY=8kbl$A zxy5IaQNzJkxEmXA3H7))8x;_6(l#y7Lx9Ch6L|hOyQMJ?=F1~(j|H<g7DHfyT&p3= z%L#~x1mpAO+&)(jvm9c{iWt06Bjk7^Y`0us$_N<UsoDq=UAF-wlB-Hs$=P-x9AT`1 z&73&)r-VgB68WtwNz<cGz4@j?DhI`}RKx<UxSl*pW91MLvwyKkC&AN*Xb41|H6rX$ zGB`qY-6Jaei7YTRk~X16dX2bX*GL1WAgH*cI%^Wg%5OmP0Ly-}9jN?&|LCu1JSF0{ zVRQwFiXo9{hA?VIEy*{6I3nZV!|6`i25j#JkL9}zI`V9jy`oVJ9tzp=J^+7?7A`|$ zq-qSUHG*xcu2$s#QtYLQJwhKKB(X&FBJ_Ni9Cl+T^EX}SZ!f}|6F337PcbY%W~g#u zg(;lB#JG}*J@XF$l|Klkrs7G*G+ym-^p<+k{A%M>hQa^O*%D7{>}O&T>0_@l3)l>r zX3bgh`jI)NWQziWaX?;IVO)tA0ejcqT4moK(2u<S1h3tbAF}u<l!{8s348~8p(`fF zt(MfNcW@l0!KRyCPN)eH_UQOILc3FsDQ}xVAf$L%%{wx1Mjj#q1@&>wySlY{6lx5{ zcX=cEgCG!$HA(1CnkVgcajdn=Zy%ZVZt7XoKhR@*m*r6@*I>akkAwFzPEB&izn>o3 z$64fsb5#FSxqu1aJ()HPh0USbP{ze*KOQZ%x}Efa_UoUBVTy@teu$;uR^+VYs!uaL zjHaheHD5HboIEv>EmdqlLj-XXS>l~sS5B^dy+N$<yZn}QP~Jk%ba&+D=OwC)B&gHu z3I7xT7B9#3$qrGZ0nmH;FzjyiGh*Kd$4xp44NTpv@jmusMHT@K@SajyDU^dX0rxOg zTX~o7mfx;m3xZ{PQi@MpjeK?i=uV#KL{DYU-#XiZ{&Saat09U8<cA;zla!Qy8)FOr z^<L><Li3Yhc|;l+#H=(zAll?}N|kI<(1Dr}&9=vF%93M82mw;uFHY`8r;`&YZmvY4 z`IUm&UK_c*#Usx@&L@3_vg+^eNX+$VN+Z$CENCCvyR1u1_H;0Xv&Kac2;RDHbfj%% z)51L_tAG_Rgg$E)Zn{q9xrwR7mr0Tu7j$2`$)KG$k~(~Z7w)^F5hW+AXN@n>P;K;| z6(T=OD`N7qVL909GWw~o8|}hWG)``Ltx79~oyZXF+e`uqZQTZ7=k`y#89bA7L zXG8fpDq8Wm9nP|wDJDW4s2ucIEV0i#7cK7hBio(T2hlu#<@y43_uoUVybA|ez>ql8 zd}b(Rosr=mUp6^(YOw7Q4kl8o^Si|8ST;-^&7QX$trD@rg2;P(m-SOBz%p!C`y>;0 zx7<QH7!1|HCcD6Y`eDAT*MvUrHQZB}Ylx3Xaqc%8JYLmWS0A#Rju92rGbBKf2O*P! zzk%{(Ybx4^+EA{Sm4ruTAz>(alKlej@UCAT7MO2&A>$*F`&=Y$dBygL(JxQ3iSGDs z|LN!3I5>J*Av$WT*w0?u9)yY|*8;AUp5w{rxbM+DJb;%chj{^=$BloifxJ*xQX#<W z+U~b>^I!R<-OU9B;)3WO*>H5&E7pL@RDX4q!ounsBYB|`E~`tX(H+9_h_}B@%c1qV zysIdJ5Z%B><9E_0VGh;QYS^9UYDh)c6R5}660!G<*h}3FCvgf;f4Q~u(lC5xGt#%$ z2{tqw`uxr+%Fiz;({;qrsX>A}aB7_QbD@tm-Zpv6P`xu@Iqp&V5WVLbS-Or4Rmzzj zu$1+zyGXA?oLJRv+LhQ$q@LCm$onWGj%^I2133VnOg$)9-5^1xkY)B6Bri8Tg{|Me zolenz<`wq8KV>%?A<JWtVAQe6CuOxT>LedLHKN;5pP589MxM8$^Qb}k70>(z8w(CS z^|5L_eplq;I`5KDiF&kJyG7*p-rPbRQ`XIOOceJMz0CC63=y^Qa`aAoFH^l=qdd$m z&R3}e9f(a;g2WzhOIF&<rJFDQZkar*AOX|m5)j@*+{ssiCx_kzHck`);_{c}MFYT# zLk8GLg-;}xe+vwkccI(WS)J4?chQH9hH$}xh)@Elb%p*g8{6&+UFXtqdw*Ua&!uOU zaonZl#dzAEqcFEP6s~&t1S{U}peqa+T+*gXv+@B3Z`iH*R82`CY2upV!wcb4)qOmn zlpz&pv`~gLb@rkkhO&$-8+>nqF{042jE*}4ACq*`%5fj{>gpS79T70Mz<Ny1OCrdv zPc}S5tfEyoxSt3IQT=lZhF)4XykHdD9xpP`ejrZj@{|hhy5EJng#!e5kTtlW?o=%# zvBU-TUEe}S=OGiA1miN_!#-%m(up#x+zl(&Bqv5w#U&tZ$VKP5p(EwCRw^a`<0Gbl zHpz+F@!{%%Iyi<FRntA3dQA2K?j7(J)1}}1{a%$|7R5n(0}JD2E@my)HpRBu7=YR- z;_6K8zJ5hSZ9BjNR-MC$XSD;}9kH`#J)f$pY4TID4t#$CI4t5yys}Gv{qnIUaR-8n zR|#J=8+t5LFK%?L{*_ul>uIyTHfTyMa9Szos)?YZU>8B8ogyv+BoWhTVdq{#d)Q3f z+MVwBK3G4b(^v4|LR66gGK<Ep#bQ$*CAfZY^M1xRZI?!x>7<fTh||%b`CFIv^8C6N zC1M}eJDq%`cn1L%-lRj&mh9G5b2Pqb<1Jpo2L;QzsZU6rwq*j6Q}jt5fQ7)|#Hrr< zbGC%PT84#dNIXcY3*UPK7FsxBH=7nJqefetHEZq`y&(D&M34;0@lThQMX_uJEe-PH z_Y52!UrL!`7^4X@xTWmS-=nBhom6Kno*3d@MGNQLlT|~+cqjhOU!73nNv@Zznpjtp zN;B4eyQ5#uFh3Z|M8KXgJq|WLVx9V)S(D3f8+m0dQNvC28%!8s|Fo{YOpKqbcAVNO zvcU!E!VA|4GU)_Ayx2ZZ<25#ML5)y0dT_=u!ykM^w0seNaIU<eEzTrjAS3c$nhHlu z-*RR3tjFO2WUiug&jll&I&`V5(c?=a8xcOFZFEBxDo{6F8XO7C(#e<hLRS9kx8=Pq zcg0LzjI+S}fycBeuysW_dr41@Sa2atk@z5+NxCh#8n>8{o1i<=DnirE5<NJK^1B;2 z2nhvZ7gM+7X<5(|{G4*)``_mcFgwzLL&B08DGP~`5J=!x$y|dls-*%XCx%L`c-~_0 zZB3-8h6C2_BO%=l+1L1-u1x9={`oKSX_^h|(3d0msDFNaoh4#K&({d)_3mRI3@mAf zL<uqkOU%MgY+b#!#h2ETdO1&ojt!^KPw5^Us&wbl;f?|fBoi|hZM+{CUFjd*x%sjb z??3$$Zl0vP&psgwMfcOz2=H;!aEyed-P%ZzXO1C5d_1Vdiv@Jsw-=Ba3klhpyY%=b z!CV$}0_%VCNXlUxV}$}x@g|c#IvERNJzn?0@nrdSJIp;@C=@244qn_!>$<5XWoY`j z6cl@8L7I!_o$Npa;^F0YnE?!<uk-rK6sp3dXOQr3`P`qcCk1|ytV?C+c{$~&VDn5( zbltJzC_{1=IQi@$ofjmFIn?7F7nf}<(=(VdP5$WQY?K?sN~~OFabmE;tttnR!x84j zP(~f3xvA(U=Zw^n2%I=QhHN}v$xsd-M7tfV;WcPc-9b;;Y6x?&2BEx3X*FisLXtIf zx(9xZ{J1Sdh)pE#PfL(8XrY17@QyTJxny}H(xn^le%~OI(cHUuL<LrpEO~ga*PzAw z3yB6~kX;Yjf1+0EU&IdTlpUEcC;`$GV<s_D#uoZ=7y~|k=|Ys4ezXbW!N$3-cbQ=q zgKU`r3?(DJykq@I?%gu^%cHa*QRq3{0mbm5uxU@&{`u>QUQH!KLN~MQw^tR2NP>Ym zW(|hz_e+y>GVhXoF9QC{yOv;YF_|BVCsO0sRpS>#*3oH!3G9^3CNKQCk8Cx{Y`(3^ zL;AZ+@$8?RQ32;9Ra(*&rTwYHu~#k7eI(Ppo^4nDJ6uI#XXe__--Ee!j$q3L$JtrL zh;4TWPo7m;2Lvt_(2txi<@Fl_j_ej}xkZ4|24tmuHSc$j(wHy*Wk-?@A;QuMl9q9H zJv7%R)=Zm;X#y@khooCxh_(g`m+<i3G-+Lqhr&5f@cGpX`s+J)#0V@Y3Y!=;X4}n5 zqgM+k?24$!?M9#C01=>=Ha3xc9PlrEcO90~-p#Kc-&l1v5#<DJfF36r$@<Yhjk@y0 z&JG~04#WL@4@Rw=4_JqRm+=ljbXNYUa@yu*CcXEzAAPYz)J!|mi7b0kttkWBWU%1| zDmjj^F4gwxa~j-hv77AStk-05H#yP;dy=SLAHRHYUq}vr{G?-Kvx3M>Gc4fAXZ5YC z7($S!N6@=xz*}jO13{}6I-9yemEJcLW#arqiC-m`>Oxd2;`}&k?u9(xuO6xo>u`^o zX<7$BetNGeP4>I``l-i<)301-8g+iT6Cp*j%S$lcjJtI2t%@_^bB^zOXZ`l$IT%Py z`}y&CIwqVm-_31YdHQTjl<)<?+mDgEh23hs9KwOm#VMv*9ZRC1msh+wa`x@vOXJ<v z?)BC_dY1mp1ctsWx!|fuFgDA4#7a2gZU7%e`1ue9LuXv^)vY|!Wa1p@Fv4P=#=MjM zUq1Sj`Zi+Dn0Mg)i=b;?=WvTYPoYNNiLgiAXvLCFY25c}Kj3pk7}fKAs(nxCrbqYf zr&#v42Z(zU{=~`<6*0iIbFqr4;hDLY8ugx&!$o!aa+C`>#U8i0e~MoDSp{-zk4j4? z_7LnHEi_+Du@EX+2?Nxz9Ly!2Y~>dFmwQaNB5FN{k}XQr+dqfKfB55*inAY2N&N<c zD5f`UZ4)aA)C_@?Zl|1<Nbsb#?7u!=lb`+fL!E7~x*e{ZA;~`oG8BK1?uu%FFFMn| zo}L#*%<cai9UTpuNwx~$zw>y;TP(MT)-3-iPX6u5kvigU6a`2P68Zn(uAp%WN!3rM zn~l4#fM;0P#5DrOL!n7Gf2mQe38*qt8P&HF=Ko(tT6Cm6-2YE6V+_$6*)*pbE3+wR z9bh~`J>36{=TaKdPh!kkc&X*s>|%3+e|=VMNdzjCU{W{`0NhR;)_oo%0cD%d<3HCY zx&G^2FUAn?Adx@`BUgvS>M&YwtC$p|1pqTi1Iv>{OtOR}17Umh@~3a+2UOqx{agIQ zi)Ms^!-}z-0F6|gQ6wBR<a=f`&{dm(Z2&sZH;|QfFz5vxXF0p$fd0tuBg+pLKLBTX z4fwXCy<z3qg!CF0%u%&wKX>JaFE}I@{cjiRAe{}%|M2zcT6q8E%8gId=g!*@_dIo? zHP2d6=>BSVS>L~Eq<2X9gqJ0hNk{)7FL-*lI(H=Z;)PERO4G|O*g5n3v}u1#SBu`0 z%ALR4dU~1572AoVk@q(poE#m4yl&O1-w*rXd{@G#bFcW9(f4klPr_#`ky<kJE?=;# zm#UvNadPkUXNoh)8Amt0RYpu{w*0A@1^%mNaXz4X^h~hV)zJOYz@xD?yM<CmS4_U$ zOW4XxZP5+T`S>NUVAM-4>Q-!rxokc9MMeN}*beuZwq5spv6Eqg$A-_vE(SHtQTfLv zhHlQh95kC26KDSAWgo0-_fmNA=xC2q!8IaW5Mt-QMM=62#o11@^TccK9cGX=z4>a| z9PW#wpPSeQ22BJT+_$fpc4YNwS`<8G^XIMA4D*)zqx1L-%>5(q2yHTaG?U#oK#s@; z*TYd1zh|(wSrDu%2mL+I6z%C|%;qV`8}u5JsAC!oE8RmEbUvJ%oKgpMcgGf?W5oZl z_P%Q_sBfxhOYe!ImYHClnpyoE>W#OUs?UtEk@@*IwVvQWD|-bR3E>rqI{VRu;m5PB zXp(T?USu9A@5kO^{B*JD&2b0@qsb#bko9V`9Qia4kpOe;3<D93(!1`5tKWCwnxhnS zb%M5^-|k`BYbvDOM@d@Xn%HjceObuuQPUsuxNm;HAQQ)%ydmn@gZ7sZ@-?k8F{d62 z=}Y4tcBJjzMSleyHhJtTh#D_7NqbBBq}O0k+Y2e*T86pHE~8@DQW}}IfOcHYp7V&F zPWpk%(jRXcexMJVpa6POwp9zQ@eXV58;0VzrjJ|fG{a8R=_~LG9;@<5bLef-15|d8 z7Wgw=4cVJ1@fK6}Nji&;d-id`8S~}bPV_R3xTLZ5xNo!GaqrO6lx@8H`|sXV4BM^; zH6}lnXgLme>R<!vZ21L?nB}=#x;6%hT89$9s@&tPT>t&=U0ETEzgKB^6x}+@eKBJD z`F5_=xGkmPbHhYs7{TuuTF!hZ>UpGTXXCLyb?N5M%nO|M!y_RXnt3X`A_SklZt}At z<bM0zXGq71F7RKWIeFJ)e2-0&n*ULM)(;OVxi1%(<<a%A%SLa{=;3Mll7NeU^7{IP zv)r3{iOf8i=uUeKZlW`M8#s7BxnP&eoAJUgBDxkT@zdgF#jxMdpMAQl{a?S#<EOJ? zu&eblB7PCkW?2+1`QQH8%or3u*P(>3Pto)jv2JPz*nB!%NbI!Q6Q9Yq;`Raoy4lm4 zis?MB7&MJM8eiV+HR66R^9_2s{$R80-W#^P+hVBl>C70Q;Vz?rAZ~t0+EniBYi2wA zglcHp*@SCW@XFqqeCa*e-%R)5ew{zZE!<EFUe<SHWVIn2XVM>*Xklll$n5Zh?Ng3< z+iSt^Ps+s8CT~pe<TEU4R~nbxjGJE0#4L~2_c}ns&ZZ6|d|`e#f}Y`4g*MNvxcL|Q zZL-l|Q=_L)PnTf=pnw5FG$tRLkVbBG8Mu?mU??|v1Xs*vqnkOc*XZLJ4D7XPKK8m# zh$|3=?mJNBuHpMUN0#{(veFX%GY0>Om255?4dE4*>^J5Dz)kxyMDlt9=(t<y1~H;D zt+Q?49Rb|Gq;BiXn1byB=;)-*S+e0lQ!~#QwXtQdEHRQwE%iXPzZ<pAt^C=We}2-= zaBV{)c@y;e#{8d9=KQ(U_H8n^Av!s>T{Rnx=Z!x99*_%a>gO-@&rzCDj&`$wib}Bl zJCnEb^DeLnW|V(u-aRuWj*E?1k!kVz8!LD#3-?Ge=xQqk3mV*Ksh_|1mnT>9)t^qO zV!ZiSc5DQgDVaEIJ^3{`mBH=Z_eazGI3=@HrXDWJt7|Wozg9|M5sZe-Zclookc8Fc zc-Cm`J;95a<;m1{=rPy$!AxPyoE@7sq(PY@RM{FSd5&t<41w4h`WOtJu0jW`3O0=( zX&H%-z1`k{ClsZp?oHa}X>_B0gPXoeBk+*7dTrDOO+EVSlaC>%=SWyyWFP7H&`0B; zxaZ2Y(7&@GT5Ol8b6TX3a_F|W_bYvO%9=j+(Ac5My0xzdHbd(jpL;NMts_x>gC3+2 zc8s2^lc7L`XEGE#oHtwkO6_d<u|IjG<7Pz@yguV@y`{|Z2uuQa#E(^#v2Eot6*8PB zFHBqWeQmnh{v#@c>3;%=(oNwjLtom8G1&>}{Iv7y{K=pyJQY+&J;GUne8VfaP9K}- zm*7d1;*XLx1=!vQL*SCSr%ZTd>@wtLMc;iE-UrBB8EUi<gMD#ovdfRZo`x9AJ$dqe z3mRXiN%L*ukdBj_IW}&*k{7!@ukMpRO4+~=({X-|yq?(GyWSL!3qQZduNh{>JhPY? zGcKj#>^C=xtS&A_p?{M<=uEg!PTFZT?uEZzkWJ#eK*B?3mFnm=Gv?tAmCkvFbLAaO zYGOm3pHEjCOZb4_^t+hxnjwhQKXkjRHhh2lh`iY^K>e<D{{Bap<%_ScGgex+r}g|l z|9hb6<k6QAgo<tjFZ0&ZYVNbmRoE|eQcY&dNAdh7uw1U)(TlS!I9%v0xs7+EO(W;~ z%k5I}IWTp^eZL#r0pVm1Vj1QPEZsQJ{1>j0-;F7LjB?oa628rX07nzTvNBF|%MTyt z;iI{EeFc9TSkG`hS?CYTvKnb_T4Md&RZ(mGrD%YpipJm!z{)S<rC1_DHs6J?tkrn7 zb=Bx;JO{JoTQB_Wr+-WZYqtms>6|cta69bo!1*!$;@tcZ%o6tCM8B0@At1y%R_Z?f zf7p8yXsXxteSAx4Iy6!#(o9IFs7xW5whRfGRfo(POi>{f&6JH~h}dLG88bVLqzv1X zp)?SiBy(i=T@Tf%-t&Hc|Mgqzzt(^K*Y92LS!bPdwD-sJd7kIK@9Vy<>s|%K&7Wuq zrf6l(qYcl&PMAx362wMF^t?tU1?1jFfImENW~rRO0fp~Z9+l-wuy<7P>2NZptd8}V zhN71i&#X*bkVgkT>RXgNu8inI|0>AlPS)DT9Z&4ASI8@uD;W0}DluJ+1AR@zbbA)+ z@zpqGGwn!!i!OU=$|krn5H{Yj?I&JlnZH&1X~8=eSC=m3zO2~$S0$CvELVp6V<qTO zVwXP@J0mBeqCpU*@g@zhMcIxL<V4#HH~ARuu7|C!07em9sJ*f!j8&|@<I;y$F}@+o z+w9m=Bbvt18Pez53P>kp&k*F~%9h6gk#=SW3F)syb>I(kZ^=xd#(zR5g>v)Ot%dIM zRTY?ES|qI`goo0==L^J@m{4#eu6lKHRCD)*V=MUC2S#gWsh{+y$O>?p@fsp1iO5dO z{ksb6@EIxtbHs-~&r0n_R`G2|Q7B(%r7H1nExX@6?i6vLJt#RalZuwP^~3kTZ@0w} z@kib9BP&lcz=mjWPTE(^(GR1%r!}XZD{69o{F)s3tRhOOQ`#I!nr?M)QB0Q|R{1Jg z_WEK>49^ZT<g%YiKR0<(AyxIfUsAM;-tDKW+0L-u$j3W_`taoVRk5FcRmzdp{)mO= z7I`t=G>(IBp$s0?HR76U4pj@ukXsj8RZ`1fZzE|VfCiNsoDziq`}t#t;@4cANZfmV zsIDY!&UybxR`AVpU8d4!2u^(H1x~?dL~t?1I7D*9PN;W%*-aT!aNRl*N3GEn(n8My zo*iM!wjGuY$KXLLa3E8+O7L7ef&8(Q`__sdCl??4h(}J~!G#D>Jvk=gd}z8u+6^)s zr-vw93xl!Sz=pUaYF(uagw4F+$};hl$oFZIUAcQO_E4}jw6%>%PMAe!=#I0q2u2x= z{Ewj2vq#gs(oPKZXkku>fN^%(H2OM?a2h%Z%D8cp9_X~LS96y<5a-Cg{zt|`N`Xcs zc1T!GbJ9MP-87xGXoGDhm<8#B>DaV7TkIS8Ghe$UK*ap~fhG@iuTMD-4!TaLVgkRk z!-q?GA_@#mCnVzd{{nL8LnWN3nDeoo=&XBbLi!9Z2GlGhUGJ32evPp|3p3xJkpIHA z<i{z+Gw^-F>qK(-_Z@yUURwLIsCJ-*To*n(3n-aVi8j%iX>_zjGw$k;f~&=Qsr}v0 zo5k4`#LiSl^nnMTX$KNOMnOEXJFZLC=~ls;%oA^=A<JQ4ffr`3dj9KX!R>e#x2uMx zL6jnULk7sJ!Kj`>rH|JPSXH+oJ~R_z#%M8_p`!ktv5&-8u5fG3Y*4xyOcM3}JidGn z6bz{meeezn0>TdlaLCpY#IQY$S0XB@4QX?Kq{{f^-XR0tub|1DAK}<q8pdTyrj~!; ztR7Nu`cy9Y>Hfn9&zl{`w8F~LcAlTFm37p7sjdsiTp1#+ni9BV1Wa=8zmPGAkY$-o zh4fn({k;IZ^Louf2;gSwXvWJg%skX&LST2>Asm`-SKm*I`ZjmmKrP#)%fzB{S=eUL zqt}gVkrI@B&38n(CGOUDJ9R)%+H`U2DvYQ-WmXcXwgKMz%<@S23x%Sa_@RBuvg^Qn zy3}dgd?upnPkRO@ah{C5W_w2SDJwHgH_XG*6FcnouzzLfWCDyI{kGd_5evKLA$RK> zEEvxtGlB%XCaB8#Q?w?F1N`V*7jBw6(Q@XR>57JBc430ZwV4anl2W%Bc7CP8tnV&H z&?2hJM2}THEx*`_neTS-eraeUr0o0KOPiC9WW*)VllISdzXAu$KI~<!u}hc{n0iNH zez`i0m{}gh(34^$k><D-k2V+0YYk-Srk_&3es**WtNB`AA{I`G(9TI%2-CqudWMMt zEs0?c?;g!$LOPWic+A9o<l0^uYG!?+Jhaeg7pKmoUgerhZSlJtiIsl^Crmk9iTnTv z{K2XcitNM?)VqF!s<*`>OgDJSd09>FPhZCYC_KhDf_<?GT2Fi<HXap6HZ0wNWBGO= zTw5+R^UF$nO;JMZnMU%ZDyP1--Bxue^cUvC7!WCGIPc(Oev5B@r!E;wHVP54-qm8Q z+?fF(y8&mAcQnG|xwusei~g8OpGq&zl4GJ=prdE5m3mN(4A}Yzw<QJ5`Xs}xaR%w} zI`0?I6k~4+Sg8o|^T4ra+5xJdme@JP`;&<UzUf>Jm}U)guW?^*ABjM2uWDI&LAP^m zEmf;?Dj=prhZ4^(IA?>SwXUMGIoH#w9A_M6r+)2Yu7Y)QdgUdM@#2@gis-{_699~^ zK0j_x?0lMuC-O3$;bR2gN|fsd9%Z-W?PNU1cT!|S=hD2tj>YQi9!5{+8DVmVjGcRr zu9eCxD!>sT49vdKS-IS0F72R^fm~cEYr={?GD}J)hcc1t;WIpiBEzmq^hIW%p`nT} zQOQHyEtyBg*(9<cRitX(2wh4;^G#<vWGxLboY6o#_GxKK5R2KPdy$)6i0GRV%}HC& zv-=G|l2YymIO62t@OXjc)HuY?x(BDwjB98-;@Z=EZ-rab5QZj4g9BR1{btVh<p=XF zdROqKEh9ES2FwsnRgi?cx=D=AJ6~#whd9EVMwdPM<He?&VWXoqI$Tp);W~^4^D3fR zemhT0w2eW(IBmMUW_<5u>-!NbJCG0w87&4MUo73V_n<2@UUo~0tf$i7=8v~VIhciu zJ3P@>RcY!-;g%Ed`svBfanagyPY^Qrv}gk-dfEa9&?Z&nm>5E72Fsg_E}W)7UTL=? zP{`;QW|fh&H`!#9Tc4#N8~G@?xSNP1DBnpB0RJ;PZz*Sm!Y6T)cBYM9eA3aDXFcGk zqZ*PhGe?zUdy~UB&S6v_X#-}}o<^w9QV*B1YVb@{#2aY0K<q_jKKW4;{gs>eU!g%s z1{U?8_iX6Y26raAuNdjwf&ic~i;65rkZ5%~E1g`fzXID!n*@2BqEx5C*)woBM=wPz zlvA3>3-O_Rs+OAQ%LP$UkkCPuJ&K-RF`4Dp1Xf(M-n|1{C#)^wSHv%+U0M9+jtdI~ zR+2e*qCj=kqrf>@QI~2FL_~KrEFygTYxw&&7i@P&VYixJVV5YsUDfTYyF#|S_#m}z zqK3iuy_pG2E&#n=2^#?(X}2n`nr6okj>of)&74@cq5kg5<!{L4dndPtYU3tjnP#bW zbDf0N*|8#OtE3Eus`m;}k=cG*4-I|z^DY$9(_E_&{?V2tS5ETXL!pm@O<g0yUocun z18>OUZIJthk*`hTF%`EmV8i(gPR@2OUx6rCLb5E2-St1-6y+RhE4)5Dh2+uZb1z&l zbcRho!!{VkU!IB=>jN=h$l+F3W7ZzrN48P=p>uvb2<6WozrMtYc#bmnw(=DT8>-7` ziWh4f&yAm+KIa)?zOB2~k5@_AH2Euce_@IHag|W!vU+KGZIOB3{k0msV>(i6cvU6q zJ&t$7IMitPsWZ^#b#0G}HAA_PA<clZ6&;BIiI-Ll8A(DAuhjV;k?=i;d=<C^THr7A zC1iLG4iM9u8h3iH6H0GWUiUBimtd-lT?qQ1yP)F<+-!}Lv<Z|E3*mIk?|MDP!7W<k ztuiqCpXWV*8=?Gzg_L`%<u>>%@5ih6%|)fefJ<D%od!ZfC6xf-iuJ(CT}($0mzgdp z8O)IVZJCY^;pP^IC27cqC1Z=O18Je6Js+BGYUQ_7klh|xOJ`zOltUI~i&0?{wyq8v zUFyr5)0>d)*TEg?#aq`E+rPYFW!5I&Obs-M+;R3}7f{Y-2(>akqQd>QCn%3R5glKY z9UCdF$P!GSwTH}ApU?xO09!kg4eRE~n!c0?dHNq<spv~8C5SqGszUXoA7FjQC`-te zgnJ!FT}(N7u!~(d-2in5GC9i?32by?T16n=XMw^tEJ=*@nsm-k49~dRUX6UdA%mc- zyspjjT;UUD20_j4(~PsT7f~UlF-L63$p7mpN6v<%wPXbCE3UjGBvAfX_agNC4+KS) zaIdzx9Y4O59%+X$n*Lr|>}OYXg_s;f5a@IyPT|v@8|VzfGF!g`(qUXkPsWtUz%eqT z_fzts^%^t3-#U|fIpk*d7dqhwlt4LXrW3t>6MuE2S^E6VS;z<tX2cQjmAKwdi$y~w z<*l8VR282y;PfqhNyDJL(~(hgX<PS`2$^(4Cs`x2<$3TP+}8(d!REA*)Ii<bf>iX{ zIt^a&W1k~BYs+=zpTqF`p?a!$3D<1-sA+U-5QUt@5ncn(?|Hp}Oik~B)~LRps9KMX zd^xfNx~8-D+QAEmo%X0WK}qaVb-baAVcOT2#tRHCVS^$pxW#w^nJ$+Bs$4@$`?&JM z1N0J!#v{6`zTYbpJ~o6CJNGB=gKn_-N<6xA;ScIK4m}mMH}VH^2NJhFb9N;$DbNc8 z&tBsm$pgV9Lql+z*ha?$(e(K`4~xM>sdv}8yH5^9jIq|@1P6Nd{wTIk1NQh<HT8#k zk^o1kCGDtgSSHM0{nlA*pN^X$@lfu)vvv;kRY&#yGhjGbmbl6EZKp4yDdrr)a=!?Z z%uEu@y9C_t<#-!$y|Q!5vllz0`y<`^=h0nC-#xzQ|6xt_1uD<_y=&%B)7NYJ<Wxr< z@Fzoa8$HHHb;FnpzX~J|1D!SvL}T=@Zaw=VB08SE?jon)!G=CJr#pLIeJI_{y@b}D ztxE%xS(8B$_;?utsvFk2DtAGeaa)c_Sknhy?qgr$RMgZg7k4}lxGBMQ(W)?S=o?r! zhZ^;2E9Vj#-hil8TN828U1Qrbe$^y-Y0AMh|9UOx#FTc|fkG3~S{e3r&uOhNku>G2 zD|I`EaD}}bP=@0E3cE!@?<MQ%Xf{8BkYAX4_|ds}&f?tG?e0lCs}J{JcumGzS10$< z@sU;;CL5i4S~YCCc57di=N_N0FM>pFrlDw<qGEi7i)QVYpcCsRNx-C_1kStn*ys|8 z$!u9}hW*+8)9DqTLKyqBHCox|a8SMmi09>a7D__hx76>EkK(B@k2XJTXo;^WmAlbu zo9l|SXM21)rH{Njle#7yaI`_o?GpBN{Zhq(T4hQa9>|U@I*rm3BojXkwb_+7xURrC zSw%V*HCh*P4{gY^D`uL1e3etH-}|jkMed^?m!`fABJ&no;oP&|QzVM#;<=L#u-p%6 z!}r^Z1QN^M&Ac*vV*j$pvdCY)|KyK*&J%u0-;#}gj{Uzz6;`c(IWg0tCy{aTxw3yC zN2njU^mLB$<^R7wC_tETh^kcpz$9T@u>vMG#GT2&MXbffv5f!gU{?@!!Ltb{CQux$ z(O*~D>TcIKF4fiGPG3cr@SsWpiiL%Oy1NKeK#&~&bs7?xLJmNKe~s^qeNE#y=Oswl zL(?A-;}-2iz1@V+O6DRGfT7O+U%#$E*WsX(rokN}@!;(zvlC7743LI={8+qfD*d-@ zA^LK#04GnMmllY05@Q7>+G19uiTnEopm*<t@`v}={l|ZK9WdeU-*%Oi8-xSDcD1I> z_x*L3VA=_*7CTjJW8Pdm)w|yk8%7^8M_JGbR}-CN>YBf>s*ir&k;JSob)h<7$3+Wh zXwB;q7^cKvcRdVm3`=MH_E2&lJciN_&w4Q01#^(+021|8nFqWW96S<5pWi+V6T257 z8YTaEK5feR9|<pZI7If%LTC5P{p11cYYnOgt^5;1+NYRj+2|nd1`sSl|7-P-_nVW* zvqI?(zds}~;|P2pFk`TZo%)LCErVq|@;h_NBl^IUrU6T9(EqCACjU85aId;I2Tyxq znEY=``~^^J*u;bT{(+AGWwIFLt!dNfOr0x=9DnD4&>)#NcKN3_bL^6HmE}6N%ZgDI zmZAVvOB%@_`RG|HV3bl5X5}I4*tCphy(TVv>n}YSNUgKbQf`3^(vL74cXvHJyCpA~ zqV-N^;>O^O3R{e0|2e!!T=?PI8G|ye3TS|kOamBR;ec^bd5*-^xYFG>c$4^FU`NM` ztE_sQb8F%E4fp2HiTmg^-YcJlKqy)qV*Gh<oY0yYediJz9qtN2cpKYnm={BRMY;cZ ze}#DUcz|3cx^Fq;jo%+9?X-B$s(^}!w8L*7q&RmPSagyN^!?rOVii$9sNtnKVENky zWmd^CA<`gOajC%vv`M~iMk&CT6iQ*p(GSm=c+uru9*J^szqLIUDoagXub&rB{Qc0Z zuSX2<lWuZM9L|=w*zgoj?eTWEgV>(Ge=eZcB{aO<(i^(ho-B|P@H;knDSuy#otoUG z5u&`+Q587+zdt_e&p)UO5CwjJfR(79em-~Km*_mQS<&#HHlgndlJ$H>l<{I5V??B( z1l?rcxGiK+KQiG`UP||l$r$&2!GI^`Pr~?zUgv57>x+YoT^rX(q*`*pe_;5Oci$q^ z_f-TWdU6~N85@Xob}saP3^)`cb+*~jfC^NEV9a2r7l8!a{H6On(5bm1|FIl^yE#LV z9Qh#?sh^uml+imH&>>xgp+qzS8WNrbnng$Kmv{n<$FE1B{P;C-VS2Eyg{*8nxsy@t z=<8Ul4Dn9;4K8QnGnu@wep<Nq+LXV4tj2U~3Qx4}*;>a2nUzWq68TlR4SW;;(K-P5 z+O}Bb5M8$oCb=*5RjokzWZXaU7g?znPHy?}<>06mp@$hJMmhg2TK=@WS>vdAX-JYA zPDIx?zCA?j!$Mcu^|qD;VOb<>3b<iTg^`IWs7Kck`UMP*b-6Jc_v7U|_;w;CvtXCK zHF;ZlKAmVF9$O%1b=Ql5!b9Aq)l!TAku5}7<hj{2{{$(CtWaH7fi0fFBYt$JL58gW zQSzNYYp+zitfCSUuQIfv&(7k!2BcpFs~3&xObfSF0-vyHelFBfO4OhYc9ZBAenczB z*)HL5br#jX>5ATZV-~YzlQH4gALQ>7>n6yL3BCmjHyFLF$1Nua7|#Fy2{zt%qW48< zeX^)F=~aqaF?K?F%11iEs6n2gqwrA*`zI|T4X_Xc-5*KcJ8;bS^Ks|4rn&i)4HI8a zq5Sd~mlOZrz{go-PfWIMe|iJQycl?QF9~+|3<Y@${>sou*uF?ej}OB7Go2a;QqIoY zL2OY3;QFk6nnCK60cf;}Q6|}D0nFs05xw1}W1sgmWB`Xkxnp*rfrW4T@0(Thgd7v~ zjqpob3<`ZA7~gxby)lxI9nJ<9Ge_tWH?7XkUlR@VXiMTJqFylViExAwg%(uXAs%Ts z$6Pe@xeZa43gUI9M|!qC4<>=<8{GHL0($q3*@!U#D55ZOEG;kE?`-_kcX<#g%WWz! zYF+CJuXKCjD7EbAiD=n(zb}cv(>RLPk1K+MA1C$DO8%B@oU(Vn|7bZ24)7bbsq|&B zQ)Ya_f<G^oh`^8LqUn2L&;za{oBn$8hlQFMDj5dc)d4#|hc2#KKunSdilM(?3Fc12 z<K~Gzs~>1VBwGD*u<;q=po;qekSx?+04jU{a;OS@Rbh{@ky1u7xKKjSF$MsaRYk|8 z1qE;rKyk_AEN0&-mx){da{;<-#hBB<kJ{c3FRmEdTDA8`<x|asg1#ftu07Gc{Hrbz z)C?sBEDf$=-H9!6GY~*<5#az8jec1W5(;J5HlZl&g}at1<}U%KJvQ~H^Yi7V^EnHk zT0PCh^0Q?tpY~u-LLkaE6_UY8J)5!0i*cB3!sw9niEreuv(${2xlt6dH92n`=_FBU z{3{6mauyYJy0uIo)UuaIQ)&AmBf_BMpC;usnTJhW+9QY1g(4Td1-m;2I&6c<<Ry|W z0!4UltFU+;&3iNdW!>HJIv<LgTAhx)63PFvQedJ|9n~RSCVbo^5r{JRaR7uyMdYkJ zVYR4;^SYMk0&JV|U)5dMNP?ErX)T@$hVm7u7G?F$Jnn-q$X1?3?UzPFn<v8vW_w;* zg;77f!NPG-y;c0|S9V7!*7=3t9c4y}%`=%mgIoDe!c~@zh8_Xqt)L>Zb2!bw#iasR zm=0~Z78*eR@o|Vy*pM5%w65$~#WbQD7;|6#BuN@NY=sxUe{Y-T6v{Zh72EOt463;L zw7Ejxqm-j8i|07P!fZJKqyOBqh2uYcJj+!45OyN2BOXo48xND&R9`eEaeQ2Av?QC{ zMbL7)(D&(;VW5cVC)@M(KvkWy!E+Kf+<@!!Uq3yUi{{)>qh^ATXrUH;s3{+Y7i%qq z``twv3Oot`?Cc?aOSb3LA2vZuu$vg&+h!e}N<Tc0b~F@YrGNefJznOxBooq{zG`uY zd>5K7dgx_#B@SsIN|!FBt!F=j?hL4y|MC0F2pOa)yJJ3z3b+yItqGUbIBeL$58N1R z9}^=C5$8cnjH4l?C8M7{auQ*%6j~2G;9#ks#wG_j!&oCKwhJgc2`;ES4rHdH=g9yU zS@H$w7R~VNPaOpxKfQN#Q}Qk2d|k`!Fd-xp;EEyKT~7!MIAA5<lZ83ZKbQ<ctR#rj zd4D0lW?|`9xN@ri^rWLbm}1wkrM1ecDH*t`!8QYcHLg9y>xloru6Z<$W!p3n4y^`b zk<AlEYJ<Aw1@zpX9a-<W?|W_$$vTTNA}3#HTbH6=S*U$lcI(C$mo8|HN_~L|uC0D@ zhX#hvoecm;ktz(pw{l<<U{WA}x|c^mH#7rkmyzh;3ZT9&(C3dOD~W*CoKt`IjT0Vj zLCGuLf}vzML=2wtAPnw-F0k&XL0^hPbJ70HlR##BJjMq-dhp-tx3lkbI%X8`x*v^8 z6XaADC2r#Ix0Tn@j34YqaT-7lRW@5ZcPN_GW?RS>|7{P>DL&08!f%j`?(VA#)PBfH z_0jTOgJ%BSedTm{N{3TNV;J|W55@jU1agZm+-<&^U#+W0Y;~2j_FlAN>1bb+8aTSu z8R)cULvMTSK_ju1jn~$3s}0#~p&kq)yi_GZrc;q426{qwtDOjMPkp#)0c~aKf9^vs z71re^PgZ(W!XtFnaidiYnBO&CubG8TkPGkV?5Ns%#|P~JrWD@Rxy3ETC8+zn&dpxW zAkSp$;_8h$4<Eu?PHPP7U7vAjDxGPZ?|p`dX;NDo=l(tZ<*7_)dfUom!?G^#%fw|o z&9dS_U}es0(ro&a(}6`*$K{if&Ky0`fP~F%Ip|U$`5Q=EV7ct)pF-5s1<9Rn&L{F$ zduq4V8bM7J!=9J$cPQhorcYw^TPrfEGz$n}3tI3Q8m)_o%*Aeqc$F1UgI-y`D7vfF zDicOXs%UQlRKIxuuYP%1glJwzb(RXYo?QvXNE)GUgq|%OF(D(7G(m~RPk3_Kdi2?T zIlf-!Yn?yemt!7s?_C<QsFFur*IXBU?FL*AFTA69Kq^R8vduz2j>~)d=R(#VJj=@g zl0$(pVJEjAsh(}l>r%9VnjSnR#-&WrH&rXF#r6SGu#F$B*f0(N-Z@-m<n5e{lc1$) z0q0CmuWqsI^LS^H!4a0wTG`vtf{3d~QV1{!0?{6CU{+?62@C!J&+5jbkXUf_;chdT zINhobYmna7`#qEp>LOMW0qJX~G(YrLVi#u&?wCt^prHB8V#zOuZpK=ZhQCuCnG9`~ zIKfmet+1PWS_P!hY)S3kTQJgd5u#!>sM<Sh#g)oZaS@86<CD53n=rlM78jac#mF8x zrrP1=bP~$J44E4!FrRh~%>Qp+_4epJxj0?<cFi1OL!3HIAGB}8iR~qnpD%LRjotMe zL11jHQxCP2e`npx%G0jf%6i!rEeR*}w}&P!+kbmo_syP^=X~av2q{BCtiObmzaQC1 z8vO_z|MrdG>EJ#(i(Y=&reDgGxw~>R9-aj=W(M^wQmfQIeo3v!zC8@W(qtt2Kl|E> zh(2_Rui_Ga1`<VR5)zPqUlg=NiUC@SfS*Ofy<7rUdCTqg7{Toa6xon$X!xVK@S2~Q zCns>z{FlU#@A@%2A3`&X1{Bp($T~+kPKzFm(q43VCK$qdacv93QsOFU2KsJ#aPHri zp#?xr3VJ5`ur?quinN(-_=arv9@ZmPy}X8J7X6oRhS+o^`WFGnYfF%&n*o0nUB30? zAN}{Lo@y`uZ-0)Jqyqo)uD4LW;3oN(U-AF`fr-o<`4#T3|GP>gIh69|;3vEP|1(>o z&|(a6^BG!f7Fh`J%}<sdq7i>kC~rzT3F{pVk|F}ZfV*|Hy-J{!bIEdK#kj(jQbv4# zI+$-Z6AlpyR2>vL8c`MVt76o{tmT;K^fsft7fAS*$wglxSZ9%o9trYP`iVf6Z#Ce} z3MvElwWJMY{#)E0{va&XHNoCs;%1lbmYcqiTzo7f;r{1V+aC3>lK{AM7AuqhE%211 zAw8{|o7=tfzx;gfnu(vE;8?eSP@74{c6m2lUMCUZx$j*%J7rAir?B*S$v05ajO{-k z7}+Ah{$vln`9Jt$+9XTtK{`oAjzs{)Yd}IDrAv1|T0qDm#|yr~Nhj3stu(>a9I@*A z$AgN%B$gx=U*>549tF8c{N!+&L&+Nj#|^)2rW3$834(YP>JJrYB+SreooPizZ8k$) z;SXa6JxZGn@@0Qyl}dSY&Re2T3`En<_?P~~A0|6nH~o6G6<SPUjhuwZJk9HT52|NX zaJL9wU00Z?gDfrx3?&Jh^O+z59=9h}W1yySi93J1o;v-1`n=5tcU47b`!r*2p7RAN z8P2JUq=h)JLLzgV=%ff-GW8S8(dyczfqcE_iAd9o+_4FEn#YB{ocO#&BIx(+F$t~5 z6%p3qG&;#t0L8uRL2Fz{s1rni+%NAgW)ORxltWG14NGrNwC7<BKLiM#2ntJeyW*gu z3Y<=d0YvJMQF?q;Np)s~!xAWTe%bhw?F_{^RFFx9Q1E3ETY+b=?^^BhsWAmsKMgSt zTk}avIdu0_`n?tW{fqwF(^|Dh^dTwS<nUpaMQ7tMVrn!pqEfD__?1ba8<tK4L+o;K z1?5?P{JdQ~=Wavc|DrP;rS)v<9G9+)63QF)$tR29pr*TNCn)>dH09?>0dWHQ2dE-D zB4YD7px+7v8H}~g9^C=b`0TI}P4IBi#Y3Y`4ql)$Ez0piLseP*EdM#LGx$e)q`?^` z;DJ+NOVL$%Vpj7E-Y3CtouPUu!N5y%&XstQ0MaHyv^`ME!q>g>wARTaUv9ByH}Vx( zL_niaX7uWWl-e*s(1@F$LKrA{9GxTG=LgEyV|~e3RETjIk5}RudHogqYX<b@PCVaR zdQ(_m>dvNGV&a<BnbEM}%hzD{%#v{F96%(>uVLQ%)wbp962EOfJu+V>AMtx-ciM_~ zvMY|Q+El1R%52(fE*ffRlIajF--JkUA!YuWP5i>UZ=IPIUH`;)d6(_9Tq|sFEwI|6 zTR$R)4U>MYsCh$zpJ%ImXsY8C=W<immVguxf-FkJNfkm$^-_b6GpK)oC@<o;!N<R} zr7=or4mvr>qlIenFD}xX9)dZ(4%`qw6e1-+PQJLat)B5u7BNMURju=G2M&~xcS*HK zKN<Na@*W=2{-bWe`&~~x0*S#%PqlM#?GwM;&l1qZp(u%NO?2k{$|7g=ECL!FvBF*I z@?AK7&j7-Q3b$H%4ni>?ZWA{O`iAZi?j^bNX-~W(s!ZFAIF_?-00hsE<n3IEMYu`+ z*y1%{^rirl%)iMpQ})ND=t-%dULg_)(01P2o;Su2#seIBeQv1D*NtNjkWxRN*~~T) zjr=$Tv|&&+iy{aDS;G<w+co!6-NF!2ezmbs0{EsrZFn%BwgEFH*2~V}m1?sc(&>p1 ztsjXd1Unv$ogA@=v6asTEghRL;)bffJ9ag9AuS(zB&+Rv0ana&+%VmD?B#o)edmVj zE4$Q&#}30I=aG?u1T2WGY7&EU!H`;V!$(_bA!GT<?$JNa$^4VcPCe(m={5ZP$Ov)^ zRa-}s5Cnw56jFYc3^B`dJjQx&n&aT7Sd{U4ADgl%xKzJiX1rHM3uUf$wf<E(D|DN} z))amfMVVN22)~H6jwNneTl*d`D`IBs0xk&ImAX@IH*gSrK0hhVDh?u2P+*_Z|CEn8 zx;$?o4feW^#zcmfU56oZYX36S@l(S}{*FqPJLysWbO79Gjc)F$!`kv%VU^-s!zXt& zS@eAk7^7sMhAa*5l|1~$lV?@CuMRfPqn~o!DQ4(VkP-D3!dndH-Ez2sBQd&U7PT6r z;&s49GFF6tsovz5g(p|vYG=PM{_itnJLL;@J_5PsnNXo1^dt>UV}X4qs>K^d_;!OM zDl!OKvax$_NYhJGV~y2Y`JD`V3ai+u{hLjFo~hXb&l@m_-v0ID=B0{zL%dzwPTb-Q zmhcGgfFz(bY3;y)Nd`1HxH|FL_fA&a_@t_V5H;v}yZ4pF<KB(uQijtne>rkmD|5}9 zUH!)y7=8LFv}Z(A?^TvVtgy#-n%2?8cDOgzz8Kuhmrt<QNx)<3IbCmnB(L=)Wq6*c zNb-sC<@rTu7o6(|a_RhXY0J*#p0k6b_?<%7VxYsNfpxawRb-0O*uGJgGtQwJ;JDSz zIu_(jmw3JpF(*_wj;YLsgO^z*%w7)VLe$4p<<qO#dub*$q?&H%+uRPkDS$y&RYfGW zE8x)RG`ZqUrTPd~b=34K=Ijc%9ih!iYfe6%Cvtw_q!<sl=gZfp!O9T?JiBY&2Qn^Y z%b7cjeS2Cr>ewqxKqs<J%q={3Hc6XsP+!H!a929tle2OwbqPlYQGZnGkCkJwe}i+A zt#<khF&P<5yyONtT?-iCDT4)<%3A|?S$nX<MbP@wnk*SvHlg!sg^mGqS`uBCosFzx z@9LiV0~*D;1xu3-3*z?XS&h41TER!)vSQBt7|wN9dF%<EGRn6y<(4P|-_ruy+;nSB zZ{yR;EoX@BEA(`1Jy1z~LTtoRI23Nn(b+;iIgG%R`fhKBIs3A0<ryudVGSP&rNEVW zaWP&#&zchN@Wje*Z;F|UWLSQN=>5uGrJP-Kxj1J7Q?SejvSR<<pH}<nafa%KtksV@ zOlqUTHkhb&8TNFzgy^bSKh4|DVGy^_3S6L4MwYnBtMV$kZ*fO*!KcLYI)8;9%HNJH z_~)h8amgB@9EusfInwRxk=9y*NmYI=a&hWDpM7LTR#aXoP8oJx{OHNJ=zZa&!58Gx zMV@IRQ<F7!c$MzxTO&osPmTKM=d5n>7|&xbn9aAn&uRI={RQI`FT&}cVg?eVZuQ&* za6Sy5re%<!32lX!&T@p^mS+-RdP(>qPT64)-m_Wamad2R3zmd0^jUK?9;$U#srkBp zuq+I2#H7pSNFUx5>QjiRo_H^*Dmf~s;Pg^6Gy4w7WgOcy(J1sid$OK@`VcW*C06C? zQMZg^X4#PD`>=TOwK6o^c}&EIHs(-IKLR7GF2(z{)r;C%nAgnarR^1@zVdVgj+h~` z+55Fx*-)vxLY&NJ8TLCx7qr-w`;{c9O>++2f9rkS<9<w~(EZ+P?XAA<N+mN+%Cv*q z-c;tfZ543)NeFx{9~t*j`Z`Twd8L0vq)UHErf$8Z*!luJwoNzL=tRa!Se|k5cc5>w zsk;3(k>z#l3YxQMtdeASe^wG^HQL;i9}bRnFt&bt+j*xAr&CV}Zkqn-I}EI%(kcx^ zlv>JeHjP=w9!)FJJ|7yT&AKqJb9ie-@8WDZD`37K-PbO%!Enu0#Fr`6+5U_1=y;aH z^>(+kjT$~uWO_vEhddlMtvoe*+4fnuWVX+7ay*@QjF)Y<Zb1eSUc^_oKm~FnBRr~i zYsa6#?#_>P$b=9QCc&(Y!}IU_Mep(_b`&~adVf1Uw|HEJ&B@&A4E5K?DonT9nERHF z5|iYO(>dl&C$@LJPP;TOM4Vs4Urk9ytG&iGF|24<AN{63Lrh`TzC8V|13ICEtX7tM zDwKmKxi?__R{rYcYj#fD5~2z48C#<x+kQcezxuB!(!3Ref7)eB!Pm?c8ChqK)6`4K zZa1Ft9)GSc`BYUd?)6xaXBFq8h$;mo{=@FW@BQ$P^sc4ZU7*fBFK_kE_l?=Q?Br^m zBay(ai7EZJ;N1;hT+}O`6ma9uC7Kqz{t#0k{<2T?_`%96)TH)`D+E_>SmY6w@SNwy zT-lK@5&mgjRG(sL#Ftd(JAdi5a=+jo&E3`EAedD0hpOg{a6P1Qp(Hm-3`^jv7T*Wy z(FQ^-XIEGf2Tc~2_qtYkgs5~k2etpYdfB2nv^P9mvYN_>a1%S`Q2hSl&8OWrY_X|% zzCDVhK5TLVPp3~}L{oMO?oWH~48{}T{MCyD9S7}@$JbzgjDwf4a;5bRTs}ni*aBHc z5W40i$d{A$9EN11CURLvt|VoHiJ}(+%{Rl=VBN(#6W&e9{XkSmguO*5nWsYbLKVqN zi^o}uZI7<K%8$m$b?Y2n)wUD&u1+LvvyScU>9XKH&@NRcVcH37)Evsn-37-VGawZ+ zd)U$LlD|y+=u73<=$*VnqREHe&~nN|Ejwdwl2?VPu#LqnXWA%2W&mM#jzmec-Y9iF zwnD9-JZOV)y;mSwtR-+a79yQPB0i~JU!co2UvQONoOiUF0edK!%8k5JMe?%Pu05=5 ze-I^qUCJUTHiY=AFT@lLb&~;?ad7sAG--5qP-)yEv`@E?Wma&Psa$>)ZPbS!PSwEe zZSam>i2CVU4@){Wc8lbGo`N$zbrpZh7nm&q@|G=Z6Y-hDBVlIxr2k@yuHR*N9eZbg zg>WQszGxIt!KU?EuZt-ai;-_*-rYUC#;D-S@wj)>XPgEA4~v1j)@=Rg($tw2CZtU< zP!iEZ-!$OQzn;AO_OQme$L{G!t%)7aK^6+S!*J!zv4!b9-ySv-N!biuv@YgMqOMc@ z+?Ujf6xE+kaCm2FLFWjQguV-uHaG7O_u$&z_PP1PEhawQukwy(0=m8=@>Z6sNLe#J zxe3Ivmm6c?|K|~!<hj+VMGY9R-4~dihY%@cn6$ocgy>(WBLv$%`xX<&zzH=2DQ$!g z$nSP;EB_mPu`;<hNncB|$|1$g&=I^jc|wL2?QGh6)^G8Y9`?dOA;z?5u(M$uVXOdp zei_tuX-m?Kie7>^ZcvrH)1T5WL0OF*s6~%_gdG+pR`@k{p<nh4>ShpA`)SS}a?%X+ zd~|DuES%0M*J6Ebdp{~Hcyxhr3^b*YQ(YFahv(9co}f(N|9o%KZpiz*-u3#{3s$y5 znN8fZDff{NESXIWDBTk;!zlODW|itk%bAK9VYWjURiu8ye+#!4<0W40SYVB>!iE~6 z;ezLu?u&TN#CXF@`+-G;k5~Nk{+V}o;SXN}{bns0kGAbN%NHQFgt)W>G~*N%dG)ZZ zBI4`=qDIT03rJlf@$J)fZ)>iw5O83Ajp67`c-RZLzb1oe6hqkn#^8^$TpD(BqprkO zBP3QtgGpor9V3-PY1iiXPv^6lq;TEnj_5nUG)gCxpN_&jT8!Fh2CA%*`$yg<T7M+O zrSOYNO8gIq;*o*L^>MJSl)}(1=SF(<b%`_gi6z>{RM~>f$nKu!%P?&;gB)6(nRn^K zpzhw_E}jY{kK4mY-RfMDFo#VW#n!><aI#Io*dQrf=h0P6b0Rq`-2*4==)ngF2gVR+ zT5}E$4@Jv&ZNVUVcRu*R$}fFgn>PX*Ia2Cc_3rFA+-i;cePAp;36z2@$#Jh2CH2&n zR8=xH^C`D}K4VszZV=Y#wccq!|E=YtS|=urk&?bHs1srugILefLwdJ%&J39|UAAVD zRi<r*u?W|M4Y$N;$6Y%+1zk6f#(E?*`)YNdUDZ!9I}a^dNfzg82)71{oNA4O{Ki$& z0#_+<WWDuX`tgfB{8)pBhh(vC@u<59Qq#~wlmtz2qMwZ*T(RqD%t{@V-QnRUv9FNw zH9uOX2j-WVp1aGM2-7Ah{0{2(0b{CZvc&4F4dm7uh~2w8K8QKi<^--n4`!|uffHfF z63cK^pS_TOUuH5o0$ZMc0@Ew$n&USvf6Q%!I~{&@{eC4bYF7ym`%X79l(NB5Uu1!- z<4^bI{Y$#E*Z4gK_Da_GEvniuI%O20cAE_)1qK9UH@2?#OM5?xmA?wdC<SPU>+Xy3 zIA=neud7Dq84DH<wLMsQp?2q}>8<o26E_v22boPvum3nfJ<B=fcxGiHdTndqZ{t`~ z3dx>R>*8w7URZOcnkNYfBOBJCfizROLF3`>q**%LiCh9&j{?gU(TLt9Fx?>6toRzS z3}M20*=~>97@89Xi{q;kq3!ckWz436t!3vCz?MLUp?yuktcC_y2fGYm;q8_XPUMdW zaUbl*PeHBNfpsaRA~B9%jKc<J{dn&mPbwt@Ip#Yg?PO%hzpoZOQT0YcUTf5}LwS)& zKoQ>Y0GfM6D7ejW#R0j>-^H`R|BB`ron(`|Yae!pV|wHZmPSzRj~~+F_RN-xGYpQ4 zbz$AbBhi>tT2&jvVSGm}?yI~uDcuwh>8n?G1mxF1*iO7+h#0h?&u1R0l(a$BFc0m5 z9II{k9g#=f)HgUE-`M2_E=&OQQw=F&{0ctv)!j`|MRu^vg<|{1p;t%SIno9BfQrQ- z>rX)z{UnahJvuDdh7P5;A&VL4>x4r5c*-_*q4exM2?1$te}=0i%O|TQSC%-mtQj7k zUnd$}Jv66Z$)5X0TX{(ES^S0p`7w@`HepSvNWQt&w};+Db?y&%nTqBSgZ;boH~p}V zj3lufJg6BTNoVt~XftnjYHtBmq0xO|<o?@iF%mBE98F*0aa#gTmEG$-&=sSFnS#Hf zBeYu;^WI;P6iRd|=wNETl1RT`awmKY83vFvwtwzr3X>u3nD(CC6B<fF<Gir()~bd3 zV|D63&5$J5)W9ge?l9{GJ@;I{8eh4_&pHLZ3MN<VD;wT38sg+XD@L_S1FcJSzH%ql z$&JGN>8em>9@doDtJV|K>&fyte<PHDjbWwf#5kAu$y9dQR+a7wlixkwzHGmNT4e8e zg^by6IgSSfP9za3NP_67=z=Ab_9+sWhg_Gg&<l5Fn3)x64SJlbdcZ}y!Y#JG+NPDL zYErk_v~_p@S1i3TX!P7hgsb)V@(a@?cAR>2xOMSmTepv!QIoW4Q*yoj34@e3oA=M8 zirpp`Q=(y}I!G0KWFmqnEb{9@Zj?Tyw^sP|5XCAkkh;)Q*&|RPzX(h>KG*#4ni4~H zfMnDZCFH_;O;iS*pZM$gG^1wpGCX-@<o)t-KSByVURE}`d}aFGY4m!l<YY4Jv9A15 zcH+a_gG9k>c=(ONqObKA72LYyyLTvoX9gPm_mD}UoLDO)XQ0+wOrdP`RoN-09amb+ zxkM3In=;AXbYci^L_68!RlIQD_->Gf1oTs)r*UFWyObWW55L>YBL9sNxn+84_yAY~ zfxyXC5gKe~NZJ{2#`K<Jj+naDeH!Y|Mm~F}<PPW$#h`6|NDNy#tllcThg+iE=pey4 zW^JZN?g`mqXZtA?S#O#BMYhAZCDKQ^cQHp9@o8kReTEoJmh6*X4_F2<85eQ@POsH@ z#XJcWT_ku}5|2l!+zRmdYe;Z3u7!7=-#d@n4)+vtcv^Eh<+y54l?~P0`%B59b0m2= zPuPx|HWCF{rDd_4&xS`-$BZ0Alr;7hxSvdTQZqE%m*ys6N07wNyG1mTML<E&t#*S0 z`!i5A&4b>qvC13JR&1K?xczT<z}JmpMCh&Oq2iUL@AKy{-GFv=j>7=xa08c!<C!TG zB24*y;wgm|59ZRWWsjl|mb58g$P(YNYluY&qScxysEh!DmquF`0mU;o_XZUpe4AGy ztG&DL;G4ozDKN@zxU)Z+Z6o*Gd@#~8Ix))gDl8se4vFzqQ??8lnaAVEryOmeS_rRU zKi&A&tLy%Ij-1j4`<xfvZH>?Z8eudO5vddE(W|ZO;i9{av@WSE*LrodM3~FAeJINK z;8DURYjDINYB0C2OL?4OGb6q?*lKRnpggN!-gx^fm!|ZgipKH%2AQk!8h8<!T0^_~ zqk5TEMX`?hH!Ui{ZQR7OO|8<upr6p`ltY{jYO)+GX0!B*a>um0<{IseXSj8m_nnj- zkL8}xA$1NU<a@1QjKLLop{V0k;V*C5<v&O2vuED;<Jmls6bi&O&%V`WAZ-WV)uz2Z z{E(e%>grgz3mkMqBm@>0^>l8qi7uH*Ef^m=Za9XEG?Aei!Vwa;B2o8THmA`B_N{%J zCJ16B$$hzq2oBIbm((_Fhgnp@mCE>>37}zG4OO4M|NQYB(W%w#e}?%80o>J%j8*H3 zHMzpJ>JHg@;`7qEwXHrALXrv?Aa=&%GTahYoFT8bvmZ$_&=&cc)f%2kc`~{@#z~Ta zou{PfRyt%NGrY{fbe)0zC}t|{Jb8!N(&o!kg>Iky{#z#AHjp?1C0mpu73QGlDh^^% zdQin63p>?+PE%6Q`*3?aZcnVtr~orPPABKn`+0MI+gF~gZOI+4+F3hyRjxms2ok7M z>a10x{rMbpE`7DBl=BM%Bho-hB$`19o7M+P>|LUFEB9~fm)6&T>i}Z;Uk<0Obqs_M z1Jh&vzAV{w%bR1tI&~UaNo#bnL0C~E`j^()_6<D4du3v;Rla$i6tPFbBF^NF?ggf) z^i6kX%g+f8*RwO%7|7n@wEARjb-gO{kg1`wMo^7;cG~<tc;~6k(r~iho3v|>L}=`o zY1%tAreDl(0i&d1zn0jUqvJlUIXvL?b5JXfkG9!7J(+K*iQA<1c9~dSDEcQanPc#U z)_-gTLv#NJr0-P(1D~t!diuu4kYT+{sg3Th&+#LxHYwuk=^LSH#I{xs%A7P_&u-Q) zy}_hy#xx31gncif$|`1g5%OB={k=DI7coyoIQLjRm68+iOvHj|C!~lbR$42v%R7D9 z>vFE40N<~|sUxv7ma$QhbsEq5tu^?WO2-XauXOWIxDKI%XLnmQY^$bEVU_0Y(@O_O z48#p`k998$xHB9a5pan6nq~EM?>M(13GLh7JQAy!@C3CEigehR9TcGZ^0vbw>$4_c zK7Le^cqVOZ5ER@9g9l58HSMDnv!vPGj3q+vxZe?Am+$vzfMZrjhvs<Gr*X|g8g7}V zp>5DsI6k^_HZ@ARwohtUqOw(===Le0Vm5(c>Y2<I=AV0eN-FP~Cgg}cAG~FmoHyHb zc{#d>ytONQ(hu~(4&JxZMI%;zdB<`8{Bf%mD=A-9=6@{K+uF4EPgT?0lqGZ1PMZj_ zUUTtdmA!Qq<W(z$YK+GM6<Ty-`QgH(^-fmRx{6HmoNE1IL<<plmNRTCC2m?AbsH<P zyI0OvoV4rW!V>d#y9(FYtGa?XJhDMf0hdiVD&SD@n(^f^E|L${Cdx5~qWg!>FB~#* zV682x&EWluJ~&d-(bIE8FRj)D*DvxZih-b}|K3aMVrv%+)n7(DW}!fH_q`A;bVxh; zw~ZX}!B6s%^SMyznsI<RcdF;HnTDF&mv!w|{ss2FFp)`yiJ2{wv--fuQcd@oAICiW z#3cA)z!gmj1yZl?0Kn&Eot}LMG~F8PGV6>C(6#~k=SQFH^C~Q^m^X{^bMhL#U<nO6 z2t7D>h23Im-aii^QlaYq^wY$ygw!!aQ7vXXf!S^S6U<a1>nCZw0CQO|!4YbpsUXfF zm|@#c7g7&G@yBhm#(t0P$JC()KnhxVLm2{be9Reyp^1-y=Z+DX+abAu@je>59~HQ7 zH6s-(70_b5#|*P!ahuPx|6?Wb34ABNbxEV;tY9Ssw;`gKz=Y(hsPC0=>2w~ugRxXF z!>Wspa74YxfZ~jpfk3rUd?f*zaeFmr!u7);wKY_%iCVRgLR6RH+bI*IFDU{aGaxd9 zlFo_>C2g(AaWyoa*d?!oKpbY*ftkHLnXno`=>Ok%Nc_u(uQPzB#kKas_Vw4J7RtW- zR#0nUkx-H9E{SjG*Hbq{R@gE+*aQm*GH+DIv+|_*GupkO)&SigV!%QT6cRw^I?b-g z?Y9f~94n8>M`&-ZqOvYRhI24X9wbG3t>Z`<4p_U@W9DWN$sNLo>ewH>-g@&6r>Qz- zn#4;7?g;u9oIk&jvp94BS@P%klS%&`gnyUL`ZcH>b4E?mBpl%{lW`IWdk-EF&KDp7 z2SB&}Xn>h5`TP@PE$hK24MgEkCy{&Vx4j#@i!}|2Z@ow}3jQ^|Qa$ISK%uA+a9oju zYNkdYHmD!*tQdU^bJ#<|Eb(5Ux6@U*IN)giJP#uRQw>DY$5n6zw-7T_2!3AX6Oa*} zBSK%Q%C+USxAOBqe6UbJYbP(H(qx!bm}1zrBRkL>v>&%PHvP9~zUivB#i4@HjI%eO zi*wF6$dRN@`pG0i_Iin{qXZnxX26Q20$!(o+8s~Y+SW;|R~D7nae*zVn7L&%az!o* zpI?q^@J`9oqRXmHE1%lv>9MyGrW^<zyJo4bk_;YMndccqKF{Ok>Ir&^sC(bG1Q`DW zkIBm$NlA}Edm#X2GloTiA;{<7HWF!|63-)j4^)Lf(L=9|pjI%8v=Hj69dLQ&6!gM4 z8z~p@auAW1?A#{=SJo5YpOglgDzMSPkMIY47Gv4n7CHjlN$dGMLRwk-Vwx&uC{}zb z7<XSvm-UId^i8Sw;5LXBrSoB#|I-8XVc__B>A&cap`~SMxGaM)paIssHFXZ|H%|@( zYbP1#U}LO;PtSn44ilIVk!040ZUjptBXyk<+z}0!Oi|JDm=cs4P6G#dlWLp}`8Rwh z4YT=*lfAm$bbNU4@#PFn(M=n1tr5b`{%D!DslP4*p`@=>4{b{fyIES7W?Q$(&^ck} zUrw;;80x(_E(G!6S<IhVX)izeWKR$A`Q)<M$1Ti{86;;@*FsBi`TkV88&C0}vhmTT zas6{i<eP6Sg^?3nxcuM@R^q;Fl8Pemz!K^1?~6c4^k7T2B|cX7aRy`+mpeZ8wKVXh z5l97_tgHBk;0R;)#kk-+7cDypJ}gB3&`LW$liGizeEq9t1j>c7x;Rv?oGaC~7T+A} zBLdyO;pe4T5rZ0t4?Ki#jZ!}q(2j*nPxc3-axG1o<%Yq6Ehxf{WIXzSHtkWMq9r7H zPhYp!*eM|CYaFxl%EyrcLUhJD2Ax1hV`c(>b;N$~iHM!yY~E{4;YAUm$a8z1%8XU) zXtx|Z4;AXB)X@)H3skzp`wGUt767R8Edmu;ONZ8OalZXkPA0gTMK?CEx_5&BRi8Fh zVosL(C&5A2PR85V{$sMftbOSb$t<H4dboP+cpsygUeCm2#TB3tr`a9H_=@Il?bim; znbz1I1MhDm5)x?1E+jnmo03gG+cC~KllNj31c_EJZ2)%o%p#7HM(8;@?}~W3nJ8r; zm`yt@HtNoGa9D=o$%hunCKcQhN&dpRr1=J*&_HL0qSY~%uDn6Em|Ios%20G1_<9Ru z@K`c`N6a|?Wd!l6Vt|^JH8$Kq2mh=Gkgndoq@a^%M;cU`cka^BrcF^6&AcV*ibl^L zR4D&2a{>Mg)iU*tOFqwLmw^t)^63^r9I*}gn(GV{PQ%1~$lP!Y>+|uLvTt5vSu>Q! zz+olKpU(PpIFeYo4LuS2D5M$T8KxU6S#CAEPmc_A@q-apy=$M(9yfRC<kwu)#HeTa zgWbC?Y{V#-@Ko&k!yL#1Bgk)hzLYaw?nbFJ_w3FYRn}8G4_C(UINd8>aR7PdT5QAa z(Pi{nBZtdp{n1*(a}&}#jA4{75T%;Mp^s_3y%1seLv&UQOiloPRRQ=*{J6q|2T11@ z>7<4sI4bZ}h`u4ga`f&h#t=x|U0L|44EE2beR$oJF;&lRC4cq4%~_<x9rY|0L)jvk ztn1l+<m{E2$jI0+3YA$k1KQ5a76^apx=&x>i+sAI-qGE0v?4fMX*{0H9gEjaXLcM$ z#hDR?^F1Lqo(Yi|*c22w96Yo6>|cp<g@cXtb&N2!HG)dR_V#^1TzWn?oo5ZdIK?_$ zYr-?E?|>boOWyBuhCYNO9Z-0vp0u(U!g9)aVB1?P1k#JpYFu+t!|5~wj&|$V<!604 z<sE^t5`mQrHI}iZs{5w)J=L-X{URf=I#OcIDcwt?q#KA@$1d&k#R~oV_A!*QYffJ2 zI6MxLmiiIiyj_F+u}@c_E=e=@(mGQC7K)3-FVBC?)P3l&w|!;2H*teO$16-aSpK1A z(#q<)>OSF>;<;(hlm+!pbJd$GYR2zR*VSe=9^mG08!-d&aCG1x5o?OT|8?E2>wH8_ z*`A5+cf*NG5>2b#EaJY@-tE8L1%|+uGP5ow@>a*OO<diZOy#vl?_Ix=68Z3bdv2$J zev(ccytb%5FROby?kNKG?!3NY$hB|!^x=o=U&SQHV(w{q2E+@OaMV8tL6R4WrRReu z>#1G0!fXv*L~+iLX!-zOPRnY#0cSTbAd|zyY?k;K)d-kCW04SEe%BsaIb8wfQ)@<V z*7XSO)2y8oNPv?U3L8|dKa~Eg`2Z4}&)4uCn5~-d$7%-W(=mfG)(bGN!8e4lG)&&- zh09<^lU}T}vbx8cm?*<&g@@HeWo}s6-7w_{TLZl+RQoJb*^xG$Pm}M2c9tv9dU`#X zO5kwNO3X`F*0O(xBFUK`+ADW#ynjS@O<eCaYvuUAZ54g|`cLEAeTpmhcQ?lH+^YXO zI8?W`{ltlh4)Trr4*uqdtQ3>^!u&eJ??d74BVpq?z6)9)_s`7=@atMdGEmvoq*NnM zP%J82N!cS==D0Wu9(E--uVyG)w+!kkHjo537neomdIl081HIdC_s^Br!Va=Ns|}iw zRvJvBo*@F8q0`63-*n_DPY<}edI2g@B)Pc;hd4^N{3I}mc_Z)8?kmTCI1=%&(CTp% zTMTz&=gWKY_@DzTEEGdZ6XIH{hcx<ApzpK}3VZG6=<bpaFqH3j^Hrs0pbml4m!Bw) z*LcUnz2KkJX`Uj<7d@2;vJC-0CENjj#-}!knCKLphq(IJ%7C)+2-;d?OI(Z&2*;@R zz|=rJeb-mrj`<UsgL{!K3n0Sq48n7M$5elM^hGN2sm+llE6rP+p6)Tz90uf2G(J)` zuGbp9g<TaP?hFhwNh$FAB6}kVqv9+G-L*mDhNjQc53@QUMeCG7-&Yjfb_Kn<WK)?q zlf3K~Aw#&nUuJ-ur~0jBmBDL;P1%DwxWOFJL<81l`(vvQ-zBmgjn>uDj%|Lhe5&;h z#jM`+T==>(O)^W(>*2*Ec@oFOE+0gsKM2oP5FHtR+$08-EqK?G#}^=Q|F_@Os{GA8 zI22|`LH^AIG4aAaEy>$plZB_Lv6ijZi7!G{W)5<!7NOO=63%Q~30B%Qr2KVm(YVf@ zA>*~vm#<FFAEw>_)J8a8AQnJYJA^>J0;0`)yW<G`(SYUfxZ$zr+;FvF^sfojN{3p> z9<PEU+>aXV_Z4MJGC=40(llqnr^3}uUrGaNtBtnMUnReCS8fK98+yG$I%q+LXwsU! zZG*YIod?1!A#A5vlbIb28N^f<{-2%M>F;zBL`e7U6cfUXkGbx$Ff0H*KAF4iBv|jc zN5ITT2xEMPkbRwwlRb(r#VgAM@QSaIt1Saj7zHeR3GC%xt!J+wG?Ws+#+e0H6?{$z zy%~u?n~%H$u&_wjz^noF_UAru2=87I?+1}08aC3#nYzJbfM)zIBumxN?Rqlk&3g7t zR#y{P|4;kU>Lt3-By0V!qFVhP2`g>4bz(3>_}<1ngE{-@j7n?s+u@2npLAMhQ`6g1 zfvq~baz7w*-e3TRXjr!_nxMNcTnRAbn0y?2MT<~K%CtpllN9?|G5syKSDiSCSkx2F z0J&?V=ZJ2Ea~_dD6PuLDLj9iu*88%+!y{hvBN`W_TGkj*e3j7eZSI|S=DC_?UBz={ z5T<X}K;Wqi^uL&E?^3E&Q1LY$dZ>>O7Un@odrIgKAw3uB3p$CNso5XE!k6&xr*bB- zrBC2hdu?*OQ_P}kh)h~p5C3;<L8Up%w!Qf{lQ-{>MB_d0YZA*lU>=x~%iQ=xHBjiD zwHAAZ*cmp@L|hZZW9Gp*Qs~S*k7hdw+Q2y0>pm<(tz;;hiyTAf5E;7B5GBvI9DRRe zyn!&RnaJmV-4k!bxp%Z{J|cRtP$^f2S7oBTn`GZWTj$Ev)BLLcb+K5E-SECfsx@%^ z<jKf9`8P4<-!1PtN75v;1$9{p4}nO#mOzGL(UO-HFPaLXo@;dLNa{h8vIw>y=3u0h z3eKOg;g<`ZqCraKXjCUhQ3wwqOtnD&8Nz;Q=?h$_d?<Z^*CyknlSJQwoiZZdn)eC) z#lDYqdw?e}Z%1+vLzkLJ`RS+z_L_lZK-^Cxx3G9!`E|W22?#tPIX=)KVS2mNG#kA8 zILwKwx?^leCTj=8qKWsg8RLPU3}EyQU)(!+5zJYqg4QgybbB%=y5usMZIV7e9qWz% zz&V5lQfHsR->}o0#)Q3X607H4V&9Ch5JCV%0&r;S*Ed><8k}fAYHcO|3D)e-uJ90x zfZUa*-k>A)(<%8Z+Ia>eKvIc4C6_fBlmGx;0%op;a3;vP#3Q*yfWJDX`j$1A#awBG z6TCx<U0Y1A{OyTXV6N!`E4Jw!Mf2jBcTL0nBT<b&_G^G|PzqHYKbi4tH+pyji8EnR z<AFjOP!W)+GlYDfu(mp@<WvN~W&VkSpGCvu`%r;rB!<y|AOzw9Q~~%SBvc&}5P|#A zT}!hbe$j;C-kE^0tZCNORK-h+S3nPc%lJwOJGGXe%Msb4*Q=jRu=MJtP+s4X8Qum_ z#xyaA1^w{OQC@7@I(o`$>^{}hWq7!<cEw!B-y$X%TujWYL9=qxX05=o>vIO&5O;_< zfr+FLh)&q3;PyT#Aqt-TD!c9X2-9T?&xO4{mDR3K9Gf70Tn%Rf6`pX3kxxj%_BB9d z<azh^#ZMZ5)FlEQRL>32$g$h@nlL!sz+n>>g=y$sEzN8Yp9Ksv5)luz;jAPC(%iig zMn54;kc5!fO6kN{SKsEq5FvDPPedD>sz=o$DLo;2e{kv7-MGkc!}hQ_LgGmjm}w@b z2G#>dwX@7^PID6-3OyikCR{bhNrvd5CQgg>_XL9c8^2iuOyQePdP@^#J@|Lg6ENV9 zi=X@$C9WLM<c}K<2`3!N*8jS?<lm8xJD=%3>PBSXbi}&}RXQePPpJg$i=UuPSbr?7 zQZsOX(mXcGmzlqPwdFfC45K0EA1$jHW;yUMY9<Bo2*M9>DQq=irHnk9^K|;~U!h3V z7?yu#0y*4P#!Hls<QXW+P;7Q%@cBvzP#kN#Vo90!V75pRqzBDNKudKWy+c|8V8BdR zX4!Jf&vY57TNMZFfD|SzlRBn}l;dv;`xyv7<ik9*XHXX$g4^sV4$?<E@NkxhVa6_4 z*tgm$2;uasl6LF!gAr8`*hfhfS7-AHei7!+1Eye=<`}YFgNP>TvYir6mJ*j+*R?Bz z5a`M0%C4VEKaX1UzU*}R1eAuEBXEtLvebRiJwff;egLfY*ynaD5|H+VMTd9H)ELVA zVhu3X_7x6|G>wnmG%E`?h5~qlq{}B7$|A|*bGass6exV0UJMeZ489Eqx?4Jq6sv@N zYa<`3{8byL`N6he1~)sEcvb~Zj`z`bA8J`-G3UWI`wDCV%^S$>lvPO+0O0(La*!OR z?4is=`#l1xRbP*hs0oKrkQnCEyyyPB_L$)jIE!;VV!Lt0luD#S^RG`ix716EB;h~* z`a#ulOptWVkgCBqY88LpVXJBMI}oBN!y<CVE*4_dO?Ktazg9_nL?4VUi9ZeT(=vzg zWogZG^vB+oE}~_VKLj$_?|<mxUQEL=gsOy&s$L6*OB2qet)WEb1BjW9zfYy}a@uIN zuiQ9|xF(SV8xi=&1`v78Nv|K;iyomkVQH?Rqb^)PbJJElt+nWsfamiMwGm{}B8e+D z1RTqlGL?=bhWvTT?zyzJCQ_#v=$)y+hC-Ns5BGIqY>z1~e|21lsLH`S38#72rxXdf z12}QeVAZli`rz{0M?6t-i`35bV&KzNz`$q*Dcd<?r;_H4bjERe3@jo~e)yg}M!#4H zbkO_rIfeO?KpFVhRM1pUd>oSCKJ$I;v7p`eP7EELa7IOt1IGARkpCo%ZJP;G3Y1b6 zTw5*lAd{m5(L3=KNR`&%E<R8dc@;Vf<k|j6MPH^c+HVu`7V&SoH45;~QT-}6R%5mf z!Wo{z>Ep}Y;T~hIvt|4*a?!Zp9ig5qeDsbz8Hn-yQE&>n?*Rnt$gPe!ML_vb>F%3R zq6y%ofy;f;gurrfQ}(b^3ovSc2{_9L`&3{`C!reR5E3a|%}{bjb}liZz)%IxG{hDh zl>;?kXyX}}bGG-L+~cc%Z92vgX^lqCo%`z^?7m8*3eL^e`>2}S_Hd5h!oDk=TaOjr zh+AttB+EerEWyAWjhh+0S;!{MtF?Zn#=-G!sr9wOg|dn8Dr^%nmxfj&gf|CeqCAo2 zcfb?^b!I*D)c|t6VoV~lyQ$0UIKKP=YOkO6^%r<uPvVVe1GdtFEg+!V1OdPw=~(v% z;w~Rn@T-}cO*|fY0-vHIUHs=<l{)lV%C#dY(^j8YlxFt<5zc4<n!h?mT)h?sSH#=T zxC?|V63pPiw!}h&Qsmm2qaKZl!_MQ&!{r|jK>~D*L(T-Y#S^K)2uQT)=4ari{NoMP z|9yMEfUrXY=U$_$w>Iw$ac;9-*9rXZz1D7mSkJEA#JJ{jC|Kb%W2M4{m*a2a6YiwQ zUKy~-0nookdTZafm=z;>p#!b`{d-u0Ry8A8u$y?`9!KDb87H<Ih{ZdEeJBYkoAMPc zj+YLb0CDa<BnZUNHB#YtQ!aktX4HvkEq$PQ%D?GCB~4-`jH`}jthAj$og7(&;KNru z!N*6Xmf;)e@=zESdd~GWvh7qseyE}HN1d=tgx-8A_Qn=F1IAqc;w+Xp4i$Z{Qb@l{ zXMqUuUV-89dMZowt$>dvS25#=cz=){#ek&)O)*OTh77z`7+@k;%!X3_`zxf(yhY{} zNi4dtl#ov!s+|V?A9)E8S*1ldB3or-*cmo_pkkPWJNr!1@&e@HkA%CyIY5e!xOo{9 z!w3-q#6Q0wRub>m--qq761}=2{bz36pnGtO8=XKulgujFtS=KnjC#IbG0J|Rx6v^v z3BB(ap08FaytHgsq6kcwqB0=X**;rQ$AE>2ZGc{sKo8g##W>TQ-4!J@r3VIcDG_61 zg9VbR`XW$kfNd^2kM=zd6ta@r9LDL2bNz5d;a+eE%<b3#M!H5-SscPj!{_%irvJDt zDaUZnFpfsb39#T=41{TkMKQVHK-s)9Y7Bd*7j>5o<FUVm3(x8QtG#QFhdN)wlUlW` zw)T{k4(YPHoK{L$O=KdGr6%Dp>sC^^Rb*^LZpEH%B)8Ql%0%uoGpKagwm40P7_=E( z>{cTo8!ANSc_*cF{yYC4f7FK<zrOSPeZTMfJkR?)3y|m_Idd3wvy{32d6i64KE3+Q z-YGVEuGn1_fUCTCJNn@5yWiSKqdlY4f--|UJjGL1eDsT1P7cX5m!u$ArG=veKD6o~ zdq)Rll$V2-37q~Ys~-*uX^^2&CRt(rjCQoU08->1pIZmBhg$tg*5J0{318D;ga-0c z>j?{N5@YT8^S|vK{c_RxiuXpXQsm=Rk}$+l3mptk_fI;58kOWf!nqx5|IstVFu_pQ z(?9>Hp<uIfy+znyTMTRueizfIJWDP43#==)!TTa;T-0DjeJ&1@m*dM{zUfHgs(HAa z?Q9#Ck`{KxFex7C?sIefp#}3i?R`kol%uNW-sOMz@Eio3`FlWaYBJn)?qzHR+|P(- z<HPqsZ9Cm?v~3c}hlw^C7LDt99SsJHKIHE+!ox^MsB8rY-W_Y^f`LWpFSz->0^Gv& zhDNsWQpBD?Amuz$nXDqq!Adc-r%FbHw<HU>3D1(vfNxZJ?$*S%5{IFh-s!hGK_}$- z{eZp!q*1k2wRpZa8trAo*yqs9Qwls|Tu5RMhZ_alINxHDGXN=91CuRD`3(t~GwDmW z)(;M%Z%HJhMJg;^5`X@=|Mkj=PasXQBQsMB(4@g2V?i(ka$|0TjE56Y#fZlgoRGW5 z;yv9wGsb=g<$YbN4e4xJqZ!sQR}Jw5=VWg%^0*hQTM&XZpne+RAv;24-yfJ>@d-k{ zk#yP(^;BQu*}-EwH$$@*4XHI0Jl@!^qy5ztK>0Q>m%f6(SDW9j<}zhm(MggH|FWKz zb3ZNTUz4#I_fmxlFTf#`K6c)%qg@1zHCzB9kAgVoE7@|>+W=d;vA^=c#AjFKTqhK` z0+v%`7Qe=S<(wEI9pAlWTW+P#O>+(UM_Z^YlLTP1w;O8P#Rp1;TTmVW>OD-}p;dQ& z+8@I9tqFLs8u!n_X~|*775U^IK>mRo653rj!dZgK<!3ZP@Ho3EddluOZzly17I56d zhmF9x6*Rs>*5(y6`Rd7?yZ$Z(w5*N8ah;N_Vb>d&%zKN~vUg=*r1Nq`sFfEy0`6Z7 z^(O!FQ<k?2h!K-tv56<DEwa^`-D$gAAD&KqR}8ujfkr6?<!4SiZ$aWD#%qewnh6m4 zm)mesw8GkZNim|eQ7Z7cqP{>q#MiU4ac*dZ|J~mU`Hz~jz%~{EOq3fg>Uf<tTkD6g zqiR)s1kxpxQF_51_l`0tID|~otDr~a7xHidGr1L0AvAd2QYM7f_=*6~n3ysgiWe4r zO^$QBN&=SzpJ)UZPD0OsJj)TYT+8^Lh;HE>o*|=hF_O6)(5oXQHU3+-^A1E+OP!Fr zG<-Bwbm%j2=PdG~3T>cikL;Zs1MTXraxpsIoxONc>dIeUcrdcak)5xLb~1=W<){*P zKSb>1EPI1w4h}1$0kFH@2&rnQIgLK4KmMe)wL5ZmFD<HUI#Qiw&>hvR<vh{8yVC2o z-wx*XT_ROC`B)CW^_^KhRa&TVzoDbA69Q3g3*#YlgF_o2)gUO+$e??}I#X|{64d0o z;{7Dcmc*_$n}r)z4;A~`SEHd-ryM3Wl9hho2DGkA4RU(n2Q?3K+2z?O+%NCptTx_L zw=UtU;Nm8Vx1ija<MT~x#|j5VIBVh3*#_G@i*O@C$$cfK?jnRDWbIzac?h9E3Vbf) zj!C%|i@Dvc&CJMSlJ>*GAcy6~pr99#JpRDkB9jqJ6BS)^j$hFdF=V3SRG6-E@G}Mi zJO^^YeK5bLCQtB3{3B_M^|k9jhNQBrBflM0)kCTAARmXZK}XX_SqA!PihzV=bJZi9 z0YARvJwUI$x&ALIE@#Ke^r&xaGYr<yz-xBe)XZ1JmX-$DSU6}jzC@njF{s$?VxnnD z?X-%ke2q5cS&IaZF}5nkfwb)^<z~slZ-H}4UjcXe9-7ud1;_f+6U>2gbX8@G0egrf z6If{fM%GyU^|qH{W{JJ*nFGf=PuiyX>)<uiJUT!z16xk@*|Ue*cGZ){Rh9clWn>9& z>g9rprKk1v`-@NXh@{(((XccjVT-NaHM|TgEE)70!=JP!cl734RPIT@tSJa_q2+-Y zWh~p}Rap10DWD}vh&!5ug3rPw4{ZzVxOMs}x9AxgM!16B4lppPzk(InK&cAN`8Ea9 z4Wf!*zRKlUUhrQKH}z_6{ipo)4#Lwg$5MWCdS?9ElM9C`5#n|ue;v95n&s_#y0~^I zd_oiw+U9M;mU>2p%EO4a6B~jg^VpkB9SJ@C#wD;FG`dwX+UpCn$tXNBajfHJyk-eN z{fXsz-AL@ZMw8PNx4;SS-0clM&PE@BSS^3EGGI%xZ0jZ1?xZDsZk?{)%!|iEl62hm zqM7N^7xvkLx!V>28R}_wqc6MwnX4*vw3RH1=;{vy7*P}sm_lSX$3r7-Stz@6>b=~A zNVI4HYK%=ND$VwwdgzY#WX>4D3GaX0BgVekjd|#jVmg_DI)?j}{;bwtKJevQE8cDp zH~u!0O~1yz%~$!Mu&-k>=n?r=6ZJWuZ!mt^*lNDVIO1A86$2qDCdoNL*@j!E!%yLJ zxOv0E7y<fF)g$M3x%gP!U0QE4pJL!(HP|4kI^|~c1)$CQW!Zn>YL;QfNa|IbnK$I@ z!|(7)Fx?^*3?a{owM9#NzXw#mbw{=)kLJ~Cq+Hcod3Ka-S70+x3G(C)s}Eiq6-ts} z@PRQukYWp4ktkHm{dKxVc_a$Mm!~UHl1{#q;V}MQY<`#e1xP|ScUCe*f)HyVW^O*N zn4_M&2<ifn4|jiEz}ev4Lf|?aHm3eOq-WrCaW6kJC~O7)TA%M$jzGM6lTXdrx^F`0 zWEC%C-f{hs`Q3yCsw;Kg*u)n!FZ;e3&<s@=qOP<o2On=4pf>E5TD#CDhj_S03^>l# zSXE%Vw3U$W<x`vHxIArAW~RihEy<dDR`J~S#{uK_PZZ8KfH{r~Utv}VqXgEaFA)P# z2V3&|NrHTK?7z^8gR(H(ED5y+jp3VC)VJOeLtZDI&=l#jmb$8KX)25<@F#nnGFqAk z@b2ZrC8j4D=FHGB11o#YUS%<N(x)S3t=Mn6ciTp?a%;Az1t5jFw6D`aN&QmiGphs@ z?zXp!_vMV)cQP<qwu>!Gx2Xp-=ams_vrsMR$9Xq`?lPi0@uodMA0pnd@@%7*UUjB= zIxy*V6g*3ht8DLTDXO-vi-36q;>NcL?jm<96o_(c0ykJx--~xaPzB)!bK23jZF*dT znA3N;qw*V&mzIY7s@0=#9xrWg=l1x+yFh=Q^-7;Dw`RV@op6&lZebs`>O?r`UCm!V zP%`KJ+b@58h~A>}&=;Q!eWIppD^ao$DhToH!kR%>&3LD0UYx3BYs`#fRT!qaoZrc; zsjlPBDIh0maAP^|(e{GN|8dQ}><p8|DE#dJ=YWH+aL8k?#C2@l=!@B>9MCj%?)zLW z#x{bew+8i`gT`AfZ2^?Qr>Qzu2Xd_d%E|)y_6>1;c=G-UzJ@0tC}7W8WC=*kZ6iiU z`z7m0LKuo#l#duCN?)WZo6s|wCrF$96ybV_;Ju|Uewsd?=D>`;!x%reyL`Yf+e~w3 zY$FKGRxbH}cHSw`L$Kt5Fc0^zr(X?X?Q+I|{0pNr(>u^HU^>z-5p{XLuMZ)NxM&d7 zRNAE6{p00fw*!ey0UXENNNkg2>jx>BvEQa>HeB!R{Vj~IFV~hE<&Y@<4HBMfK}y>@ z1cYEz9_CJevxxhwjAdV9HdubbqrfmlJ~8HGn2EAac`3IFzBMAV>I3%Gw=l1DJ(bcp zq6-vrh|&%KDx3!X`s;fla{9rzdcXs85G0>j|NNk0u6pwMnS7@I4!}xX2B-&<=*%xq z8@~q_9&l&WMeg4xYmQnxKLHzDLMB}<@2w`Y-wZ`_=4T~}rc)|*Pv)aKNWx|bfjHvG z<R(12gXK=CsW=_X?TUJu#1h$VxG@D>UUB*044qA4s2qqdLj*(Xvn+sfBD-r&)vf_> z^hw1Kp4n58kFXQ}*cHrK7KSQmRka=jg@84aI>Py!jrkjk?|gijfw7G+&~m>0=zx*c zQ=IcVqW{%%??Ms8s%;7q6bi<<EN84Tjy07P%>o}u;V&pg&*=Zy<0?Hf7qsg6nY@3d z!Jsfy&183}?lZOs&4fT!IW@AtKwH<fvQ+ovjwALeZib9zrS<%jlkfsnVPRBYI44U0 zDensi^I9)~+j7zj@4cG$>bi;zj?^8;8~Y5mw>hKV-uldaJpO<YZYeXj)l58p>JvWp zY*Ce#8?&v0PHd>50!3PdziT9SPOBJlZOZoJ)=CK~;GJUjpR4;kf1`I8(1u~We;B`- z*Z>kV2SSDGc~i5Gr{dU`CMfos_@V$esyQ2%5w<*7(;nx}#<RjCN10Bu<XiWP#+?x` z|H$+jD8A5>M1zs8XP6%O+g~B`O1@>_k7-kYmuZ9uVD)P>V;fm5qg%1g&#|b)0&;OR z^-peaebUp9ZuEKe{DB_ev5=O=)COrug%8<CaeU9~y_o#T(O1_W-#>{?lT+I{Yy6?m znuh=MB8{NGTWq)j{|<xo2EV~?G9X_BJV`d=Pa(pubwHqylH>005DdS+D6MIj{EN0; zscdsJ@Z+xnqL@D3o8!Bq5f6K49A>~*rc5Hcmk+QOzQWQ%D(3ug_y}K8K#i@2lmFvo zKwvXeNgr)qEG=!z)#DvHer!_A>||epyT&ko^c>`B)m>%5R$uY)bwU6#kBYa)FyKAr zS5oa%d}+wH3Jk|KL7pxuz$D-$q@{y&)`FtlO^$uQ^zm!77GtPI8@pc$wJPWr{GA=u zbvbZ`J+eOsC37knEaKtgZJquB#;2>hfv`2o<|2Ad`ATrl8vKx?Jw%w~V9^MqS&UmI z^S^#1F3ydkmUk@=&-%?LnK=!o3?ue-^sPFnw=bvteGi3~W@rV!ulDJ)eUQ7+-|~;B z+Yk-B|AaA(Ilc}IhWUr!PJ9EaV|;P(K52|EK7)}Ba{9w-{QsBz56h@_^zG+E_ql@) SLcHQ=1=m=vT~%!E8S`%=*!=ha literal 0 HcmV?d00001 diff --git a/documentation/images/simulink_lqr_top.png b/documentation/images/simulink_lqr_top.png new file mode 100644 index 0000000000000000000000000000000000000000..c2788ab123be6355915c0ee06c7e0c93fc48588f GIT binary patch literal 84585 zcmeFZc{r5)-#@HHYD60eNnLdzLRqtoeQB{9vXdGNL$YNrT~aEvkr87l%LvJqJuN84 z5@Q=%$-eK)V1DmY-)s4P@B8`P_w(;_JdWeKG!D-5bACSW_4R(e&U<<~nk*<T6axbT z%Q-DI0|o{rGy}u7eLHu+PvVC67QweI?gpAF3|aMuN8rPDdu45928Nsn<~3VJ_`K_y zmZ>`f1M5fRzb)0SX;&B+=&#PHDI49e8t-O$$42?SF+;qY^xI`d_3hkV#}9627Ubf- z99)*9tf&0GJ!!whCH<{oVT?j*ISFbxwrZ6+YL&rTHPn^D9vxIV)iOt~2$gBG?Y>?s z6CKwvHRLl`B$w-FZ*PzF#@5RXy`YQ38vgYad2KuK&wn#8?2qU>@Yg4$AN%~b{`E;q zK3Mm!4-EG-r+5AJ>FCT(^p?Lqoj6j-|JR3`pN=nY|LarajsH*HOb>7T`jTywh$Sv? zb%bBsu4=b9w(ii}Xht@{#LDOMZeDa(>Dp{<PpEXyjgJ=z5?|`#<l0VIylXsVRocF` zHrL=KlPAx>aFpk-ZQNeyzj8hI%9s6f8?>p|`y$0P63*?7YrXV!>wMN&=ePG{2A&$$ zMIKYF^X?6>A8a7H1}=YRDzPvFJB)PxYm<Xbi>|-QG?lsfmCe11)BZV^B<^`HePd~G zvSdn%*MIs}=0cG}({J2Lceplay>vo^;zs-K!)F^`-1u=18|T@2hKa``lJm^vKVoFu zQ&^OO)@C$IUYJ?IJud!zk86oT!%fL}mIhT;nNJV6rA2(b$SbR3+2mdPFKnc`uBp2B z1}t^xc`c52NS*k7Z9Bu!qQ9Rraj$;B4MCgI@wc^MBpK6?*!9(g+<Zma(v<5*J<4v+ z?_f$=NB*)rMoiwpmn!um&8e{(54mDQEQ{3)?>9^o_PXHOvheW%i>BOxq`_1|*{cRH z*2kfLTC<Y!wjH}qPf!b`pYZF3r~E90t!*xHx6f@r({7|I7ui&9btg-<wQnd>bcgPX zmLF0ultg*Zm#Y;CSTZ3d0=-%z<(Gk0%wL0JGW~1$Y%d3G=u`BKhL+c+xi$>Nmp`M# z-F~Q1AB@*LI-Z>VEVVDsXKqkRjYs~*o1&G$ShDX}ru_~UF1E5HoKds;M1EU=c5mRu z$`E$2E~em%c>pVH?cu++7InQcm3x*k0VU{KJi?btn=H{ZBn=KkTT4meTHf4xnT%Fl z>hYU$cs*+LWWMHjgajOI1%5Bdj5xori$Uq_-ap+}KtO!Cj^pMAnA%{%ZB{W8OHYi% zD_oSYIktRtG{eF989Z~l({y@@zjUX=@lDH}>93BRDyP*4{>PfWvilbwJ91M5OxL-f z13P$+KmP6pl?Zm&X5lxHkG;(zb-F=e$wDH36usQHjV5y>Xw41r2XTC-1Wks4LFxM6 z>q^s`9@)W|VE@AHPQZ9_P{YO1v0S(Qs+4n2_^_Yu?rUlx#i9d>EeENt72TzC^>PJw zMm~fvC);mfP}=|3Rn+;8oZ!Q^U%oF~*SoPOP32E*un}vvrmvdh*2|7PcP(GxBN#{; zrd-Ua&F-6fDBW}V37_`cb=aJnKac(yox&b$eRtU~ttxeELr<9>b<lQ*9BV(?mhHMR z6A`3FpXdeOaA-Ai5}s>R-J=f2P`1>QOYDE7dE`v8#zV0K{5mJ#Qb%q7w2hm;B{O8T z|3sntZ>1)`e}l;|PPq^*()5(n<TnLR($p>}ZeO1_MgRFkR|BqAJeDOM>r$NVGn$^7 zHUo#J@>lFt*SKYs^JO<WmoYwkwW@R^CH5lRu`Y~VC<!dAGddqf5i9du5EC-V%A2Eq z<lV3-=)?)-Iy5B>V=&Emj)v~b-$P>)RYSj3gEQ??|1)s2#aw1Z&%s6GX|RZkak8Fu z2Xy84X=f5_Ki-KEF6{bNp9{u6cyk-;n_Fpnz!tLbQYHaU(Db!AY~AxS*v>phAI0Mg z3<BssEmrB#$*Mj>?XL$>@^QqVjSl~%Ztuaz7esRM(Hy5P?FFYIDXfyEd)v`!0j9+s z=^gmO?u&4fI=cu3tj2>wwp9_luF=-SZ43-2nEuQndRM~EEWh3va&MH^{lg!-2E8k2 zaWaeTcI4TC+GP9tp#-wR`h2r?cd@575gkzH-k@N=u|5?Pn_aQdDN=!Ef&jw$X8=j4 zIiav@M6TlvT&}EpA=6w6PMM;7d&l5&yYMq~2!Tl^uYD@kX79^<|KosjZz4F#Gvr9> zxLr$a;lbTYy37K3*PnptjH>><kuRBuZy}<XJ6-?!^yFZEo0YiVWKpVP`<q0c`6kUa zhY4NEtdU|o)ukk}<H{55I>a`qd(xw3k|WS>YcmE~XSXrjymIU>TfE2>tQ!)mxUrlZ zqu^J7mo?U|i4WRX+4QZ2v9`hpUZ0=)=DrGLKW|Fbqz<XFpd{JfS>5;^BITcHnwugs z->6DPf})e}=nA+~$3V+0uIPS_BNDlJ|K8Vcd;P;!YmA=c&|$yuX=z-~Ncawjiqxf{ zlvo!Wt|iS@(RDacCr%a{%H#EhOznaAHJDR<Bsaj9<YO)z9i>~FKJdyF3AOkB47CDc zsL^jq<gdlkhLR^K4_>b}8VT3!JFd~bcYY+5SRkp$>pOgG?)|ns&uLQ?y|mNU`jo_P zOxsXjPKY<i+x41EWe+sYIuzyki_EuNhi&=!k8Lpv)^+=yN{GPp#vtC4FH{ZoQuTn- zuE%GHM;zB8K<#?{p~l2IfU-7bO`nx=2qa_=W-m3-MgkT#%vgmZqAt{G4kMxQZ|~yM zu1rlvi$|X_z3hY$bXbGbSeNJ6To-K}=*Xw@!U0Vi7oUTb6LirlpJ)jyxD8+4GGfo4 z>l|)A0BiiK$O*g1bz9f|a~OL8cA!C#?tD<x%K4y(g~K*2NlDuJQZF@7DqzpQFKQ1M zDAV5t`ceilgPkGb0>8?pgqqDjXLQ(J@7E8M9-T9rP9MAyarVbfq&$F}KqO>htmEq` zCf4}Lcm3fGyBQdsZvFd`Cxn+@h+Pe{9OSU}KSMBB*HKt7a$gyU*0ig#xc=q$6z{2? zrbFPzjDP#_vE|oiDQ6!tL2Z~Y|Bp!fuyQC#{eB(0iG{6KkB@yW_)lzqxLo}MUPZL8 z*Rw6#c0BK0pY+Dw7cMw0Y+fMYTDD+3|KN;k#d?7ZIN3!=?__K&9&475yNVnf(Qu;v zp;Tv$b3Vm*aJfH1H1=Tjj0~J4O>tqAl3UxDVIrFAzcM>)YDbWEb&0l~N?e%&3mp8y zPkay$we&fqzuhp8kqALhBJ}X}yN=&p-s433zvGnidW|O-+YU(g`rBDIXIm>8mU!Ve z%@2;J>&{DV=Qp>IYGvZhWbqh5D7*CA#pkCh9~@EWJnYe^>=l?)uCUZ$&nu^^z^}<0 zkXJPQfq9}I%=tNZIn~0Gf*E|Gi#~IkX^#|AmW_1gX9QT~t)VQY%9gCS)8ZixY!*@w z<if0=Mh@fohx;A$FNghGT-l?zcA9Xx?%S&i<N~UTlSujUWx1X=wyK*YNp*N|t#^-4 z^_^$kCEkTwNOR-44V^w4(;xSE$>*k1Z%q5N+lF><rMT@uFDJ054%NljRZEJNh2~!S zt|B+FGDM6>VPLp<`LBANjg!&koPofy5x!p5b5zZ)LY6k3i+@tk8$>T#52EZKU!D2! zxnQItUcryhtRqL3aA<tL(Eyc&BF(?NFW05JIK{QMd@(24?By!`(Q(aAH-&oVPUFhq z#zfWRGYkxR<Nrv3dqvKn7>VB9p3xK1;)b-v336iS5i@x1jn%Ox@eEo+(1smtvCFNR zN4q+lhurPmiyum-pVXZ$f;30iSf^2|>%kev=@m0o++G$DM88QHTD$)AN}YIvnjP3? z``?bNam?Z|8wyQd$PVflVwb9t#CNv5fSp^+S*000=WNTeloN+wL*rT)D!TIJ@o)@A zn}Um<8)_)*uYdsPzJn-imiOkEQ`Z~YkK^<p+C(ATa2GT-T2g<zlE5Dq_H+36cr<Gx zVcs0S{Nui8-P^0Rby+2oxNzA~0dc=YXKKYzW?|1}{DksMK`sI@D+ydnjX#unUKY3d zWyfCIA;nR1rnz+PLaTXfk^4~R5E5x}yS=C#OGpqJ&y&J;w%gAB{Ng2l#Gmzue0%*E zk-nBX!9QOsS|L#~{`NlNQR8ze-~dXqfA0fddZm3qA`}~ok|?32PAAb^C|hDY+br7< zC(Bq!Pe;q^LIj|#A=M~tzzDA!14ULxz*6@FJ^hP$Nc?IqLDGr9VRfUjd^6hjqt3GD zRo&JdX-W=_bIml%ckc83agRTWF+J((??~0t@oz_-+0r!uG5G4oFV0Zb+R^48NIMCU z(q%kHjpi2Gtf|!<YxB*zQcC23YTh6TsGKC`2FdpkE0y?1tS8)tv~pAL?CpQGpkcca z&r$m9wgc&);fswEIhLDY{kxGy9KHm^Hscq2H7DDzALw1#T$f<@|0R}g-ZAZLeZsFl zx%t~>TGw-Xq5Q9oR{ai=*%E&I{|otlw<Ay6g6K4B_fPvYfAUxbEKr6iBc2NslUTXQ zcgMMy$B@crY+;BPRM21E>o?w>({$V}-hcL7b9n&G;ZzY)2qFzNZ_w-)ey??5=r+PR z4hXmTO_gyx+@kdxoL9o9%u6{R>IjmxyAPdy?=jick%y<Y9)?CZ1*+}JJFS`K)F+GP zu4NP?qQ?)9URLIRZ*~MZX8}(~R&){Tg44#@${;BtOOTr&g~v&Cdo)v0KHtvEEB^WT z!o{hcvgDjMR(=zbG@kYEp}gbo8kWkT-y)aOCb=JS&J8C=AOTXC>q3gI;(80x0y+nj zA#rLQ$|-to|7W$@g)a97bvuT~cfp3vw?M&4wkHN)H;}$EztybP8RGvST&I8|7*ewv zM9@&y!FIa{NfvIYJpQK;k4}r0%|9-?)O>FG@$VPLXAzrJN<VKm{l(K^;T_~6a=qNt z;fKfmsOxJ^g&Nf@zfYV6ilI14D@P^&%}B8Sgio(6ioRJjS_Z8zV4>rb3R?ciTURnw zUZNo~op-8uZ0dDxy%;o<r;#o!M%I&5HoZ1e%{viS=*xm^)>AI_@>IsQM2e94G=dhm ze`YsnA3?o{kefV9op(S(Gx9e7>KG-%o}O)zZFQCE-1W|FvB*B&rwY1yk(9vo)j{z0 zLh__6NuL&7vG&=yu-j`<ftu%N2L;w41*f{(d(aLd6>Ha<3tg>qKeEa_7cOZ3;1U5* zQ6u|O+y)(zMp%`x4@6IV^UK;OVVZVkEnGIn(z~0|8i;Rw9m6ShMGNW-4vTBIipH`^ zl5#L?;l0obG(FFmdPQ%hyCR`4pxj>)4Sn2==2D-z-rex8cL9OW#SFf1uRrsUOHvF; z;T=xdWzLy8P1YfE`A%&Gbn$@I`QDc0HKay(>zqrL!j5GYN`c{)$4I+c&A-l}FF_6< z*oDhfA^k8mLSgX@dBFG&r>`bde8u`=F4c4{4yyQo^51C9@MkVwRJ?Rac^*2SY%!fa z&<O@He*K8=aALtO3(cw2p~BukzucjCzs~ifMp~4833{Q$u)sKP!<ssJi|NQ|exm>N z`EgQj50bMMHFgzl{GhSk{DGwR-_<x=i>Dhy{?O_2OtL!FG9Iqe>8X;54fPPqWZwA! zf+YjPD*@q3emF}}@#PkKnV*rW7oiufoBsZBVhFhrS%VvY1u05~F&W%|`>>=_E@pj5 ztGvxbjm&at%UbkdG(m;4UmDH%@DmQLeH^;rtJ+K%yX+L`v$dksqnUQq;ZkarZ)|P_ zl-oDNZ+0x2Jf2T|=E%}`VL3)^%VLk52K&`HBHcM~siarkE+egKnz%8a`nGy?d=~0~ z=1JG=(%G;W3CG7s5#TIrM>!jHn^m^vPL><0bKYkFsy}h)dEX}XgU{IB{)BX@cOE?E z^snlrL3%07ZcAtg{IHAvIduB%BB8Bh9l41ss^{=bAzrAlye#&+xU<lKk2~dA1p!*; zUMpPq6yJa#9XmeZihYpA_Gir_DYh10lVu?@kunYK!BI&#k1SLBI8W!fZv%--Y37Al zj%`_SD^Rdb6tsCY`LlmA_6Rb2cP)|S_yXOxEb1d8arFgCr8kg<rzy0^^C)Cro4v#B z@`iTar>C&di$Zs_6l!llXZU37vYJQ@?<s^HYY^f}?wBqu+A0~p?I<VWx_=D+(B?oD zA3xppnM{zduRrXUnl{O`4m&*&_jEF86RJIb57pazbF6VRn$us<sAXdwLY0Q0F+Li4 z>sG04FUYo`JXojZ&*^tkRE}qgb6A|zx}I_|=JH3q5I5Ab`O+S${<VB4;X4V*NvEC4 z7FvavRR+FY5Y0bkCFK$?Qfj1>I-u{sH#4n2XRK{#qN;y~mB;Mh20N;T?L$uxeH|)6 z&jCULnZv&-J>@6h80H6;GaOCIH09L{@pj}3%IR06Jh}Ivvr8srxsPOcy@jJ+tG-hV z$lGh4w$ftnDHq=R!J68J?=KxeZOfmuh!g}YsW2`yxZ&%#ZV{n40Q_zIokN@xp*3_k zXOSsYe#+dTgd}RqSnNich~e}nc@-z)Qyg8^w+aM81rVuMoQsFDsp*m}E?mP~el+~^ z^0~`bM?RVIci~o5wQqNU2U>~j_Dp<PqD46zPH=5f57QZL{?@ixM?4Mv@bGeOO15f$ zi(=|3YT+2ZEitAtmEezIDYyvETHx66_NqjIEM?j7K%SeKH0masv*0^}_LR<2H`F@} zIstom!HiO4nESy+PdtmXE`;LmuRV!cZ^?5I!5v(Hradnr-ydZVcVjv2v|c_NyDaHT zD}rx<<$Xl+hinzouStDlLJPrN!tszy&7c^T@tt?z9%nst`Y7RT7%pG~dRwu=9^Z`2 z?jpbhsXj%4zt1reJBKJgUHLNGAbz!?TT8`a3ouHr`wHca3{A90s?xEf!3<A>nDvt; z)9HJ=-Ll=N=OUO`xUTSC*fdEDnOZlI*qH{8x^?VqrXt0kF>?3jZm!do3bpZhQ1n}H z#1}g>TfT<k&Qs#mY~acO2bDMYPAG3+d(TSh;H|fD{w8;HWIe?)N>)6!kV@8Dc%c)8 z3=(Fs<pUv)5BAi;oroIpKiBN(fSpcnNZEV(NkQ@|rcQ(W3FlXx9+jkWEX0_LZATFn z&-08WjZ^;_d)i{^R!v6Z8D-md0?QuCNy&}6$~Gcqd?EfM1ri-|pg;$^oQ6+hSbS=z zlXEMYpyrvcn#*_vhodlFL6x`2k8fc*Y(twedQvzl^tQBe2&qhC9Vzsx^bxbN!h+Bb z>LCOim&u%<?z9gSwS*@+vR}~QhAi5dy7wAtn+m?}p1ZEkQd8GwxbA@~N1=ss6$emg zOzbze>?S|0!6AVL+QH7OPCnSUuX$p(8=S{<$-LXNc0h5eB@j10cIBdKBD1dLU3mbh z3Z@<`pSyZ><cg{Hcvb8JA7~QC-~Jq}EB~$KMcCy2iLRntg`#-C+7)E#OB0a7_h#N` zdyd_F+Kty=#v0G&%jc~xQvF!a%^o}i#PAafOtHKn#WALmthtU&Ng>_kZXfTk<j$=u zQeA6<g%%!;rae&F@@O^R<Crm)v+{U^yg_TJ<JI5>fTcTTcXGVOnZ5u!Y*_oiEZSb3 zL`X*+Xpo<~D3?|Ko1Ew96<#@Wd_KlhDP?^OQe;j959N|)z=J_%H0Hj(q`s&7jlqp% z1`M5p-Xm~=BGLAg^r6e5GS%g`#?t;d3hm@eN~!uB={&&7F5<naW9D-h0n?cE5$N*r z>4wkxa(_8;I<;=yOuKi#|JD(tmD$B!(dVI>#jGo-oN>U*Gi~a&$X4;#<!j!7;fK!r z20$*7dOM(<AwvdqrM?KCY?*I*DuUSA31t8PlQciuX<LQLn(YX=IvUhuKYh}%h?Tq> z%|1Hn&g0plFZH6u-atG9#p-#$U8;D{<atVG49PNmLl@(>1SnumLrLHHIinl-Q0bT- z(BJYH_f=5B&^nHEYlt9%nal9i<q*X1Ewh>2Hk{(&*ux9xGS;vnaQ&@~@zsM+LkMQD zr?)v;G_!}{ilfMkR}dg@qO}?yB%DhidyYwh_Z@u8DnG513us`BX!-I7Kwc@WM_Z>6 zbZ8-+-i+o$3Fqrbk|lLB`25*FICbQU^jD@XUSO<1DJ@uy@?!Fp7ECRz(+MW!eTLt2 z(AldO$r`k~I7RDgm5c?781jX=HvfEKu+#Jy=XH8Ub~$b-`s;S$fKRUqb>W$bRZfK| zNkJCo6z0cG$M|}#Tpy&ND)}Q%ZF+l$$l2~lpYQ2U6eRtw1CHN5v$v)C4&kAGFA<$q zad3e{%zycsUuYUZ?CZGP=49{NC;~DZVULgu;2|B=x)uH5`K@hCzI)Kk*AXKPYmHIS z2tYI5ATdUF?75P1M8UTmEy$jCQr_Ubl=q|s?FDld+d(I)Q{x)HHsK19BjgpCAeozO z4)rSjc}l{Ubm!^xiDVzFNRa%pkwDsp`ht%%OqIATPM*fh)y^Vt@?PyZH=?$7Y4OdA z(w-TnM#8zPK?=)#xAEd-X5MB@MZvn6_Sy|nX+b(6-oBz`Ls8}~j<IaUH&PcoI<7`{ z_&6%Id8|hetiqXyNeqU{FM}P)np@_e)Y`9Les<YI^5Pt$59%0&NJ3|;bXBZRxGn}E z^Rmt%p<>1Kd)C6KgKpiPZ5YAjrz%Kp3L_NbyWZuj2QAP^y}}`@It5G6CO-~=CSbo{ zFJmfqS4gT3<e&YcA68&|@`nE@ZuJv~<*5;Ic~~@ptuMNieZJ43*?@!qrQ-C0OF5=b z+7d}CDSX1NB@<F|M}AvA6*8t5z{hBf>iepyoQSJRkFv3le`jzg<^4$x%KkM3S@~Eq znqn5&5oK-k1T&^W=CV%?(5Y2$YJKexrbt>(Ul%q}eA|i6+F>tM8!cK`d(d^X@HgLu z(R?$*_iiK%p+jv3I+6)*x!fHd>WloDu9T$KUeed4@|A)NTzs(&1<)?1`toyIP8<O9 z**kN8=Z-sJtXb#ww?*91E%r0<E-$*TYwhv<<yGT3o#HWF{>*Y5Am`A23D1ljzcb3| zZymZZAR2TA5CuVIZI$gri_j?R0xmzT9e8m`<rhLNCU{LsBSuRAwHI?d-*c?hOa9Bo z+K?g@`@oWn>F!JD%!eMccjD|#518ZZSK)u6WZ^TJ*A0^(q<fp_c7_UGWK5u!X`w9< zd&z?-8|S~8Qo_8zISJ^TpYkiYW1jX$VL=Q=PqTy{^QB9oRV_kEF&Fd2T3((z09}H+ zoHLa0i+mOei<pe3V~w+h2VR@eS8%^4-MHG?^`M!|NMcM+@u0Ni5T0QS%W<nRBSv#3 zWa_BjB*CrKUf7kzf#HkN<E<zDV69QIC}-C3P8^x+X}%Y?dRvcar9AD4-$G_miH+(Z zDd$V3yeOoV(r&(1iHz10#604jN)!<iEuOTtc&4dvm3jN0MWDJ&2?b-~UGy~`)Y^IS z;fz-I0&MUTonEH^skR}Zn;yr`ZP~BFu}|rR$Rx_rK~^?V4(2svXh>-e=P7BfOl8&) zM--exH)d>MAlsBdO0g{QDo|ZbjrR?c!z2Br(Y-9|#~S3!gRzo6JcN^KhJ_ZPTNxt# zPn=XzIWhAai|uF8v+i)^(I;1GB99fsJpStC&+82>V|1DKU_$v((s}Q$bg7XT`*=rH z<5gqil6vgL#^(s(JaQTlVbz3ER`O4|<)5-_3~+9++TZSRIPSc_@ghV-f=59SP$Kuf zTTBGS^%32smLHz|52ZWn2PoNLt2ll8x#kpYp=BB5nnz<#SQ!>NcZm5K$-iR-Oz3m? z2}Z4*!Maxn@;=v#MBl?))t<U*y;)ZgKUEO0*kPY+AJzc1ibJcVx21c%%ustE=HF*d z3=D#T_u5)u!UExJPnPO^>QZlzD`Ii60LyJ6q2th=4Z?6FiT9(tQN~g*v&d-}jXalu zj-n2V!-ERBq}JJenuqnJ(mDnKz<Zu$S<-1!D&L|w0r;9dtK!<V+=&8er}Es5na>=_ zCV#vd2!tviDW|s>2C-xw@2-6hF%NOJ)*emjO_#jraBniq7#*Rr<j#fM9}8%62cXlk z0Jg)>tW`>q=L1Xv$7Ox!>r2TeL&!1W)jivfjV_tct?RUH#-uNd=~Z0qKp+5QsPE-B zveY%v>(Ut5Q-C)wab+WAX0Mx*-%eG~VREXe9pc1$mu{`z)&aM1>@0NUeYoYBDwyx~ zN`8_G|8KID%gA6KlCM27Z}0J+BM*1{IAi-^yWi5ZG84}g(cLZ1lSp1h=48k;n}H!M z4bF+b>@d=zEC6!(JkGnPV?3`}N2<m^@fGPasUbyA*OtjRmFo*>z^~IWwPWGc;4A5N zn{C`JcejcL?4eJGDn8H1D*kHWGw=)<qGDmgq?|JIql)Mow286n`qw&>)R}X?@Wr;% z+q4-FEFN05sC7C(NgCO^HEW647m_ZB6n$##TTIl9ID!Q}!o#XSr^W>3MR#jtYWCC* zMx=O?^H4e$_y9(dWWwoQb1d|=)MPVYyW_IyTGJNUR%LJ7U<fyq0<{yir_{%*^itfl z54*6$fW>=N#?se+YL&3E&C(I*C!*nO|85vIRJ>KDWdzq{7Ic0E%7^r7L$3ioP;%c! zVZ}OmM-<ZLbO1&{M$!>XTCZ9gHhFqMKib|amLRBQaPyBw<(+A#x|<e1?ooUW6R*w# z;k6<qbv<O#lbFlz?lv<%*NOBv_FB#$-=cW9ktfj1O1Lm;b9(wOOFk#c)F+$go34?$ z$Y~-@_5n<LVqQO4L*4M(NOsVAMiH2zbEKhF&`Pbf^F;fyl<_5xkyp{3)gsF+f%{Vf zH1pLkPkdme+0@c23t<F595W$_@}3XS6Yh@8TU!a%B?7!(LF=A++xpWGuM`qTNffJ0 z4el5vCB{C){Vw#vq~hbi0(6rd4I?URXDQAmdryii8%;D^^tD#-9*XmZPBrzYq4J_4 zjM*K&3KCLX1oRG>ac(D0-$J~Z$KfXF(%UQd%FHqRUAzJFk5(Y<x=8i<yZcEG-`uio zT;0;Mc~*X7xj)4;7mJ1NRXo$Yu)sS7J@e_n;v`x)HOeHr8K$d{Mz5ZjA;_`}Fj#~d z^HTU)(8+wh;w*q0<trI&`3eXVPKxR*&V4$qikPua)}`xgGYKO!2fI{z=O*g(yjdos z<8;1cS`cOUVQ47IRB{jHY4aR1c!%T}5icp_q5nKBMF%5yQSvK_oVzz5aKeO?lddO5 z^{sh{MT_75QMTBbVKaS_L{48C?Z~y4xa!#%1ij+}vc^;<R}oIfRMvaax#9rH=QY*_ zBWI=^<u%pQjX-Dx#&NCD1YXPyeiw6vxjOMhN!$?{Kx)#++;(CvX`pRMN1KT2o&;#b zE9jb-lRvIk5zrj`!!kJF`Yh(QF89QNlWhKiSBwv2#N=gKfhRdQFK`iE%F;M57b>O~ zb;0!L{iG-%#VmPJ+^Kjmn;5wICHy|_niHYCp(D5<^oVcG#t{c=6PD^_*_OA%3%=I) zvAWLtt33`Y^OjAk6#pM&Uqz^11_7KX%=hzdw`DTlW}YuJM@g!Cc~qaCyq@mZoZ{uv zPZZ@2=ryu4qzdUsyANac2uJ^9M(3BaO*$!(H4@7<mSB<+ma=v}|9pPX`9axcDGc5* zKsTQ#>C)9cDK|-r=k&(~VXT|j9peun*+YeCe}bULx8y(tY(qRgcD!j<&0K?`Ydug< z{I0(acn#*hc;#nWa<~}G?>ycp^UumEXXz*3>A3chWnxzyOmUoI*}w4=$W~Hj9cA)M z%_f)C_alMJNNs<1db1wudw^Q?BU9ca07fHq!XQ%4uIj;XhxN%r2G8993Vn`%zq@&4 zTka^J_|+w?Fdy;2dMK1+#Ml|xhF7VRO<GBqTEKx727zSrhMs*?y+3I~e}Rq@oP#Kv zqg_I3O<w)%k=M<BvlrGRbx}~FVb);hD+u9#NIJFVB|h7#&rvs!gblV1T)E19<K$g^ z>w?Fk%WP!pN*}4thJ}g_T-Vj)Yo@eUxO=!b2dd|AW94Kn&>xC7K{SA@CpI$rtnxA? zvXrzV@)h8yZK!P7%#ZSRck<^EGpr3HwMm}+Tdf16TjpP%GRp&~jgZnNSZY9gIk}=z zYY4-__LKpA7N-eUz{y-%J9|4hx@6mYO`${w)|7=^^a#x3@@RK(5rQ@?Ud>X5&-qr5 zj47~9%b+ll+Ld_d_4&LP0)a-A*1aTQIoIqJ3HU{ApoVaE!7CM`^$O<K3*1Q)DGezL z*#TzRZRk^-QK*^)TFPnj-jj?kabiVDY!XPekrFV{%9xslVeSD1nmI~g!OYw6wm@IY zYI8x9Gc-v&6G6aZdE0xH!v>p-ja~4exMnUgg}jInYl|sJZ@p)>Melif=c2FGmhw-x zb+wyW1Xp>s2nKJ48it#sZ@XUUY<NJUH|SBFq7&}<Hm&3&g&0C;Xxvo`GfESwVYQyN zgq0B&`LYO|`IakH+xE!Y=t_BRO&e&s?zoco!mQ`zd^%F%CY=2pqK)vcXcKY>MKqez zr$y|bs2QI9nKq@ku)>+TkZ@X!Xga1sUjm|_M#BczkMyWyzYU1>58^G^-=|k7HI?R< z_p_l+D(OcGtOl867(iSROVK5|Z1W;Zn;6E0_h?Fvu<`N0$iqu9Ql&B#CrWCyl|peX zRFGCi9M%O}ni7s`ABzgUs(<Kd2Y)hdm*ABLhJC4AfBa~rBAD;Hw5pU~fsm-AA+Q!- z+9iv|0o?B}=)?1e-0*#v+^DzZ8Jk%=Tv*_FtG9k-bd+l1xH^YrUZ)=xrlsZuc@gUQ zstZ9ggP45Lk*Xc(4%6vVL0Icd0A^=!#N$0Jc==DwYiwT^N1ChALjt>7eD^UDQIiKx zU9zcGug$nt{Fdz^jy5v5uiGf{z7t8Rr|@lSs>_3GT^o`3#;Lnh-Rn){W2711_gk3S z*LCP^FcUX#?g*Lc2-Yn_>x_L|=X=*@NY$X-V}5ii>{l?@nLzT0jxHH);dw24thM`+ z?5?ISsUlbp>1UI>DcwfJ{o4Fb%9+R}b8WQY_4#t&AmPv`&DvK3?i{f*CC!N6CnP<- zp&b`>ogquLZ8v4u@8=^;XR<Nlevuj@fy9*a?Dg-IzrR^5L`t)(wgl#rYTErc0%6E# zLW|Pg{O*IwLgosLPc*Y7Qeajtb@aYrWLjJG$9KRo>Zmqwh<8I7vgLgaz47EzrwdMM zX;0Ad?aYoeKC9a1@yxWSDJUQOxQmAaAg^j3@p%~#03JSHF~jA9i#N)T?M@&RqN>zv zBXM?EgQMAf#*$b}tRZm(y1m>09qRdjQ^hF`aWH%?etpkU`1az`Sw^3%9hT5IXMO>E zp%-2Md++R1{$-CmGJ8#WYtjc}axGBHEb%%`OGd<#J>!mR0YY5<VJg={%17rgy^J9_ zxY_nE?EW}jN`H=Bb?4AwN%f40Bt1Q98^y|_#p5;MaJ@z?S8pL;oW9oU6}UlCO2LOY z|GW(k_j?ZAjzt;~NAT630S>Pp@yoI?m%b}t<eBL2bMmLjrF63*UtT=Ny=?I&v7&%_ zeZ}l7<9ETj-FFkGLeX~eY)oJ8Z#w2t2Hr09RGnc@gCsP@V_y>U7D?`;13U}WiBHrm zw~zkN;$SJ?LDrq4tSz8@70a@FtZNfD{c)!P(kLuPesUU>c(&~t4_EvLXbE%K`qI-o z4RvHbhYOw7Ka@83yEs!O6TsIWcVvocyGu&thu>l0#(rd$e3c%lN*5(bc2oof0qbCA z2EDCRJ%T;*(?G2Kiw`F#llS+a*z%o6YYnt>1pP6+&qy=I`Xq()f#$$RqRTDU(<-WN zkSS*+88hgZzWDneUfq};*{Y^FXIv4E>ThYuP&v(beWuSa@kNH|kOQ}qrB;DwCS70H z8cw8t%as(B+9#sRFJK@SfIgxnD_S}oY+1kS0AKq|U7vWlmBln?HjjnCvOg4T<9QJL zRBRcYNw?AhG^iJ}SEKlsTc$#f*tcE;$Cc)GC~=@w4gHQ1v21RNF*=}7?g}+<w^wmN ze)&fiQ})+ma)x)K)Yo$a9gJCMbxWR=_E=t`uPEcU6#~v!{C&~t8;r1RfZ_@B>6oHy zp=A#;T@Wh76uz2#(TqVUJ$<A%9A?<E{PKxMH+%XMWy`*i?P?syAz{5z$Z5J4yUMRe zJpA9e9a5Pw@FEUZg*e<t{j&*#s~sQqQZ5<^pVEJyz-QKP)NGi)+@kA{*k?GVM}8-Z zx`#2$0B`cL(5@(O?d?H(u{n&=p-nfJ%c`C^oz*B`tGez!2~3&-qH;j^Y$N@ONXBYL z%dBH>4TnF;m>6$(GycAcnj{B_FIe2s+R!=z0f>ai*7;ujMs_CJIbl>|k<)AxGh@9W zf^_TL01F!UOJ3YnRWvn9fyvzG(WSh`S*Thta~L{Ncqh`pjk~W}oyUOjwkHfxuH+}D zT#^(vpH5F$+r&-dZW!h#nPo!Q>J~`6Y54u}i>*dv6G1M2Y;w6K#UiV`KPLYIbCZ}$ zUX#Y6TpFRLv&s$Dv@Sx*Hl%#2UnohVHx;`D{HRLjBhfaD`IbHMujKQN1+iOgV^>Dd zg}|S;_IfZ8L>_o-O}oD>E^=(UCV%bdSxf%=|Gw#(gK=TVj_YC0m8R&p%P_PhZlrf; zha5+-vmH#UN+OVqgcU->QGclAt6*XcY#(lA3Go|M)z_{&pV&9I3EWN*bSb_@#CTt8 z{R1S@vqfZNx8pe~m+jqQ_qsESK24=RY%LOfqC#<O#!pq`DW}}WG$hr$f#dTQecp09 z-9}q-m*lYf$-E}}I_E6$CurJWtgDL`)QfY#X`(h-N-8guoAsg|-r3E0**cbU$4FVe zjtkJp<g&Q@5DuT8bzvsLv?(b&C~S5`M|R`{Eih}Px6V@-wk$xmrOs(-5|}IvvC<79 z(W^gCH6TZ&uAIB-Y(!5f-lsgKn!n1%T1|_~JU=Z1T>X*?A&ZucOuaH79WMsGWdx2< zQR=$?<ee><LK6pO1|2bTGsx_&(h_?&6?+AvYD(0kmEfW?VvGyp{kIcW(GKe-Q3VkM z<JKVqcM5WFO-uR>10+hi9%joF!sv?4YGq;TuX-qsFrh5%Nw$KRU1)V_ynxz6I^UL% z$d?Se61V-5Nu<4lcG-~iW|#r-9_nV^)H~afi2`w`F+JwPFfKp?=dKs9G0=L+Cuw=@ zlE5+>;{nv0R_mYuD4&4Lel>qVP5G(HCFvl_>4!`r1QYBb6NmUjffr5JNiurEP9<Iw zU(qGZ=>FS;Sxly}<T<l=zDE@QH#jz2K#9+=xM0GAB|C!f?$Pd&LY7PH@q&>?ya`A} zHKx&3u-O6LB`F_^{eaPIh?ZVvqr5h(2t$3zL$hg(+}Uz6Pd+4ASMuEJhP0Hs-NlV- z^=JDZP!=Od+lfh$24gD9nK%k*<m$R^0dRzEN*XphcC%vKWtk)UN5w~j*y^!&ZZID_ zb(;Uhwcr3z;lf2*#_Fu7ml1urB!n$hQU@RvPGZ1hC0JMAx~S7TzbCh8>W)?NMB0i& zqxVRsQ?_tP;!9FxYI!J5%A{92p%h3v&>-wYOrAl{4QxK;FvGJ~1YeT&5Fv`JaV*j* z*(~r`BHiS)42=05zK$AkUz}@u`_v@S=T1`ReP3%~cL9=q+O*bG@{*7!<wuLJ(fg>A zM+}_gK&-&a)|tL&RS<9-Qfl-EP2r5KW)$ph<=WJNQw_z&6UG5O(37eg240wR&sWLS zKbyM5T(pN>JisMWl|ra5jK4Yhfs-wAuf=qNyvOyXR9)U&z%!`Wqh8&fChkq@90O(T zUo__Q#d*qyf9iU>rk_ikHQ=9laSBOl)3^HE$%bj3<2lt)l+l?9gig~I=gXVGb|oW@ znE`=AZ}%M-NW^Niy!^Duia%9@u<K|-dZ9m8CM{}T4vGTfVivRm2(6h)RPvdcHyS2k z&p|O6>aaNpH9Ar`L|B3ucP!+?PQGIp@fzuciZstE&lBfE2vWwm`Iz*8T?~$DzW^eX zep(uHP0(6DZ_`tZ#}IKf0XliB;tQ?z)28}a^t~dNHnXwPbkQJEu_C;ix9i8Pd`Dh2 z83iFkt(%A+C{N#0DW`Avl@PlCW@>tB{qV5NH$+v!C5{lz5hjT=0Cdv8>&c&}>FGXp z<IC^S&k+i#7Z&s>)l|ngIq!me%>~8LdCPn)OU>o_H2vg@8OE6xp;ve2{|WyW9II2v ztx6sA2Fxs$S>)aORt*HNpLk%!LmbNoe~Vo|1v3b7V2GBk^LmP8r}(k|z^#JZX50g@ zB!Lrv5;_Vp=>-KA>n{P(T574wJz|sD4UWpDP!g8K2^Fw9#KY?6WGQMLoYIkk-;Zmy zMJxC%N>K5Iab@A-t(mc9l_qWRz+51Gp;oL7h%PP^hvS=59!}i(tZ(g6JV+@uI*=bg zTPz@M%6gC_`*I|h>H7=MR?`&Fzbpn%0>3c-*kwM(7bq_1t{f1Zh2M7{sF$B7hs%CN zXJfGldzIQX0TP{wJk>o4Ex`7XT};yF2n9vVn|@>p9}oyqivl0^?lKy%YM&!y59SU8 zw;V$71!}-DkcD#l3B5bGooz%)#>EiQF;&m7K@p$`?Dr2LQl*q-=qB(7%8;5E-?suY z?)LgAM6=@8wANuy>{vlgUI~rl97CD+NXxyg=9!QQVP$S87MQ>>FfY<*$VzG``Fzm4 z-O1E41L4gs7B_oRlg6|epBK9v1{$x-%Fibgo(`d`JmYgQmG;yEJegH)+{Ox;Vk+Gp z=%W)4izid8yBjm;6wf(Wvy<z41&~RNy8~EUgurQ9&5V0KH1WJa{my<xkbx4IEN6mD zQ_N!xCQIjZ3{!P@KsE83oCwf1G6OQ1WyNEQF?#7GuKhr=k_RO40&V%tM^^D_9`6?c z<H)FH@i!yyIxN5!58Qy5=56Y(83Q_m5?^4x;H$3!BbI%%5aA*!jhz1>>A62zhTHPK z3s8s_i|h5@zXNaAw96Qt1DHpFOMEfqlD46c5~<7-At*yC)NJ6I1H82T-~-4>#fc^n z6ebvcd&1pMImKzUWq@HkjJKp1JTeo5j`NEKc%hn^$PK*!4~_{$1W^xzTyr@C?Jr;9 z2=GpJBrga5#<)COpfOx;bA(?I7Oc&fW>DzTO%XXXFqU0WK+7a_kPrHke7et;rDhz1 z@!iIdB0Wc&C$nU-c+nHU?~<4^c6WXuyQp*UP-b7Zv|Nus-&Y|66`_GOXtkL*o_8bq z6jy{a9;gqV%^79~zs(`uFkdIgAAjR=Yu_AzZEqtekM-AzO{8}a-Ksdj@HbkVK%I64 zD9Kl%4Zj2TT}$dQ+tFhlVyr*sTFqTM2yq>0=S(FzPfT>?i)#}ka>%t<R-BF&JWCs- zKZ$~{$vljEeiGIJ(T?%TjcOXvCV&z5NOE}%Asg|^`8I%Dti2lM^a3@M&l!`udv5eU z#4EnUrEnll{nyi+$Xsn|k+k-2WP!bEZ5pDGOWaUsN?s<;Zgd4`0CV*R{YQN<nMX%b zI_k!(JYW4tqa2q^%s6;=z5+6r$~<r$v;>jGf4g3J`&x_Qd59(CpI@FNpR6bbYL)iw z9W3Mhu(YO@Z0p`rmc=dM_X#^kn^PkuDhvY=5enaO-T2r`^FkK{)LeACe^B@$P^TyC z?AzbidR1V=i`iMwl!~wtn`c4mW7dNq99C~4)X9e@z~&32gph|}dyMovPq!gL!-B44 zv-lXcv!oTXwxJZXYgV6O+s)#cMPB-{=6oF~%c|w~^96m)-52Eo*KW{W%z==sJ@yVj z%5Im)BeK4{>kS}<;M4{eK8HklH7=1Gds`7TQ~|<N1Avi$w6=q`6z4|Z<6YfU{J}J| zqYdOZ-BuP>Fv(a9iUN6ss+Of%J&10~Q?z5HysjN11)sOPCg^X}tcYM$0cALwuYHxb z@rFgk?#2ycDsIu1UT3NgyFUmhPpTXO7R1Dub-)5<4#o=&I|@-w{1>0w5KZs~lA3H& z$9Eu4eH}4KuCH5+J{nXG0mU!rWW_hh40Ljqsd|JvBQa^x1W`u$S*{{6Db{sCF{{-9 zTH}f&(r2GWWu|AIPm-`67-plX85kOM82`~C`#9^~f^Yuymrg_K_YZcoAu65Ukckxw zhx|_0(U$Z<q<v>Omfzr@m;0v8$}h7l(%lMdomzNL<TuZKq&G$!_v#UGlT!o^4aCJ< z<pE@xGnGOaYcqFMn1ew8K7T{EB{VIi4NyX>i==G!Zgn9zU(bD`1TF)c46gLiSoMHs zqbf$VnOtco7bKD<L?R;<w;1t>qM>-7*a&>b+gAu9V!|$<#~=7R=kw)XW*K`}-hgQZ zwKWuYOaOK@u@vE6X*DCYA`<DS^O@o>$)}1v&hqo*$<V{JeT6XDu^A>mGVUQoY*p@7 z$VhSO*Y2!3nb$H0@;OssHcvJ*BK$*pDZf(DTS$LA#(Jr2>eIagxjkfaeKYjJ80Q`n z%J#?ED@b1_z_VF!*?7WOQ_$&PTL)|es$ly|E@Cmdl_fu>#Ud-~9{Xc#i3ptDmyf?{ zAsg+l#;Tjdw#UJJ;wy{5Uw5A@8tU9Yvm2n-rau;75@0B&=!=lRVd{LyV%kPq7JiQJ z1$H>do7A=wzbsWU@jj39>ii-VlriWCV4?e5-|amb$Ta=+ze+CTcNz3#wi8DZvh=X^ zFC2mN$W3LxkiI$K0y-8Rq63RK40XgWf7-bzwE{1QxdmU}>3deSjhGom<1bjcrCU2l z+J}Gp^lR~dT~+HXl0VmxU%z#1=?x^5j=(rXnz2nUgeag5<nmpKysp1~{a<CNPPB++ z9WXo{pf+OK0bh4c0UMa74xYuC4~P-qG}w>2lr^=_r!KvDpXc21?J$r=2k#yaf749_ zJ|xN6p{KNHf>nFWBEUryqDn!Po-<Pa{x;9pAX>4el6!JDeElvlEWH6jAxS{7Pp%#? z28t2sw`H}*p1_|z?DO*x2!W0^14GZ=9Rc0MSVM@Um2@*=+H)8Y_QVJM<OXQ~c2g`2 z$(wqu=uj-%;BJ)G&h@lEjN*AEHy1w7f<vXW>mv0Y>HLtwxhJ2lY8-+t;<x4PH|1dp z5$U(S&_;ge)?Wuv5ii3eh;4msn(>VDDtF7)TdVP{P8d}q=_U^D`UDt(MV!}~)P$Lw zm3d|i!>`M;LJqj_X%|E~B}_<p3hS|ZwGU2<yz4_GPc^EQLr@gqp@NVB!RS=G84)*m z5UTD~55J8^uI)kebuth;E`Pk5*?)Qb!ZUG!qsQix_dllT)0QgeJP_tyc0)jYe)mA@ zWli@PWXndl=jF0`-MbIHJh;!p|0U*+E6f4fJSzL6Ic;CSKyVQLE<j=jL(R*+IYgVd zQmwdQyMd@suCwO5goMR_^h$wVBMrJ8^dQvWk_Y%Mz8U&DDx2PZZ3iRt?nWxt6>&hm z(UX<+8vnN&^MIz0(a$b&_3n?sge%R97YQds#6LiBe{*dodR_0n&5ZkZ=i9BhtvLj? zcqu%g?A)976N9@);o)=Qnn#ZY0sH<r0Loo?I7(Pz@JD3Ig~+JnRxk&=1-p!%c!6H( zL90aAvwtiCHmy|c#hZh2g!}e3Ha1$leP*8!4dnQY{&)WBn!g_&WMN7`xD14%kDfEc zyK)B^k|W7BPr6CSu(8NJ=Ug495$J9v&X>)9yFmUu+Tt?PL>(eRQ)RpZB}!XXHAqc6 zM9XEDDWAEu7ugi?g^^tmTp;v#8jj5W@13<3_LAV(!!WWL^*0I>kq8ix#wm`4bJfaf zY->4o!YyXs4)}|on$sgpmG+Wj-(KC98BI%0I%5=7a)TR`*WD*Es<xHEj0LUyVX+0~ zTF6%W!u}-`-C)q-^`7Vgc#kR=y!xT_;m7}nYXUJ(X13;d@~>;2wz;`JJN83cd$G~v z+)T3<Ga`OGzo#;l*Ua^>>XxIHUHR_7KOw_L+BpS`c5;4UUnR)?@z1k6y8Ifu=@Ikq zElU?BsBM$a5wplgQ`-K0k$s0y3?uznarDK)3jG^V`xCR%RkePI9p8=EdPHCIp5O+Y zS0y9IUVq;{ksg?x$<nqZ@cALpg0`aOhAd9SoIyYV>52#+&oUmM;?jyKU=dm<lbq zL94aiP&sD*!J#BXEm4@^DJbt1&)(Upw7S<nMR(X~bnoMLbvtig*Z=F*Ra<&s1wX(2 zUvD#zgvd@)dAAcO54M%Uw=b_I4(<;r_;n1MPpCQ_gZ}H$zN&9Ist9-9iO%3;x&hyw zT%Zb{K;gF_QpDBDGi(gsLi@x6RICj{BazVZ^!_hH-0N>F&N>~q*PkyMj+w1<tJ27^ z<@wuo0t_$rRNAlp@n@(I;9%TzAmk7Z_pKjYz9<5QCy>W@^P4IdQMDeJMR3FXu0Oq8 zPXxuVvd@22dD@hG_B~B`I>w^Y<(R$$GsCM;IDzm)hDeY=j~w{(kP|G}7-o;do%?bL zZa0^1_lXzfb*m&b9{gn_U?NY0Lzp=TtUR($S%46KW*ZZ$1TsaodL;7C>(pRG%y1QC zhDhdrZQkZ_|L11wp@29pM>B5&abq)>vODmlJMHdfQJU|<CXG@uI26u@gYA9Q9qJok z5paKYKdRGJoZ+X+FMruw=YL(`R+D!dFh|ui++?XD>hPo-55#!jr2!fdkB>vhouz^t z0?`jR9}7ri$kUrP75rZ;R*boAq0nz>GG&v`h2M#8P6f?C({XxB*DzA#Srb)6#9QTI zVi4D)C%_==Ivumvi)E+@`DN=Go2$O=`0oZPz?gMS0o?*6)Put^V!rCdh`nx-K{t?h zY*+xv1Dl!O`j&Qo18313ursGl;K)p0GfUCdMwLo?f33Oy)rOSAYa+~(wSt)T9C1eY zFF>Q;UnZykk1(`Jfm}(BG^CvyY)m&y9cITIxE!M|5ABId&2A-TM&hek>TZT2uwTTA zAo~0_R`=>?u8g`pup*=oeVzoit|i@28_I(5nX8EAgz50Ln<Lc1>_V<<ln^-Dau6R5 zKjOu;wo>Nn4oh@v<`$MmbAJBa8s4eEag)^1?_X)3z9zLz35*Jy!dQIMrT){Glulj? z852BVUEmx8l3;6Rd>)_+)yP{)$_Ei>gBzdsr~|s&O>t(t&md=WuDxz9H0sY4mb#kj zkDu(y7vHvRo9da}e&acsJ$<=Gfw5bTa{SAEHx2hc-93Tr-3L$U*DwNJJS2ulGS@&; zjKDK>j;V22=H7mwK-wbRAOJoGv`+@MEMMfs`6snMO|2RNB*h7Y!-j9t&81(i7jiOO zM_e2nZPP#hi(}f<0ZZf}G+^!rPp3D?tQ!Y{2F(k4gF!4bQ=8RO2%YK3jf9xfw!y-$ zfqoR{Z1@1)B_J+j{Q6CHG@`sk>a4{DTvZO}q_G2EpEc!H`Gc(AD=^lzyr=_41J0Rz zWewvUxf63Z)LSrZEYi6^gO}40NSh!-v9%t1S_!cdC@k(CSvgP~(XhAn!4H@bdE81h z?6}^PxBfq!62k+TvDdkEphjbVxZWDf$UN>kfDE6j7v6yo3X4#g4!s;ah)D<pHE;|v zT<?N2+thoh-r1d#O@{*5x%r`qg<Hr9Kxkwjc9M<F@mGQFd6j6AnOf{QM(~>GjDfzc z{or7Up6%-V$f6{Vtj8P1QKUP=Z#9?#CI!nJz=71Ee#C3RznYE*wUnl*=$OnI21!n4 z^nTiWEaBz4-STl?qwc3n{4dT2>4yN$Pjfg`0_vUKE@;XZa{{Ha%NEUOmq3#(B8LYv zXkxRYC69srG{7IEJ?+6u@2ZdZ)wN_<QjrF_3wRS)!0pU4??kS?ZI-wE?%P`)fUop@ zfvVX=Imb;Pt~SE}bNEpZuGN@!KVlHykHneM8`CjD(;kB6B7}nfG0NOL1C`@jL^TC` zJ%hwT-1PiZZ*TaRcQfVC{sqm{@{u2`vcm~)gQpO{6uTGW_k{(aBh58UT|?k1c#D9G z^%zLyd(cy;Hg#<gM5&hovZ_HiodRtoQo^YNkf)%w7xQJiv&hk_A}Zc`N^;#y;D5iu z!mjK0I~<Z9I$PsA()OHPHy+I%o<ZOs-utLFjH-Z$)w^<lB-?K$SXTsAa3ZY_^O87o zn<AjVG<4Rrbs%d=f`Tqf_-Vx;!Kn^7D-N+YPb{Be!Ig`jm=G-wvBJJKMKRQ7yd6k# zq~UkmwAc)0ud$m!=D%d#L*_TjDtB-{2XqNdn9X1pGHxI9p`gs*#YAx_z2q>qEMB)y z`vyN9(9MhBS>GVR0U8>)hk;5oIY4v>v`ht4$yaG0XPD@RdH4xmFLsJ?F$BKk9P54l zDG>$sTE_-?ePbRSekRPJP5mFkxXm+g_V-dTX~F#KQX)WgDFqa+AV`M&MRlxu%M?}} z)dqY%Q$#Y|@!|DAZFH=R`(Qg(DHimhL?X!eAhw4W^#wB{Y)|Y^X6JQZB2taEjnR=; z9ne-`<oS6~KXnMkwJLJL;Si?t6jV`X=#8}xex{u-av(r-{39{;z<dBw%T7FGk{f?> zTV^7!dE8aq;6JlN7#HB4F+gXPh~oWcxm4l%J%q#gK**|POTq^)$=hdbKm0Mwo-tem z+gYnE-F?N{FvD0_&KhCUwhVV*w52AY`6&3J#?#AYHX2}&Xo8fdhzgxXF;p%Mzm1G| z=uhtb`)YAT4rZ|0<<#;(L^Meyx&l&Ihwy3P6-G#GwyS7{UOZ_2>kp0T81t)Q!T#GS zQ#Jpx1NC%wU(cQ3h_qlumw#4cYf-ovf1tniL<o(hy8QTbui|9Qw=<`5D@s8C+c}o_ z>O!=J;e*VPmvrklHp&ve%Rw=gUMK0P{>Ss6;j0?gmjyYrSK+AXEo=oY7ByZ98FNPi ztQA*>lO4{_{I*<|DaNT>eygwf_^*WL2pF|j$%w1^uqJu^DEq2g@;@pu8?qtGD<tsr zG>O1FMI;d1AMx3Kc6BI8JL8Xq{JQ6fe2bPPxMxMnrwQccC?dtfNiZ*(FC~=Wp~aDS zbz`6ZpmEHDqrFPgBagDTts&ImitU|eS-2!l1MiZEfBYTf?hmZ=(Z#AbB%)oSC;+1E z6)Gg!&AtGkLBno9b2{eK=uWEuuC$76c<FV@yOe0nHBB;0QD7H}y%QIN^dR88&UOg& z<_^l}Sa|=7W<wNFu46%6JGT_X$Dn#EZay7oa*W}r*yiJJu_2p-vmtM$z>DZ>=Z|!b zfZ|vR=Kq%SVPR0w@!}gIRq7Py#g5B7=JH?N!0+gbUhSde@b!H1<O@l9$SoaS6~<9% z@AB-+&RLf2#3L(b-)Gz&|C7c$7%n$?8tRp&MR0fWL33wYK;=*SofgT4+!BK{dt4dC zK)q}6I%Hu51H4h(#7Hz;?ybPjx;5LTgmTue$EgtnZn2=QS@uqnr8h@08s6?Rh`2t! z0@6Sy@}`CRR+x6snmR2)1MN^30k0Z+*;Shm%Q#=u(YwWl{nwKw+!#(7%r0O3S{ExV zN-#jso#Y8lgS#uCR@f7o-^@SEEl_vA&qiKaVfRq5uyppT&|(g^(WDUQNp5ErS;Ctu z+%qm}M7kbbp0BCivH>t*J~v-(3iA3Xd};)Udk6;4%a_r&8^UCN+&#V%ZKy-;EGERq z+)jy3?V$QA;#{sNx*+M2r@`1E<Mth^C+BF1!PT?h9_}cIKhg_bU41Y<#qb8TSr+~3 z8veOLc;&(85$M<RstKTS>Os(3V-dI8D*8n~!i1bZ=fGP${`NC8>oiQ8^14sQ#NldT zHf7AL2CsBerm5?5x8eNIN3IJFH~Aa+<smX$P-G*b_(34$pF!Rnk#1d4E(3xz6WV2< z>O+ZC2QQznLkO^Px{NtGrB$i1#PS3XvVMoRT?vn=EyGKk&TLkKxQtBaOt~gYL*LSY zD02dm=;DmXGuSXDqKoELo5qA~&o{6_d6b9_P_`U;xPHF(_imP-!*VYJtb1<(F{!h4 zuP0Bl6K`8NGUq@f76>$hyo=2pXp>ZW2eACefL}N|J*^t4Hf+eaXGu1!V4RWL-Y<!k ztU%rwWC1#-#gYW<A>a97TWT`!k{c$58tq$_beTLx+OmlV6k1z8wkphU(?A(%7x;hm ze-3_k*e-7*Mst2qp5Arz4}{^`I#>!x4sc>mL~;NlGeIsPD<D7TJV~6rUHiAWTdRdU zgHU<~YV-fY-h0PW{rCUl8d8)78fH5q4IJA^Bn^8cyOMRRbWk`(N<*P#k7E?hvC1AH zEoI9JiIPoZWrXkJc~H{0uIr!Q@1M_K*X?%Q-W}(>UeED(+#mN5id2Hdw>I%d7`r?) zI){kr$WG>+T>_dVp>sETODp_PiliRVgTde;Ws(l3!#3IVIIt3pjY<$ewPZskfSV=2 zEHGK3E|JLnX`F~ozjmw4*7e!u5%w{MJHZ9SvZ3~bry4aM^M=X1#mblq-Qy?KPF00V z)3AIo5lI~kIbX;%k|~TM?3A^w9<B1$M6wt6C$Ey>w8*Q*cQI&8<ctIrJM%G}<2F&# zUj?Aw<B48SL@L>xQsX4|g#-rHU=x<aE_NCo44YK`m}5y_o{`NZ>4Y^ItLn^YBZ+yY zBz9+~LPavc>?Bkzn_%KR{zcEO&ae&WWa;5izS=@NOq>Aj*R><S5D)=*BVu7sRX_GV zIC{_AB~L4T{KFDSF4#~oj-F}Tf8K`xWUcYwqgGEUv<r>IZ)UrBS4sH_Gci+r=eE~E z0BC&frb@iIp_)o{^poIysTTmi)?pLFR4`=-<`DbRL9^M}So#S`+g&)&`x&D#@YDt0 zsVNOY+u9(u3kp~UiR?m9Z5!qxbvVu$P6jgDhH8aMfem&qgR*pU37NW~a68poD^mr= zcj~#7on28^5IwQKa@8W0m~uNb6+Q9TO(sV{XiW^>tXK6sy#9Jq7{?^F3_xpCUz_EM zO(tnm`;aF$MW0JCEb<+BoO`WHQN!t=u$F@Ry*;c*cbN8yYdgZfdRvO4EY%Gh5uYR3 zxGb$DB4{n6$KroJ94$|^J>kB)^&L8QIMNH?+vKzp;(RBn*69Z)(W$E-OF?<Klg$}2 z3-^DDALU|Man!ISz;MITpU;r-6ICL!iMRN`_4tJN+ba4>7MvF1)SR?C8^azQmM;>8 zahTgi>R@Y}uWG6cIF1>Jl|h+&xGZh}c7ENo>bU@3unH0?pcWk8a;F%J1qKO@XjK(+ zXYy0*vY^1)l0$H3jptX4R5=5IH;?(kfkW<RCzOl6@5dKvn@k|V2LSM(d`-|QCO7Uz z0%|lUKQZyaL}`@*<^T_n%R!<j%B(GudYmb&5KW~(<ij!{tRUY;UY~k)8Iks83sB6z zN%LJ+bTYz7<UmtUU)u<+m8RLHC6Zc{#%~2xCxVcE-q!$5E<YM@Ig1{M0>jXlUM{@N zWXYX<y#fB61&<?6qKukI?r$wTJA87>*(2PmOMBY9oB7iV&n_JU>8>|{wK=u2V4~Va ztw>e=4cYYFn|r$&Jfru<=RW;<5K|uvbHJ7aO>J4Hb;xTjeR4A{G@!&7XU~|?H4Qy~ z!p@M4r>~sC`7bLf$7dn&O3k@SGezN#S2_ZqZryngH_k1*S8*`S`YT7O&H*EZ1gQq7 zEbF!2){Wdj#yeAGS5`2{!NW%Qit}JjMVJw8hjza`0Ov3>7Dq7X2~v!H#jIMHSH8OD zKF|UOpOX8IA;h2sz96y%wUR3T<^mF`G<mU@06mJu7eE0sfZn{~86Z*e<t#zf%%||O z27}_H)v&thmbyWYIs2<HkGS6e%~m%&707nJ$z*MQO;BW5FsW)D6Yo>9Pty9RI+hf> zMbzqpxLAVkZe1bcQlzp9datgzC*Sy`+T3Ptp>jckoOAn=t)wW03{r^ool@%EJ50S1 ze2NkSfO!CxWMHH+C?wz5Rn*mSJa(U&d<Qu|fjW5n?Mq$oDjT6+fmp`2AAueBI>yLU zoKcl{)nSq{q11G5PEP5NjW72OxEEV~f<{!{1=@6&x;g+suW*FlJrIZ^`n?ma^n@>x z(O3cg%Vov6CbpHAEDx=zUe<^R-eTolVqsbjEbY11fy$tEAZt>W<{+CKTXlWSKxaA? z)v-l?yt(0uaXk}e`9_UL&2R;-Rb@+z)bR}jXDD&gbS^*%!w2<qh6EAHK9WewEq?QW zKB$qDe8X9R7Dq7*X<XAa4eE&{lyNHZ;taN{H;sasV_P)QIVmv*DisUWCxO?ZcrI)i z-JLgYl@1$LZBYGqeeqEX#_ArGX&2g^x<vo+^IT7nAgp&3{yDCINlg^@X%KPPN-DC# zRGeJ9isG>J>c{2v&o)+UW)rg$fFdt#P=z4{cS6JBY!moGjf{CLBjTo1FXLjmXe3js z5btBcnf8X-O@*S3eOAiLvBz(YcuT>`&6UzlZB5YfhpR4Wq90~~C8~-Nh7*MnJ&&IE zm?5_MH`Cz>(j)ze2zuf11F3X-yRMy(m+YpBZXedIx^(PgWbTH!`LD-_JarJQBvV9J z!j|gA)!&r8A8yT${&MUsy4;(nF|}d#nM)D^^G@I^5(K%Z9<a^5jW6{9&HNI-+$>7F zt1SErFYVwTW%P;78qiGL+7Wd#iw$XodJU+FIK5htj<Cyxg%?{9Mbjq-39yQS)hpz5 z(%nETt?{#ze=@#P%`;*2s!DPIg@;FLAawtWl+wm5FfnV$BlD7*Un(ECIj--H-4j#A zN8TB;tg$-GE`iNm0OxSRNq{>>IioVi@mrE$5>Ttj$)|F>ak-@WZ$O!$PysU95~q&n zdR7U$DSp12SbpMT7CpPDe<y}HC9%`-(|8C|FTTq~^>h?Yp?eQowXYrHKA-_cjZ6>g zswt7`YsTrjhO_n`q^A2iWvcF|`SHOA#U>d{Yupk))jQ3q#OE05c(MCKA;{gO_nV3k ztx2Z(67_t*_F-BE(E6gyP5|b}Ht;`KGq^gZm|~UrGGc3fdxb2A#q%TX!OZj^7YRCj z{Z(~qK+Nuwt<R8J*RdC_V4QYqrM-V4zD2O^EQ4DaAY8EleM_Fy-#ihY3aFT1;D9!6 zuU6ul>cog=au^s5a}OJ;REA}C(2?xNm!Dw#^x~d_d(3#aa&lx{ee-(w`6{7O+U`B| zc}!jHS;r62aAPcDo%T04$Jl4o2g0)zz_{Pml&-7Djc+ab=ES>~mzdk|^_+T9WZy&Q z4OC(GDed#0ZUWBrOe?U}XC7*;QPWIf(WxcS3bkOwyQ@eB+DmTb*#VxIHgHR-TsUWM zzVSwwQpEYM?ytj{tmlF6l(du9BDuPJDU}+>KOUG;zdf9?z7o0Mq+)(EAVEyhJq*XB z3Vsl277g|5`DA=dwbCsuruBXDhC(A{z0=A_bkb}bE3nVe5aK1lwN{q~x3#kR3=iNa zuMOoH>)BxroMxp(^)&FWHEh^P@Viq#DyMso6rh#rOFDlINMUtfXuiEOSlyr!23IGp zvkz+1l*BqX+`t&PT$Ry|eB(VV^}6XuQp33)1C~2<^WlXBS1F7?HXp4jA;z|H(e5j9 zWPiA)(1zXj=wOh9qn*Hr_AIze8N6)W@Y|H;=cfE^EW(hfv~Y&<vm2uMZEEz|ec>c) zUhDeXOy|&^`H%x;05q=w$mIMnFoek$oZsie=YawX_rz}lssHr6ejOLx(D`k)R57xW z>&18Jz5I87o2Ds#mRdM^n|D+HHtYJoM-GV4Zxg!zd*rCi{r_r}Bko1E3L>Ch<z9(g zG`qio5mfR4D#Uq*YMvi87AaB6<bUl0=nv<HrmMj163y(|z$u#_wG1L~d&vWYF5g`f zzlnPvD=>ZSawMP%wkrsR!A$_h%y$e%aFG~K6`6l*9^`N`JBT)~h>$UYgWu@wgQLiC zqYW@XA@Dm1ZoIRp@PIh{J&Msf==!}T2NXla>xw~HzgshDyH+Kq`oB&Vu&|k%6<0CF zE*8ZUk^5EUQ@Ed0DikYCovw;eMy<0@OM!Q~*h8G-9w76;2txoqHW5g#1+3?uE*g0; z2(+GkP(^2$R+D|$=p}}f5K_YOw)<uxbE;MWVr@)ikN)fQoX3bz^*mHPt~N>vB$7!n zRBB@Tq{pry^IHPU`vfIxHn@NbqM({yF2NpNksjDVl#IXhUJX7%$BP}J{&6bKV<1F5 zJ@PU7**37Mzsu-`Yd7Sa-UmLY{Lm6;7x8mp*4|V{>?UPdHlN|5zGcJmLH7ew|MU>m zz)7d$4zm8e$-c$YhF<Rj%V)4)on-@DT33s3A`s*mO%7zAe(JhtL{@Nx6G`Pyw+OK9 zB4wwp`0w&4K!(GC0;Xr^I_apxey#z@8&CnL<~JvUwbcmCDex9gtBJ<FThFub4%0;r z&gs!pSKm@5NC&pG-S`A*q=|=Dr516{K4{rDONrnG6opo5@1l!f3b7AS;Y$EIWRnQm z1JkNFR3St>CM(~I0_e#U#=AfKns={sqLh{thX;Vv0ug6N98gfbpvO?2n-47qW5a{_ z&4ZL(l>)med6G;fwVnB8v0H0DKI6Vg_*_`d;hNN>LP7Ao6QCGGCyw&EmD!wpa`7>; zFD}tCi#LQ{g9hQ<Fvc5tO<Xg0=<9U=@Ln^yt_O#!K`|OCQ=kXP9$iXA2o|zM5CO7x zN!Y>5=GX1s9^F;PAk!;piaZkhf%VAC9Lwzf5_&Lu_)&=E<M8bZo99?GvpaHEmRJGv z(`)8UchOW8hL~PCN`oH(0mA@c*h*m8g|`8{MSWKh|NRD+-2C+xb`d0|#b~c1VSjS% zYXo=lHkklJo&*AJ<o*z;kpLqWHpcT=-GifH>w^i7Fc^uDoe~F7uwvT-W#F~03Rq+U zzQsv-c&ghwp;mc-9VGycWB$}0AaGD;*uoGlV3pAOa=qo7v$uH(p8*Ta6x4$CfRlD! z=C&TxH|@e=am<J>yp*^f7Le-$#F_wJ31cG6wLSpvfT!CkMG9sIW`S@Dat03Y04YW_ zIV~Z|xGk(RHz;QkJR;$Hq2(x>3twsvm3nePCRp4}l`fJDgu?aCc(ZEBmX0N7DNMEW z^6z7Vy`z7#+Wvsu1u6$Y#NfYV3U8>VJLL?;PZ)eK#N;pR%w$t8aZAHh7e0YWnGrOg zNrP&u3SsCSfSibt4Y1&6q-*WzmMQW20N@?O5x}f>ACfUReTQLW{bm)XJ><-5$cHl+ z2--$p-e->3zlr-wGOY2FNmRc!Fk|ffxMY$YR1V1FbL5arkr>DiCW3JnkdDnxWH|GE z%0<sI7#r73TZ8J#OxL6no0l5~CN|!6;Gm4WpaZ{cZ;iOQhYwLntQMCdlA$=PG`n$R zTSYJ2?Ao-nMr(BzgWULVw=ojNOoXBd4Vr0Jf**u(gW6#r1ImMea4&W<?dw!?Et+xG z@mmR|jfLg~+mX5NcGM&S<t9v+)G4dm(B&Y)B9S<735MP9@>|^$5!3R_M%ZiKarwsT z&h1p2<zb+C#Hqh7MtNH$7zml{7IN32U1>}67Kt1<ZqueSes=;pOR!gdh1j$dm+o^) z^6lJ`m0qL3@(V;jrFmwnui$2;;bhWIJ0@S#UF!HP<kRHlc<?WwL`Ni6vmHks_S1M^ z9#2MHeYltc6Jfv9B}ZG(j(}f5(xfjIUWi~^<#*ObwqeL<s4t+UO1-sOyx(;UFmH=T zphvx0g?!8F`xWGiy}+|PH?QVWjFlp_uhwb@1uwXd8(w(a+PMFjGnO|f*A?e$cTZlB zOS|dIAn5qN*oiPDabKyrxW_?}mzWmxOfbH(IC}#op*O7TGva@IiK`D!P3}6|i9Ew9 zDRPbtpV8QJB3kWS4p`sTwNAj?%KTh>lufGT&=k;BQ%^@p>5z);<krFEAo&)cImFiT zxR+o!JQ3I3rNg*h0Gu_LCzvqUd)~}MPP<mpS9?&$)F)Nx$Tyy7y+BX(_DXZ5cNGnh zwxUW7w}p1?@M$zCHSyRFPY#0;6fB(8842W94<hTs#yNVgls@#+!#$T)J{8q2>&0qX z&<dku0XTJ?G%ch;!n!aCSB>mJl{S_I<Q=g+4rMS!5@Xhe6bRwyFhPa<hdAM`<CON? za4mI)7JK>~P<?>!J#zJlXJUzFCef|{;;!n*n7VYOavpu4Z{G`@T`$P3WUU7d@rz|r z+Y{GRiolZY9XU5OUYl316&7Ke0!+vNu=r@OR`wS$tJysv3{LF~3c~r$zQV&xVxOLz zkTgs)xC=lW)m^U{2ANW@4KKOLxbb!z3!%|AaG9>l%|Z#A%jb5&$*m+JN660Ja)^Vt zWxQo&g%u~|451EHNN7&xo_DU9mxo=7f1`07cesY6x{G<jXR+W0J8lzvDg*%C=dz>D zffEym6fibXUQf<^Dp!&sii}Myv}%+K8XY_Xm3;=55^)|Fg@d7i9_PTF_FMH6^~)GP zup(=y#pUAGpX@$9-4b{QygtEPxmGZfC7SKfbRxt0Z)16In4>{+Ax`Uw=?5J~?yj4S zplEZH^;3B8-tRjUSLqi70eVdzv32-hdp;pVD^cCz1n)G!=$44>L%auo<;Q-2na)6F zOI%VoVuy)f5`W*toy#mHu{^imrlweC*j~;)sL{&a^<gLQCPZU;4sVH$9V6v2*V;6x zEo;%fZXa>+EFG4AiQ+Deeodby5vn5$(8H^65Xezs<Hp5@A;w~p2F8}`jIj+Xt%6ZN zQlR^IEL)j%zVQ=Z6SzFwuSY!Ht#>?0Jii@%dB|PZsnNpt`DKtdLiX1gMS3RYN>m?s zD7pbXfL@2|d+}h(SMp{Acp+H3s{3(M`b3F__6uOmaK%W)mE=_nm2itmVWOI&Dn?gV zKYCBk6YzhxuxKpSdeoIZ3@0LAbntnPIwVcG_Y#NG0ML7wi_F01-V|^-Fd_c;t(9eB z-T3A6d6-|-@3H0sPQ*<!i^2<lEOT=V@V*dN7XOrQoba>~H2lA8FGcaMSI{lmo6KJc zPO(OPcPEgotiprUvCVrDz^Wxp@d(KaOfPR4393g-?c`w~cq~5P9$?+IoY4IA(g>b( zplru+-$P|_IP!_2$Yv!QzPmi5P*uCHy4nIIjM20{W<RnLcqW&g+k(8fw6_U;NQ~a| zzREaeoDoH~M3P=v7G31$9@n>E7=FXuHOS9S;C`=OnQA?L<~=ZDM!p<%Q$**;uyVe? zSBa%CntmVM6>_$$;e0g?jg-(0yw{c{vU|duT0cSD0Q|^6F*wT$`MM{RuwuU=qc=DN zJ~`Fg30XW3=T`x0B~MYA#eN0dBieK-AKM@r>jEV*2$@CYD&$uqkgJbXrB`aWH>Umy zt$Y)>`A-CPEypr(3xb{hp2)>w)FE0|3zrcg=j&le6S8+MAOc5jB2&F66$CuUD|(Na z-3hiEu~u@t-e#d-*np9PZo;eJav2iZ*_*bPJDhNh+i9T7@W^KcmS*L~Q^eXEw`(Sl zPibCrV07B)CpX?hW%(+BMP6fKx)gqmxml6|Sekp8>EhT-8gB%)SGU&;(mGWqk`|wv z^xv(Y`+iT5LLrj_UH&epPQ%7Kf)5v*3Yjn|&%9-sqLSB(+hhO<B^5j_GBa#fPQ5Gz z^>m@EHfQ7|Fig_oRN;|>n@_LTs96}e7XVg}^l}`4?WK13@(}X@XTng-BOn(Vy8OH? zxo~?9ZXwd&{US|rIadAs=7vzNQPr53HFA^E<fw;qYaWV1q>Vl8DU5u0C~hk_y}$9H z$Ex#7m5g=qlSEEBSyqqShgh$M=}P13qcKv7llpMa7vba(7r;(uQM50Ho#25@Y>WM7 zQ`G(J4ft7}hx)Cq&3IT;C`N?N=?%YWP>j9`wQnhC9aKgFkVRy}imbpVlgP__kXF1} z4*s#xd6@~fk=5Ts)E<G-Ol^X7?g_o$?ws%ux%f=wW=C}czikrHl3&W#)+0;toMjhk zab0~1LesAjZy@s9PrTF%1UG7JbNANW<yba%Razb<6T?{E=9sHtIOeWlGdG-K*QBk+ zy}h)|sgGMq>ODRj@0Mmc;hn5}E;#Wyf!YH`#4{NPqv2(VxB2vskT=)3KMSa8H%@4M zo96j#1vmM0Y^`7Y>J{jH`ol`L&5dZfkg9j*4K?wrfkxV*F>4@qpH-q$&)QSzSvgiH zcm=pTQpCzD{s-Dmp93=y1(~_hhLhCH&>8Ofw)$|j!i_?dT*G)zC%+w?#M=1sK0?$$ z6%4><K5>RF-Y&4Et;~L7@W3))&XXy0uR~jVK?<4HKL~zs-ceymNWc5?P<}h|+79xm zJqJvKKxlKDrqU=*cCjZAJO3xKT7lurRPeQYsLy7J*oU@uegYqN&5Dg=Hvj^Z<QNHp zrf**$rK_EAdoaG(&`;NBf}^Z@_ko#mjsnr`8WNGeK89yshJxN^zyk(OYgC}0xf@Gr zAk4l-3Z5BWW-3)o9NZ^7zX7EDdcdwR*Wf6bA&Fz7SL}Bwecn8$Zh-&Y;YImM%dxer zKe^t)J70VkS$!GBMa=a3EAD5g&|x(o32+%bs|j-Ys|3Fqik&^mQ9(qr3XrUrtpimx z`d5GdR>!6KGtajcb|{}7qqXpZkTx%%UnN8MQUEy01i(nAekHTOYsf`;1!%(a_aJGh z;8{d<ltSp9<vLvX)6dwmBEKEcVL?ndqeska<w?nbDTX{?`bpSmH`gBx%wnn|wDaKZ zKR@WB%dtpo=_j3kHk?X8BRoDZ10odUOTZ$CQC>47R3kYZigT3g0a`9lDu5&M46pvT z*T3|b&RsV}q0e-Zc&2)1@M^Rh2hQRK`7z#E0uqQ1=fmKC{&_bbE-#5XER)s(Rf5sr zb6Jl#KCvanC}}S-^W#;PVpy+M980L~UjENt=(3{FizVec?rD$~79N7a^H5GpAd>l+ zD{*ooE^QrHjrJH&BJF_J{m*v_%7SIoVY@<X?m7i)noJ;tVSR9|4qjfMH68f@<ExZq zAu7W4!F;a7j~$E#H8YZkOY1Z~H1jtMoncYauH-dKlWG7Nfj<b~IlJ@03vIFqs6Y{1 z|IO$4U1cWHiUVKS0#d4i!ImDxnMTkW3nGS)JzNFmTb=^y)%zV7sul_dCWktFs9d3^ z`bp*Z<Ja^1+|18@QPiE*qB^ggdV|g>kniSHx8b2>3Ial<Y@${x%HTsJyE3TqN~Zcy zug4DT@eZa}ashlh92gHrD};Cq$ZnwWSTQ%@qv#_3wCA=jBi1cejDF&t1`R?gu@y+! z`+>WCJu1NxDmEbqoZ^QOIyW75VyM$#53n*Pp0IbHVpM@8Z!WJ+C22{SU(88d@PTUv z+r?MX|A5bSDSf)jNNA%IXVZ621EB&2zA^@>=2wYh@{qsH?ok~`J1}j^&7ov+qHBBF z_|4rNC`F*{<p%u}>XoH1%P$6gcnRI!CrT%zZIF2+0k*CYILX@u4g%AyKKF2Y8Bq~d zP%F>}e=wH*yv$)2gK?bZzJ415Q@tKoilm9?FhwEr1Hq;0CY^3&$W>avtfsgJh;wal z{iRdWg5nl~@;&0&vLIjM-BVRy?FlCXD&-H(s0CBgG#rFeX^nQ;c$irSq2nsWq~aNh z=^05yrA_Z;wZZZs__!cA32Fc13iZ3voV=B=zTOfAVjw2DwNXD8SRd>*>q-LyPQyy1 zg53{v$R|#5P-1$BqMXrH_z-YqEkN%4h(;6z9eSEw4ClFO<Db{W(pdr1?2W|w1A<fx zdx7|ucbZWwOB&6N*|}w9*uf<e!LMKgpPsk~)cv%brr-oosFw{4=RnAtt7I=8`QT_Z zA!-bbG5Rx$DYx5y{xiw&K%*e-1i{CK&!OQrC8}m@O8lq^(pq#UCXUntEto=mxf*8e zp#SrW{^JZ}1(Kz^TNzRg^n3*?SPGL8rND|MtQoq(pzz2WC<`!84E)lV-B19FoU)0g z6P>ZcGc&~;NSPf;o_BN23b+2Ws)6gs!$`;l(q`0&c&)U6dSKnwyM05ks$dOOi!3YJ zU}GjF7Oli0b0uWTTVIPnF~Q~P9bB|x)rTx0)vRZ_qKcP_ks{0a*WKgQoQ!jZC7Pra z8bOu(geDTnN8PT=1vbIPfZQ<2E&p*Jq8j7qf2bpt9)psOYIEm*b@R_bL;s<cm;?KM zs}Ex0;F$#iX84Q%rYYch0v3hxcz{O(knJYQifKcstf<w3AYQ{Ek1iB&gYcq52C<F+ zipl|bD`LL^O34Dj-g?hT56Z2C*78qeU{+i9^Xv;tLhY2JIGA{9L~y-&4|EMAZsJ3> zIjd-|fo&2p60OlRW~&4hGH&$&WcUbT?|u_=TNG$%3g?f25k+qUI45v4J%IQG$aWxb zoMa84n3*YfZri{c`KcM4x8;0%z_KJNTB;0Szq+p(b7^=phAsWb-4B@n47PY50DD)6 zCBcm?$MQtEOix9@<T(m_E2x(!xlwlPzkcPDHb`Ivn`YKzL^MTFKd3%uSJdgR1Mgy# zh6_nzoUE#q>D4kt(MEP5C~-&tLf=rTQrd_qOdJZ`D51p8zKE<m)KgcffQMzT+D{se z3Rj{!*1zIDkS>1WR5Pl=xuO}C+x=^SF%rNMDF(F6Eb*&8WI?g4>$>>Ktqi%kT)mQs zLLEkiK^uP~>Pq!v16e$HyVMnkwySuSVx7h*)}S_E;##9%o8Jz%pdpIXM3Ng6EEx^_ z<jj{)WPGNTT!Fo`4n_DJfi7vD;PU6bbsZ?jki6I+RMlSKr9XmHO=+=yd-W|jc!X`_ zn_pc+LZv5Q5IyqMf4@P5$d!ln4=wG{L=Mr!8w$K|_HU~!ssRmYyuHa4vKA;c?cZN< zt2NBR{K4NH*k&;GdQlT-gTW4eM_3!mx;DG=ie@-{3>o{jAf{SRx3o%g9R%l@6jQRB zYDR8NKuXE6eoYxLYZA(!8Uh5UY@9#<%BRXLxI_N+m!Sj+1U=GWhz1&K0B|~e_oz6K zi6}~V4&%r$<&PZ@l^DtOaR_v?HXY?#z#0gS@BMJq-+Xlfks{$>>w5P_Y3$%fd|Kz% zOU(>N_W%1m7hGSvt>>`;I6446mN<whp(a9((>q*?HPQs2VBXI6nRtO6yC)Nn0dIx> zexw=WjlM1h$e#u{!SUZ=CNimp&J|R(+G*`AOTeGt%=~G=ZwCnH>gu=VkW^{fn3Zag zW(PV2WQ{R$aouWBMesG#=C^?vR~y)R@Iy?Y5KQFwky->I3v_$zl}rFiij3D}c1cA3 z8}%gUdz0cxWc)r)z!uOz1F53yGNE0?7i}P9J;g(=<49@(VH+qERy^4F&ttOC42?x$ z38ctBBinsORh)F`#eUM11fnOaChAEz##KB*{3k4Xdua$u4)^Zi9c1RvfCP|jAr3Ul zMN616AaD6tY9dmX6vggzq<oe21fyl4P+uv1`saDBw3f^}23Utb#X~EpvKukUK=DY2 z=)JP48qs5vy_a<Xl77;nT1UUOXvA8R>Vr_N&Z}6Cr`5l<n#0l;b_lUHbpYgU8fI?a zfIXhx7g7Ral^$_$Bv}Vd3Jx4r4juzqz4&M`(?!vxM9CYdDV)0+!p2FRY4dfuyLnE< za#O^?vrP;DYgeaumnzj)eUEoTwhw_|OXm-_cg1@!_-;cs+wp8&s7Y%>Cb=Kmp}sM` z1}JpHRWpl*wAASa2!X7GSwlmx#d0_ixJGv~{_%VGUUGJvfGG$a9=YK;%2nD1uKrOK zBPPi<js8vJ>1!lS8vs1(wZ9#6_2D>`dOuQi*0<qxd6hAm6JRx4-;77M1sXn7suv|A zsLxav$sZ^4q&{jJt|7EV1!lGCw*USpGM_;kY7S(|P~fU62%NzD^5-L!`ZsmKpYK#r zifZzM5hqt*5_#pp{AgA}e?CQd0QN0Db#Pl*WRRNiK^AF`%Z@{jRt(>d-824ehP45| z<@*ei;u)URf&+25Xm?L-6BIr{DA(^RcvgUp9o<P3@fTP$I!&)%%&Cjxa|ALv2Kd!p zQ5*4vT+#Qbi4d>)NTl<@y<#{^j1#iDxWypy7k5JxsXi=r3MBxv)dqK!*Q@U{z0C}Q zFn8;#9ng5k!2$jnhKIdaH$iYa(muk)R}r~Ss#xFs`H{ULm;KWBmV%Brrb&wGp?rQD zvP9;H4XB6X(~p|SEmm%g18sv45&~2Lp6kOeVE(Qgi95Vv%akB@q-5Ch5BI*(q|WJS zP<ooL+BJy+<auug@fjW)A_HVItHOS^oT4kkm_emM@kDYTa;FHIDPN=)t#-_77SPdp zK~!)h%m%e9D@9<WBoB2PC>WO!-)3L1qLj#@lWnA)ElVjK|8Ec8{6mHE=>}kRGI^@A zgFexw=iPqj(Lh$C)rMs3P&(A-oy5bLd*QG&MF>t=2c|51XRqgkKU3}}4Q`dqlZR>L z^;hS$L1!EQ2}iv&0*rtBb9nd3n;Z6~xtpRGZWQ@P(W!w03S$m=U`}_6o_*6d@nNSQ z1MP2CNG=6N+A|j_2(H7O=@#8j1Jmw0W+M4$!YSoenyiX5-$%bjA!j9s#creMv2u)N z2;{$(0%Rgj&xPkGAl2Ix)cGLWLW_M6Vv-Jd!((@$K8fY}e9Oh^eVChtS{}HsvhXbd zDS0#t0WCv|tZ=E+0>_aaQwT$tO7dNdMjV!Kays(r?4Ic`eyvkq8iFDW1q-x+k)KCY zT!d8i@x3_$%tgRSccSRLl{ao_>%)g~$Jt>d_-W)pZq(%m`r*rTlGQ!dY0dl`9C_|k zw;5-O=wC1QPsspT1VE`L%*>yrnTDjkaAU}*4&d{5{ZwwdUsfb_S#6=(PEBdK7aW75 z2#}A0onlyW2n$6|6g=0~FV{SniJj7(ia5ghAV3WfW1$4fkMn}I+DFt~=oW3}`s0r^ zhH0`9+NRI1txj(NdGCHCH1;k6qXZ|yH@^U2#yNdsImSVJiL~s{+$X_g_U|7DTU&t- zioYlnmQI5FbBP)s5ST&VS-Fd{PA5X!KfSzZ@wyY|+?DtW!&bc)d~7#e6!lq!eaQXy z#|D~>y#dHsaHzYsOu+Q*_CPIU^FWaiqu0TK3#g8ZAF&Ed*G--ovXG$Q@qt5N7CT$8 zldM&Uc95s#gN8fu5GN5qYDJm_AUWJ(cVByEYKvb0{t3nkaFV?nFN%UgXzYOY@;Th= z*Xxo~4|U~eegk%FhXo!2(pedeAbPYhfI~A5ehR_`+Jg|I$|1oW#|;?uNcx&N7;Zs- zAvfO0E@~44(Vxg%^XHkq2j4NgD38ocXuH?<*MGblC2qq#hCyMah~a^9G{ND_BUBf8 z6i^T%m)C~$IoM{6>k#?%*T;QUxg-jzpFpG#{t7n7{%D<|$)h#JvV?NfpAV2uTs_JJ z;YVeETdA8hkt&QL`Zo7@<;fBR8(qd=DbbX19Cc9AGd~KlhFZsXm(GE0zn=Kpi=cWs zm1Wn<>=~~DrOqI-^Zp+{;-;59WVj08+e=ehP$HZABtoZJq~Lv1fan9C`L5}4^z$6* z*9`sZf*Bb4(%69Vw-J~F3-ARy4H`bofU(zf+RD3^IJ+;$J}m$1!w3Mk4kM)ThN69~ z{1_8*K|#py^z9;62dAfrO8L>BC;s*vewM3q|M_hw8XwF^Abvd`=5^4s-wV1(iaF36 zeEx@mpJV2A%0S;UhoJwZ9h+T15NSKh+WmX=xW!LoXxvqQA;>>h&;9@KMURP$>SWoF zL_jfG43xf&@|vws*9sscxXv=Ww;1Vpy~GEO3<7b%A6zjHC&pl*M}{H-u;H{Ul)Pcn zUBe4a4#H=Va(E-vefr<P`9C~&g!hA`3I*$b{GD6HWCBU!YI6Y-hc*XQk(6j~L`+~m zh3uC9H{4*6WasA5V%{oXc%Z0A@V}Y2!{!6l2o9Xz{nJ^+uKS+>ghltax|O|`Vv}A3 ziCPP`(arhepQ9_VjY*8$Pf9dQ#DIW^lAiogMr;p|=ZwIUb0l@osCh$LJSFhF#e4`- zyV9~i?pT}von4tfI)mW-ysyFbLYJx8Zx1B5cV$W7B^DGa0r^B!O5D&<4ce}xrh?qF zU-#4ApD<t8iyge9kYo6)0R{-Th>@_%^n3tWBu=sd9V>9vieaq{1O$(cG~X>kl6w6E zz|k-{b`q&^ARal$DQ-y!&ISc15XL*BqX4B(vm?`CL7T&?3O*c_u^M~%A;M2=6;q_s zS!Dk)Q4R$(LUiBt6@Z9~A?FzfMnaPbh351UPo(<dD{fRE0}3P^M}sLmKvqHUpBJ0q zOVlS>UH3xoF(!P~!|UjHqxEIWVr7?iq6(0^E$qOgghBej#yp_Qf*niV8mEwgcG4gZ zZv!H!38SK8PG>!HCaonzY_)NU?xt6lQmT6ep0ehU0>CCg_kdxxv^b9I@4Q+}c{I$m zL%>B94?I&0HoZLp)I=0T=gq{Lwewudb7Y|P0cGfB@VQ(2gfobxKLI6qibVcRRbIuw ztYHHH&{4;Xs*yGio`e}4It<z<3R@&gVG*1-4-HE_RW3K<do%swVO_)*t~+&kRnLV9 z#J0E$X;E-(B|BA<%Zq3@h)eq6+7jX@P*T3R9A_(85@(hH+ogB9EB&z0dI%if>aat} zUaU9ep2RewL`HJ8Ziq-692K`!h#K6Jx_R;T6|g2|ga$v3BF?>y{s}Bo$P&Vl;Tw<+ z%+Wwkd*mVC+RgE^6_U<dC|on1HGr9EqnGje`VTPwLJ&AG^N#!Oe!NRL;Z<~K9+V^& zALA7wK3yJfpcwx@Vd8d=dWNZfi%)xZhEBVI{|hvnJo(YPgc@z`X#z>F7>Zn0c}<zg zSaMrCcnPw~ld=F{-hZ**9zp%6PhB={jas3};LLH)_~r8-K|e|Anp{HN#YWbpYVIRj z8p9&j3!?Niekg4_0tQxCv%kn>dg}`J{EW(D=2n4SaNp03LpSoQ3LPtXIn@KE+1Jhk zUQQMc`{`+y4+|xikATsf08CRnU!73CN8~<<&u@pQVqc+VmGYQ#Hl1%DR@^@~KGJI@ zYSXdCbCY)WBQPw1rvYo5KR=p=Hj72T<P;oO@Z&=0oq-U@Ww!MMjTB}}EHf7}hn}Q= zY35=QWFm%a>C?u}Qb#Ld#~wI+0bNt-rL>W4IhIf$w!sq-fRRmV;|H>4gvDO+o%g`y z6q7IEixo_w<AW|@gRadT-P~f=LDWq-y~NEC6RET}uD|eVlkqz-9+`>Y@#kppiTbJ@ zhuh{vX*K?Fkk6(PwTs?oU+7C376jJYgnf!7va@W^=p{vm;%Y;1UKWUn8K=&FO;W~3 zX!Pvs1D{2&9!qG(0}eIfGSskG?Ijp|ngtowK2|8W0zV4l(58V%pYBxk8qi3Y295g_ z=ayntvk`|Jn>(%w$>S%|wMLa{7oiCrg+nxGD#{+qwERu5v5}`DTT_ZSB40{;=@cFV zqGEmfp@MIq(0$Kdi}ISXi$!0RhKLC{P%9x%t67diW^s5e&3CYfwC^1M0$0?nSI!vc z@1sfQ#g)^Saz`R30p7?8%uVjS!ra};H}w!-qV9YVuSM-)35Ow0v&V;9w~Z4~7<FhO zX}4@6od^<8^Iq-@R%+ddtdw<^$qv?vglpw1ixk7~&NO$ti$_~by)Qb6fjXlL7}hX2 zK2XR)FbdME&fisf-u2kA<DQBk!JKC+@+DgW+|#xlzV)b5U9!6)*(6Zxv`XcsuU|7z zT3Y`u4dJ$+w4+bfj3E&e^@KH&67ag>)eNpRCx5EC7M+%j<7FBEONlzCcvy*PZ(6_` zA`tmn3Et?YJ%-r}>EHQX81C2Vt9${6s$&>{YoJW9_1h~JD}Ur4us+H%<KtC9Mzwgo z5><$LGso;AIcdpPbASH=ej85S&=Cf<sSn<RqByCk3GqUA>tyT$6B|#EJdU@4-RJeF zjr`DBi0Oy0c8Dc9={3>FYs8<dzC8u+C&}3h#d0|-=&tFQOvS37i+_4zNYrVkd#I>2 zB0Bf9*T_gBV!dNuj&YuTz4x%w67C3baQzyvUg<N->2P5g%3h@AOMBmjzvStqCA}G5 zx&Tr);^aBIjaYLI7x22@7X8q1GP=*vNWWclr<uMNaYJUp%J=r6mclCUNP(rIrJWh^ z_DDB5GFEKg<rqF)o9U|K*qb^c9ObH7AdyNAtIZx<!Pb;YKuPbsR3Kw$H<u(Euq%c9 zaT&25Z|Vc2x-8VYQ*>|gR=33p)B#=W$6EK|4jvM^*!{hzqNGlA7cAkTV%T(6Wn372 zjkYMuOC#VlGcipoK!HYm!v~Kxc0>hzM8y890QJ4{Vl%U9{(!8HH1C>BiSDY(jUUWI z-aO~GhM08)s~5$aRio6GTy{=GF~z92s16R_NM;SYdzYP%^{k%4a?IjLEtb*_VeLF5 zbIC{H7UOt~qHK;JyG_?pS&X!8x-V@SQdJ{<TVIuir)zP&^_C7xex{z6O~*0)YGUe( zd=;M9G*?~}AFaCKOWUY(iM3GnQpm{V0fEYk$P}5`|7+m=`gXOBKAgRY9{J!W6aC5* z<n`fYEVwq7!GP&LP9Lu}aq`02SDg>^^TWTa+s#NQ1Q!+M6F1co)x%<(^xU((p5a3t zh>@$~ZZ54jPbwGrP!&dtXKFsy)(!%5hMw~Uokoj$i^iw8AcKbUovqEcDB2L+c%}4& zp)pqvDA`I1_NxI}V?@(f9DdMgAK6thQG*vB#?5Hdb@5|vde;fb313=&)<(|RQ5EMc z4YMWdtj1tzMdQwJ58YB-bQxzV`qdtyqDqbntv0liJ_qBbI{WKhkvKi9UW=qIcZU&I znCMT3rnyr8hDW*lN3sa1S*2+h7+CMjR%_@*)ieso3ss1KOK!Xq#i%}`P+UjkTIAsV z5WgFt8unM|)YaP}SZYw<xZ_}8+c27#w;xJW?NzefzkS>#mFiPW>)H_MtePi>7R6`{ zFD{&6cR&q>87<x&XA8zM-2D~08lsDomp?Gt!+0LPc=hfKm@5@N+q#PTok}ueb+tgi z_&W7fWpZRqB?^Gu^(7hZ-}v<eyRND?d#sE`uYAw_K5#tyL&^ubu@;VLljqOnxFO$S zZAlTvqT7Us$4G+mU)0pA(s|Q?qwAf%30P5IYh3|^Fb~nADj(y%Tv4-NxbW=3VjvP^ z?JMsF>mb*)PJTmLy;fb)(y3WC?Gg9JL{jK&@UFB@jbSXSQi22h=&;rA6C(Q$mAn?N zqa|M&KyR;hzZ!&WZ$97DhvwxUF!A*bU)rd{l5DV%_!LxQnk%WE;qF++CYECL>T<ap zxJk>D_>-Q>@p8vxFA3owhvfrkO;$W7QKLI;y;@@EwnPH?>G6UKm>cV(4Wa{|(vVSM zyP$}PS-C-q{Bm{UP+u15ZOMBa8;>4+_`!JP%%oM+_X2opV{Sc9jREnCVjW)6)+tOY zpsT(>cNfVn#;qE{9&NKX2f7&1Sp=p#2UXGf6?WN7y}>XP-kilfp;j(dKiU16Cxt1* zBu0c*!;E)Bj>6=6a!oL8VNwMl6a+I9q4#zvrcs~9t>32CqJmjsYwTYW5UM&#mJ+Mg zi1byxbn?jxJ*F?2SO)&iJ%T0DlWK;MTGRpZE}IW9d37!QMq#SODPWEcNhp`dRx7E+ zH_MSXkrpddOhsoeX;C}Z6{!3Myzj?qg)#eMC$S18MYs>NYX+%_^%sUU)i{HW5)Y;- z!r8_ymQc&xqjmt7b^Uc*K!jEd_lxQ`c{O(e@zxjv{sY&>lY{{X>vcca78Yfu3o%V^ z;+pyOl6{&Pe85vGDAB+q0ZudWTeklCKATEE+VJ;bVqdGbx_P<m87+<r-=x6_*-D9~ zU_+xjm6a(g)ETprq!-&_4K((U%Ff4uF5apiulQ;Ty)_ie?S4n<TleR4Hs+Sx<T<14 zs7g=2@ei@?Yt)yQmju)mZmF_~=k&itY`Rg3X=z*?Bd1t<G%#UMy0I#Lunb)Oi$1Ig zJ?gVfKp)(*l|5B$^&jB1coT6xi(6+1Sipx_M_A7tXA7jl+?X+K-g{p@;ehr_kr?+b z#W0Z>Hp^b{Cy7Y96KM+sIv&UpBLN>8aj7P{ep#%FPdmx4HlY#HTo5E{Jq6LO?|LJp zih*cQZ`pm3Xn<QLbAh2NL9${B&`mY{00@-n-SBntNJ^RM2XcsJ%&X{Ua>MxnN4MmD zIdSV-H%aOd5;Hp?Pebo0X2<gn>1buAV_R#cb_WopH!P>U+A`#%CePg4x0JXX?9GJq z3t;kmB_i-S*m9lhea9`T*Kw7V$>D}&uJT9KVA^b*ys#|QCbk1M2Hqovjrn~YMuPIH z{hfi5NG=m$tfAaZolwVjqYS9ZU9SYGgSl^A&;ES(xH-cYss0;hz!`Sdf@B8q0>GkB znrYQgqh0H6Ycw};Qi#9M`JM~_U938lQm<0#MX;mPulovhLKf58#}&#lOH<RL&NHwH z4eMpC-HUkGhK73r1~tsAQB&AkSfFfwTiYmX%`9{dowe!(JtlY?WS&vAN<-1n>k5ym zXkuWcyod=<(KxP_x<L<2^H~VwPX1~FL-jz_jk`RbD?@POc>~T0qYoLDV>sfRH!*UP zqaxF8JY%#F>Ya|5)Zg`#R??O)zWxsFgiS;*?ig+wMu_AU+U{|IdAKh|JR8wKVwLJ} zF87ma=Z9kSy2+2=O${r@whvF%$XrqwP0j0?uC_V#q|QiJDW?BKWlPC)BRD&a;7vtj zc8$}zrarklCQ?;Es_{`MR*TfU^eE7|!Wn!@=e?vbJSX)aE^RkUqd8&#)Ys|);bBDh z0dqt|3)#!3D^{CtLbNtBFfh8->XMdtxdB_BO<d*vV+FfYFK!l%;yG14#nDvOGI)!I z2)aF4$H)p~hT&Z;+N65mp=Ib&BIo))G_Fr<4ARC&da7gnB$@(+ts`<s7SSPg+})p! zZh2UmSJfA7DW_U@MQYn5k;etb%<N#9K7vUIKGaCpDXwg|kvsAoOqohR>1bHC%T|Gm zmk3cM$I0-uPb0z~%ZLr0=quamjPp6(?o(%(MgxR>L>#=Iv3)6#Ng1R{w6}-ZMFXtW zIv}Q@s@9dZg;9`e<J+TNAYq~IiaFN{Bz<pam_F8JShs-1wGg!{xsk+hGQE$d+%7yi z(jrz;$vxg79@qb>kG^WUl@80qNaoVcfx`^m8dL8!a%V)CdS9e#b;xzUXm7<{@A~%l z#t;*U&5iR?s8Vlug~{K|y_Dh>u_8~Qe0WpU=lDH4w-4g4<1TeYJm(#Rm}j+`Tm1RE zq_$F+fYtIsZa{uIeL|4?;@d&)&u_>4#P)QK#<0B7u~2-|)BPRBduat+IePNGombgI z{4#?GYIIr!=Nm^OYt{^jMc8-j<lKcV1Nn!LIOz>viGG0u(<58(vFbT_>@QpDxS=Jj zt4(QiU*@uq>=2Nr#Wohl4=hQo59gx`8MFX{rL^J~5O+)7eWcw*G+NdE6`cK6Wp%8! z7GZeN3ksy5HX;zvJL-A{H8yB)8&nK*i7QV_i$LJuk2&0lVA>R$q{!?XR%)p|qln*Q zao~2X?u8JGGJW{uwo8%qOA@x(BG6rP!tl_r%A@GXBa<SZBb+1?l~wJ1!d>@%@H5(@ zwZ5@h*y_U*lVdMC_sF{6CpX?Lf(}$SEz#)h`8KVq&?}~f3_B<kqBDFl#>;?HNnJG5 zRKKLADbwrd*QnAVX106h+3>ctPPy$n@Sy=I;(^z)_b=xZ{KMLfQ2P>g?mSHHMYNNY zyIIJDeSj%7*$|cVvNGk{ZN46(x5iN)?}I4d)jlky_El~ghJGs^-hkh%k$VSB?+`U3 z`8=b!9@Kp!kEM1rGPSuW#&fv)XGQAol1Cm|x?NrZ7yJUpt*WL!^PF5lsGJ%D;anZI zc&KsN-5K)I48LvG-(Uu9pN|E~_G^leSG~)!HEXE7ANbk?ZjSiQ&X^TtaE{9u<Uy$- zA4lq>%SnJVHoM8i)ko#W$eHVhg%)k!L_raLG0mHUo908!$>#ydOwvj=0h0W_^C^0u zs959K8nu(Jijk{C@07gK!FO?*$r1ZEXU-rm6h`5!k;Dur{|lP9l;~3lVk+$xe1CKP zi0cE6W5X805R_7hruKlijXNxM#m#44FDRSl1m_4Zk7KQ_B7l>=Tv@0@39#d>kghno z%zyv$_s}rgiBM5h&!;8-;~6es3eEaM%oW-H!qXQ3HM2(Ue<EYeT5<g8886`P{Ojrc z)XGxE3IBLHKS>u9kbVLDFeemPK=3oG@nGVSgPe>cdT1XkhRE|AEoVn8z>4_vZ8g>1 z>p%APPuAHZBP21NqHltc93rU2uEMt!-_TPBk?*gNW-BdL`uo%($#s7k7T4_7=s$q+ z<BnA??0D2UM~B8HXdpU=LhJo?igz-3IaZl{#<T24!SLq^$H`=!{Am=x1-|3Df-(KE zptzVvLzp<l2`CM1rO4<&Yf<Fm?@*gzU8bov-<U-ge<4Mh`SOes0R>&PyYUh1zYZoQ zu$BBdhODQNUXg=UdiRTJ9&UGHo(m;j1^I{lI$*}|98&d$CpJ47&27&+_faZ)b(ht0 z^re7qXAuW<J1x%92PAE(he+_akp1__DAR2k8K4z>J&hc;W4W&as7SH!qkUfceZyWo zb41;y*z!6lxnL4HvF>^toV%fM-=cv&`CkuNC*LLQG-%dlKNT`H+&h#v=C&o?=EonX znQ?1(zJfkZ8^O}Z$v(g$rl*gCYWvz*<nk9vP=*A`IR_?<Aks{OR{=jIitCLheC63$ zJ+>{;$U;}XtoUH1lb|DugHssjrJ`AMsK`+_lBtRAYHfd8kxK6!fHr{mlPG__;Ys`J zJKG|S&;K&2e+atqd5iIZlFax4IK6+8mVjTA2Si>YFm|Z8|19Qf0JdsWhYf?ReX?*$ zZ|MAUm8f*ME}?&Pz$+l+wJ{Q?{2(J*tL9Hbj3tYw4~kKsXzL^Q5lZs1#z$AeN;wIF zb`YbgyOnuN{oEoCZi{sm_Z-5q%xB(t1kp|*t2dK4G_jT~Azb}zHihUOKZKh^sl?Tc zzB3l$5FE)gIl07j`%I;AB)s@uDS_g+@Ppv{(zBU?;>rLov>l##>gsXx4}yD!#wAaG z<%`j|6g^L$^FS%V=rHI*=2P+*h1?X6P^=<OU-8cy$yY*uJ`E^@8&-<5!8bQeI`fjY z5{x<Ho<sN<OAh(W%#Kpw)PS{e5phW8J*RD>SE^tzLm?fQaje{dz6Kb5c(XGd2FFo( zG>rAO7W!~8va=~~8uvU{1RtTHzH(-b(K69u8^frEKvqRrZOrh0qcD+xp==484kdoD z9|hg$LO_jd-XCy0x9I@Ya-b}NnS*zf+Kefhq}y3%kyz0fuDd`O2fioOI>a$T@+CB} zPpQTKd0zj^^`M_`Y>(E5fLqxon9^=PVxK4Mjw8I9&<lf&{6pS-S0*($5d5(x{O&HC z+y8Pi6oCjgboQ$vV+azk1M9+?li(=Bv-~u=2G-=}*2zyGa!a-qM3RUf>o94kqvE*^ zpg=GN0LMB(@WHtG3ZBT38TYaoq<Vmf;M)$nO9~GlNp87_9}DpD7;_?kZirWHB4NyG z1bQ3N_ijWa*cB=t_9__l2k`dW{6a?bWwFf2x9P3NFl#^j!4CWD9|9+>u7?m#tPSL+ z`@l85J>YDu(;u*R!H2GA8)OzVH)$&kF)O$R03zKKK)1L8#FF^)Q{O;<u~s$KYjxMn z3_kewH)k9=X1{kSxD)Gw2IQA79{M52F$mnb{h^u)0M69AmQx@q_!Y{@byMUTf-5OJ z6J$jD&NV;nP-g-jiuR0G2KbrW-kh5!EH(eZ^O4FefTV7ORHHxiwLpNGDL7jBNADBh za(EOq|6qKS`WAF%EE4xvK-KUY3E1OG-(D}cNPg(wDJ=J2N{%sl?4mILVPI{W1ICW* zi&3NplGRl3XJ$6576@G}T&->XSf++T@#S2%@LQwMnuV27*nQ5?I7FK{;NmRsa32md zBNWnZHDgxIEN53~JHf^J%0iCvFDn@;L`g2?{!F0xgKIZ>c$6a$9b}2Ntt`kvH0;Re z)TiaYk!%-S_O2=s&3G6Hd%P-yM4NPT$lY%4gvYYt)5Ohf^UtY27Ei}O9i{)ZnP207 z{Wr8&I%>qh{rye<`I&(~3C4clvm50&-G2Q)zB(X(xIV6Z4~7sJAc}fMeV=I!HXr=& zo-Fb!H-!nkDKrP25R+;OcC(uVOq7OtxM%on|K;Nez}X9e9w6@I<7ZxqAegR-*S?V2 zro94%uPj~n;@bw<Up5cYCN8YG?<cWKIQYYiOdO5^pb{Y`?TU^0(J(ESbo=k#u-)@j zLjJ%D20lAn4rK%o!TgV(5H;X|Oo2drSpO9TW;NqsI%=mga}!a1$FUuwY7L!Gj=UBn zfa<Lx7KJs=6Ot_~yN~HYgN@uL<zQq<iSXHUn04kJLci(=X(<sd#pFt>CtnXkrqFct zRfs`2l(=}VBKmU|_LO|S3k}{pL<8o3H{Q`;tdoNPHPvkZTo$^|{?@ZlmKUfDb&z5v zW*^+al<+Fp6cjPj!VNt~9h&=RtPswH#CVj{gdOQp`RzZd<_<|vwF=H7&it*#pgdA= z=OA+^@XCS=oo-ne$g<#Wdw0`CXt!1hC!`N<Ce8fBf3}ZD)->s}9#w%#fv^bj>+eNb zQtUR-^7}9T-5L0I=IGy1=E2s4m?In!RIZ;;L>1y;p;~O=d!2PRqb$uMcY#p=0#+a< zQ_9~Tv+mCF@XI8P#8Ai*vKm5KX-ab1fAfjVpylACk^sVGPm9O;`jJ1L&Hu{>+Fvd+ zue@pT4rH{2zNviq#xN)?23ASrLILY9H{?&24dq1Hz6yh7x;O${Immj-c<Y`<iv_T> z!DJ=XZ9vuj%LOMgdW(iq!$RNy5AzZ#;Blb9vOh2MIc6K>96GuZn@l-PXX4Tj*fGyi zb#8qAqko-QTr-l=|8;Q#Xtj%uqMrC){uV?(E&YqV=Wku-?2QmWY~!CRI%%oG-u>>Z z`qzKiSm?t;vFbyywV-d4gY?g0Fb<0_28RF`yh88yZ-{8=*U6V_-O75@DB1*6bJ!8U zn=J~o@2y?Nj8sZF|LxA(GFqGfa?`dM%+wSjzBdV3>OfQ@LVo}Ax_CWp)`xxiFos^x z%Vi|t@#(!=&fM@kc_Zf=JEmsi@g5AbCuZ3yx3KHWkI@`FD7k3u?GKK!9&WBSOAkpp zh!Oivw`E<Z%WnOEKV{rL?HD@vh(G&+ot<6b$0v@Z8Q61R(2xp`DhT*F;{Npy;J7n_ z@;0B5YP0?tLKYH}y8}z1zhh$PO~HUuLULd4qI9&jBw!CN$6i`)?bN(H-xxO@2L!<w z%@mV6A(n9Lt-=C6U>3cIY7CI1RcL)BAXYgfcBjisTRDJYuo#T_-HanIE&S|bpeNg- zt7Vg`jtrU5olp#(TbDJcB*kaG&!OwxOW?vh4r);hzCWKP2oUW?wHT#*XJ;zOsV%@o zhnmR)$r_81Obi92fy<i&in0y@E!A_dJrTJmGqr7WxA-{LY2Yz|*xlpk_%!~mTN!-C zy1pc+Sx17kQ*r9rd9~e(HY+U0Ho`%<^~LZdD1|yfFJ6i~7|q{3+Ty>2>b1~Pq9wW% zAe&hqI{H&M2I_EdYgE|hGrb&3=bfuaB<yZ#7oGUPevU`AKNAETr@T<mUdjQ%MXtg# zU-$Z&S{h0f8Udihs)TSVC7m<<nbs|b#fp1@i?p6JxIN$aW5u`5d)}=RI>t>6ODqjp z2whDukFU_NtyZ^VruqcV2JoCWOX+Y>YUb;p;1kM#$VB*F4Ac4#&clEw2%3(iiLYIj z65ZRO#a_-n_R(MrTU+;SMAC?S+1PP!sa(GCnL5ZGL&)Iok9-l8G91y%YL%!s74q9r zn3E%WyiVp@Nad@hgkk6rl_6E`Vkt0Jn(uI6ef#hsPFAbWrh&^>AT1O3yTjvhi%g=L z@gPed366EqPBA$RDkLF<ur$LQYV?;UP34-@)s&Yf0v37}kp+;zY(Q3zHM+L+KH|n8 zwh)S~p4vLy7G$L$k_d8!#%5-)N_m)7U<@@w3FwAd<e1X!dbKE8@{iB2(clYFT74VX zh^>h7FnjkX97SljaTy@^6O<8a<tDGfY83B(x+H(wfw{N#T5g(Vd4o3}by$E~*$YR4 z$COnCe34V+jL(CoG-Gy6ua#vzy`=Umsk9deK+D+|xq=fhS`lkMjXzxrD_>G`C5vD& z2nXrYWQ&0Yiw>m{m|mPEtC7wS`x>*;(a5p{`CPM{tCqZj)6;~7o{s^)GSz-$uoeWA zpgKO|QdT@{n?SG>lej2jjeAsUp8{O&{NN-J@FkH0_1k6AC&t&1j2Do9e?Nd%{6OJc z8RaYuFNCa-$Sywce0Kj{DqeTF?9qKjSECu}W?6cy1_eWUG+kCc>7#lSyV_R<38FR` z2d|Z5@*`L#YNsbq3?&Vy&O!S=f1PpOL<!>b6MiwUdF)PdPl{@7i7qX|Wh{Rfr~${D z<+)YVuAkQRea!@^sz0LJAdDIL_~r9>;6cAzTY=(55HGx#Yfomr3rtP6jo!KeDnh=C zpRdiW_kf4A*yndy(N}(sIIs=lPH-}~X_%K9_LDfQfvXjpuV($GeFRVq*#EAxyYlBd zK;e0Iuk(P(nH+<*%!p1L{`|)CQ*bKe>wjNQ*jdU$H@jmjoyR+Op-Ai!){D)T+CXWZ z9Le4xPJZ<jco=o3n=ynl5nx4GGbPE%z}pStj8##$U_k0gI{7$al|HO>%Rv}MFkwcC zAch@r!fgNSGBwB{wih_|7jxkW%-<Tmdq!6t-{^`n`J|R_EciBrCNZ-uu;lQa3h&*R zL-7u`jm|^Nod2aIH1!3YrM(<3-ycs-dpmz7eG3Jv*+~|va}Y=Q>+1kpg<|>%4XCF} zJgzQXDXoBca#f{-=jOiAm5JJ8dIL<beP4%uF$BK_;|9G0<1Q-SzBF3&#|*|W7i<8@ z^fi<3;1TJTw{PS-IW!WWoYigj<vu<|6j+YfisKTZm<Q2UeO!RF*?a!kvS~0Y3q+(k zdj1252E3PX8Ih6J{qAa+MFysBWpeHL`#6u-fb_3nde>P#@M2B=_QA11j}%bao8>nE z0)Jzxy71}BIGs$sleAPBFxrO<-8EYhR<k0{#QW~fGESB9Le#239XdL|hH>-`<=sR$ z{88&+Sx6!}-9~H@szmT0rpjkEK!WCW_vc%1!lN(DK7)XX5{`9>TVnDNr%oDkADCAe zO$a~G3q5@~Z(o%Kp}Zwo*nwc_R5vtQwR#6&_gbHn(gV(luI64@Jpn^vAv-PU_O2)I zAkS1R#LL0sYEfz1`%<NJD#BLECG+FdE|ikc95ORgFC6CSL_#z;8EfgKcPu5o?8LY8 zz;S*%2XTzT=^0E<YU?sQe`Ve1cn+qyNws1U(dRY?owlrQP6%g|29{Y~Z|nUIxVE;A z-r~~uc4Y63pBsP<`}`@tT75Hr&|ouHbnux_&|ptwpaTt=G<x$ZcWk1+7gUlN0?S`< z;SrPrP-5C8NzZI%oZ@q7_iufWq^Cd>)3=7**<*V4GO9NH>kmn9{{qWh#<L|W@jayT zoa(AgwCWoJ@~0z357Yiu`SK(Tj5y>ri7k!1dRuWQZ+a4>VNrLVbJYGgFn6o>2e4ke zdJL$Nc=kBm?6k>>>!mMIWZ~q2V>`z`M)|URh~*E$i$V85{PoDE+5oq@VIR*4U)nLK z)#M=Vj#4LxyxKDeQ*%B*>M($sDb}5mo4JTy>p^MPBf|eZ+`D5u(*ATyhBycd?XJJl zw#<Av)x^UxJ{^#7Egam`%#tUnP(IL0=I?-@I=Yqlmrv^dxc)aMzi3W=F!y}Jrpm%N z&LC^Gsf{p*3CQQ)Q8~>9Wa-gU+}Zf-#p-aZ=l)WSK%vtN1oM>INDxH5L{wjyybnOF z?6!C~4JlIlL4upkmUPUM873i=d#X-5+b*7@6z-PUMUE}LyW@B<u>8T1LC2sh@<x6; zXxYsb!;#s*)YDxIlTT$MIk$Uxl&6@gX5Rudt}av-x3tpc%;jlxcyenbnD?3afvl;& z!*?-u>|}14?MRNqZ4~?Ix4(a-kKkx=n>gqAoi}~X-^B2s+os09t(=w!g)@NigB)5p z&cEI=@;%}7xkXQR%rES~!-C`c)VI8J>1L18R^*lA%|yTsl}nF2eh;5+cQW?S>>2;w z<cb@EqId;8e=NHn&_%=8w(j3QdY`{k`1w@KE*7M@?XA1t12mIViGZqd7qA<x<5;po za1_~Uj<7mIcJxv_c%SSRhr5ezerW>mDjmDwiTY+$z7U#+AY~c}u1zv5I;G$MdnmBC zHGs1+Q}<FkN)Bs6X`puOR2eV{oqv#gzKk~D)mx}k966~8MmZsg&HUCG2XekZ`9L29 zf7j-+8F=w4NO%L0-w41_mf|;_2^X@aqn*D;I=TVt)LZ6T;PEs_plaBxud;gEu!4%! zL-_IT1s8Om{iuu!*Ab3I4W8ObZU?wK&4jZ7iBj=aNpkIWlb)rSRLuaVvjApug;IIL z{Bm!VaBO!87!jFVOJSlW-pG4bvnIo3qM^x+1pcp-rJ{WTvI|RqqiZ57SpLW(%Q(2Z z8+3&qzv}w+|EOM*mJuI5+>F9i_W5wD^C7Pf5qPk@{h3s^t$y8PuJQ7D{xweLAvX9- zG&mgL`rOl;CmmP_+{@JsUP4f_MPxsssOWD%=Nvp0b4_IFF@~-ME(4GX2_k118dWHA z*0VR+uHY#8mRXvcPV>HAD?i%79<K5VD30?L%rdlA>1Pwh&Wo+08e34FzNSIIIk^2i zLe)z#6uCysz@u;H8AbcI1e9)8NQ>0Kb9jr%)|q?xsc$65pgEKWFB3H60|oYjnABol z>#~IpBA$r=^vI$%fTdSO2~yNfFuJ<TMfH01f<rO4Jja2eNsHHFDy{=E#g>cE<fVNT zgcv_mI>R4SUS$V_^kkS$LeUOoSZb|=AFAs6vaZY>%$64MKvrliL<UEzqXfA$5`s5L zIN0o?rW%9j$N6{jYva@X0rY76CcWrXQ5K4#M_wEp-LeO=zUhDuR8I=e!u6DPqMtOq z4HYjk2LutGG}l<ob!W5P5S%}8DDf9u2=di%vs;q)__q`+iu8197x)}8Wfe7{myL=L zLhX*Z!}^?=88s0+s4$LZo^yTFRNf-0fmOe*(>1oUpBXPLaU14G>*X?Ke*2_l#0U<* zdA-rtg5u;yPx29M^W5%ra~(oPYAQqyzP_;F1y!w`se@?&V)|vZ^P=7zLg(i{-M@c0 z683e%M?o+9<7xe9WW*Of@!xt|I0Cz7cOs<|9!)qtI(x!4uSWnF>WStREr($6g<f%3 z|HA#T6~S!__F~MonLWnH?pF4!C40|YM~1oxs@v>;c?-`_RX_hVBCg0=^ij<WKgyCH z&E&;}OBRVD9sciO|KG#@=gM}C(FVOJvbVokXy7eDi7u!~)aQ5-VgA1?;s{Idc^au# zO*WEOg{Vzc09G2<!v}-t{+9))ykQv;9MfpqHu6JIJCYYJRW(FbhX3uxTVwksKYGdu z+LjV^4PC?NA{YhD9Utr5oAD5`XasVnd^HDw`o)spXFKpeo;>Kg+%SaN<NxvY<$+MI zZP-&CD%lDpikwoYBqB?OLYC}nSyS1!tl5cZPf2zrOBk|b%^oVL82g$nB7-PqY~j0~ z>2%)CId#tW{qy<bJ=I$?zvX%E=f1D|y01$Rq~vIgHGl%gy<g?z-7F~jJ*ojE0#`C& z<3;d_cK8JPD!29>WwTqe%lBVmh=1CqK%`>a*%!Z91a52QfEx>;(#u!}w&~wK9K4!b z>s*|YnzmxzUxk}MaM90p__Y%4x%sg3cf?-iTetB=@<|2|LLcnit)K^}-Lb*NXZO;m zaHhOt!zYstVxBYnOUz<)HJvVoV?58kS3J*?WDPWg^%OZ#pvF;U|KxM2ai)sc;wEsz z_>5i=!i#<uW@U}ONMfNxw&>w#0x)oZ1zzZx+~y0vjnP0$a326!TSx;!2L|gh0X%h! zK52lt2B0l~jz15r>aUQxMZ>WfWg(EaI@_>!b%EdqleEW}lpg`x?=K%5YBwEa?TZbk zNW-2&4`4kd(*FEO^0=Vl#REX^K;H9HR3%8p0<uJE=jKg;YDWD$j}Dps@b-h6hqU(P z0nXR8`pV|NulggBbO8X?0=AYzDoBFZ0coEh59l5eaT_H8=8V3z%Lt0$FINEeOyuwm z-Y3+nu5X!7<v;&N()!b*gQgdmHh{XKB^stq1z3U28Jze)s%+Q%fiqTu0WLuUOs|-r z(7tXx9px>!=|5lB^D2{-FWa19R4$Tg)7DNe)%3XE;gI^<>fD4qB_0*@pO^Q30I2qY zFrk%-gfgHGIw5dW;vXNj5i1n;_QZc~NXLguUK}os$44$zF2&(BA1VFpvo>HM)s6mq zVQb=lZk(HF5DI0Q=FnNHik)Ee4u5=P`|%RsA`EW?q*fLHeX84q7)Gf-lA@m;$G4WH zE+ME7WPcdnF8nH=`r26L;Y@imiK`TUMWp0dl~?@t3`s|Gx)_F06KCT8jKx=P{^oz; z382KzsI#l|fG=uaynFQy@M}u}II1cy=5H11_nhYy1DdrdMpm#sw|)YRlObIoK=se~ zBV?$(o*?q@0PlS4QHOX*y|%|^TH=?|bu+EU=R74b%rvAg(A`c1<+Z@Lcr@4y_}C4) zex;uW=v`7g^WHEw2qg~ll?p)fs<bKJ2{;4$kKYL<+a_8GC#ZT9aJ-m$X74O;{EIyQ z7EKR^U@;HX%YK&U2dJR{_pL4QL+ZA`b$Gt@t|i+D8GzXRZ3|I9Lwc)H8-)0x);8J( zsx2=;xf6{XQ&rbVbEO#;=XyZHJP@yfwkjGUSB8ud7Q{a?%2x~kQLf$$`hbXeHtml$ z8sCG+Tdf85D1QO|SiOTEC1Z|gO-G#ukIj88AQd&hf?@Qr&K8C8nxYNn0>l-&>0*Ge zB@X`Lu>2AjKmc^6f$XjiWCf5;NiQA<*fdd&bw=qqDun*>rF?)kI$@%D=MBL+RdQ~u zA8CX^kFs7Fhm~|^!N{5vShrCG?m%bP#p{kX`$<%N{rrKpNn+9P?;U8WoaOUEO$ETF z>3*!-K?64D%9^y`y{g;1_x25G-4PpM1v+8ISsDyY4d|-81?JgXpcDj%RsNz8a+j0Y z8w(wPLX88qtfepkUl01=9A&?InNBMvsPinStHP*Ze$^<@O(#7ZfCHHVWDj#N&B&P( zqxOHg>*pEqUCy5a(z)^>gld@(!uyY(i%DiJLt0XOtl}<~FB9zl0y_V_74^Tq$hBaE z|Doxn9Vi|FFeeCAqcF^h=h^KzbrN1l>!yZ%-wS3zFlP<EY>}2cAjHo0rSRN~8|2zu zNY)t*GfU2`k>>i<Q(1*UZc9F$^b4wzByF$yaTpWXDeeRjOQ=5PD1$MH{bwtVZ(f=H zn9L(OtOT401ZS|uEZh!sH$1FugcQ|t!Wa}RL3P$&WOu_z(5GwA!8LQ!ZBD7a_{xpg zp+SHp{?bRfUS**Ow*;>Q)VD8u0>Mh?h>^&9=6_SS{N?8YCQLwBdsV9gpwhs9i4+AC zAW+`-d!cnVDmcELnSv><e7aOAgsc(-3hDqb1!CSq&`AGjarep(8PUHU(5hNjWpONQ zzaIaO9R&a&_}#<KSOu!Z4FN?VjsXn5m=Uw!r>p(Y4x$_IfB|L(kq2u+|8Ka@13y-4 z@K}XgCn4QqSGG$`aQL^+YEs8*ay!GIY801Da3n}zMIn$Zz7pDDo6Fuq=i;xB65yzA zW6dvYLHyRuz2`d9zGwgwJ8U6EMC*&jcnv1#Z$QJJrSOrr;9Xz{QxxVAMs81P`r6ZV z-oW=1ShM{6du{}mNFsR{ls52J%%AI7Hw&E%x_B!8YLJ8eS+2cnmG{*Ibm`7i`uYge zMndk|HFF6#J%MOP|Fy=~0l`1WvdQwC*E#&YIy!@-+Ip>jTWzqFx(9axJSdX~haAd? zX224PBIgg@635)z0N45}6azq~HseKT>TQjy45r^{jTX}k<l#M57#>gu`Ab*sJGhXT z0CcLtDw7&XK(;{Wxi+++_b0Dl1t$C4+zovCQ3naNNNq!qYB*Ik=GV_gytNbP_%5Ju z7<*O~K$(BM*I*Dlw?#0VS1BAaKXer=PbWifq^R>a&d}I*!3+rP@)BX!R-EGqEXw~{ zOz55gAcY4MbHCr~J=B)(T!VvVqvnfQV%wWrJ0;rR#!L2~mdpJ3SDF9H{{MnlAgRwN zm`2+Ul6n+I9JIZxppi;R;-E=LVakExz;>+nQ%Td0vZc_I8OWYt_|IhNN9^LGe|w$Q z`Xbe2@kUq8w&U4@c5N+M38~dhh|{&i3sW<D|DP`$YR6pD5ztPp2dlk$q=OEi;N+TY zFHdWCgE$^$Pvn0Xj{!}`ZC_ni68<Yi{1H952M#5uI}!;6TqIhv7#9$zA)m!zeM-s! zU(KSCcb&G0>;WCF-~8hI{xdcH5%jqL*ta?8$%<gw7z>GO(syaEFIh2ylb%k36zl29 zH{04jy#M=xXmo2?9K-gP+|lG=rr}-$O=y1dJ7d81fH~)f#2uCb^<*P{gf9Pv1Mvc! z{Vl1rOkNN3RwokFX|h|hjC%T-Ws8nBSz@p8`{4d;FZ><+iaj9<KpU#~UP3El(p8&o z2>SYmk&qA!w;X}9IZ2&|SxNS0!;m;`d{v$}i8qKkU{H8KbY}OB?^xETb1zK{@Xmi+ zbz0Y4LYv*rMPg}!PFz=8Xu+*q*#CG@?eYnU-VFVkg3%=Jig244t9cnaDd9Ud2G*x# z?eyTUCdlS}JeD<6+%PU)IerY6-Jx*dJ5=wC?a0g#`x}TDbj@@TJ-GM}NaFlK8{&{7 zs-u_g=<ZCList3AwoMAR-xD_{4>Go?XRTUlpuZh0H|iKia5e5&FdFrUo7!yj9oC#F zwhyZR#{;Hqk%zS9Gau5yhX#Q#NR#BOa;XnxvAN9@XdK05e;Dt`F6vQ{yxb~~<@L<U zfGBka`l%<bn>TqFjylJ6xcYW@7>|1W?>%-aCPF1g0snUIU~z&#f7oxnhErs}XV!@z z8aMXR9b#`?%dhCupSw)sWB&d7k)0xF)f|TPmB(U0BBOlp44^X?&0ZZce6t2f3*TYR z6nmC~sGZXVr;b)%MF1=cp1}Gji+HO*0_um0*cCWrWU?1)^nlWg<OS$QVVz+<F$$pV zHl+MJlAe(zh>{wguh2u0;QZOuz-+=%G*mC;-juzoEkjN!psu6uz)!9N6jYZR;IRj3 zIyEsqW@}U0>DgMC=|(?%a=|}$&4;zf`mIOHG}p7a5L^dcKrn&&jkTVWm{VkhR7Bc` zU0VTE`2L=a&8h;ZD8BaP$6TeTmrtmbOCGg<$7;C!%cc$|3`TwH_g9HGkh|G!@l<j% zEUGX=7gcSZ)Ew1>xN3<4$K6NAP6o}w=Z|}CEZFgUEsG}xlX%+(M(B7peQ%AlW+n#p zFu`h3T1<3KY`85hPc+0kr!>U9QYq2k^0~8Pq{R5d!Szq1gE%n$mP7jV7|iSHKblHH zt{IktWLeZwulN|7=A6`UPh5`}J9chE`%}fEe944+HHICh(4D0<uEQ|e{qvc<i@yf1 zta)1;ldFBJnC7TboRHD1?DO!!fBVw?80bv>>jzU|FkgcH^`<cx>57X+hZ4dAPd_}t zfRWC3Jh&c%F&q3NYl<pi!C+o(%Nplybz<D4{c#QEnn>0M4Cdj1@3BCuXe|b_Q2l-J zN@6fgFAH{HfEDmPh7ol!KvR2~6`}s-_yP5V^_X4VPs7&%acKIF)|hfH4F)s3se`n| zTI?DX-z)|r%l`Lwy9VR${r~tdG|Iyrpu+{d?RGduo6&KKG~r=VqYY~G7cQUPb)mKA zF$UzGs3TUPh!%GSu+%dZ-o<AMtREOLWHMkdj>F#{h1-^YJa3KC@NARHJ~-@N(ry=g zer)k$(g;P$$@Ek>5^Y8-nvpyLRtPL7g@Eucf@Erq4rOw}=O)@DseNy)U@-o+#Xmlv zM5lxOPaTsc&xk>4;tVA17)0MNbgJVX31q+uAd$#&EHe99r(j|RgIkCVm;y-ONJ@;o zAd>w?CW9)_bw|aUEv5w0veI~c6Ab44v+rwma?d|rOX9_Y3^D{H5Y7<~y6W-U#hflo zPqfbf02hM@L=#XbjDR9pe!>Kj8dgx6-?*#6#do438@KcKG7CaHdHwHfHw<fn$4%%| zvN#`q^xjUty+KT<<ojZ2QH90w*A;n?ro&12+Bio%4J(2IN7^ptTBl_L+%&n2LS0X1 zc6@^A{6>u9ECi;W@lz$u6+T{G6|`P>XmV#(p3?!rM9c;~MG-uLvLQPLih^1e%Q? z@<&Eo#em|4QP6M_hBPt;HA`*h@$tAU_AlGM)5{(hAz~V(MliF0RJdw4h9|0_!y?W# zy!>UDwm#6|2occV76zrY!P?(9r%bi{Su4VBD*VfaG+5MM0nS)gjva!nV`sst<UFVV zY(`?!q7KY{vrY0U!0ZXc=W0CkS|)W+Xp*<sgkRHpWf&{#`{^MdL)>kGRrx_La6fI4 zX(Y8)R2vv7#(EO*KmZL>9-RdB-&W)EN_-_8x3&wtG-jBsp^q3nWqala<|GD#x$x%4 zO<MRU`vV)j?o=^woh)djkJ@&gMLq*p@3l$3H`Gv|sP&W7v*q<#ovq+m<;nElfpQY{ z4e32H2!jFPlY;Ya+hA2d!*17pfX^<z9LPgsgdjq1j@*$uQa_QdTQ>hdhlKTJ@M9z? zJm_<f0Z4AiAWK{WOrHKDaEsmosc4x=I0GFi1~Jj7uk#106(iY<^Q!|@fp(1P#yC^8 zHju>X)=t;1n*hQ4k;wCR4#OXKK2gtyx!e(;;~ny>&@Zr-lUax8U2a}hD-?Fu6d=t< zfFB`(w7r&(QQX?LSu6NuaOe;ZW|*ZPO%Hxg$2~XS`i1$ivEvICG6{O>Cz{AjHUP${ zOT=ayrw(4tOGxl=fd0Dkvo-4@W$4A89|I`JP2tVm@JDkzCKY93pPw@!WJt3C$ya-T z2F%20hebJ%-|9hzA>ffM(I|zGZs*u(dNm4sAATcXI@vft_52n9TbIQT-Ps}59KZj_ zG0{XtAWHl)LKMyx91{beC>^6+?#Fzg9K4!=WvC_X_U2$wB)Eyj#JP3Xc}(M{?Le6S z2vBkgs@|1(%uI}`JM1kt0g?T;K(MjtF0`|ekyUvEW(>9j-5@XUEGi&y0xFUMNF{mU zJ8w)iW7}iP(y?+RpS4#l-uCLJUZ{L-o~Q#gyf)RNAUeyBy6bM+^$U?hrHBHpl?UQU z?QGUvLj<1b`3}YLEcN&BUWJe(BZ|1l<78ToTkDy}^Ud;|56`@TlnS>ngIl!)ThH79 zmY6=R<0<V2X<hD*@;=j<HUNaN1^m3da7`#@@g)Oz+EuA>_Ay~G#P4g(%Iyjhj6uj9 zxn)M#T4%)%Caa4P6x-WuwPkf#$>Gf^|Fsvmq0gd7D~((-yf}bcm|A5LVRY{7=<a!K ze>~wc(1tp5)GjAruU4O^=frxuPb-}tr5O8uMzjzw+r8F(WyN&zH5^HGGQHLwAXDir zP+(;_kaS1<HFZ3V!KE&<Z4`L1OXU*~kCE|9S1mq(0PNtyk%H!EM#mV~Z4)k8GQ9`^ zK$bd%Mdp@3Y;uc&*_+%J&#$n0J8Kh$J&5IakLx|EJ;M~k7!WFq0|G*PCguwuC}lr# zz<(AJEdcpU#LPm$T@+%}*DrK0WI(I@U_k>=BC~duxPkYph_qq3XMq^vBsfFKlt0J1 z6Sxx7dN1jBgYQ;t_gTRM$Qj0`Jb3g0h)V@uS5B@h1+l`(TvC~*{9bD)HM?LQ95KSR zsBv{YGE>{hjP=6vW#FUq7NBgS2_byiHi{Ls&1^g**##jobu%smZK|}o{I7_Yht-{4 zn5$gv#Zu>xHhaIk`2#;20$G>Sj|t0|etd|WOjZS4fSYAI@cyZ6#=}DfoB;=NTL$GS z`B7+FP55Bt%9&w=#bL@B&vlkXny;0qHv*8#?EIEGGmy$93*!US=q|^6gw(k3GCsJg zZN@aDSsiIKis(!=0`IfbZ4#jH*?3SOe-h$Mhb`b|ix+9LpqY}3CQ9BPMRvJ`qYi>3 zTHOKO#W@gd%ney%>jMZ>;;#<~f5QvJ&-iC~5USkVJCR1<j*HLMh&-ODlAjiX7V451 z+fjR4M46nb#Sdt$8Ag)8Wv@Gzbg{s78UdiCumu*-lj5<In2Djgo}SiEPup$MIMfNQ zYGv}43N@X4%BR8Solf+AQ7<q@>|RG4a^M_g^9IwK7%?gwjS^`&NQQL7v%-4bh;-$F z_Egj{wQ_x7wHoSunuIgGm$U(9`}$sx;##)Mwed^Duipg5Nkelwiq$=snH3GqkHGrf zH1hPr?s;!G*Xj}P3+__qacwFaxvfTsb~8yV8wkOP95+q8KL`03AAb~_VD$82!p@gE zgT|J~0RhyFMIdj=Yw5N}hc}%b=_o=&cb?Rp;zhRBlV{*yJk6dD^-Wu!5VTLz$qR;o z1U6x7N>o;c89tPlHJp;KSs^ZS02s;soan%;3KrN|a^<JB$}PT>0XP&jbVs7W(5=f% z1fy{`o$&Ci-f?7#weUi28b4%|-Q@AS!xdxyFS}~jwz?{d^k+iJUgy&z5~?NX>WR^? zr;dL>*y_~HDEAOGjmES_2ZZijeve3@D1_ped~}7UZOWO6aX|1Jfjis~FFXQTb%i|> z0h{=9T09?nnG+q{-Z{$mlnNdeK(${n_;1-gOgAHz!!wg(4^_&lN?ofKRN`p_Fvdig za;uEa+@Ut7{5$d-9?4@c-8*edoKqH7lQdVuE?ihTlOG#MFP_$U3Cx3rBXWPkUB7HG zuOC48nlkn3S1F9Y;gu?j61cfhfJ@G!rsoXk0#iHpI_~ri2EwdEGx(i!E}gb^Z+}jB z3N37QxAdbI_&kjzMZu$v^DVEcskx}j<HDr1)n;$PyG$LKu7;^3_a*74cp8O2@HDaB z>6FlyLgVkc+LBA%*&VMR-o8$Hg->M~?=0&yuzl-)T^*0*TR@zd*IJ*}>y6Najtbqo z!aYHE{Jsux)*}Jq=%Wty(8DkXad(Rj6I{*uwwh3{lWV21uej&GLi1;0yluZ^+c>QA znV5>*e@=n?Ey`fLH6qiN&Rbt=yRRx<X9&_#ay9uQOeD)P80vj%>@{fy<bC^^SIDH7 zLs@?{)bm{UgWwPyLUZQv8X|EfT$|Y)b1mBzTy3L3v$wnp{1LRUxYPgjtxY*;C8Ir% z!cRzYLwSGJ`2~w!B-lEMxxZ*Hf+oKgrwU!n68KC+0wXsHjdOn<s_h}QFD^Zm;>8T- z!57kb#9RBOCk}w1m(mLJuWwL4&;0hJFy5=ub*is7*8Tl;RLBSem;JNu<TBnko@fW+ zRr1lOswsn}BpI8mUyGcjNNt`r%WHPo=WfK}e8^|mEs636@$qU0X6J7mom`i-aN7LU zXzm&e#_5OZ4Kts7(HU5L=1|+aeLPLa#oo6`wI-7Y81HQrBvA^i;)$7x8z)q#vQQV4 z&IFNx5f&YTP<8Tb>&$NXJNe^y`0~-A#xl%+fk>5wdk6vLD@A>tZ&vQ^p}f-}l_h^0 zZ20ys#kNpl8U9d%Vk*WsqSyr8pmq|`)(%l36?((%O_WQ`0UDhLZ?)U=`cy8mJe2x6 z$N-Q&G{mC8W2}dQMP^2{tHHOETpbW0uJ|_`(%BtVr90mT);wAj-V61{r>3_%bgws@ zdGhuy!E7DWw?CH1(<(Kug9lSRHLY3C^vY<J3zWhVm1#s~HSsuP1wb0_I0{&tvoXrJ zP|0yM-wse*ACvORcA4=cQuAU^LTWoZNLe0%tT8SZj=lP|>H!4z7VJQDh*_{VKRaaG zKi2Kf!Wn~cY*^j7hFBqsJ9a#rN9|*`gOLM>OH_`b&Xm2b=>-@EtB3VD`PkA!KPx<Y zu4!q^hqR*4kQvf`YFz%~#$BI)IvczN4B6nDR^I>Wo07fEvmo+{+}&@9I?>=d5eyTy zxd@YnbH@SA*C6MQ*lh>(-gGQ|T%N7)^vk^3E<gT4QgY2RmFex8nDiO`_otR_{^I2s zKmp8dOLz@q{!!o(8iU*jF`6><hyYB+#$??L&-gIzGwbX5?Rl-kbUrtm-e~FPSYInB zgN>kryy!=`0oDe9suvZ1`F$7+sES-U)ot>N_X*E>bJae>=3hM$2q!=(9}FdL0|LI# zuyYsuLGcf;3;b3AaM_6b%BLgeqquNyr~!5P5x9ZE5?Z`Zlb2rzbH1TnFcg75;Qyi0 zgbx6*p=$2QL%-N@aL3mMnE0*!?Ga=J5}@5i9l|L8Z#Q}`W55~qE!h<*lnbnP{MT!G zAUsdIj(~dC6=akU#2?>b#d-19Zvh%~_tz0}7`<P{kk|bBS%uk5i`jMx%z%KX-B$Nt zP{ruWXZZD_OSBCnfWAef#HXh<AQa5cYr+Hv%dhtedR-9D2%<x@d0=n)$eX|TKd(q- z+5-jWb@ZaUJ~-FOK}N6;HqZPow=k(*gep<6UriK)xiig*y%006*mP%mfBt8*f(7_m zWd17@w)No2{1&311+hKT2GTj)mjYP2DoYOz{d`>)Q{(#mR?CsE*IPIU(SWVUCa@43 zj3)0l`Dd6ww+_9`;80|`_%vnt^|qfb#zbJUCkS9N;RFy^e^F-X;Xl9KUsNBeh%u<@ zP`NkOm6wWoQBddH9BaihapNsZEtin36%t%PdD>%>N^EB+#{a}H-~4ahP1uh&{}DHL z-2qcjc`v%;3noZhHxGoP@__2k?z<L41L~Py;>gE;a!ZcMeK$*}-QZXgY1LHXhm<}S zMRQ$q$Y?~qY7+=9(5GiTwiY7`d-zwM!5r)X;{Ws`5BEr|e$DIEEs^hmvI6<^+GP{8 zk&7jJHD$7t9<%Gl2JF45e1^sM|Jdi(l8|e?%`Q;xFr7y5mXOo10*Li!=ed7=KhUL8 z{mdCU#(CL32&l5aU^HZ>uY0HZH2(7?NbkU3*6olEAiS*}K;;9{BLm1Kxb(sBGob^h zLuB_G?$xF4^*;YxP0yRq`pLfh8!jrSY7|I7<`pZ8HbUlaS%pliuY_H;fV^bQuI^vo z#cmk5=BCEMc^`$Qj^1XKezJyA@c-gp!S|i9h%<8oKH-w67Vq#t9x`Jf_^ss8{f2tk z&P{ULqQLlAAo~r>HJZYl<aYFiQCk__8(SW58wQxxJRAA-wI!wfh69$qAVPR3Q>jho z>w7}02WBAa7eda#KCyU6Y12n34GLE1${5`L`Lbbt07*R37*GcLC1oUm0qPDakhV+? z9n^u+!?Nf>aLHsV{=Nq)aL|A$JOi5I+Ei>0crI>Lma735G&AH$irRWY=U>vI1=};j zgi(5*TRRE}>ICUGICOrxcW!_=6e1wJbF7U*4$Z1_U@JwLSdx@3lGT_`w|g`&GoD>3 za{lG5!@x=sK~73=6c!P<BTmp`IT6MPrrgw8O%DgOYGxowZw<yRt{j;-hzWZRmCZA) z>@I+mX%<WTGk>vtZ=9I!N|I;DgZd~MW<VNk-#u+=&<fcebk9IjwAJq1w3y$D_tHBE zDw-g9@$T6&Oliss&LgMANv!aX3;PVF)9?(;<vtVgJ_yHTi|>b@?d>mO^Y4I~2GqbC zVldrXzj0se*{el#SL52wlb*c`Z3dIJVNCvA_NOee@`vZYq7EZ?=2<L)sl1nu^-}{3 zkD^ro0XCQe<w#)4va0;@;vcyuqx=G!H{XRar~)S#ix4u5?Cg(QywAytF5)(0@(!-X zXwPvU)HY>h<fg$Q`S=zHPq+HHFbe!tqsXz_q!NIP6z@17!2a@H4$toZ){Yo4Ey;Fh zI$GE!pxD5Kzsh0<RF>BQAuTt`&H}tL4`_9%-q<IM-qpgBdKL5kIM?6v^al_i?W7=~ z;IjRD<bA0P*qhLMWnAC&8xAlwzt;=+8vz9E8Q!p5=AT8sutQa&FfLTTJLK3oKJB!# zPzh~&TMv>nFQD&<u7v<wrJWkR;)}0GnKnscH*<GeK*s*%^8Y$V(mO!72vl8^oxz(i z8VO#3&+DGZ7{4DbW>69fR5+VHFr9IRT>9GsN|aqX0J#eGhh*nkQsz!?GKg~_GEoYY z?dFj7SH1fRLoc8_=r0PD8Pa8002zWwQX-r%Dc%cTV#>n@m^2c7wnD1K`9mK6ys4cA zi@<9%r!4~m@m|!<Gaw@62qEzO!y{FrFrs{J)eTHrVvv^GwJno*aKtS<`yUj(>rUax zX*}jLiVtWg3zh`U$cPlEm_a;yejL`V`Z-W;yUx?Jg7QX&AF{6ZmZ#R^kj*=?GO(LB z0`k1TQMT`ogg=0AcWon3fvB~lS6Y7dkEwA$1Um}d9UM?H<OKHV|M^b?)pl9u`=PR7 z-Tzt|{-WJme)2AF!%zz4TGv$Vd#}87^zV;*cYoC=;P#YmFc?r!gGYGiS^Fa&*t`*) z0$jr+BKeMCp;BB2t`#a2+}$Rt_+`FbkBIwAVBcek!OtVsY8B<A>wm!S9fyVHCz_J3 zqRpz(mabC|D=V<rpaJ=tuj{zUU-C*jL$@B<ZzAp^M^Q)yERi;)`3=y22Jk1RQBv6V zCSQGF0~Qg$oIwgA8Z3xkmBBowIq;W{KpjLIe^BDzE@1bc5rYm`{uA5Z_U2+2hM7>( z7KP+8AT~uKgdUkqSLIb|OjY+Uf4T(Y14tzRLZB9Kg!{sHwJ5e)pai?+ZP)BFg5VIH z1K@OEbl=?{p!Ph9>;N@__rU+Uv5fLrfoeg4NaGi;jSr0yw$T;1^hR^48QNp-$VcdI zb4YgkHVk{+D%pV5qKY?#F9K~i(py;6oXU2B(A6v537)eYZ+VgA;V+-C;Qzu%XAwwV zoVD*N2M`F&&8eILXqc&tcy!PrTEO&#fW>{}Ev^j~bRZCNpeprK{{pz%r_dg&0Ux>Y zZN~0Zu^@h2)w-7`iBOAZC^kWBAsEETvNm8hTXe%b+26K&F%32b;1fWKrN9sL=2=xY z-E3n!nM`Ce0%{2dB1`K~4`CHSpY>qbjLU^l;QETa8c@PdSOC@43@!>x#QLcpTvuZ9 z#sXV#1j;`V<Tn$i3IyQ1R6AE-7*lIiHo4gYqgp@*rZg~4a?{sE|GHnctPUvwqk&mz z$4yUx5q$)R2G)UAg{{afTM_6N2=*j7K*O?dT>Z&8xtS@y)t+~t(K-S$l$(qnz<6?Z zr<dGb3NaO$5lq1S8*m24W`%{W&{MT{c20_igUVs2+bO+jfJvN#Gz~of|F1_xXXRx? zQxyPe3~kEKpB1c&wJhZMuV7$p?IjzYqMc>fg<|9BbM`1CA?_GFX^U=vo{`<LgyAO^ zJwsDyl$n{d!0E~^p2COB{<0O5KYSFjifomQF!scIz-9ojIiHp)3XcV51T=FeolHDF zuux3LfWgtKn!0~>{%!oHI!{OyskLIRl-p7^z_;b(w9}i2ZI#xx{9)5V*rN%1<K?~R z1Wm`DCCd~(yk`_Wbgg|;hNZ`c@2iOb9&0U7aNX01ul4OonEH^vv%|{k7Pun!HK^&J zw{_7ObpnsOr@;V(TYO<T3<qJHKJZb{VV}597PPWKKW-GD2}sMq!fylB-HFCx6X3`R z)OMcyh-{?D)5_Z6146X*tp)`U;&~CIFkvN;4vx#0`mCmw)9((1X{kPGLE}2Fbj}14 z1g2X<TxYvaRPaBXw!{Ik;g48^ZcCes8utbD3lMIFR4ZVo2m?ZeU{I80Pv1~6{0*0& z4Qikk_W3HS$Vgy7UsAH*YcqXPEF9zhhCoUL-Yskui1XM@f5v(Ebmp`ZbXXS6^aM|E z!VyMm7Y&5d6^9nnVr8zQkNo7aT3UC1Ur%GVFxtznh39vO*hWfr>{*ZYy=>S&E;j*+ zC)A<?4cll$ICH)+v)MbC*<UqQ^f1I?&|HLx`!&OSJp*~Drw>HW9H~M@QZ&@XzboYv zpojj)u>hAxmEIUgP-Zs2!yzdisdT7gAg}TJxsC{{6ZtKwytq>!mjBnI4-SdTH@v2! zHhn+mM5;#7!lV}+@DC$!Z==HDN3?hr^x+%+$OF(q2S*B^$$vW-MWFLjVh3L2$QrC3 znQ?s)HchDA2mj)(MB5`Hn4<)Kjrwo6E)em#17T*z1$J*=!0^nWLrgBwFS0j6NLg4m zH~Nbhr__@CQ?Q=kj&2MH0a5*1dIEs{ROM<PP~;Dp!y%pmYlU)<!{3wsq#faQ9avSc z%r<+QhYaK)Lr6z;5MKz}fdo6@?-Xkpb;GFq->)6klRB$^JAic{4usm$>6c*Ub|cV< z9>O|@IV4IVa*>7d89b70r9ZhFSeWon4RFL>et6)pPIzDiKiE4Dnt$h~(_pN0?X`92 zn=xm{waR<`cM;`=0R%Lf6FdzunJZEYroz@dhoc+*W)2D8H@OA<Qu^}ma9{wa$?E<I zq8PaV!qw?%Wf;kY#E<fnp0%fX7X9$RfW`l<@`HI^N=S!r?w_efvX6kzM|(s&fPg?^ zV59WJ`mHP!eta@wrw9#5V9+IhJ0widqPu|}D5i5!d+PhMl>@oJMwA+~fC03@>{DRC z%e5FJg0XXx{eG&yRDt@f({btG3BC>O15c2B5~9XI0+w5T5;1RJe4!Vr{om(p;2SXf zX@A};6gz-0({RebsVh{w!&zB_q4A&wbA`1*oNN0TbBOHx*3+tbG-C7GtPct9fMv+1 zSo)wx(voE)@trsc)m1g6IOKpq>~o_e?MKkVPSMLYHlOHxf`)|5L9?LB1ikQ!$A5S( zfohWNWe0h85Xpa(i0T@FmrAx!<M8o_3yDaIfBffyp5Y&>T7!eAJ5!hpN<+x+2c;|{ z*LL6G(cP%VAM|d>8Jq?SE$(}&Si9GPB4lTL7~4q^lbaOG7{TQvG0ej~B_^rC&)dr- zgpU<|8p0>!x~i$sIb_7ggUvBA|2_hQ<RgeOgr-wg*x;h2vERRZBNo`<W`PaQO)Z2S zPASo1YnEjAL~TI$lGmid`w0L5K|8#O9ByoT-4MnhyF<(=c_&u4XYUW!P`r)P-v#M- z)Vu}$WHbszNV9O}+FJGHYbR=Yi2CV`2<H>wF@l{s-GN@&7XU~ofkSCJib0bKN2J<g zJ*>*&ztw3P&!Iv*h@Vzple2aW)s1fc1^s+qeYMQ&c7t&>!U4<}VqvXFpF^5bWeFH< zsaSP}MudgTT+gDSk!SG)U-fPz*7a>|EC5#d$F@EMo;XVM(wo2+wbHkoj*evmkF<7D z<%u<R_q`A5OJ%0E>y2lUIz}=6p{PKO-^c7vj7{KpDDKBI+**m$i%nDGTZE+(Qdb~> z1?{o_#iciU=V^o1SVH9-08~Kq^Xl8)qEeC}@xILf5)z#hFE?Z}C7pIUX#74~fi5PU z<I1<cd<|?>QDAwrbf5Qa(ghQwVFs@6R#Pl^Q>~#BTnk_mZ?Af+*yZkK3`R*sQTDj@ zXIW>&`an4mxb)iI?0*9u_Kt3^6eCXFV%>ZU1r!V>2!bWL`GZC!t@M{Nc4dQFMha9J zDbPSerrKf2iIa(wNqsotq!?)RcxAs5{n%Gt+6B|UZxOhH1up&!B#6NN^mvKlKN56f zF#gbwV0Sd{I+Z!91hKRpdem&n5F6koPC!c#ML&>*FuiIM2Y@}@470yAt6pzSsAd_0 z>MSL!ysS#CmRQ6|)(1g80r7^uW&ANnq_l9GEr?MCi2065G%mr(2pajQbU;7nkUTEj zPbPqTWPR;xsT{Z1Ds-y)paa08DAyy`Bj2OgbE-$BC%X}UbrhnV4Mo^v;dVgdT)$tx za+KgB%S8|h5=@PCx`7C;l*S%tr*B${<q@p_;)~tg#~t8+hjn}P4$cRvYyomHZ2hiE zDIf;D1(3x4YRgV3-!h61SD@O#A|RlWNpSGyx9GPcjW48@A%wt;*jNzeDomxMXb~PD z>eSg+nm9m4oiM}~^XUa7V8WYnSL#o{#no0|IoP?U#^0p*(psvP5FfBx=`-d1OeRl0 znoOD0`?x|bs_e=UV2AW79ofhtCDn<Xd}wbMCV+6Q-Q-NU*PI9>7ja_Hzfb|5fileS z*jnPPG@hmpI*+&F&x0V9!O|rfZsAPRD3)Bl`H6SMc|LZ~9G@I#IZGtbh(bSHdIk|; z_|;|?fv(q2ZzTbejKHOsi`?nfS+!E``Kb>c-3XKfh2w?5)fvd9+=g@lWj|offxu0c zAoy2m2<YUZwu+Hk*9%H9kynQ@GF8AqmQD{Q2D}1s+HNZif=azs&UUPn_xv>AmVSu6 z)maP77rtX{%X&<b3&Zzc1ZTC4L!bJ^S?d-bJK;kUhhKv#6Z(0+iE`R8YF&Egcoor1 z0`Q@zUZTE%wAn^%6B8_py3E;oBt&RMM(bm?9a}PpEC%cYjWsVBM`ytdqX%GH6HYSt zPoMFFR&6!2i0?yZH3#i!XBYrpPp}7)OM;yY(UpyS;#+=!*=0<5VRxHgZq%N?d{&dP z6=5VT27DyDXxWbNxQkE%FCtXz)YokXX~e6l^}(NN@s&mu-W~$$&0ulS_1xD=xWI>$ zTi_nm-U6e`_7y9+ffiKz-okEOatW>)1@g}hbkX>PD{}p=0E*Nj()AtD_Z!%wfdSZp zjo9H`Xw~wP-e74|YPAa?W^S)~5SWuUpd~581Xg_gkd;y%)@P)xjq%S%n(6EKf^<rz z&LNG=f(~Pwbt#{EOV?+=?wkKSM5*qPB$|ZJcxF*Ff^@JAdvu-#H!lIFfHEu82W#(a zgF|bnR)49dA+aKrMwG>6ujVfNE<-_}f~X*gpMmY?(a;)Y^aqabp0PFSsF^om3k-V$ zk7&GaED7bEN19tOIE60m8dA=~V3Hp_90OVpU5al~d;}cU#sWH?`t((!?KAzWD;>c> zz|1R&60wU$iau75Fp3S|l~IPnd16`e15Bpnlpkr6&`Wsq=|gdkeQ6Xx^WCFDa6uw0 z$-xQ9o|9ln)rKg2MJ+V?Bz<TZiUPsT?pc;`Vxqqm*Cf&$OyvgO2#(Cf9ZY+b1>nGZ zGDCTG(u0)6Ev-+X1E?JBWmaB3S%X7^TG$G}@RT76PM$~I&&f8tshtcmTV8-`)&rJ` zCoK^7;zz)VIhRWhb`3W7@;Jm%2aruPY$<Xuk&vS8a51Sx9+8NGC?eXz_>`v{mBthi zyPkA33MMi^e>Lp^8aYAq+29Cd1>A)!pKcziu$-FWjS5infY&wAZ{==86}Cvf4-rF< zpfzQF!X%rq5GpNm_@KNw(mU|&tOp&Q^H*Q!%;UX+Zy3k$1Cmlqz%F%mkih!60cAFD zd?1w(493bTO^Zq%X)hr_b+ULHxq1`6Hs#X`*5-09($T?X_BNSmWZ@vWaXkZvEe<OE z_({pM=~Fem!E>~2{b~D5Ase$(SbXP9=*pRZ#d(OP;|_Mw5(x{mfZAFqIEiWJ_}y%7 zxs*I5d;CI4-#wbcES5I&J<aM2n&q_+Dq&)@N&I79_M%=sN59WpT$IG6tT_JLK)UH_ z1RxK7m;rZ!|6EA!yF|Q)$7oh1c@9bfi(0OHsdcxO<YcuK)qNt~10=UP$6yYx(>S2S z@BF!GUWhd5ql5di%eFu<zjQNw?kr5|N=nN~t{hRjyq)sVnD^fv#2Eu<L+upQE*F6K zcS+)Fn&ne1I*AOflYaAq>k$AO1A+N9{rQYh<_kpMJE8pZaGY^YI>$*|Dr~6(M8I)F z`$f?<sMppzfBRrYc}fP(bMM4kWYS7*RVG7st^1kAoJJTdg`RhQtIKZJ^n;?<nzh%Y z1vEhU+s)<79W#)JBof5Wlq@Nvu!#e)9{qeq;;k6}EkJ{-5556>3rB&`qeyv_Fy?zZ zu`ix2g$zfc5STNE$6c!9j_5SC7N*TQp`u8SB}G3^ux~px3-KN_jWp7_lNFi%ICC*! zlne@E#rvwYTrvZI2;_K*2)@uOGMgImKtf*Gg65E@Qm{5u)^3NQHBJvWTI`-kbIeU2 z<}G{IYnuUc*==!Q6n7M{u(rcF8mIfP1OyB_&A!!GaJKKEJP-vNNU%pBs}Kag*9baR z9cEeZ<DN7JY_lpur1<@f{fPZ%Cjw|~D#8{_Ov*i7B@P063QjUgW)e}1)GI*6!WjiI zyTY!Q^ba!TbR5)>&LH}cR{R#kS%N~@7To|c5{Y$D9JKx-i0IphHVo)(^jVnAKtJk& z-=7Bh-91W*gMI}+yS`99=i6^EvK)T|Tl9PXSIAN0`wycB<<|cA?e8I!z4h&P(!-Rx z?~niM+Ohu+U*`W9<+w*crk*ki040Y2Mf9syYQ+?^F1D7fHFHGrqre1OuVv6)9ki() z7~ui<iCe6Pe|HZnMRTbTdOAV+S~N1xEX*v<$XCjyBTE?4OS+V=jb4`Q44l|wk@riH zkUgy1Xe3mbZ_~jaIj;IAEq)Dt8F&_y7flJQV2f?5DlvIv2EaWuV+ZQB^&mOuFavL! zO6%n<_M;6Phq~tBsI!8mHM_Ez2(%i#cJRY^Xrz|7nb;*ey6ZjpP+^XM$9isv(T#2q zbiCwzKqa>SEd-xsfiectlZixQ^g#7{jl}W4j;Z+xLR2i8W86m%{@}-2Adxz2{RWiw zV#gra6?hQEwxT9UYCX$$2@NknKAf@uq_6<7l?Sfq&VeeF;Q`~PfxJ?v5?YyBT_M0| z2zTUtiRGt*z`_#%u2nG%G^z@8#Dz$$bbcje`_ZNN*Jnbtf|_xZbjtKmmLy2u2Y11? zpRB-h4i6LIOGE$>&kJ##>_$V|s0ooOL}^EEh&i}?`b6y@$`Rhy8J!^*8R&lzS%wzq zc~wNx>wJ)AhvGNJ0LfNiUMZB@pl+#<=j=yNOCdTYT^x>eZrC`o>js2{(%1ksDh3T3 zu(xy7Wys-yju12x5bhhmd-e?yN0{)9eYd+D%+TF@p^F(H_6SwWrLo@h*d(_KmA({g z0D;Fi5PhGm7+UGOG9fSS9HfE<;=Qw~j=*aYK(sCm0=uw+2{7VE;K&d_wz0*Kch@&2 z$V@sX#{1HA&9X^m4`|C6hs##IffE#7!+j9*i-coCDpGI+H7cRElKVz$>LKupdb2Jm z&^@uvp~vYt;6goVZUf~#%NfZ?0!PF~sumiP=HQ&nSytU?mp~Fn=%>I#7*l*QgKXSU zDhkQ|QX~*seewh}ZqE`QB}*&f49d-Au1nIS!lW)jTAc?jua8DhDgFBNK}#8$HTkOg zMW`7-zxye4KnA+%9~s2=>D_Ma=C^*h_28<5-%<<`<FgAf7S_+W6#voW;Ca-H@Be_3 z{;!6Gj!q$Jc4~GvQ7<$rDOeM%Wg>1?$k=tDI;#xm{p1<q0-(2bWZ7_Jyzl|3E~~zQ znT5$R$PSYYN0oa-&%B?zZ{<S@#Q5w(=;UNnijPlgng&^nB+>)fIz@80Un<P19}Vor zWsj1I>XwoVA5{ot5<q|00`c`LJ3<50e2#WsRTKNbycB2EMH40arrAw1I}?)GZ3YBc zPnDAMV!d7pP9cQQJ3|O-TBzgF13Fp#eKqWM<pjn8``+$PwQS<TQCSk=dShR`kRNl7 zlnZoSI!&!)0C~t?x*J?i=jBa2mOSWO;5``wZV@@zaWE`9`5^QB7+|gCl5<zyw2P^B zaO~{&G#*umi%=5p2&ziGW3n?soYNAgHgP=DY!y)P+^I)4fhYAEFAjuye`<E+jUezv zH5`n}+81?aMiyUa#p(?>Tn&)y{BnAv$74H(q<TdZbldGh$I4I`-nED#wX}Z8)l{~_ zEXfzXz-bqQ5M<;mg$7N`8y_AQ+3^^}X{K+O?B}fHKShUQOIN-85zQSSVL+ivpWY3y zyx>(=`qcFqxRRaJYEAu6b*PHaLJjLM>6w09yCqRw`Ar97IVcMd_KT)N#^i&IVoQhj zZ_p#1QM<@avTVz#FwJ@Natelrdi#d7Z<j#Vy|6|Av58ZFmH@G@;xI^x-!VEwRg<`M zk5@r+C@UPl6mMk^MEA<mZhrnblUn}mackN3{tT{#a0B}%1pIOR<2{f%*cagfMx<c; zX#~hgd4$wZdk-)PE5PaX$k5d<-eS|$y!}q!f{LDIzIDGg-7p`pqj5gB3qz`38Wue{ zp*Xo7&QG98$9KC~r*Xj0HyZTzF{bNIw0r!)#B=NsSqKfi@k>p3Jd)PTR+}hz^h|B0 zl{MZvuEp-Y_LfSV^7s;5T_ggGeWkj6{TAMsOf2%HwUIRfO9NPTa)!csgz<(r-M~t+ zV-O>aQU2<6wlA)+W1>y{mR>xft>O=uz4;zDVIQl@j%!2Xr<C(!sn+Solga+N{Z>!o zf!6O*>r^s#7m+iwQZI<#AuTYQU&+T2*KhAO=P@ifnnK=8mzQ;Z9`<y>XpbyW1@D~E zuqlyKz*4FuM5Nleki2{6P@;2cbvbbTq7g3esTO5uO9LP>IuUZFdd3Etzmp8Cvz|>) zDnZ4%^SlY+YV8VWLY>2@r3@($_BXaX5d}`YSBPdD=ZT~5E(VtOq4~cR>G!AzsR<c3 z#K8g;6N(^2kG%`6C+%r*jOS?+X<IPpQSM+qXu_4Wws!g}_gLZa++6$n%A?#UYBo`_ zie}BUM<<nqPn!$E$u<LFckB4_7J41lU`@}*9amb_(>+WbVlF__F~`(netOVN|A^Y{ zGN+;2N4t%~uQTuA)ka+k$omGrv|6%jGVBt*mA=`qbv|>NFZrboNmGNNK$fPxntB*y z4V?41F1KySjF;X*ZG)zexsp6<uP`?RmG>fvDjAG$<JHy}x$#)Ohp+RGDefTZas?D- zvqi`NlvwzN!Q}q2w`a3@M0KX|FUhhr(QPeCtrxS*xXG`yH>3?lw3P~KP4iwKkF6I` z-0CY83X!U;P;tJipl`CfAa8De7$lr|U6*Eyu9pYON$#v6Fxjj51mDHp9C<{8El>dx z{kER-g7?T8B-%~9vFf7gTMkwxpBIanQ=r8P?W`47&1c}*a39F3T^~|uPO6`FQEhgW zJ|02d%o69v5*pNcN@`*-^`dt9yvti+Eqh|4%A30a^I^lLX9_C!Gq-pJyU+%`X@8PA zr<B}xi<@+eer`Oc=qXQU$1#$&&h%C+{n(;MtA;$w^2I$1-Z7IF^&{v#%7!=>o2Rl7 zb!)R4+PIc2xsNei$fFB=;1+Yi>l3P(5LF7De5i+WvJR>NzR3IW0UN1gttVRV`Vt>J zs$^gfC5h7BJwcP8M6|odJFgv?%yC5D9&v#f)2`3`-geiWEmxN=#uVuUPmEW>0Xd*k zsUcI~nR?~&83h>(UmCNp?>_p<jQA}5_>p}TA?*f|%d#~)()ZaaZV4=axwm)xYBf9n z-PIHhO48n+DjDbRxzGLCN4s_1KCvB};HcUI!kyI4bP|xj>-6M}Kn7OimyJ;kWsh_2 zeF-?ez_ks$J6b(&lDX-$A{AuXthcj8i*|q<uigC%kYbmR?Ap>FOkSQX?O$#n|E{CJ zPVE-T>TRAkbuD;QhbM`nrn``4fA!J`{^<RHAX#Doe)%+Rf7Bg@atl_PE6n^bIYE00 z8WM`NP9jtH;2(<LVR@T28ok!F815Dc{@8Qw#?A)b0v13|f(q$;SWX1a)0lXSTm0z$ zi53PGC<W}iCdTIJWJoU1I(niyaXU)6b_`I<tx&@aosneL+L*mhoP%j>M^^kjagNy) z;+lB(uj8?7pZe=YvuveoL`K7Hv-atq<nNe(d7P&eTt0iLVnXZTwCJ`Aoh)X6S1Fy3 za&rItBgazL#zGoWSrz-f^%b6L+=UYxWLTmW$#$fT@hc>(%yeE6P%^I3SGb)vD3DMG zXf~U#5G__tavZg4+4F>Laclx@jC^c`)8D3qxIbfUxP-NBe5$#=oY23+rXfdHHz<%H z2<*M3;v>(kzIdg{-v-Gn$iF9sw6_EbYdEk|l@S%w%re#|@Ju%~R@F@<C7NzHrP=&t z56D~z<gn>#Cq#T&O1YR0b>WMOqT!RHhDDC)P;q+QsJ<d_R=vi<=}^YSm<)NRbfBV@ zk3f)BDzOVaAU3aDRFOz(@%c^IM22lYEB#b4+zh<RkDcm_3C1ZUQV9Xtq;8r(wQ_sF zG;%{^XdFouXuzp5V~*BKEBMIQ-0I|u{e->q2gXh}j7V+?R8zdP<0jdM^iGp-n5vv+ zRHHM$GPz_mk<3XVZn~OEAF_K{T3V{G$yITbE-1D;l{qm8K%+Xz8Kws=6XWj6ave;| z8-8DqXJLD()A178+g(G0=%k#Ohhv&BX>*@o)aBc5+i<YUP%ZzKVOAHc*l9zSW{c*= z!k@mvTP`8;BzNT<^oLwP5WLIS*;+t*N?JH^FWFw>Vq)+~x(L2vkwi50C2~Y5S(={~ z+vdLjP*-<tBDFcGOlv4LO=A(Jq0!A-woS)$ZaTzFuaf2!7R*ev-dU5ta-Y4j?UXFn zeYRXC-n%wn9_I6SGOUclx>F}9|4LOi5FTs^nsobEn+u!7@pGAM-Yoq4=(#fboY+d# z%6Hv2(~nOx#nNI~(#OPv_gt;+dti$B3`xLNNXA{+BcQb~b#J?7;L~;knYiGZk_McV zlzV$5BDgewjO26I2J@IbZ@A}MvDv0L8S7ge{a5Fb%3#VBxLmg6I0Q>pE>Aj;9Tg-K zs}r^hPh_+&L;ao8vV}}mV)5n^)!tpnw#3A%-R2bpoP6^cj_XwxDMP1cCHG@=)e~nn zbIA?1Ebl1@NoEr?nER?yHkIM|bxi&+Te@y`htGkwQ>SZH--m307hisI$&t00*Slpw z__JXWql%2jc!_TGfY3r&qF0!8yk|x*SHjw2Sz=rI(xFpd7IbqL9(TnW<QB&#OEhRH z_NBn7W(!ARv;BQrf)6?p6TxK@K|0ckRrfz-q@2_Wilm_yPLB073n~|6e$RVXJ!cP% zknieJf6vK!f#KH$n{`a@v+=Qb@_cOcdEpY0B`~i&l+w=i)r-mw=ynBm54Q%ndK%Nk zS#M}x-U^7ep+u}XpQ%j2r^_kE=`>!eUm_|yPj(A5s<h2#dX?eVc)YsH<)%M(uqB^O zTMn?SQSB+FAn|TrPwWotQQG#_At(5d{JH%tOJhPAMVV~Q1^hHktv!=4s9kXTspsu> zIl3~ur=Gcf{6|MXG$sMx(!`kzCR=*pBjQGas&Jof<EPHxj=y<JdC{%o!e8-h`7E#b zXgdUMC+<4Fbd9Zrw9-Ar{A}C-;YV>S;pW|Y>zp=XSzdh<9&~)@Rb#zm*&m8nR^bAM z4f#`)c^hy#JxH_9<ttC)1{s<9j?p&8r;D~UE(P8`D==l5CST~OLoCmi;=9u1`)KgC zjM+vkcZ(OC3Q>2?Hwhvg?mXb(^u(9&c(X-o&wXk0eaIQl)7Y_`;wsfUUBcMx!{ch# z=(vmKkno;-vZ7JZiR%!CkG1(e_R$*kG8&&fsvq7!C$&6#-^XF6pJwwD9Kg^ds4Sk~ zm-TD&8zlIMj#<WJ@eoD#`b{C3!!wyMQ6?0JR>B4GhWp$OE#ONd(zEN#nL<U8Q7l>s zO<-h-!Q=|sbsy=m(YSrjx>Z}F#_YYii?ysy_NE{~YeSuncxq+R+a+l4Pue)y$?7Df z^y&Gfo|UD0N%L&W)e;^5#9)14PwO)@mP}rqX_v0CiLe-3Ew??3?v&uy=v2=f^eX7% zv(Aq@Vx>8KqxE(_u@`c0s|9_A<%~Whq9jwZ=SMN&VH-&n=8Psi2+Bdp#Ick<yXfpj zvCkZ_o{tlj@@egCf{tIOE3Fees5bYs)j~IWukhB4xs>+RXX_Y_K=B!3$Jm||N<$-e zyFNO*61tWlaS?As_+dt^Pc%A}kg+Un>T)hbg{o*VYc_UmDUeco<~9TphFu%-RYJLa zrJ~yPYHyH_XWlHlUg0b}d({P}l$p_I&?C`Ok;D;)Dt5c)9n14am{UDB*%(|IOed@D zWbfXWZ%b-!pDu#IWEutG{OooOoJws-z&fhh1R&o>_3idZ>rt+Ka)rzN{pV}dDMLEt zOS9!y<vPL<u`9b%b}&9(E4%*g+Ea9GSwjcHSiOl?xdzocN)9DkM%u<PxOk79Zhewz zys8;JptV%7a&jsEHRtNQycd?ninC)uXZ)d$Nv+3w3kBDTdUBq*v(al8$)=@Yr+QVi z<<;u)A%ilDx#0X`2DOjKl4z=2v&6Dji-Cs9m>88*o0T?qJ-BbbRTRzBR`>L2VHQbn zAbEbSCLskH?50zkL8pt=9Zr|4o#Tm6=usnFt-*xL-p&D4-69+>tvr*Jgr(O<VVEZi zxAL&2Ro(GPy+6D9QO;2nLE$~)4qMDhZ#zHeyqIMi%020&&spwwF3C5M^4wo5Rb{oy zAD0%aKgB^U+FOw{b-cD0l%)d2Vp^~X%fh`jq4-N#eOgP84i%TlL*N{=d>_KW$Vohm zUq&<6RXdKly!+UBs;uziyN5&dABvSn16?`<NN%lODdK*Q#QR5nZ*k@A7+2g2C9FuZ zUEl??-n|Cz->rvbe|8-CD`OPyvU>k6l}tQ*#a&}p5|?TlliJ+MH;i5Zi2-4DT@J2q z5%4t|Q(Rl*vZ_ModVRiGJ#q1Pz^4bV?uMZa^c`8ne2EUOc<b6}MfpRdXiE77<$wMY zlk}%WY%|2JM|!tsRaX}OMB?nkfO;zg03cn;Yko%$qyPmff7w2_nt8|P@=R-}y=Xz# zWKZO}`O&3Lhvww#9>5(7#D5h&_x##`#uzOp_8mthKcT7E$%oz(ICCmMahy1hE(?t_ z0TJjph+EXJF88lS0s9MZwaNyVi$`NSR9Xfv|L8|g*)HulGzHCa5x?belgabL4KL>M z00;J>1&YbxZ{O_)Sj)G5^@n}ScON|-?|gJ>o7Y$SOwOr!(e;!GTIhHegdp4yjbcG2 zNDVe%q^bV?F|uQM*;D5yk{hua*Af}MD}X<Fj{)lw8~6<Z4x_ZEFU$ggF$T%ALYJ(A zg6+W{6xB2YwWi^p9rQ+O5{RcvE=I;yFrm=MKLiA|!zeuXWCn-Ondu{dZ9)(UcHpuB zKtN)9(~l1$&~fLMCqQ8yffD-&_}tONcMXHVMz5`C4Pc&Kl`$a28fOo1j~HUkFYZK| zlnC;l86^Ole?1QAI(dL9@Z?Y<U>^<u$AeaK|6WZ*)`jtauDO;aUjQ+ygkGR7P%JQJ zUa&o$dOAcek!(ki4_HEQEm^XFAI(xysP&L1*-QDo_aa0duJNsanWbktkhMqwNSbVn z@6DHNd+H6tOr0dD!7EG?WEC^8?iqpZa#AmLaR)+zW`ulJLMvvp-<+BtJ*Zzv_89{7 zB4lBC%Fm&w3j9S(VI)?#v_CntUa(+!6+qK2vrj-39f`KdIt<*Fd_p<Y3?r!Q4w388 z#ASjaA!s(D#Crt}^WU^$mH@(htGF-j0=eJM&lx&#(J<OcO<+Y*G(A(}pbneY-yyZ~ znPCP111dtwYK5j90a+RQL0aJ^)pS?~TD42vF12TzJ_?w<W_F$|=;)qAc5~f>3aD3r zTW6@~I$^_k47#|Jj_%NI=srIPO^%|`Nu=0t#Qt4pg)vfUnSo-Vb4WhBgOmW?S)kXu z9yfN!x#^3`W7JQVtF1%rWSB-Y5AmpPaolVyk$hm(z{hu|3575amt_z-_Ej8E0cX^^ zAv^@Wi=Mb|3l+{xY`s;fW#<_qc2`wVkaL_UJUABn>HUtd9o~>Ebo<tkt|+^rk_OX6 z*-FjP&^)6^8m7%bu@w!@CEX`G1%|Z(r|2an&Vqf7m_%$`yxuw&RzVWDTT-Ma;k_S) z%3TOLd3m>S(c#K(reFqZc?q$BMMn6PyHQUO(Nu8TgoD#B7XdFoWLha@u1&ye)7AqU zMp$Rs4IH|t)d7#-G8}(+(mXSeO}EWG<E0U_pR`CvG?LQWH3aRLgv0h5Y8{FNvSJjd zsJ7VV)r%lJ><M8XY8*|LTmtw>b-!UZ_{dF)Y+$!6$ZX9yU_IZK%X|w>rcgiDpMweY z=h$rOOTtPJDL#-rd^ka|1y>J~H0HQ%<;J)B+0JQXqiLgw(WXleY+;T}?luu2K-qP( z3oSmQ`0&&zrQ6M+R(@N27`i#T^R3QL-M$39>YhrC-ClfM2Pm#9NOVmZB&Kb5r9afV zJp+)L$*f1svP^$=`zqL_6t#e0Q&E`vq2oUCi(g>~w}|U<VGkN_stKmp4!#GLL~g$v zKuvZ@%ea-<eeAy}luYe!Bex#Tg(cnNp8(usx2UK)dBcsz#~)7ONjqVbp?7t5`<e*N zol7*5ET?@Sl(|Xi3e1COXB6@b!>EqFfzgW2%BBVN+JI{1AQH{ok>wZLOgcyJ2NGOr zi!D7+dk%)q^(LOAa3*~0)H$1GMx1h)Z1hw(LnxwAVaWw`gC_D!HmF4oE$B%3FZ53N zS|Hv@R8tageIq{su1@v=)5bTR^v!Nf<F36;lA<-^cN(fH8jfG@7*y_&1x$zZTc&(T z2|B_2KT;a!R`@46biqJKV;HfG-WKeF%;+h~#Y1-kWQBJD6QuCtRLy{D>yXS$>#k@> zyT}mO>^QHs8pzTmn=%M3FN3oCdCt^CYAs>ojL*W!4^PrPOw2h|uCoPEMC9n+!+2s; zp<*Zd;ltN-k}}xNX=w~y?5sh%x*#Ez&6b6D-IE5t#-tUK*|ASk{UKpDNFV3k9-#OQ zCvqe$djBDf0+<_Aep8Aw)qSybtu1>UmoAj5h0Vt8J9J3wYojywq?&bS$I=n&RvxIr z+A{QdjFo^f>GDQfri3G7&Q9TSv1bI{)MyHS(vRwJqOltB@T2MD<qu|~fV8ew%K0d9 z;N)?o-$^trZt4tsCQJA0KHd<2cm%q=d4q1OeU`n=J|=ZNT1&X<nHM*=^;p%p#BvAI zFDgfKlAE^#aT7DCo`w-S^%S<2fKtZ|-)FxMR&a9Ih;tI(#VQ<6yrTxTutGaW6F&s` z?T14q&kv0poxSs<<9DOo&tEKvpj2;E&n^$NzdEt>_}bF&Gn&(9+MVwf-dx)&OLMYj zJa^pr?jGZ-LUv3|{d?P)1dXnu&>;&`k#H8DN@xNtRCD$XaM_l|o@3lSH}@n{w*d6g z{tlD~<m4n}W<7=P1mC_%6y8F^eq6ZKFy+G(P)uH|-Kuejxg2YY=@^3kVs|aK#zps+ z+bue4X=vL%ruQA;qT@<CsY{}5Ud(u+e>q{84FxYgHhl*)z(FC>@VNr>lI)<RF%^|F zHwdkvOFfJ}FccRF=RprB#J&rDXgZY1_ONY<_g>%7<+D8PNSK+NsAzbUg%rNA#w63? zOJkw6x2|Z6l2ejf3IR7Jp=NBHKAn`jtSA{Yds@<c3-7KvX7BKPWxBw}wQRaVpM}Pp zQRA6RBKB^#pM$}tX0mPbTt>VC5_06S?3CcU=V@Wp<>|wxpB3DroHEzW_%g9lZO(_= zK`n@0zgG6!{w>crl9>?3={s-Q<0a;JTJc$sc5TI-sJou>#H*YM!^_&EGIaQ81yGdi z=ROSPU7{UdVD+Kdj-{i-53EXtDK}^AoTj73z@x9DZcU=67I6V8xtr*<1vJZ+e7aID z3~9)g?3$>;>mMD@NpiKgZh*HY?Lq;uZnd62F~_4_lM+0srN$8CnCRte1VO+}yx8(- zRn8NAnZn@elZ`pG<|Q9&6gpAWQOiXYzUXz(VD@ymNQ=fH`f_`48bW>A+&QUDR-#y8 z*^JuPu(j;2mgy*jpPI%~w+hU^%~z3?G-_?kI%yqrj<`9^lu;`R6v}=4g7S!UNt3C; z=jm{1lPM?r@3K84Eo{NB5vN@S#b|rbd=Cm6PcfzCZX;{Uloe|6)!pvy@?LT2_xSQf zGl&zm9ML1K77RUtOF<SMUJr>wM?K45d|}4&v_X^25!n>-A<~K==uRy2=YQ%>ZDqtM zv5NETP?5WAm+lpqUYkQ+)6}23R1sQ~y2AgiNaovHX+5v9ROab6CPpe*Yxvq_V*k7{ z?E=7etB`$64&A+@vok4_Rny!#b|229W<cmk$JzISMzIbMN?{A_yn4OH_Ga*!_NC-a z*f&n}d}Ad{E3D6J#dto8$JPtW`^A*SwfuGOT!v)HmsQ!0ZBeaUl=<0pwxewV(F&3W zjy%VC?lz}+Ab7A6%nU}L*9|g8)@iN%Hm{@=+a5;Us8;M%)0#WGY086_jZb4v=2Y@S zr8&F%!viyAGYxs=@BUABR~`-Z{`b|r)Rl>Q<En9SyLBsW3o+wnmn7L@l!^%1jZv1u z7~-NXQjs-8!WbH|X03>_jBTtVLn@3l!;IbY{!aJzJLmc9Ip;agInQ~X{w#fczMt=B zc`vW!rwNiRcuhGc|HaMTL6*OaVpLdL>d{AW++$q<9rTNoRoUFHR+A}xbqauPI=z5| zX-D^ErXH(kOPaZTkX-6mF^rphSRQaZV8Z~JbSN;?**NYBPo=l#xnv&0&+Sp~DTsps zySuFbF;Dsr)pJf6vuAD>J6TtbXGFNonRJ%!3LUyzCl|4G*N0@|>TX54!z~T-4rQ4f zbIoIy%e<K8^Be;)WytS;(%!Zh901_1sr!%jR>!BB&+RDx_}h{}4R;EO_riC?*WW*$ zJgV9|-1T<(!q|iQVTG>c^J?OY`y%T-PxmF4WTv~r<<lfetWe*kXN$b{nRy?Ymn4FD z6}iGIz#qX}%oRV?x1DnO6h@Jfj`NB>rbd0Dw<QLB%3D|wC3!IM<THb20+j0TSI<XF zU<_n0cHH;5TPJZq$tf-qh{UBgpM}u@K4mZ0n}E37Spp74C#vgmT$l_>VlXDecyVWk zNE$0DBkUUHqwInpED6RZh#1rGLTN}4-gBe4s(@=CTd{2rNJX~cv%4@`UCU2n?uT=W zVjiNO)U`vk%$r#R8fNsNB15%Zi+-V@6MhY_mM~rg8>hMN=-kH>Y{wN^OnkiloQzA3 zxk$dpr6`7rK`(p6qZTR*IMfEKJ130eamE&9NS;-_u0n1ssM&|oI*i^hW#AF0`@l_8 zU!X}$bE!kQfFupDs{7=Uql>c7Ys-8EjqBe_Z(FZMOGWf3eBeH+Qp1Jrgnd!puGM%i z_$QQf{<<zhx0)r|ba1Fy<j^1D(2(U%*->mwF@H+)7To%~d?uVz#_F|T(F&UavqqUQ z$(sz_P=}9oJMFo(GOa{Sw1Cy9=9dOe%P&$x&cZ46IvcrMkc;~6e!`eR?_T6;=|Bv- z_>P;77NK3lSUFl8$cAKkiuBb?>E)CL6U<K(t$Czi*=E1X%>Hr>`k|OqXtViKieF0T zLkUIwj1l{iU-;widTkbc6Zxx<PM%34kIc|-<#8dn%m#ly;Jy5*a?Da1^$abL_Ru{! z=j%o81Kd-}o8JN)7SEd2-O>}ym{?a7vO8mgpReAh?-FD*HJt<JRWya$?MScg`KhkU zjG<7tS3NPfz@r@ZA<(QdfTYJof&yraj0E|4JCC2jGZ7F=sglW!V;|08o9Pwg_=GRc zDJ9hXBym&dwXCk?m^_^-Mh`Ep?-u~!ve#;Z(#3(Y3FgL>`=ym91wywD#0_98;+@aT zCeEy$9ZDsi+@^Q)F<6yWNI&sA?VPgU$KN{Q8T1G6K@p)w&Qi}yqg5_KyAQ$W3Ca8p zZARBQ8GALR>>T~20d<mBUxGX1R}V<~%4V~BksO6HtIvzxU<0lExedto51o@U2WW{b zDdb~h@MtjCbWm9?B4)yIW(#ZecXzd}Ewe*TynJ6w3=O`#VXUz(+HzgrCeg16R2P(> z!-b}G#~hd{i8-5v&lozcu7Oh?S)q)mU*BHW**PzIIQ(|-wUxCAB+F|C-e2|Ke!qo+ zkHhzjKC26?AF|d@jg+_wUMg{$j(9Jc!FuU&Ys}KVQqA)Ot=MQFa6z)7FPyLUjiymL zOiD67`dV+}%X^hC9urD7-j5Z-Nt~j)kQlRhG$kh`<e~k*0di*LP9%B1bASh<5*1zC zZ)z-uar)z$6VMu_-)CAC@qOHP-uM*qx|%jTh?b^SN5BLENmTJl4|AZ)HK5Rn+f(^P z!~w?qpj!M0@}s}1^RoPN9*U1M!uIy8U&I*fNB$ldG1C7>Kwsa63sdtyhcJ^b1~CN% z;?f!R`|PwtuEtV()%pA|^4b@RFSP_Sd8+w__2CHh&CMY{Miq`7&{c39$M)`>aoAXs z4mpC*C?G{3@;culyCkq~a_ifKfI^=;9R0AOYS9PP#fk9Yq5k5&527RREdgOETeK41 zeJFrh>RZ&r;OL5xX-7gW7ZNFE`R*>&){TmUuVnDKuq+5g9{%bWvI>HBk2A{B$fhL? z4pCh$3GORj4`z*;Uol{kzH521x31;BP2F^Db>Mn3M^ZWIfMIenYqrXK?%CzVq^tqP z>_&y*5SFk;WjQd;KI?Bh(gHw%;Cw;8hCBdoEsXa!)1R|V^88yJWeIDuM{rcFeF`4! zBCFb<UChTfcN;0tJqe0JEA&*Y8@1X-waxbUF}+xw-9!aaMxqL#CUJ8#dQWr9rJ|O1 z9d-ucROQ49X-olXE!4`Td!wCxD?1JqZcSaYNchTB8aj?wCpd=h5D>8zob@_txTt+M z%rH68D5Vzr-8NzQr@GM?CQ;#aoJnn}?lvK`t#aUp){XH~+OFc3zGZQ0H*2mu&5}I5 z-YVOTWvC}nQwxzXf=ek<=i1Wg5wR$tc(kW|Fh>u^Ze9ApVQ7s$@?~(D-TL??`|q=Q z)Gp7Ea3O_7G*)lV?w?&u>`1n+()S+DCTd{%KJtCMHvHsu*4YxKUq|iNT9>TzlURqo zf(H%_Eth24Qpioh3JwYBb*B^B7~XQy^!)hwLEQGw>%y!gbZx5kqV~gjt3r%R&v8Ir z3zo_v<BFB!jqCQMs#}HRjTwI(RI|5wp5y6z=%Py@t1bOSt+C{;mU=yA()H1U35Co^ zW*$+&CL?j-!!-r(6=4U?AeaJ^IFC<c-DGZL&4e%FuwLRWCdOHFsR1iDU%k?L9k=b= z_`^Um)8#-y;;~wmEh$01sBhUsM?<PZSjV9?)voTG7;w5i_2wF+aO$Ydtl0S~+!-Bi z;srwc=7GUgvuY5shE>MTTV-31`!;cP>I7L#n)OYL=h%AByXU95v!nn+JuSzq<D`%K z+3R%Yw_)#6HtK}BK6bU4Vm-v&3Q^qIpD_bv?yEX;D855xcQs_mYYt*vxrP=B0GZA3 zOh3C6@>9wmxD@SO&41}J2iRm<^WEkppZQPL@$0@UPvb3O{7<@bYc1&C71MMVcb`NS zo@U}VF5z}mB^vwd<c4!dn9vcIGihp$&zF7XV`HOcpUDUs)uv%vcSch_w<W6ddM&+} z^OyZS{^k(nN^xs)nbRKPE<V918g(T4tfJ*)kXA?pjmjpe3A2bfQuAb5e81@WG<~8g zB5ZeWt(req&v!_s*mQEe;!Bila@dbl4yTg0buaMh0E6F#6ZBSN(`|@2iD!7MSxqZD zto?OYCu%IFHZAEz`Uf2ozFes^8@~2z>&;jcBh=Dmy`tJXPy@dzrRKklxgG4UuD*Vg zaTRR#CfEFiB&@wi-EzbBKd8n;#9^kxrT?ap_vuDqy=~<lm-_|QEON5^vvS1`sc9hJ zD3*tU)U2OK^@LUS0@W~EW6ppr7>t+e4fy1>Ni&O@d>-+pyCB<?D^+cZbrZi~^0eA7 zgv=eQzZ(-w5YVK{1nmg7%fC{VD%o&h?8FE5t&>03^~XV7Uvg-NS7#aX?Qd&l<PBO@ z`d=7OM?rokc&NaqsK>Ys(y^kwx60!7{CVpR{!rQp*U~PlGySo5nIy;AgSj@+4APLg z{ZpU4@m$wl%%e?iobPDh`Br0%BRgv(`AjZwpRRD$F0-o#bkrssTOOZht?nN)_1f9{ z(sK5MOG{tuSjx%6gx(zIvJ+e*<WxO}<`wpT%o+-H`Sn6{ChbavyP%q5+t6=O^W?w% zG$(4(ibz+&542v+bfX{rG;fu!T<UnSS|BQfuwB#4d!n;7)w+Af^||{toHb?qim*&u zfO_-7p5(Ayvt3F+RyGe<m8_g@-1Iwwv>}2lc@)-DeJZmxgj_g>(O7qfa2@(wghfTR z<Bg7jNHoU><|oUo{pdo*NLcq(@JWdrw%96yL5w=Mi}dKT%04XHkVa{T76V@z<EP)J zmY01imlm?9ri*yoXv*c+N<2ziKM%frCr3*=Y+xu9ZR_24=Yhja)v`lXqd)DlX-)Ec zH9nKjn{L-6Fn#ja`P^=~64JUA-znTAHjS~$VGSh-s+Ktz`-xR^r%rgba+${ZzBHNo z4F7}XB=!-7tHV!*Es(_$)WW;$e`DpBx%T;|V_Z8rIR$I(uy0UbEGSO58fLQ_vLC1y z9$Fw)-w;#qnJOP<Y!wkhpi#FOl_f68RspL6(vRGxQx{|_8gpjS2cNled0z?bu$1qD z;kjTDkd1*jIY5i&&XbXSrxTh87fMidb`1e`;aUdW=V~w!!NKL2&VxUPcCLtP78kGN zMNOAnsnxPm@TdL42vO@k;qD5e6WRSzIjp-$M4AkJzF{*riL@^8J(CAr2eVp;twpq? zdt9#$!399>eNs3brMTBPtlaP@F3SkB%g&E#jOxk}SVh_@OFew2ZqH1Ttr)PM<%=BJ z^nBeJNjlscGxV3PO>CpRaY?h?rM;@ixZnM=ww>N-@Vk`2#qTxK*=+zEq1dR=WmAXN zL_2?@XD;x;O&6zc8bqg72NQN`)+DRktbu#DLXC9LXl15%9^b?s=sC<JDfLH6skj%h z4fn>E<sKhIc25u(@xezw6*<GsTJ_JBzcp1(n15lTUP#oyS4_-%m$jl_jGh~!oNpx3 zpV-W`Zh3cex^~KGh`d}gZKz@QB`<cYn0QE|<*~DRj>WOhzS$!BB`i$qod-{Y2{0+Z zq~tY~Mdb0dPLAOlU1~#K)H1WEkIQBauDge>kK(Wnjp=5A*$%u%&-Oldjb<2G-&DZW zq$SNijuW<L6;EVcsoa^ILJ%yW=U!=4#P|HR6o)+d$u(XY>Vvd!i~w8f$s%VbAs~2= z&q;=2Fwn|op2b@o2c2GLxz7!V9ek*`l@r2gziPxuQgn5f2-a|3PFyCjieq6!7hqwp zJD~cn%XBk++wv^RjxKRtAWXT0?}SwgoHWjNY|KOPU4VKh1rad>2)g{W{qsEl2(9T~ zzSw9CmHSrcYT*$HDbFF_vHta2P#pA0L$rUV*AN`PrN?XjFMwoK0O0%14P~WSh@_-| z-WV;%G)PF8C&mfuXdIf*xZ3V8mVELkD>Rt`6gIId>=Ntoq)q6;B|;@M8L8MqMM8z6 z-U0~wyb}|dF;g!&h#<t~QlrL{H;;R~z{BGAAv)|WP->dC!?@+9R|AvBNBI$Phq?qD z9TK-yyf^%CgeFns-46t6baT!by1%=p?OS#MuK=>i!;I#8!N$|sE{|_cK;={ckl+CW zPo(>jpn4;yhCtpV&b<eXa<^B@&^2HTv%$?t2?!l8+VsX~DM%|IjxD?sLF$LU?7psY zV<91S>;+L)J4~24MZ~?+>Ai0$vt&^91<K%^mH>OrLSR)Oxtf6>b*UX2TtFf*f<)m< zYyR^(dT!r8;!HD=!4mHS_KrIA-%4LwQh%tU$u0c?`j{^P)Q$I8Ksb6{<L$4BkdKva zu|j3D0u}(T-$jH<eij0)-{ZFqh-90ep|4a&1Lni5&$7}7uNb`35yQFuCnmcX+XpGe z%-E=r<%<Ubl$LuJ-779>`=~aBJJ1v4Uzf$F0HAwXo7LS@?SGRE&7A=$59oj^AxhJ? zA8?fTS$;;VY`|_iKd+iU%V?*1Y{DABf-p$}>R}KOIz}!Uh`35C@BpE|jeuG$5j!y; z_ayVDfutiAWNNO^wroN;*y2A+K(l<NsEt>1Juj(0dhoPie~PPMW!2{7OGWedug5;V zjlf5bKwlzmH}P*$UIzP*YJ}_;G|oH23uAsE?%XZ+$`YsmrG;xy8Y`^}%Dujj5pnbd zD&1zTA3U%WZ0onLD!F(e;BOa+9?%tcmpF9<q=v!_z&4=-MX}KifIhL?F!Yk86QM{9 zs$u}FUg`WkZBfEaP~D$16Z1k|RXV~i3+votTNE}`9xHFxz|XYuDGua0_C+et<dDAV z5u~B{fr%&+OMDUwLWH0>E)=lk`>^>5D$Qj;YQKlDG~MRNnpUgVK!d0S^5TiFcdO!l zA@aP!mO7T%W7|BjU<O~T*2dEP9nInx2d>0OHZ0uN-dU)DeP0q^VvwRdU1o=U>wB2l zbf-gphq^|N1QFMdoAU(+fId%WgvuBl=XI2>9tVs(Nlo@ct_pIVEc4hx^+q@5`b+T^ zj8U96gZ$O<_5CJ<r7dAtH|#k#{F<kTgAh?(j)Y0HAm**BT<d_vN2q6)!L|`vV4Deh zAOc6A{fj%#Yi}SjUK`L+6<hr6yf)=zC+r=R5`UWY&B+HaY1aB((W4T?dlKeVWtR_3 zgjJlE3k0xJUup`%itGY<S>g0Z*80Wt95lxodbC|2{69>^+T>V#sx(tm_uiy^l1jT$ z;Uy1VK=?wbw3SMPt|29@jJ*LAhN%oYpHJh3GHrItW?s^r^=yOmct{@Q#zrDy{D}w7 ziW7|zkG~DeT;LI?GQyD@s@}+U-#A!J;rYmOxV;@f+;H`OH(^B(j0RWBYazz``iPdi z<eLkM`E$5pAxsbDN2}Y9&>t~t`Di11!1jNEgH8@I`+|{Nr$eTTnliAbs@`Uo{#d>q zZ~e?osI9lNT#t?1Dy9y!HT-Ux8<gY3mJWTY0yq@DjfS+=q|!lVU1R}Txr*=_il7ct zq^;x{*yD;AAwe8)G1&N1$){mlu?9svduEKh>c=7hy}lnhT&+Mc_ACo~1+ajd(_Tlt zjtWQj@2v~VR*n9QgOl}KAu<WVlVY2Db+I6F<g(c{F4U&Vj!Z!UIuURLg&M@aZxj_` z#zy!0PO;tOE$ax{jH_)%zFd-v=L0;pjrJrcdiqO|w`?Hf0MvqwoeQAP@Ih$K=?Re8 zntqTiaEm_!ZEF@qVeQGa2ZnuAsiT!M$a<ueltjIP3^Sg$0w5m5y1u)ok0hvYxJdG+ zZIilnwF5+;hjaziN`#G)6yL8cO&<52)m}W+LwdIU70?DntAhY)IOi7F<B86_R2Sw_ z+g0s!n^+8UC_c>=Tv!E_y*A2hH8*uSlsc-ZGuDe>@Kd#8X1|h$(xKZk=umx1p+gw; z#;$ZWNQ<{b{5UM!lqzog+4ZjI5Q40Kzd+i*FBnqx-WY`Js3QIE<CyQyxdsV>D9Ub< zVV+W38uf~`oR|yeK=V6!J0;ipd$>!5w)S(=TRgP1;$~jvN#~b~K1;7x@fq+saz}r8 zEn?^EG6>1|_<rYwW{1986sdq)trcj$*ZlkNKYX_hRT%Y3x|<M-94^g}7$FbUhuG>m zFI2z}lomBkk4-CQs>XlDL3ao@yICHaTD|%`6O4Z#D~RM_b`bG)Q@V(%(_DKj3hp_G zfKBtZs2F{Y@L4e3nqfP4Kb=#a&&+Xd^1M_ND?eHz@2%ld(7&8@KjJwL9(n(VZ`p-Y zA06Z_nyJd!ZlY~votc*+Y*BsJW$VJCg=$XlEzdMci;GHDLU};XSG_sBGn*M?JC=Cz zn72kA0XXEli2BH&zEK>5w!17}l3?r}%)G=#0uQsWsNF9w?elruw6?4vz(fZfYWF?g z=&rt5a7z2@fizdamtNz2GD|+l6Mj|WCBfU#CtM6nLgv~>_L*WM$Mh%Gyt%ybNFy1g z9bZO<F>`~ngzqcA)Z{tPbM$HBJt!zB4j>or=j5-ug8y?^jKnj_(miFUHxQ<!y|}I_ z-86oknIM2lcJH|(8UIGEOmpGz#qxsj-5V7a(XnHt`IkQWw0-hJp_9*3%(wlgFxbR~ znkmfcQ3wg&Y22?_Q=&gct>itW^N9&=MsM3GvtD<#sq1;|czVKhnKpvO)5zVJ2I7)Q zNGnY#)be!XFOo#C$^taf9^TBKLU>tpO09EwU0nV^rrUmIl07}4@XOPy>mM(|T_R4z z@nwJ^hkcfNJ4HQhW^qrMzdwsaf$h1YhR51{_iZV>2}4Pn&@~6MH-lnPpDifFj*VvC zoV6we+V&9oMBp1`<S>J7b8cOru8`KZWvRB|-*-}OT2~%@j|6194j2j6fT$pZ<vV#p z`z!xSB~8(Nr4aw?MgeJ`g4fbJBz39qn(TKi5}5k)(fgR}@0lV&Ii2UakErAAqbKqK zYNB{8hb&RF*ImVH>KY<tO9bt2cw0%{hrI)_dn$RC(EGleiAJA0{br~!i(H}IiseoL zA1}fV-9=R3%a|GaUEg3m%y6nOpFR05--Fa0pf;)GQqlhsmhD!@nFm7fz$c2l>`L&} zUq8hBjgHiC?jDHT!!>LY@M7AJ-+7Q_71Hn)T`+1kK<Y@{>wbHyg6EgKjJ*yLO0Mo< z>wc;F-WzNa0bxlb%`D|TIM{)ohK%%|w3k1FP`gD31zd>EPWXb#_SzNH&cOC37sFEx zlS<@3%0&n!EA$#td>C<rQ_i6Fb_gzY+m*PXfYrC|w;0hZB}E7qca|z6PyO_djLNu` z)0LW;3-q8tSS|{;-W9~6SkLv#q^fPzs_;(_NGF3EBtH{Ox)<sq6LmCZ+LxcRd#_Y4 zJeOAUc|6fx$aX-sU90*={o%{?zP#wMpO@l@ChXM?7sKrD&F^g|e#j3mODE_?O4+GH zB71Svd+;o!2M@&0!@{NNK_^RZeQnF~jfm4}tR-FTtahA@9c#3VpmkZ_oc*ymm0fW! z4_veRns~F}$14KxJ2l15wuUdFf5ymCbZx2X0XS@Fd{&NbCmfC&i)tS+LUuPMI!h`q zfjmz^_m=wCkfj*5Sq1zZR&&1NT(7dUkn{=J&nFbF>`^BEH9>zyQ8PZ6Y7OAql+I{x ztOwy5^2_dhdy^b~FhuUb*B<J5H<<S}+vnmy=g_7n90p$~N3D}rP^13GjKu;rI_w$* zEYO<2K%8vbRfvmkr3o8qxZBjM<wjKNj@`G}Hzlm|#&bMJezav6YO}&7@GmjWgNh`Z z?7vTr!cm&=xq0FU0&047<Xh=Y>GLW%Yx!U;s&zM3IdHJ**|a^KFg*NINV`p)Zi0Hi zYBI;#2b3U{{wR(7GY$%@a^I0YSh2qH^Bwo6S^5Wl_FI&Arb_th_rh=|%ZTUu1Xab4 zS^eS$E_5LB#N+?}DxerSti&`p<U^?Vl(Bjn>(p02RAj_Wps;P$W2q5#%Q+-%mEzAY ztVutV9^w-%Bdz<f>x2~ys6zpUUC|nPzDMs`nDj9|c3p6Q+9RmT`SSEidw7)%4c?Zp zbr`Bz&e{yp%KGexH^rLauwsh_oocHG0#;KHW>>)?G9K8H)NeoTw#dR@x2OC$VWDt? z?gVR6u8Z(Wvx^#7)$~eByQN@cUuz$nmQYqv1Z}__r6S+{dqyyF1O4;oe}R4euV4K? z*ogS&k^d!z^<TgG{{xBtU+?nYoW?r}UpBWam*_U$+t=|7d6u4z(W&PruLl1Ir@?zF literal 0 HcmV?d00001 -- GitLab