From 917bec2903b0e92dc2840009ac9a87272149c421 Mon Sep 17 00:00:00 2001 From: Kevin Lee Stone Date: Thu, 15 Jul 2021 13:06:19 -0700 Subject: [PATCH] Initial commit --- .gitignore | 3 + LICENSE.md | 21 + README.md | 100 +++ ckpts/.gitignore | 1 + config/net_config.txt | 23 + config/net_config_overfit.txt | 23 + datasets/.gitignore | 1 + frozen_requirements.txt | 79 +++ learning/simnet/lib/datapoint.py | 1 + .../simnet/lib/net/post_processing/eval3d.py | 1 + media/model.png | Bin 0 -> 172513 bytes media/small_objects.png | Bin 0 -> 117472 bytes media/tri-logo.png | Bin 0 -> 9260 bytes media/wandb_example_3dmap.png | Bin 0 -> 10918 bytes media/wandb_example_val_images.png | Bin 0 -> 396801 bytes net_train.py | 98 +++ requirements.txt | 11 + runner.sh | 9 + simnet/lib/camera.py | 160 +++++ simnet/lib/color_stuff.py | 40 ++ simnet/lib/datapoint.py | 442 ++++++++++++ simnet/lib/net/common.py | 167 +++++ simnet/lib/net/dataset.py | 81 +++ simnet/lib/net/functions/learning_rate.py | 28 + simnet/lib/net/init/default_init.py | 25 + simnet/lib/net/losses.py | 65 ++ simnet/lib/net/models/panoptic_net.py | 433 ++++++++++++ simnet/lib/net/models/simplenet.py | 408 +++++++++++ simnet/lib/net/panoptic_trainer.py | 168 +++++ .../lib/net/post_processing/depth_outputs.py | 97 +++ simnet/lib/net/post_processing/epnp.py | 263 +++++++ simnet/lib/net/post_processing/eval3d.py | 652 ++++++++++++++++++ simnet/lib/net/post_processing/nms.py | 87 +++ simnet/lib/net/post_processing/obb_outputs.py | 209 ++++++ .../lib/net/post_processing/pose_outputs.py | 310 +++++++++ .../post_processing/segmentation_outputs.py | 78 +++ simnet/lib/occlusions.py | 50 ++ simnet/lib/transform.py | 114 +++ 38 files changed, 4248 insertions(+) create mode 100644 .gitignore create mode 100644 LICENSE.md create mode 100644 README.md create mode 100644 ckpts/.gitignore create mode 100644 config/net_config.txt create mode 100644 config/net_config_overfit.txt create mode 100644 datasets/.gitignore create mode 100644 frozen_requirements.txt create mode 120000 learning/simnet/lib/datapoint.py create mode 120000 learning/simnet/lib/net/post_processing/eval3d.py create mode 100644 media/model.png create mode 100644 media/small_objects.png create mode 100644 media/tri-logo.png create mode 100644 media/wandb_example_3dmap.png create mode 100644 media/wandb_example_val_images.png create mode 100644 net_train.py create mode 100644 requirements.txt create mode 100755 runner.sh create mode 100644 simnet/lib/camera.py create mode 100644 simnet/lib/color_stuff.py create mode 100644 simnet/lib/datapoint.py create mode 100644 simnet/lib/net/common.py create mode 100644 simnet/lib/net/dataset.py create mode 100644 simnet/lib/net/functions/learning_rate.py create mode 100644 simnet/lib/net/init/default_init.py create mode 100644 simnet/lib/net/losses.py create mode 100644 simnet/lib/net/models/panoptic_net.py create mode 100644 simnet/lib/net/models/simplenet.py create mode 100644 simnet/lib/net/panoptic_trainer.py create mode 100644 simnet/lib/net/post_processing/depth_outputs.py create mode 100644 simnet/lib/net/post_processing/epnp.py create mode 100644 simnet/lib/net/post_processing/eval3d.py create mode 100644 simnet/lib/net/post_processing/nms.py create mode 100644 simnet/lib/net/post_processing/obb_outputs.py create mode 100644 simnet/lib/net/post_processing/pose_outputs.py create mode 100644 simnet/lib/net/post_processing/segmentation_outputs.py create mode 100644 simnet/lib/occlusions.py create mode 100644 simnet/lib/transform.py diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..61b8d92 --- /dev/null +++ b/.gitignore @@ -0,0 +1,3 @@ +env/ +wandb/ +**/*.pyc diff --git a/LICENSE.md b/LICENSE.md new file mode 100644 index 0000000..9963469 --- /dev/null +++ b/LICENSE.md @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) 2021 Toyota Research Institute (TRI) + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/README.md b/README.md new file mode 100644 index 0000000..d48b329 --- /dev/null +++ b/README.md @@ -0,0 +1,100 @@ +# **SimNet**: Enabling Robust Unknown Object Manipulation from Pure Synthetic Data via Stereo +[Thomas Kollar](mailto:thomas.kollar@tri.global), [Michael Laskey](mailto:michael.laskey@tri.global), [Kevin Stone](mailto:kevin.stone@tri.global), [Brijen Thananjeyan](mailto:bthananjeyan@berkeley.edu), [Mark Tjersland](mailto:mark.tjersland@tri.global) + + + + +[**paper**](https://arxiv.org/abs/2106.16118) / [**project site**](https://sites.google.com/view/simnet-corl-2021) / **blog** + + + +This repo contains the code to train the SimNet architecture on procedurally generated simulation +data from scratch (no transfer learning required). We also provide a small set of in-house +manually labelled validation data containing 3d oriented bounding box labels. + + +## Training the model + +### Requirements + +You will need a Nvidia GPU with at least 12GB of RAM. All code was tested and developed on Ubuntu +20.04. + +All commands are assumed to be run from the root of the `simnet` repo directory (represented by +`$SIMNET_REPO` in commands below). + +### Setup + +#### Python +Create a python 3.8 virtual environment and install requirements: + +```bash +cd $SIMNET_REPO +conda create -y --prefix ./env python=3.8 +./env/bin/python -m pip install --upgrade pip +./env/bin/python -m pip install -r frozen_requirements.txt +``` + +#### Docker +Make sure docker is installed and working without requiring `sudo`. If it is not installed, follow +the [official instructions](https://docs.docker.com/engine/install/) for setting it up. +```bash +docker ps +``` + +#### Wandb + +Launch `wandb` local server for logging training results (*you do not need to do this if you already have a wandb +account setup*). This will launch a local webserver [http://localhost:8080](http://localhost:8080) using docker that you +can use to visualize training progress and validation images. You will have to visit the +[http://localhost:8080/authorize](http://localhost:8080/authorize) page to get the local API access token (this can +take a few minutes the first time). Once you get the key you can paste it into the terminal to continue. + +```bash +cd $SIMNET_REPO +./env/bin/wandb local +``` + + +#### Datasets + +Download and untar train+val datasets +[simnet2021a.tar](https://tri-robotics-public.s3.amazonaws.com/github/simnet/datasets/simnet2021a.tar) +(18GB, md5 checksum:`b8e1d3cb7200b44b1de223e87141f14b`). This file contains all the training and +validation you need to replicate our small objects results. + +```bash +cd $SIMNET_REPO +wget https://tri-robotics-public.s3.amazonaws.com/github/simnet/datasets/simnet2021a.tar -P datasets +tar xf datasets/simnet2021a.tar -C datasets +``` + +### Train and Validate + +Overfit test: +```bash +./runner.sh net_train.py @config/net_config_overfit.txt +``` + +Full training run (requires 12GB GPU memory) +```bash +./runner.sh net_train.py @config/net_config.txt +``` + +#### Results + +Check wandb ([http://localhost:8080](http://localhost:8080)) to see training progress. On a Titan V, it takes about 48 +hours for training to converge, but decent validation results can be seen around 24 hours. + +Example validation image visualization: + + +Example 3D oriented bounding box mAP on validation dataset: + + + +## Licenses + +The source code is released under the MIT license. + +The datasets are released under the [Creative Commons Attribution-NonCommercial-ShareAlike 4.0 International License](http://creativecommons.org/licenses/by-nc-sa/4.0/). diff --git a/ckpts/.gitignore b/ckpts/.gitignore new file mode 100644 index 0000000..017234e --- /dev/null +++ b/ckpts/.gitignore @@ -0,0 +1 @@ +*.ckpt diff --git a/config/net_config.txt b/config/net_config.txt new file mode 100644 index 0000000..ad846c3 --- /dev/null +++ b/config/net_config.txt @@ -0,0 +1,23 @@ +--max_steps=400000 +--model_file=models/panoptic_net.py +--model_name=res_fpn +--output=ckpts +--train_path=file://datasets/simnet2021a/train +--train_batch_size=12 +--train_num_workers=4 +--val_path=file://datasets/simnet2021a/val +--val_batch_size=1 +--val_num_workers=10 +--optim_learning_rate=0.0006 +--optim_momentum=0.9 +--optim_weight_decay=1e-4 +--optim_poly_exp=0.9 +--optim_warmup_epochs=1 +--loss_seg_mult=1.0 +--loss_depth_mult=1.0 +--loss_depth_refine_mult=1.0 +--loss_vertex_mult=0.1 +--loss_rotation_mult=0.1 +--loss_heatmap_mult=100.0 +--loss_z_centroid_mult=0.1 +--wandb_name=simnet-github diff --git a/config/net_config_overfit.txt b/config/net_config_overfit.txt new file mode 100644 index 0000000..0b8d508 --- /dev/null +++ b/config/net_config_overfit.txt @@ -0,0 +1,23 @@ +--max_steps=4000 +--model_file=models/panoptic_net.py +--model_name=res_fpn +--output=ckpts +--train_path=file://datasets/simnet2021a/train?samples=400 +--train_batch_size=1 +--train_num_workers=4 +--val_path=file://datasets/simnet2021a/train?samples=1 +--val_batch_size=1 +--val_num_workers=4 +--optim_learning_rate=0.0006 +--optim_momentum=0.9 +--optim_weight_decay=1e-4 +--optim_poly_exp=0.9 +--optim_warmup_epochs=1 +--loss_seg_mult=1.0 +--loss_depth_mult=1.0 +--loss_depth_refine_mult=1.0 +--loss_vertex_mult=0.1 +--loss_rotation_mult=0.1 +--loss_heatmap_mult=100.0 +--loss_z_centroid_mult=0.1 +--wandb_name=simnet-github-overfit diff --git a/datasets/.gitignore b/datasets/.gitignore new file mode 100644 index 0000000..72e8ffc --- /dev/null +++ b/datasets/.gitignore @@ -0,0 +1 @@ +* diff --git a/frozen_requirements.txt b/frozen_requirements.txt new file mode 100644 index 0000000..3ca2bc6 --- /dev/null +++ b/frozen_requirements.txt @@ -0,0 +1,79 @@ +absl-py==0.13.0 +backcall==0.2.0 +boto3==1.18.1 +botocore==1.21.1 +cachetools==4.2.2 +certifi==2021.5.30 +charset-normalizer==2.0.3 +click==8.0.1 +colour==0.1.5 +configparser==5.0.2 +cycler==0.10.0 +decorator==4.4.2 +docker-pycreds==0.4.0 +future==0.18.2 +gitdb==4.0.7 +GitPython==3.1.18 +google-auth==1.33.0 +google-auth-oauthlib==0.4.4 +greenlet==1.1.0 +grpcio==1.38.1 +idna==3.2 +imageio==2.9.0 +ipython==7.25.0 +ipython-genutils==0.2.0 +jedi==0.18.0 +jmespath==0.10.0 +kiwisolver==1.3.1 +Markdown==3.3.4 +matplotlib==3.4.2 +matplotlib-inline==0.1.2 +msgpack==1.0.2 +networkx==2.5.1 +numpy==1.21.0 +oauthlib==3.1.1 +opencv-python==4.5.3.56 +parso==0.8.2 +pathtools==0.1.2 +pexpect==4.8.0 +pickleshare==0.7.5 +Pillow==8.3.1 +promise==2.3 +prompt-toolkit==3.0.19 +protobuf==3.17.3 +psutil==5.8.0 +ptyprocess==0.7.0 +pyasn1==0.4.8 +pyasn1-modules==0.2.8 +Pygments==2.9.0 +pynvim==0.4.3 +pyparsing==2.4.7 +python-dateutil==2.8.2 +pytorch-lightning==0.7.5 +PyWavelets==1.1.1 +PyYAML==5.4.1 +requests==2.26.0 +requests-oauthlib==1.3.0 +rsa==4.7.2 +s3transfer==0.5.0 +scikit-image==0.18.2 +scipy==1.7.0 +sentry-sdk==1.3.0 +shortuuid==1.0.1 +six==1.16.0 +smmap==4.0.0 +subprocess32==3.5.4 +tensorboard==2.5.0 +tensorboard-data-server==0.6.1 +tensorboard-plugin-wit==1.8.0 +tifffile==2021.7.2 +torch==1.4.0 +torchvision==0.5.0 +tqdm==4.61.2 +traitlets==5.0.5 +urllib3==1.26.6 +wandb==0.11.0 +wcwidth==0.2.5 +Werkzeug==2.0.1 +ydiff==1.2 +zstandard==0.15.2 diff --git a/learning/simnet/lib/datapoint.py b/learning/simnet/lib/datapoint.py new file mode 120000 index 0000000..7e06a07 --- /dev/null +++ b/learning/simnet/lib/datapoint.py @@ -0,0 +1 @@ +../../../simnet/lib/datapoint.py \ No newline at end of file diff --git a/learning/simnet/lib/net/post_processing/eval3d.py b/learning/simnet/lib/net/post_processing/eval3d.py new file mode 120000 index 0000000..ab19f79 --- /dev/null +++ b/learning/simnet/lib/net/post_processing/eval3d.py @@ -0,0 +1 @@ +../../../../../simnet/lib/net/post_processing/eval3d.py \ No newline at end of file diff --git a/media/model.png b/media/model.png new file mode 100644 index 0000000000000000000000000000000000000000..9e1d4bb82a1ce7c2272f9abb10cb129876f3791f GIT binary patch literal 172513 zcmYg%2Q=Gl|9*@bwW6wxRikQ_+FL295j$p4T2Xr|YOhiwW~oilP$Sfc*483c&63)& zwf3mJ{@*^&`~KhGeU1|+Cvv{-`!lZ3bzOI~uC^-Gb;j!;5Qs`$4GIT=h|54Af*LYH z;2qa|qIlqi+)eF?CkRB{@%M)ym7kgk1Y!fJLmwHu%HC-9$$n~Be|072h<>V_VIh*C zo}uZ-mN=wwlbD=1)zSB9RR}%p2Q|H+b^0b)mk0fqh31#X7ERYp>|!`zG=vH=ACg2$ zI5WO~xA)&R%*C@h=81CWLtttg>*$5=(v9WKgX&Uw`*MS;;ZS1gH|_IoQp|r}UeUDG z9TEQX>%Z^p3bOy7H{w~Yafo0ch`O0w0uU{JZ;K4%YU=}q)+#tvm7*tDENpk9x*;{B z!H$leO^#C6e*Ncb-9m&{QjIO1)HzM`X}r7tw4wIK<3o4ohtiFbXeKCSm?G2LejDl4 z@bGZcl74FAsXGLr1Rw$ibm12fIWaN&-V|8e&euEy#?}HkKMC74s7eJs0qsNAdm#_g}LGjsMde#WQs_??Rlrs+0qgX zTjz}L1~VWklcFeTY5CBU422k6sX3qP_@{?i{etGTJUih7dO1-@q#kUtlU7gXDBT^= zrJW<;{OvXQBd}9eTKDe2+|Bp@*|o)H?JC_bi}AAC4eQ#xD5DtB$oo0(tdI-{wp94o zb%>QjR#LQ+lf(CAkM{QVRG2}qA`}|w?L*ATRv3qC5E5$&nlV)%<6o`@7hurM`T1Y% za=Jg%-31kmiIuZZ5a_Ab+Z-@Pl2KCWq0Gq%Ey?ss4Ax3tVXjRQ37<8>9o&8tEo-ES zOGt97Z&0+NP~zWT!`0E0;|tsj93!T5Nk*pj0;wY+4AWxcc>JJr@MVVW)YN3M6bTfa zf}5PB<1jtkt0t{=adF9Q?z+P&xA7^Oj$32}+wZNLP5AQPxNvJKW`IDx9Dj=q_MCDy z-}(Kcc-f==Pjo*gq=>$umN6URag?Or8Rj={mm2ShU{SDC>K#iqr4hW;;l zz#JX}l1|gd-FFk1y+-v~wp$x3ix*iJ|Ce3z*J*zDiBE8M0Q4I#2ErGc_yxXobX&PM6nmDMwO*g(4M81WW7Ul`#4@h*wp3iECXRJO?j{ zWWcyY;m~sa1z~3CLR@AyTY-4&qY$aYs4a4F$*5`H?0{# zAr!PWB9FlFjN&k^Xo<+RON2ixP6FO56(0d!Hm@+@Ddl{g{U(F*_8o@^TiD4&!QY6Mr5@i2;HI2k!osWB6b+|e75W}O(Vd(Bbc z4fsLY)|Nbv;m7HNKa^BByauJpb40`-kds0YV{G=V<0+;f|`+x zfIOO(5el7p4T}nC14pb9Slx>uQXp#=GEC2&x;vHsXmrxMU~)e>Un)LL@ag2l#P2jIt6S?V4z^^@ z>@>6ls1y`jnoJp_sE8H^xmhccJuBC=MzZhKQrqtnOWTIH-!RJ|vG+}IAGmfqbLtf6 z^NGT*y=T6&u@i=ll)_6Wsht=_ZSI4XnHYhR=!vHxzFj9m4#Lr3<3;$Ct!v>xbLxX~ zAb^rvQZjKQ&!JDjD~1I#tUn}D#DP=UIg~j{PdcQ$d9n%5i@!k%Q{opto@yZxOdPLQ z&vI9Nr~KLf?eVi5_6EuV!~|rZ6wPi(saGg25>!SMiYYKk=FH_zf8Me!E-v{v^`kaH zn7}sz5Mp{OzxLMO-i2I*fWFMBFtJ0y#FTn()vs|ET@hJRwi!_nJbG17Rn=3`0R|^+ zpXKf}0bR{`=hs<(+M4?trwa;TB$6aoa) zx`x35Z4KuoV?z-tqQz_}!EK|QY#>@xyN5kIZ!TNzdYB^2{!D6fBF+m=P`a6p+e>G` zDkDbfM%Z>zanBm{qrrL%FOZR9wRc`QkP;;psewR3SUKSFSwV5aEvrPK?C1|7lZXDv z2EC`Dll1n^;E-B4{Io^klRJWoQsj9gMFJ%O!%adEQkYWFJ}x`Fs_NG3bZkeX?lB8p zG04Y-ghb+?()>w@K^U8pqhr>Pti`L`xv=`ovpQ8rG^WC!VE)_AnqgU5vyumyS7M5f_!#3%$^tR6H5iB`G$N4Gka=}1Y3PT zQ6#zB^!dVJ*eA{K|~p(WzUZfyIprHhVo*ZCiYUx zjQXYBS}O+h<_z$M?U$Wv@wjE`_(tQ+03T^USoQcKUrqKO48#kcVhy2JUR4UJiTPoF-w{tgZuSiApR&i ziae=97~JV@9?fT6I368BwxQ5H+Vr&CoQ09`dH`!FR;;~UIl@X$og74&1TqmImA%29y5FRw70GpwjHjdx6;*u3BgI`^60XkI?!?W7$o52w5kNp}BSx}D zQ@YV)KuR(&kKa_K1wllxc8X-}x@7t5MF&p56GdH8&9Xa`$go1uciEwWX^Tj+zU)j# zY6LTge1sYv*$vimcq0lwf4QM6b?wVr+OFN$2ZG~X*gq9|g>^@!%#{Qj*V(=Er1vjL zSxxIb3|+Th9c`xl4M=a5s5Xc|DjYuXy}@VmyAm0@+#ucdK&vus5}8wED3y|82fPH> zZK}99Gl%q~-z{RH^6DSJVckpBzPO1e_iu&3*L6a~NM`H82|)~ZQ8B$Q(Bgz11B+55 zZSU%EY?QTd!{Lt724Rd>m8TDbb1&)!A;j5<87i2ytklg}$7GQ85bXzzj6%|8@MwQX zp$rWHP;47y|8-Y=b;0Ng!DRS29|us4!`g0ti!G4K>R(}E{4!T(Vru&q0ag^Uc_D^~ zLJ}~ls2Qs2aufOhIA%J7t-u)P3VOf0*yX&9k(wpLo{aM9zZ0;;jfs~^sBZn8Ub_au zgl*jHzO=Ts8t~B)EN(ny{>6b3w{0q^$}cW%EGe;{%0+hDDO;CLJ_!7B!w`moBM^vE z3kOCUPkDXuKmurdh?3j9??I;RhwC_BNkh{yO2=O}l;O>$0M}$+B*PoRa zBH0&xbBATT2=56&P5DGXY9{gm%GP(ag+jUm2PwjJvE(1_29rdk7{MGxuoC6TB@vQf zS{_vIay8YPA@~cC2`53b=J+J@j!6OKccoU)rR=xt%G)cqN#i9$^+ROou<6DYzNq42 zGqR&^o4;x?7(ufZt7p&N>WBR8ALGAGYG3Up-+Pd-#VDWe69BP+1REoYDD|pzO=@gr zE@2yeves}6)xnf9 z`&3QDY3Xyp=HtI2*eK(K+atd13<)u`ORGj^d$JQRn!8a;_{<&+lk`%==YFz%)CQ}E z^W56}@_vqkjF99#hD)Ve`UV%AnudlbBzfdWj*XDmTGJl=7Rq-Gn(fIpf^~E8*ZuLl zn~iMmXXwHn>y6?j8=7w~ z9CwkiPnw!ZP*Wlqe$+JoT=?g(aU3Y~I;WHB<%`A*k;1~}z}QzIKBUw`lmD!Vi7LC@ z8-(fOKR*lTsNtwkTu&fG*zvX@E>sGbV@!IiMYY_4Gj^CU6by`V=oC1N|0z&zrc69< z>D$U=I(B;sg4roW;V|p+k`g_#=e5ErQ^GP9{XW!TZ7|)zqX@7m4D{(9)S8D_c?lE} z1>^nr?)MEQN;0sG5)?pT_vtn26uU|hF$H|+q^iu%TBl?jwD#y^P6^Xh59yYAQ9co< z5);&NJJnP+%JFjgx%+iDTaFlxfqDvNJg;I07K;UHSg^86iYc zD#-s#!!=TcQKXDsy5J?X9@EGqr#c6*tG&x3Z1?HZD5l6|m+xnv1V=KQwo`fu1$kuDQ?-b|L*O7B{d5<`uftABc6`Eqj89A{?!?q71!HgQ*QO@|DL0fUWLIs zfu|CP(?3NkSe6eVKX8+{8Tr%UlZ3~5wF2>$jcVvPILxuEw-(N)ZBSyK&!<~<=^SKB zsW(Rohe55go%7$9_g&Y0noA5KaKj?m0V>7Sq%~+J6VquW9K%;+)1ZHQ+d|gdFd(eJ zfNXLBRkGIh#~K9sfO!YZ%#*b?W2O0Dzgm?<;Xcu2fC(jxZ4LY1VU-|=4{*JkseQ{I z;n53HS$$(F9L|68F2;;*5`;V%;Up&}MAU9d2ToNcFS6J)j)6!?N%Q;&$%eWhOpPTM3SOMO^a{zS5!}afTbev(p4TLa{rt8f1m@dle^w{#uJRI_WHB}LpnV9GTne_lx+ zu^5kY<|NJ=l6CnpH}`96cp=Av$uQN@IRwo$j~qr>4L9VD)^#<+85s)ZaH0nI1`JL_y*v-rFMAXIBmybQrr41`|2!dfWyMC3 zimZj34~fd85Q>|xd5XrewVOX2yry9#Ehd%H^BNi{8cC)^W<>9V3mILrz}Cx~mY65O z`AT|IVHNDFz7~8-;HYvbmioAo;|>SiX8C4e=$8KuOVZ~GP%8ZMw6`OK_|2f~LO);I zYHsl58->$(Uj?b{@j;e8X_|JonFcS(8Mnpqi5hC@KSMunO0VP4jY}gM+*+A`?ih!} z=TLHwvj7FZY9IVqPgQj){??odbaQhPz}RuPPXePQRAFq@R<4{qIaONW%2)`0^twi{ zE?sC8rJnlo*~8T^_LaRSJbL{?bdKaS-5bS(93xmB-Z+U6%C=W6ti+*RCvN#{ue+}4 z96e%NUxA}RHlFq0c629Sled9u>douTX>)hvA3Oyo5{Q{52_vi6$RMjsl1|Kw%s0O+ zBJYOHeG|m)LouD=^huZvRg|@XAc10u2{V3*|Fzm%D(6lbT7WA^Dv7%}X<9s*93_@C zJQ+xH=?%H_cWrHL1$8lj@J6?JXqzKi?;wQ}`t$H3BO=?~z9#{bHbO!|ZWoxJnwcK+ z>zfgn4>$ii`%8p$3r*9$(Q;$@{AeQCQ0sDRfS$W5Wn{le;9SA+nj$|12AAzwNPk_& z?Rm3eAinS=!t6)cyCbpy1vUg9N@UgC(OF)BVNu;G_Kmgv`A9AtO04P6TgFajpU2Gx z;t{|M@06NZ$HrqJSSgVEfV_?!x?QMUIt|8$s{8c>Qy6f_rN)~I{1tJAPt6!1>|r7TXpqqe{j$je}*f6vOg3~!?CC%fAV2YE~_U1C_VV&In#CS+*cfw?EwGV zy7P^~(Wvsy%#6I(ngRakC)(_2f#QMNfX|HA&$`3INkMooJ-^YPqa)R2*xTanKV@L8kyY_I**~WrzDQ2tPjwQs{al5rm=r9z&q)aV`k3QwqNg<(8H`uZ zAyt`4B;C}9V=?NNuLWx0Egi^Y435g=7<3Sq{8UX5QswX}e1;>=?OC})f3ga7(IAdd zpBD5QoV%LZms(V0V}$0w#T&`mcx@#n^GFcGVS`82^-dTkspL0mA?de3`Y-GN0ijmH z)V|~ou93Z)Q~GcmF=cAz?}vq;CCc%Mc3un7+yfb+wxlQB7p;;rFV9$fEc||>YL3z` zDspOXs7`%L_A$F)*Gyijklj8#Eh*N{lQ@{TZSiYkqiG?A|8UB+)vD^arccoSPyU-) zxNY#opZt&KOZqx9zGs`pmm41HE0K;BXD2Vxbk^4WcXnG_cXu&37j^H+xf6 zzOdm|OViRf3c=%_Izb~0AMeDFFwxdH8zagyvBi`y#1F1 zL0MHbqtRUF-RXYZnjhB`Ih+OHQmfhSBG$_{%HHh(JQ<0-GmV@eI7Ap*Hul&$it@)5 zqMLmTVb3lse|vI8=VOD15%;!G|7uyUf;A4hNFCzEo+Qo(uc-mRew#3??MlE59gDX zfRp94r$MK`i!D75#{9Q1Kh1))@Q+B|MCJyq*q1CR%>KziFr_knjwUpK$-7-$6z6*M z9$hZ_@2~WiL5J_%whWj(Y7M@KldP+)JwNVJc(_ff@MSgEKj^FxFD@?b_3~xF3BTop z=XUd;9I)*=^2?vvsTa+TmUWXmXykX=c7}$wgN|eo-y>FYj`GqhWPGu}rxcv=fkzkn z^1(8z)1JWx!Bm@+6jmL`E@rT z*X`VxTPI_0pFen3-0u&I&$Ro5PO!|M-pI+k&CAQnnn9`kHf8FQQ-)$&k&G#q=7TT_ z!Cz}@GEQ65EX5L=e<23YHi(plg(-bB8^ z;0h{aY=c8&Xw{&TAvW?Dt_()= zwn@cHQc#qWP%uCF?f6TCBWCfHo0~3|y0Wq|LjSG&Sy5=HRn_?HFl}W1 zjGkk&!*VYhnT(9A^Puz1$A9I`-;vnJqM{;nGr~38xd22F@vSoWV*PHs)Ok%8Gh(r? z^$_z`TmEFpHZSlnQJMPpuV3A(9^dv=e7rEVb%Y_?XN4+p3rI{I#_OnwJP%)YSXa~H zby#cv1A-{d@m(ReeCU$))LZ`aS79LD)!zQ(hy0P;aT`(I>7U}7iTi8=vj`d}Ct`u~ zq+3sQ#=VP$=Hc;NKI{3jWKPMeJ)5oFSiu&%-W1-bR~uDb?=(;~0}mU$3rM$GgFhLZ zV<&7UB$rnoUY(p>d0)u~pZ@sDdK}Vc`!Cr#|B47K{3jgAx)FlUDi-Hw>@j>Z8Nvc0 zxJl8;sr`EOQO=o$41tLxvl^BRU&F<(^a{3~H1QZZbs{~|kg*jr#_6Y6T3TmnYiDYz zQ4H|G{D~Nw;Uu2JOvT4WvaB`2^w1^p=c!ZOm~qAzIcQaJ4KPwzB2o{R z#HX}`AJpk1yJv+8O!sY*)d1b8%bnQ~J=@`^r3^(GKk>B5c0^NRK5zx*4M(*->(V7xu zz(;>GpeOm>8)gr(QFEVl?+K0#YkmfW=Sn_02^Uk=BOTFn#hMv1UNM{WF0QVuvO&{7 zbQI`Rt7gU_HE#3Y?#14|3f6gevJm?~z^uV(^3QLO5TKVl`x-VFd`ST`@Pm8jzj}Ay3w|nFhkn`E(>?UDRYKlnm^7dW@fV+6^@FUEqEmZ4vd7Yn; z=tZ3qaV_6~AT}s{_I_qT1MM@vdq`n6kx4T4+Tl=EvadZLup5>^NU7RkD5NAuiB}*s z8GhrDG9vubT9x-_aNO`AVQA^sBdCfa$}pJ|UJ8ZTUub`3Brd;~1Wc-Dmmc`JouM=Q zRS?Jo<1v^CWIj6?#C*mGnAiSlD61qW(ASn1PwS%{Zl_TQ_(smnEbOy2T%7Zc zvxjx7;ZJ& z(-F}@InOae(?4d6rFAYl=+09)>yI(abWc7% zHEuoK<_}JCbvpi~r@C2pw#6jrQfsE7XCRoy{YU%bgL{iBcs;av{oZfeTxp;Wt+Qs! zJK|*hrT+uhu87AA7(d9z$m)LTVA7>CI%v)Ty-$H9bFy5O)z=A0z};$i!$6cnY#sv_ zZIuRmx?`esxyBE!oal${C<44l)n+axp(&l4NQ)p!ASz;0UW`7$Z~>e9l0n+nu=G2_ag+Dm`s)%k}()M=e- z^?cH?Lf&e&=}CC2C|EDeOFp5zF1+A42MbP;LBDf z*QU!zrufseVDhl{?0E{yj+R+6fs+xpEvIp~!+Dxu>*0dOt!Ee8t1Q0Oj*jbPUAOUb z&gGb(UtdWdG%O|iUmkZ6QOkj8yAqg!{~%N?gJ-<(a_i;s@$o>z-3@(n#~hddEG;do zOq%vTx8l8&@Ry{_AP|kh`3{~n=jv_VW%1@q7D<=sZP%-d832x-8@D!S$-k}Z$q#4y zzEaH{xar7x)xo{S8eBNidclRrx?tJeOTMRYxtpM{U!oIy&_TC%0!VEQn{`tg`Wc#B zd3_fb+rbJ}v$RH;bi+eKx)+Z4$w@z;;+Xp`r)HHvJ6Hrn#{M-CAm==^@BJG%Ll`| zXdjV*vMG39Y)UmS=C`1hK3+7O(3zTjrmq&rC_l8$>8GF_msaGs9{!0@QwlCy5-p=f zQNT%OMwmhdu~7mMibOgbeW+t+aNgKbS%-4L`A{i1Q+@%Im}?QmO^}4s_!pr3d(@wg zBN8@Sfl|NO8Vn`|`24Dqg#L74MA}myOqOr1&r*`=tXn(P(bcAFBd`x)*C_7fC|s=< z=itW1UR2tBPZze$cE=vI95n+|j>$C$caMvx?IaOl+g6PY#^)uo+gzxCfBR0B5~9*d_M*A3M}$2cmsoJ-Z);EhiDzbJVH39M4@=8{sQVy3b^bc)>5WENIZ3D;kLBX?$u7{UZ%}29Lpz9IeTwTw! zn7c4D#oAfkUul9qIZagm9S9d4J^uy%$Hk$-hrlFxh3{`I?*N+I)2Pb`^98`OaBnn~YK#WNFD|bX8^OFi3O`kkR(t;TJr6sXT`&9P0CSj!S@1(L$ zxsOJN3!Lf;oY4qCBT00sA51K{uJCcd)gBResBSi23>Z?l;9TlA9>ZJ6uYFutYFEAE zyJv5i1|P^%xVp=F(hVGC&gnrV4HXsIqQ-A8rRRXj=jF?nK0XRp=liDX7)Klgq2d)^ zYJAUgje9q>@6d@kQx5R z^DW!1leP9e1)UG%4!+awuZ&sjSyg@M+L+M0>3k9BPto-B+86i5HbjE_t;qa~RDul= zPaA#xAFD0ro%-6+%S^VpCzW~U*82Ky;ibAf%zrM!ziE=$v-^vxczJ7QOYH*n4gj5Y zj`kCdd4YA~A$4vJrP{Ia0SJQkV>Y=pm}o-~1V05V|8^?L<40gaKA^At2#cUNoC#I{ zk%i5rhznTn8D9RdE*at zrV29DP_?_r=P3izRi@}<2i8<7T5@*EM-Y9{l;?=e&~* zTj|wYu(%_QM!mVvpSub~{+i5Bp zQjT4Jojw9#(_@nPEiAq1|_MW4xi|lLzp*51lt&IS{ZcB#7PhYUI7br$;1GV^dOG`NQ!{fEG%F7wo zAkW1(Nk)X+;M9v#q_pP>2t=rvDY8uFye7++m6??wdwJ|w*?fp)a@k-~*c!Vol-9@M zyOb2CW&fC#_GlVG1Jq`==a8-XpSd}ODr4RNkaW<{C~FRHZf?fQ9!;+UmO8*!*ZaaV z@9cc_XvPO`y3w&QQR8~K{J^#G0B7b>e~n?vEA45^!S>bR#9&aJ_fc0IlTXjRwCU4z zOT2qmj>LlJ=tn&S7U|pPGx%>`X|D=bjHG0Uyqot;e%}472I>YaPzVL17d0g)5>G9Z z4)*=f8FZi&1JL{0UXmvR^%oc;zSqX$-Xhpq9NBy4S8N2U=VPddq_8Y@bS=wR4Ic#v zm=*a;h}k@HaSs!PMvEs z5_V`{D#~SR5Q5e+ly^X*Qbg1jq@wv!Kf+5=dPUS{C;7igUv;!zuBSabI_Y8!K5u6| z9V(x(mA@F(XOeKTb9Md9^miz8{8=u4zSAzf+PKxQ{;Q&bl=YQcW%JR%>OM%9=ceG7 zoiO!4y0cTRmI?j41>0w4tjc+Vt4EWz+pHW}N65bUgnC9}G+bv;N!r z59F?Zl05V99x;o6+9^F1Wc@Pj<%JeGNXD(aXf1|z_H%Z4q)(*thXwlOMaE~KL`rkl}Q9>gSxMQ ziKc$>>HVYLwUhV7?_)ksHn{M0LPS-j#JmwvYExWYrJVPykxX}AC`EqqyCuSvL{4ju z!VH7n$4T_!_K_q}iyusQINi;8Zkm}*F%$@sL^+YYmTyKw7z?A@AZYOk;wYY&0uSl< zMNai(&RHeiCSGg;)6bE~YU`dG*psHa2~8LAvO&P{-?JtCI4g~ux`e7X5OK0 z7ou#xyVBoyIk_Gb)EOLj@#hBsI}0&e+uPfln_3a%-+*tFk&&sq%)0_&(SNJHc;@HP z#oyFF{mT?C8)pZtFl@50VABD@r$X;3rr@W<0-9eDT5Gj^@C^AvB*R#hAJ^Mx))w(e z*{?Es)%SorIw~E1zLC8zU_-r5Uo`XnGU-&j!@cP;^*{hE@EmeuIJq!q<&m`{Uc?N+<}d7Hv~}*7vx8$!o3Z2U{3^7sTjOwP#71Werf-*frR*Oet?lwkJ^Z>qZA?9{ud!Mg~kbfZ~% zA%%Vo;nUr#`+)Ck8%UT7ek1U3(Al=nfHeMM{@U%U%fl&ul?00~);+YIs{lQi0Wd}& zaOAvwah}Efn}Q8H1?!c~g6a$N^YiB`tgww~LOL99;a!%AB#Qj?R z8wbk;tG>^<_Lm<73@dXggLH@2f-71awx;X>gj+Ym*_>*669?E&2OCi3;7?!zQ zU2Jn}XA*(Z zdYAX^(mbqnfA#B^PN2gonjl`W?OMV@_vndH`P0uXR+g5KNThJ}3q^E(Dg8CNIul!s z;8fT(f)q_KZHUuI9?PZvjimg|ADYP@;Jp0zPzLJBCJ|h3UmI$~mWWf((mn~-A_)i_ zR9Sg$RIz#A2FpeGVNJsddkqw;6fE^t;JV&*A|)IBl{ks;aAoym1HM$Am<1`Wg8cb; zA+il(R>Qz&@EXQ280vYh zsfkm@_uvJ9Zm*=VcC~YoI`Ut2Kt=J8g(UNc%mmZU zjywmXw~iMnA_x)XRaI4ujg5!u7G&;wJ>0i}O#N!(<8y@hY4KCKw8r~2P4Lp)ZGZe( zgGxeBGkp+HUsnQuDIaVDrbuTVC!lWszgM4FB2bu=)AkHXy9t1~opyt@1fQ z6xnT|F(!ls28j0 zrogCasFpqJ#f}CYq_GgIg1dIhC)jLSv0pSQ^)QA$xw%p;1{d(K5dpynR{NI7yB8tv z>DuWO97=`SDFm(!n1sn_-&jnd&2(h1<+1I1Z7m1?#+mEjSHHJQ%45!=R}al5U>K+$ zZZH=-YZ)w;5O^2VBq8YKoC_#d#gcv-rJ2fxZjpD6FX8@#m1!@!t8b$W+i{&gS$E#qp5Z6W5; zu*|6P_a@6vQNNeU%I(@bg!t(&TH%-l+q~eaVq53!WA{QC+4ZNtKDPzUNsyd}@S_)a zW*07bP?02WRN`QCt0~DUOc`oBA=|e}-d1x|TIs&Xb;AM|iWae-V^yqQx0OBGm}5Uy z1F^4&jz0rS??=@l~O&P*eQr%Bg!r)OkLg zYEkmCbu2>@cNk;JV7Huyn}nc0Xx_-^a8KqGQHQUmaV7!WR5EmOU<@7HlLEisKec?d z3z(%oZJz;7_Zpji2N#!Fa(o&1anjh5S$$x>ZuhbWW)q;Q&QJFD>!*P^)j76A?0<~w z%W`ORf!(WDQZWS$LtoGw>Q?vODzO8NX*KPBknh@P&s%P-NeTWL3AS6;mHW~jte$HH zc(X7w;!KZ@Dgol#*~jN6^7oI-%uI{BF8P@?Z=%R_`QDZH_t;EzJ=#KekG#46$QVRUx!_vN{25Z-OqNT=LmG##CPEPn-=ywxHmwDNXj zQ&O_|>sR++Okc3zBCDy7EaCzss(<@3q<8=I9N-J9HTbsgQBJ^+Ea9F^Hb{ihtRg1) z10oP}dq&AHL39@sN)X;Au=n?@!j;$7tb!sE}a2b+64Zi8Q{BIds>pdR4QRuu*_<>mikPWpR4>vCznJaSG+gs7dY| zamoxNzxk4AhORmqL;bDoh)7ThOn?1ap|u2_M~*g?UsGrV?m!nefS#%Jnzzt0?*U)@ zA$jsf=hKrYs2vyr0@$!jHo8A7GQNv%ncf!Dy*J==yqAg-NrIJd*3m2QzU8b)0layL zlo53f6b{B)!s&eALm#0upS_(c>bv&=(3V~SCLKTq8ba__>h|$0 z8<~`?>+{4)b3y#oTzlyU{|42gc-Ei86L(1FB}`8wLO&K32BtBH2H>aGrq+Uj?@I*JlOif`GKh8&)4X4VbQv}|*$FOY_= zM#H2D+3ux+!-Rwo)p*{`QF@PjS=Q}M?<59?1E6*$ei>>!7s`EfQ= z(@?4qByj0R*?^Dbq-IZtOC+9-7b6U~*HcGfye}x;IF!-N1L{J<4k}GsVRN01OA{2b zva$k9TTWH|b8~Y5Rhg2qh)rOX_1?HOC}{HO8Q=+e1lG)waDMgbOYq~X?=v=&AL}D1 zZolhWehToz2Wy6XX##*;m?7hwx#|m?80xmA0YF#CV9;piSR!ht$y&Fsg!jf?w~!xD zCjl@dU?s!WW-zxO;=kK@8WN#^d-cR}EoaZ%P~z=l7_Yu?;lt6Kb?0Yc!q_$b z>cjgI7okxhA&H5ff;hkXWt)`PZ<;tI6NA9Ir9&Vph5;$vNtWJF;{`I|cKOQM=NS)7 zjJKg9Seh_ciPMzWJ{8qrQ#g|Z)P2eSvNT+^a^~~cez@YX38skvG-cLHMXF|O=LY?L z0}LYA)%3qb-HACW=WCK09mn0LOYM-@d;m*^V%?KF)C*FKpedZa?=F$rW~y11_sT31 zged!#M}W(=qhYt!^u-q0Nt~&*ViZ` zOY4getT`ee1yCfN@%c}BBZAAn^rO?|`Q25P6IT2c4FmVcueSid^f4h|=}Tq63%gDJ zPM$r_3^UjI7g)i@QSGB4Wg5TjhHOsZ-cp+BR zCoX>R)h2&sz~+a_z};BO@2mR&RV`@|+`d29Iy5|TTBs2$^(p8=p!Ll8VIE#eXlJu# z;Ib|M4KR=~9Ll%a|0voHTEzoOpCvG?{r#@f1MZxcBR$-CPTL^FMzHIbXm-s^ndL5p zlW1EzsrZMxRS9`#7gw+P8$JUFrHd&aBbW+fA|>HVjoJ3?@9#eeXfI3{aCLIZ7I!>y zwjNpnVlV#aKCJBW(lGY+0|xm9N8FYuzQmQOU1;1juQ~9F^@-IbU1&F#Rwjh_tI=g& zCdIt31v+EjP*oYBd7n;6D7xp5^`x!WF+-kbOQ(R=B1h@KWhAAtjqQ1&N`sH1cN$sx zmK7OfyiSL(y7~Pf+u=>*^G-Fa$D@{EuzE>1Gx0l}P0L_(plUv`%{vI+A9Qqd1(s?DgQ)H0 zA6o?`S(ogTy;H|Z*@IDiKtC4&;66Z${WV}bUd;G$t}i~j2cKqUBLNR$7D;`)uQUC%* zkwBfSWX=vXeK6p2=laG5+25Vr_&Dv@Yj52xRp{V%2XXglV@Xqo!R18Wb56mB&I9Gk zq(%PEO|_Ro9;`GI;Rsi!2bUtYHA-rMu8(**M{bRbg0y>-WINm2+u0$RJcAs=m2P&^ zrVH#vudN1`+bd1^U5_MMZF6jO7$Tv9bSF6O`L!3j`a1mXMFBSqm=wIr;nncy6gZq0 zfrOhfp^<=sSC|5iqoQgKq~k;F8MP2AMb!*GY^<+8nFOlW*+Ao=!cNHG9nbHhCHiQ; zll8zOEkMnnusjY6)JnMgQ@nMtpU3L^Dx_;6OvqP#|H7V56RZ*DB3=?ItFVev`E#(R>3aW%7 zT^OT+2nJn*4%>-{vDgqQ7v%kk_f;_cxYCmWeQn!u|H^~Qaqb!yDn2T^FZY&pVq%(B zSLA*7vI9kqCLPh+XTvZQA!z#||44pkj;K#V!|{lf1d!%;!hL3axj{VW*3+NC?eX}N z0iUrqYg2Wu_^V%qmglh#2Konol90v;1Nmp{<2-fwl_s!Tqo!$He*0t%e=#H3dZNWj zK&Y6>sjqJ~dxcOiDlw>NSu2f*h;Y3cRbZ8S<+lG$fDTwpTK! zG=*+Z-h&EWG>K@?`yN>ug09e=rb4 zJYGEL*$LSPZhk*JTzV_nvUTcg_F2V!soZ~|r}&QF@qDNQ%KPz}-4UQI>g0L#za^!S zV2lIQ_2-|A8pB#%)Z!3}i;o~GdM^d*>POrLB(nP1D3ir}i~b)?=i$!g`-c65AZSUf znqLuW&)TDeh8m@)U88F6qNr7yn5C#aYSfHbwMW&gP3>8usa1Qg_xZi=@%{Gh|6_=`Ij7VOL_kIjsSxESTQwT9 zDb-&q2xiGc8ozpiHmAMkG*b|Q7;(38az6a-!-R%tIxITZrStHFJn>-rnevjG2ty4$ zrx*p{LEf%V6`OXK1fWo@EzBTJO-PdbpN?drpBYPEH%fZ5=g3~_)0e45s~MG5EQVMd zh~})89|e6C@^o|@T%WyOSa5HLFo-!{7nwTw>o9_-7miLpJdT15= zE@y-suphpxYHyxO|J$#m?LJs)^;NX=u$oM%@)4R|3Wg$U>U!gtuFBf42LjF`Tx2}X zN0qT{f^vIa{EIfG*5Hkm?;*m%!e=cTe2;A~k&%&EFJ9!_-N{Nne*9QgHV%U)Sm&|* zr=sMhM?Is5z2`y7r`Ga7y9`rh zQKSs#rqNQR{B87N*yfx^9_@gI5=l|PXvS1cw8Os5B#u-)py-I3wPW&OVJ{SDDje}O z!Xrl*fbv994m786I!_|}=csqAUXdY)=9_Ra6S<2QyoorkdTmSf=Y)I*(!+j*R zq81|njLA7X=$fsyA(y$G84_Rin*hd~e1@N_4E4BEq_fsboYC?^1Sz z$y(O+aQ*mrkg0yrhpzSKNk8xdWiNUIx{!bqEX8rv={0-#j? z^EL?sNF;zw+MTV%op>!Zx-7Rn_gkf$HuW;e#?{u=n%!MalgpgW%;BcPw?LzgViOuR zM?LBeXHVXmOA7pMe6hvjsG=pHH>N6omRE0tZJeDYV)pslcC}|FO;I{&zxNaw)pQ|+ zX4C!p!t~Ie&f@lZSCoa+2r4%WN zdcID95t!D_Y4PIs?V41UrQd6$`bX#e5K!)4V@VGI_{cDpH_OB@eZFS5 zX(M^^{`{97F~@tsHC6I#Fs|_n1jaN*1(n*Z^6By6ihtC4!qwh#<5_7!^?^wL+|Z<6 zt&sa_*Fs6y!lOWmPi~D(cJ>4J>lZKo)VEBE7qk@^I20AxSpWHxS*PkfRK>GbdtMmm zALz`7jEjwRn)`Z?_Dn48Vt*_j7|1TP<=1bleEy-Prsmc9`~HWWfVZBW>;sSP#vb&# z-rf6u2kCbb(Z5htxllGOzzhzv45i_ke+yWOwr??r$|t)t)$1fl=H}F$($(0p@ z@m~7h&H$iabo;Ry&Qt?!cVnD#+ia41Tl7E3{cQOntG@Nbsr|65U7H^$_-Jkm0DA1c zM^4^bcz(P&(TWfpsOj$c+4V(TfVbw|X*~<_=?9sM=DQ314>H$PERt`(fz1snmFr}I zTo*17n*z>&Yoj)eTXR?f&P5(qC`nGHM`&NDQJe5}ZjcP71xYY~z%e>5@wLDqIGio} zf{C7KUPM%SnY~kH;8RLUnu+;K1qdF7S7C7;AI|uZcR1UwocEIhYfpo9zG7iBUp}{*IkQ|IUG9O^JNjE)G?JY)TfY~s*2Ge1CnhW{ zEhYt|e2~gSM@L_gGtPKTs7rry$;ir*K0U7H9U)_ud?YOGe&)60VP(ku|4vkou)5Rp z14?O6M+PRkMg=v_%Hx^Jh$@KGyD!i;)2Al$OD$RU;F8yFicz`y?w~-Vv{n+H4-ZDP z)$dk*zt}2Y>HYR{#nc1Z8kyQ2sSMA#Oq(Y!zfk=izxMNg zSMW$`)Yu7PE+HZFlN}#o?OZ=M8SzEjky+;bL>1vy+CZh#o%@Q$}K%1F-0;Gj%XfLzNc z3tjKQq`ukB#faY@;1!*-H+#@uOJL_PCWXjLPNrV|EG{j5bv%~Od_5X*eK~x4b2TkX z2XDQvQa0)HMYhACVzJqE;?GFHsXOqX*)J^O0O+2#>wS;q_P+s%LM?&hu{M#Qw2Mf5 z@|$J3yL`2YT6yCasF01rG~uIYwV}(ts_m$mC=i#F{>2bVwb~uT4TP6jMhwqrG+V{u zo5K#m@{6He(M&9X65EHo4!r!j_D?VeU@KC1I zhO{#n?U4M<=;+A3#{f3*SVNmFkPR;#L=B>-GD($0d-dW}?i!0{lQu5jN|bi_Re;IfV{QmU#N zs6x#vgK(4JBX|2dLl=xPZMb2!$(w!TBjvisd#&`}92O_<*pSOm-Strzl}8y*;mcjF z(P(^dZi)ccKD8aLbbj>Z9ZQ~vv!4{RR7NbLeZ8J=3JyPUw>z2WMCS2CMzfHHFDNk_#nXaZT7H}LKokQmq6Bs>?uS0!MFO>-9Im# z(=sy`8hy_m+^q_TInDjD6}kOOnX^!9QMA3~$6Z*_bZHMd&$>HZb_Q6@=H>Gqz``MM zM>bdIFnzUjwseO(d*80Zzv#A&HB7&qebAN*3b+no-l2{)^K0%;Xa7O^?h|ysYob^7 zVE)d^%9#t}uO5sBd!Y36Go}pc#3<*Q!G0ZHpN1!~P=Ay`__dtbbFI z$VZPJ`K+~NoRefmNqDk^2a&nCXD3VIY3yc|?$Id}`s>u5=C`FFwp4tmKCfIX6SlP- z<2gL_e0F(F7lxWr>1_jUZ7kG#`hm3H`2Xg$>UW~ zca9NK7Lk&r2{pIyo|LpXycbvG!!;0r%&DM?C*@u7-8;A@!acl49sfN1p8BuKfbElI zDUTcvJ=7x$So9lxt~nq)sI#;4=T?+UMYBZy`7@xidwpC7v=ndcbw-yZsT1*lBk^go zfL1vZX|LUD?D8e{`TJGMoZH0bKpG8l_3!zNQ~e?#NQhT_3>9pKc;|P%VPk}oDa8uKiuw< z-|Y(nud+g8!Vc9!zcYsAnX4nf_~-vd{ktbE#H;OgI4G#Jz2?P>7jhS$bIzmNuUDC` zKip|CFt%)0G{66cd;jml-T8;RWx4Z^Ap4Vu+g;!qGWz68hQg>(`|efyT`%+d^V_R` za-QpbyIu=If`Yk8bJgy>Gc&1jod5-$D0lK=gR|`}r|srE2tUr-(sAcU`>omOzr}g! zaJ~$2Tu*scmh*g*D1VB8q*<#mq_6XCny1!ZMYEG?!dU^`ZLissBsQYeIhgAttMzd9SxXe}xt`P`6H zO(6%+erzCyvy(Fq6`EC>rhf6eolm$l;dWhoujU2Z56wW{**Q`kKDbjRKvBNg-)qdR%TAwj`#YKt%OLh^ z8&|jZR7)pnP03HvFcxg{*ptUqC>BpHGxt-C=jY zlLrwv4#akSh>Zof{bSwW|J4kmr2pkJ=feZh#4#Qw+ybEO+-+f9e9JKJJVx~|G1)}J zl3-1v@AUA;*8gQNX8By5R?!%lWkiBx_n&|WL7J+>YLyvrVJiH_lsnYs6@1^&TbH-q zk~DA!M~B8)zrQ81Wl!|=pT4Dv*M7x|q<7$RFPmlS)GI4|OPe%M=$2+EwHq#~mr#0t z3O2ef35rKLC`#%F*t5)Q|3-aJSKfQ{E{r@NuyqgtmaNKqv&}R=F|qsf_RpA1Ke1*! zIy3Oz6d`FjzxBd_VgJ4vVdzh?%CqLz=$| z6&YG9ws-o7dwrBNYcBBA=sE=b^MPVC)yEo4dKf0Db~sH&jWPq*S@VTZzkoKO4=*&3 z)6PC7euSAqE8W_#Xsuiq9f%kBj07w~fvjP7(1J_aaAAUr3zDKb^k1L!v(b&m;ng)$_G>{-%cwH;3N5Xw8NtXmCirJ>Ne*e(PT)D<(@%$bvMf(OxU; zNcHomJLtQ;Ihk9@e%!ou;v=WE00?^n7BOkrX=!sUo84~j%{Ty>OKn(sT8=k!!!CDZ z!$J|A*mUE&N4qRZsPGpO;{H9u>X~oO7+e9Z|F#7l>SG2ng^}NN6U#{Q$Ie)=`zvJ`48!aHZ-;DWc=#{kjhcR zZH~DpDnw0B!qW$bkwIbp7H#l@7DQEwKAZ}Mw=ViSr!vMk@jo`aD36virplMk^#8kC zU7Iqrh!xUvz*1$&`ukW}g=Gm(71&+29CiTB^{|sfi}8cmFD?$GUHTtGJ**x)A?xb2 z{%-R#{*~Omh1^s#*1nFuTxHe{+uPGK^>6(n>r`2FgsKAJJ`mw>R}Xe8S+<4 z6{~y5NJrQBDrdvZ+i9N$^8Nh$oM2?LJ0iu>DXbJ1eAe)3Krv7lP)QkQ1#(TM)j(im zY)Ikw7^RJr3cXV6{MxmFrkyp5f_3k3-JA*+SvMCjzsDJ%F(4F%q&e*|^0ke6c3~D| z6sbyOYmIY}VZ~d)K(%0WTEy|^NNsC{D(^W1Q{_j5g($AVW7To{@``ou@D&s!FkYFY zk_M%ThIFbF3AtY$Pfo{5cI8sBZfZ!|VR^wAZtVz=Q3xpNiMh?AjITIgh%5R>Uc#=v zS3IW3Zq8n0rm=zXrA3I~o2g_*4q|IY4y;~wP5*A^p*HJK8}7dN!-3wE6dKb7XjS!G zvCdE6RABAE#ZCFVd-u-O&KnnZ^hpE*$jc7a*4B5Ydu?KMRs*`tURU8Ap3O%qPsqO+ zVKZEsHq+jsuUe3TN1dyy-$Nn*dJ%vh{l0h34D_t8ub=MDYh=l~uT=Ne11gu*QCVpj z@KwqR@FU0ny`9?~9=dY&Dg03Q9E|tJup*f~&sjWZr_J1J_nS|N3B82g(DucasJcGI z!8bF9n5&NZPL`8v(DZwPR}WB#TvNUL>4?rw)87g_OgbS<(=N+?lYe?Y@Ribi-gD_V~O03xY2()Y=IW|{Et_7BWiI4F}kx7+qSI8JjUF0d~sBB2rTRV_7A zkA<_|N;x}KuBpYi|8p?A+1k5V+Pjb%@oe_r=}VAyZoi2LSbu8z&7xto!5EV2X=LXc zcC4IG_m6C~+J19AGI`^o@bhQWIm_5kII=n070-bnnv^F)%!N4L&BJ!VI#QXXGPEF` z3Ij@Dj_x!3^kwN~7m-;UlbxuDAWTW?cM);mIs^|*h1LlTM0Xg% z=`ti)`uSb0ixUr`zP_ghnl?3AcP!NA&(|}jN+fwIesB6|Z`kZ|IcoiibM}v;d&akC zMZatGK4CR-WD+^jrnuFm2Kl)a(UymdaBTIk8`V?xdi9TCA{jZ^S#~1M4W83ILzD{f zZ2i&O>FErVkek$XZ_1QaKj)=N!}3L0W9D>P=8UWiC$aRWAO2%tEPtrtwmvgqGo0CG zwcM6nVw>ZkkU#crJ>e!p%z388dxGa>5MB81xZU|b+{sTO$a-BxZU=eZ08hfriA}bX z@89*+iB_!QNs}d}1Td*qhAtX{QesUTO!N8G4cE%Vbalji3HU^dr*h^jx-)GdAp9rO z%PxGT*Duf{DHvzG(doF;Ymn~#_}NOo!(C%-3AS!3-y(m2heu5P zDMv4Ec=+3V)=!jVJ^xS!NKi&<+|CPz7!XGDc0VLkmf{n45?|K0+b!96=zp*?vE8w9 zaXS4s`fro7FGuMsUB_gmae45d|3)$DgJD3nb`bwXzi9n3Pf4;*1*vEobT z`FjBYK&tDo9d`M`<#uQrxVWl{=y}gJI5Ov2d_x%}#U+edmoS%Zs2UT8P)0m=UTjn( znefCzm=W!!JccAm;B(`>O5DIWx&Ft`M6#>kq+ z9C4~fj{d2lHTQ7o*d#vqRjycS0Xy`ohX$Mi%pFD*D99BSWxz!N&VzmDLbAbP^6e!A z^HdWQesLoTNh64n0-x~*K^;>P4ie8F4rHn@{=rDud2|^A-kk6nhO4 zS73||oled3E_1b6lq5YD)z0DFVFsf{GMe@`o*ep8^74WsG4WNUpGp4tdi~e%u)n>j zWuwEMG0c)L@`-2SOYuSGoM>v@@TY>Kg>GS4Ji4oT`J$RwYrAxI6)Gk3+^n_3XVL~k zM;{3r&=Kgd`I$0ef*{fRLAdcu+#t)Z3J0%%=?^Uz1ML@u6v^WvPF`~$Sjy|YzFq+} z_IS*rK_FGo(u=@8?qCp85Do}2%p#V`I!WC5iZ%KzlE7b$$86oOL6beFO@U;=V zt8Z!7(_}KQpK?@}-d#sgthEH!>tJGF0n<;C-v16y8E$j)D}#Cu-Qcm32~p%wa++ojc|I zQm?TfiEq%qnN|+v{j&uhy$&@j-v9Y3k@1B~u@FH5Qb1E!(~xz>&r0Gls|$)nG{J@E zeVd=wq@CxbrG)ana_bW&`6LG{n8_PIaw7|QwHzz%JpXOiqte%;c1*eU8PWF+)I*Yy zI(z8RL%xv9mcg$^SnIMno3jf2OVn@>2AH${VKy~3FrEP(m^}Uxz=2@+0TbA-zEA&` z3z7HX{f_uJZ78)9tP)`h7%^~w~}wVqV>fE5tX-4rK!84_!2@}0_ypZzgH^y<%^5& zE6x_5E#@*(n_5qL6-g#08hZa?>cHXJo#Tn#a1Jq;*0_qY*0^&r_l6)R&U@;o^kgqh zIzv6@zoDL+gDldWVjI%2+9EkQp$3|_`+y8EE4g@EByc^U>dui(>Gpb(w8=~TZUukFp+i_aOohvY zp){lGO}1#^92VnH!CzHd9mgoViHOQaFb+*TOC<=+B7lEOt4$N7n_1X! zrJuMS>=#jyj_p~|oZL2Mq4KKn;t*kvXy63vOU?N2#yRP`%(vS3(ms{?Rj8eoT`RAe zqaT`(knsDrd4N2T04!>=#_8(xATn}51QMle#`nkSm7SgBy%3v2E&oDj@T;};@U*nq z|4p%<=h&doQG+8=s}EDN0Z-3`6x}wn0w7|!%<5&ApF3uMNKgj-H8ze2!{r#S!2U9o z`ZftX?tXyW>h5S=##4arc?buGN%~GJS24t^aE%X@kYpvjE2mm$t6rU(9oP2xR=x4r zu}apoLI?D@t|{GXyg?^wwQ54;XJL>w%*xJM%5G|h(RY=r(cvwE_d!k6D9<4N-%p<} zy;kZuH641pjELzd-t^&@*6ez`FuR+mEVA3G7Zzrf{wI)7X~w_I=icU*5Lin_oE8R~ z`P0)79|WTd%C)`WL7T>dAn@|KeT8_>rn$ zyuzR`I?e9S!>_A`Bm6NPs&FKNT$9wsNyN7)XEHW3X1dy)>au*E!CR0 z`iq_&$V8iV&XI%Bn&~q_mr*vJhU2AE4%(rQ-ggJLRA~vczyWxoaq%a*i{2&{Zlef^ zgh0peC_tA{%IH_}+F-3=$GSK_rN_Gk-syOxh|3LF|6yk=ECCdc0W;Zt2Z?gCzj|co zJg$>j2fh8m_b9M9)Gc-?IzB8IQO=3I|Hr(94Y_MQVcB?AX_HY~>qr51H4JwwSCJl? zYvzLN!KAYF5722qp}Mb*`6#*dIu(AZ z;Rm~Ga1kgL6SXojkw#Mr5dVH6p98YAKD2*u8>^WhsG~~VGZ$$3U(fb;W7zAUw*(5) z5=v~|KDNk(s_$Xy{LKCJS%LU2^zRPi4!`@ukyU~ynmUNAM7@$_I!qeIb#GS#jHZFN|B_}%_$*%ow&TT4yLvH)m{ zpHVv3TQ!p2lW%5aQ4MJD%WA>zogKSM?(Y;dFMK;*KC6JoE3!d2`0LB-*dc{=wT9W& zaox-0i!qId+dLg{X^DEmD&t#%Jc^BVAQ*za_Y)mdvCkJsHTsVS&4$N5qW1?^v+#K; z>7`QAf@-#*MT5Zt_`kS@a)SBAaZgnei<1)@iC)y)7 zZPwtWbC;p$6LuJ}_R!o0br}W{%E!v$^Wt&%YPIrj@J!b6B`=afYTNI|xU!-~u#H_J z#WATO*cM(u46@8}6dL95+!oZeWYN#8rzvRt(-*BUT+!V^{#>!FZF+!23L7tlXX2c5(r))f$K}>z1A=Kgg(n`_e!A742^cM{pFIZL; z$TsH}>*0UtMr;qnqB`iepGYfWLS6j>;hFBHVme?W5)c~9i3NtNs@`o9t;$jmSeVMe+~7o&%<;&uyEIcxA8VHRf2DZ-6>MuMQ zEe*FoZ()QRs*Mv{U4`0(Qn~pC5sQTg6xdaxqe{DD3KTp=FTtt~y@vs*@@$;})g<3_ zP(5}-M8?a@`|MeHrOO0x!pV3Q4Dk3P{Ie->#?zNF0pSr5z$jp1^X*h}&eg(#W9=k8 z6Vv-hWQUpoD}vs}y3K8h&H8UC3rVuG)}}$`LkP43v{RI0spPmlM->^Y{mOmYf{!Hm zLElrwu)|g`2o)O)($LZP$)yD6WAs+Mk5bSHyCmg$-MeIoN8C-#bv*Nf$iN^-EGU-8HG8A6zjf|Da=oWT#wgd{6qGWg zhQUyecH(h%j+=~FpN{8Zt)*3JRAJJHu+SCZVdJk5yvx#Ijn_J_((tR4jS>iOFfI56 zH5uv`hC~a74_|Mf>Jfs+Bi}-e3@w1?q!HdD5Tx%_qiyQLFa;=HoP5Z5m>Y#w?bzT) zs!V+C_uW6>NIGP)l`7mG%pnys@Yeu3JBJwc{#2O7HgaDYmr39-Luca-!yOLJhB~Ex zVdqZP_)q$=L1p)bc5ZS?G0QKcV;Y-a6anKt*%Z-sNXYgnkKmHAakEv<7J_97W685)Q1m&&6m zQYAyHh$*S6FPaUm!``l4DXTsw-dYVUG{qQ;HyZHc6%YQJ?!UOKS0=%Xx7WcfDegCIpj~kfWkjtI9|8ERjBzFSP$v4XZ zg&+PYcseehcHooq@$xw}ja!Za*QMAWgU@9>_J3_oJUIbw?OG<|+t2IrN5TZvYG)f>P%xCi8X+OZw_@?t@1fn-W~ELglpoJFB$wbf#F9w1F3pTZyjwZf7=pijo;c-exV$2$Tdp}Vfb z6Z4;9N!i1PfL|kB@j?glpqZ5DuTw&`4)rgYgaz+`koOe2+Jfo6t9^YJ$to|>Lz^gV zQS{A4&X;~x3S}0xb7dzA{^<1z_v=sA*F`*=WbJeeSX{%&8L)+VFJZS)TvTZ4cg+N0 zA30)^XEiup1i2Be3Z~A~xSD_CAI1Y+Ky~3CJ3Fl?lh(e@Zj}#4XsyTaDVoC|YYgm( zpW!w!Rqj)mp;;?O?7)laMt53RG7&c@Rk}DfRzqmB(X`S&7IPp?Me# z0QJ;-ZQw*6xx1TP9;O7GCCgSt19rsT;az~ZsG{nA^5o=}=yi_lHZ$C=ex6+J5aaIl zW4nU6bo#39nLdn?(gJ{g0xmb#?yfuj@0asuDC5#Tbc6}bn=;_F@O~SgT=uvxpXi%Y z7CkL3^vBAElZiZBW#Vn!7~mONf7R-_TQ~i#ZZHK(qfuL~hsBmxWY+SaL4l{L^L$cC z&Ougt%Petu%BUI1?V0t)5C2hXrP~mD*oLD6(*zpd{5k?bKxj7h-ri=k#_>`SQm;G3 z8Uh@#zU>Jq9E`+xiL#-$-bzgwR+@%jqLS*w#J|WI%-6Y3zlb2Cx9|WJN@&y$P7hj` z>3I4dIU42izHYrGf#uPXqInfUIr|31oNDTYz^`z^Va3o9Nj0QIuY7L#+F&CpB`IoD z{5F!RHLn;}Hx>3U3e>v+=8wVi-yu`jpem3p^6UW|c9+@J@|;2S{0}o$gy>Z6*C$jjSSwhe)=0vIQ~TGthrBs?VRW< zKRGR&qo`Z?LT~eeB&`1#5t!a%p=OUai6(F%#5nwL1k3M@cHCCKEtCXY`*2Q=>~`XSUJ%}lvCjGpGEA{Uyr9B+ zxHBy+65FhkYdC!0t#`HeQ3xKKP+X@>(&Cx3)R1R3ZrC8_SV;jjPGayC34yV}IrN}R zP+?Z^EBCrt`|>6kuffjXf>b(1kY?X98)$e)eS{uP^BR$2l_gw6A017C_A}$7{x7UR zlQj~lK#@^d;ko*~ns;CTf09=nSClf&=E_cKz*&zWQl$|l90X|(c82^erP{X>_1S z5f~zHrlq#2sYODr(J4ciox8h0$1ayXR0xDG4d32y8WjMM=GNLtn`EXriOh5Jrj-5& zWcm0*;VS976be-sc>fj3GD*v>erx+8*BF!DJ%R9}a{trJboi7hMSCmtC@Wih?Re{YB;f*g?U4@5l-< zpm<3yu@ZJZo?%Jr!g5U+%|gVz@jh}R@ZMmgvd%(ksCHDiQm;Nkne45ORQa#%Phnxr zKb!ul6-Be7UYWm$`_VWXDabv$pr}>wwc`Gy^sY`h{M#_StI`Y!g{}M#nhreV*4K&1 zHO>k>O_r$F@(P3~77Ft~P-JMVHvIMH&m?4_Oo>~nC#T*{L74n}*8g>7zydM5xe3J7 zbh$EiyXGd51*_>twftep6H%KzIG`-j*JGIf@@;3X?np5+4ie~E0&$pfR#V+xYGF>m zC{%_|=Sa6%+lpljyEeAO73^QNy!twoA?_sMarx|%l`CWWc*KN_NeD(|JTf?UGPZo` z5LtnL+IB$P|I{C3;vXaWdwC8=n$1IV;_vepOEj&Nfk7-K|MymtHp7F#GIW-U`W(O^ zr=@WiO^4n4KMxlm@++Bj!xt*0BUf||d4h+@Iha0#_s8>I4P!3;$LA{{|4Xvp-t)Ve zzPsHnNUHU$8%xbG6BKY+Y8W|Mb%W>D4zn}XoCR=(vk70p*#|*^R296uP74pw1~W!@ zP)?ANJPfR$pqi*5BZx7QUdwbJBbk>Z=k<-<-C4Vi`V)sDJFD1rULCUEm zoZyE<MvqgL|v5c`2ymvqyHS`E}!&42El47VU{&9yFn4Q=a~>y-OGOTi7ffuX4O7x62o-!ykyKdGC?k-1g#c3tj9A7<5K@u0?ZM<} zi8Vp6S<3-;chczS`5zsI(NLN(Em-o;Qr=LM!Gc2pQWF{Xa)8t(N4Bl0A+^Zc=^bax z59j5IDo!LEg-xy^FxL+4n3BZt!Y_QE&jbmg+CTrTQ>(1_A}evO$~-{b0Td9!(9|nz zlgn}}<=Wbfb&ITks7gB7J)O(wN0szRQ|7tY-Ad*YZyGdP9IL0__a0JVx0J1We&AP? zr2BNTPEmsDP3C6P^W_YFk#9qkc6x#}{S@<_Z)35hn_-rV%T!PQWg-&B=M1)ISU%QG zO?RAe8>u^A)9^}_4zsG&(yW@@OzO9t`L@|uTRYcPN2S&(JKsaywY@Ad79;Ab>ZC9P zcZb?$f#6bvp~k>24luZuO{hna-ctP!JzP-}L=0*gW%5Zp05A)+)O zbI88cD4Imxrzyoz8>^GP5!Dxrr(NjA*jwEnBN5RVr^u2oApMXcg;l#z+b}b0c;c&= z%wVp3sAec#D1j!L1&<=gR)?f}3*-Sz5=<2ylt|!is8+1rP4REZRx*W05Q;lzE_}6H zLlv4OPvbUn%|0#`jW~RAD*@2`fbTt~uycXPvlYXy=KP<04nAj}=}T9N92-yCR$eDU zyPiiRq$Q673r8RItfVvMy6@mROzH`l@7F*bu+3bffnf=)DjAsbo`*tHsCviAy{fa+ zFs!>>`s4GCkdV5$)z!Q@GGa4Rq6FEI4*7+IAbb|lGsb- zy}w40%lw`#xYdIg%!Y7vjOB_*2+Y-!b&o9uhoLC*U|5a~6D2URj) z@PxrhgH+scGg5Ge`e6pE{@J zQjxG?g70!##qWRH{`v1}%E&jz9Vgx%5kUu0fmz}+HqY*STEKpKT~=l>>)c;c`ml(b zS;WvTS^J~0t8sGFiyFq+>cyHeHhtU^ZNMeR&Ad)tqLZgr__~f;uiobs`A(2yAe;5d z%b$A_x5ct=8w&TAiiF2)Now~e}XGtHMo)_WPF575% zK+MuoM$(RXcd|7JEV*HQ8uwNziye0a#+@HLrSH!KgtG8(FKXSathAFQX`J&(`gAPF zMUL0cA|aJ&7PFYKf>u_xq&g@3aFX#s=y7?^tqcUKXtmWrk)Wd(YJoK!WQ&4=y4yIP zB(X)hS2*vNnGuhD5)O^+82N-*ja~!0xtL!0GIV>+=sc?|A&Db^D%8?7K4`ffGJEG>{q#q}kir z+BU$E6T6EwLWM1Z0uwe*4WfAHPJBgQ@T$jEJ>=Xso@y zwq{SP7P9vAJl!nHzU~pvdGLu%MJFRY>MBWm6aSt(d)W3j3I<;di=PG-d|!%fbsrgJ z-mBLq+j)S(!&7{OD5a=0DCA_NZ-LMVa=ri?5`e%cf*7Wdd&*)e#6osne{^-_CEnq5 zdb3R1A4{7xA_funEJ1lx_bKQx^AAe$xGatM)Gbl@&YTz$Ax^wvC>=8@#75wz(EHik zJ@(=cLztePP7Olp4hS*buUt+dcg)_mGW&HyvemDlarIXySu$ypyG}%K-BXPQbV-@-d+NMGLegStX9yrnXI(w%y-@x|Bj#rhzy1HkO*p%o)$rZW(8}L{97N(4tWwhCO^yLS3hH z5+bcWv1#$?X?^B*=N;FNAez}y-zm9aB%mPsMM9psLe-dBP2GG-h=LzWFt9)R4yVonZ^0}4)b2fw$+yVZtnSk&TbI@Q-^Xh6`qN3? zf)g%v6i+Y^DB%-LPz-&3u>t8uJepjCOp8FIL80q`6?C|yCCuz$sT3nwef`ttGP3R? ztR2lACbuzrlW~LLXVAeN|D*N}-wznf*5xJ80e&x$KG5*{TRl5FOWx`73;62AL2w{( zxH70y z^QGN3klLhcb+XW#BRnNCEOo|FUx&|4vPASmnGhV>UuB~s_%pPF#Of2Z;;j7{lv-3d z=66SNDT&e=<)8RtnnRT-`=Zi1KH};7WynxaXt)pzMnGnz#b%e6#1;~^aYHn&(O%k8 zjKB*9lm|K!VlZ5?A(qre$LeHX3nbLDUKm;$lR*iB-De9m><;N0?4+QdYjAV58{wvP zNYnwB)?lKtb~RE6{hwG8V;>ScDxT&yqjz#_K8 zBEIMVLtBb4QY4)Hz7A94zWnv#xk$SX1HJ6Z@zsq#aL@nF;G#?5v-r(Cy{?&ytb9^e zrxJIJ=?fN|mPcrOIHIQ>W%xfdon=5&@ALK#9fB;K!m=VDprmxOC@2j}Nl7;--3?1g zNq56i($XOvn#ed)}^#u;+?h~Mz{W^ zU*)Heaun8M6H{`tP(4{Svr!euq&_ENTm<%nMH?4Gc0po#XdFqF(EW}LZn1vsDG*X$ z)9%g69Tj$Um3uRs+ZuAzw7$IEMD>JlSER_aBTAX;M}BBHW~5{a#d=a@RKrgj+dNaFA0oqY z;L2`OY$%=FF!fRB861q5x$<&{F;^o-Mv8WpHrkc-#o7cXJ>}&oGT;J;2tsC`89-&Pp*F(m<(BKw@DOWeQ^NUmrvGpb82Q8xFA*~4xnU~^ z6`kzLkP;*mJCcyamvs>2ec3$611+8cK!Gj0sS-&P2Q3!Rq;21K`PUksRMr{RcxnVA z9?fQ9ei8_n$if};2=kx>5bq;ca`HQ!vE4)A3%5?j~y~8Am|{BTZiG2!EZ{L5=i-Q8a7f&>giZ3W~Vxo*i$-xwb7g zyVTJ;%J0AGn60<=43LE$xVJ?L9O6};LmNKxpnh$}9WA$c*OX3u|L$xY2>*x53qiX8 zoP6W%I_C6nUq3#NnJkTH6JZagmzVLt(*mSjLn?CNWFQR#*`!)3_a{pw#YN{q(#bKC z=oRVqCbD6Or zP%{ug!Y48w0@`SW0dN5sEen={G%mawG*6L4l}=$w%%;a8C#Wp;2nr5GdpI~gU{=zM zB?OA{)06<73D(m$4?5=O=}*?*v*8j$NNFL6E-cE69vw=bL535ub{C5jm{+GuZu|4& z>Tf4EXFI7~cjr!wlCIVkURNp;AJA)Fa#-LEv$#k1k*YV1tT%Sn)^lSKXmG%U|3!UG z=BD>E{4Zi#luS^O%WOPdo&M=sO+%_z6dqZd0UjUKbed@qA?-HaB<=(a&_bImLC_(C zm&XSuBrRaFt-rDIUCX_;8s~gPr<#zt&s2;5(Jak_Ky#%G7G6zSxjs;^N@k5wGZ}Fy zUB1||K<(mQ5FX=YvGLzxqZ-tVs>0W{@yuW7rDy_jyFE~@0)|2;j3OweJUW{cofxRR z(u=!>5+0 z${uS08u^#`jH22$5Hbir$ASfz6GisH$r8ZYWxTNWr#z9@FaazrANB@y)F43Z6(fkDIzH~f z!eeIv@8udpXjB2s!&hj+wM_;Z!<4^OTwHQjk2W(|KQM_w!&Ox4sh82`oBY=Q{xtXg zhLgMNgzf%Lb&V>A82FsTi&aK{Rej&^@p9K!zw$I=S52*QQ9zw$(_1J{n+0a#C(&1FQRHz_mBf;YO`9L?pZba?OVPA8tv{H6%15IzL4S#XSd zRalhm$z;F8Q2Ug9c1O}8i-S|iu8bH$KnFk}I2vI#dgZ2QjzSDG_(7<-T3Q&|*d3?N zT)7>Jt~5y%Zq7nM8_gh0yrcAx;87x6d|NfJ<&K>cWzKFF4@ZT!yM=QyPaERHxX3}tH@@e~-5;*r9_N3>>$>c}pA?~XJmZ-wFNkSPO<+GK0K$p- zF5}f;Sa_5cs6_>=mgc$DN`lf}HwBHYw0cWpr(de$DmT0%HRbQS7!D$$HfNK-@kXj6;oji>it|{A7drZncJWws!0tTA_L7rqkjAH=P$vz2z+Hx^tkb%i)?RFUq^@Iak%QSlWobhXO zS}?%_5|lF7va#=#Mw8@}r06OT3W1@R<{$uU%Y>1~j3wBph>4id<)H$)L4A8~r75N7 zMX1GflF@=PA+g87l_@_7@G<%TJ$ac>>GX6KVPpkgO;o|iH%LvCqTq1!ur=TC^2I_J z(|v86)LmZ^%2!?%irz6n=X=FO^!xGq-4`jKjK&~Io|EV9lHj7;9i6&|lh{ZeiLyZc znK|VoQ$h`ljPB5!JTI$PNwaW+7Xtqa-#lF-y{izZOC(yi5rBFV@VB_e_q+lI>)e!E z`}hM%&m~f#LLwxgC#1B@j`w%Kthj1Mg%&v`C9gC^0kor9D@u>OH;`3_6%}NYyDJ@1 zw^LHL|2U6mP?yue0kKD_P#n;x0y0G95JA)(homdTsW8Erzmk-oF||SlsWh54_yF@~ zPR?D|ETl@!5$j{H2A={=rqQszyeyyfP=kIb3+AUL7CIa{dfzl#i1Mu#1$e-nCTSD5 zJcSTej&jnX8SXRq+h9VW6)6IO2R05Y{KUkZ$BsAcdYm7nz@P$D)SX!9!7MULvW+72 zU>!gmBqSJ)0K*ZV%Rb;U7;IIvbDXquWK|gK$R_A)stYn$2JJj+k!klqZ{VT)*QwK5 zR*wRH&0DET-d*NNd7hM)c3$>#qr2p~6Fd$VEWj6wz0)?uN@#>(hSq&QQpzdjcqQP_ zB{$mT`p+xLlYDZv!~M%i%2M>tLZNM~`>$wqWpGax({#CykzVkPa^`9bt zA8wZvh;@WDzlfU?{_>4*qa@de8?G&XEO!cz}a9vU7NmkK@ueF;f+MLL&aDx=WuE#T@ zCgAhgR#PApP^=)Pv6CX;q2rE^0@IeA9^rEUxTFdppMgMyc<=4t*R>Ha3|Nqwd;(nh z%d}&&Mu<&@J`tC>L%R@0Y#k;kUL1mfg+9(Vfl_|*&~-|M8$URBprIhDEEo|E=0YF} zs$Jh{Xv?ojSAUQ<`jkwOB%VnjiO+uW_I+poO1dwbby>S&+O`o``%xT?-kZO9mE-5` z?|65ARWBuWH&=*9^62k^P8VI8)bX(Dip6Ss#h#9_=XzLau2%;9ZnwhN?{cmdjaK*H zyK+L0?6SnYHX4(<$TKj1{OiSqhvNd!ebjZVruEnBOrfLkEJP1NrGnFpwif=`dPjCk z?q;XBk<%-uhghQA&HEv`5g8N{1;IX=WK|~$2lW)$z8%p2X`{(hps0aKxqUUCQzN@C zBQM*huS!6QL0nL72UW*ND1QQBNW)2%4^E}Y>vw*GO$z-<2TBGBN6q);$eVT3d={G| z#_XGsJZ3Nuq-#NB#0=PQIyAn`D1M7P}fJGGaK5I)XY+IpgO0Kw#TmOR$CGS?&oBt&ohxnpej*Y`v;9xL4HeAJ{MoOmLP zG!RXhn1E!2|TywpNhE&jVUZrbT$=RBtF1k2+aKUVz=#?nHgu{_7HMk zD;m4%3Pa|XVi|WP+ttb@LeQV|XPY?Rk5EZ{15ee-?_RV^XiZndRG5~|$ZN4xkDT}} z+*Jm(Y&dHsDE+JG(DBtLb2_i>(E`)I^;zuW2dG>I=*uoJ)nsWy9b$6)^M1EZ_#w^d(!*)Qy!VbxE{v*HhHzWs$46gl+_+3rVi-3$s z?sC1y_ezP2C`1g^51aFJ(FCh&K?%r=M+*uH3`782*wc`2(RJ)2kcpR@@3muIZh0D5 z$`|)ME+9E*{$#6*UWL!5HuC)4Qy9k>fF4f?wA6%$H&2-GT<))4?X#hqI$vLX>|2Qm z!Fzaf;dHOkHg$;dMr4%ipxKyWLj2c#!%49@ZvXdau0s~zhkP$D$H&YAuQhxl0cj>R zXtpI&0(9+d?VZ~ktA`CHrS9r4@^uMcQ;7YsfAF0K6Kc9HSg@wmKu#K;=WZ_aTJUoN zDKoBK-pZSbhmv|h0NS6KV?$on8BsvimugB*$;}X&jv+(J_1Pt!rND&rg)=*=un;n; zmsQbumy;U;Ehy;GVZc;Pis(%HVwz=TCPnM9@Qjqw1WJ@VU4-skx~`ETI2VHiTYcM;mB8gxh2wY}=Oa+NADJ zN0+iz|4TmMDB|W+teD1BM4+2?O_LYi?*?-1@-N!UORetDGL`fXv<1enNoCC;SWz_n zEKj05_1_%h$mqiG2^50V3(QM7=qZn6VNpE&t(qxodhKyPUTQpWM!f!G1j-wI02^bK z{LF?2+kw6K3<%>qAx$umPYAx`$V-{W*E$_$w{b)Kuqq@iOLX9UgD;b&t|vo~pFt#- zuG}O943|8kmW_!?mzQ~gt@iGM46{|kKraQBqRg74E;xMBK3XrHX)bS6R-*;eB0+zq zMixY)JFA)2l)=5u!ci7B^qFtv^-65KFTdwso6G-Isfx*VkyjrbT{_p-?Bkm7zx+z= zgfwW!wXn21=RNU_ zue0xXamnT07Aj$o21>JKzD@d9Ew9iJ$-voPU*c_tay4;5lU`#1MT9UtNCCuobpIVD z%>j!-`kcsk-9;XhRVTR?OI-!*K#U66*>sGxt*ev)%oXl~L4uo1;hZ znn@75R=DqmT(`j_3)PFu;S1JFQ(*>o?+{Y~I!AljOqQy(4m=CAK|r_~fPk18e-vz9 z?D*)=D8f@#2b7^zGZ07*-b0lNj!)<#wmHc@5nWd~Qpa`L&h^Gv$&^z);GKoV{T*JM zr1SpV<7R5^HFOiAxhVot*U)hJi=0g-CG}{{yo=tT&HY)ZGh6k%I%KkUyL&b)R&&piH%FMccH zm;wsrPrA#~8S@$`wj>v`-BT=7C`(DD^roz~>aU@)CY+ENOmGQ-mPNX1aDDGV z-AU4ED&U-ypgl8Wi>&hZ_LX$LE|Ip{yt_+i@! zDm=!9&;g1*^$JaCG1MegiORYHP50#pXAmizvJ|#{vP7vTnEp#%k3v2NDW8&Tu^z=B z3jj>Qt1F$Z$9$x;a?MG68nAzo(fzv)A12SWpgww3%ObJ<|Iwp66kB1(%+gOO#MCfE zMF!>-SeyP(eJS5^{mjThfWgHi9DvsbfwZRFOQja;+y_{m&7{C_a#=eh{B~)`k=}-dn{yp(+8= zP18FQDuUH%Eax2ASN+4zc6BZ4>Q0}X70CBdi*e#-N;Ru0#A!b>KH+|=hvVZ0mdIBF zV4!TdCt{J`h5PQ$baAqU9IGdZ8|Du*)HHQ1*aar|{_4w6G}pINF3xXtLv@geih_6! zo#eINGFKcOq_JNkN5!I)st>CAaK3(N@BFahCJ}MC*mjgHO2;qd{42<@`Pzu9h@~KT zYpZ3xrLnOQ-7>pgBY7n3S;IDsX4n50&iu`r_!Hxt3F?(mr)XC&4iU0&0 zXw=cV-SJ>_be~fv#R5hVCxI&Oe;h}Xgh^LduBgFcJK?^-9~~YV7Q@Vf4F<~zVn|Ex zb3qd2`OL{1ou56MlDctKe_G|b7!u|yjtP?{OtwSel`J0= z99!&EaL~tD@HBh*yJU^IE=>RMt@Cys@0)bERWt=DRGLVGl4Ov7lH%@v23(LlzhARU zYtVv*&ikkl^wigU8S>pa_0`zcOW2ZE|0KVTKyVT2BpdwNHSC{bB6=w9{d<}p86{3K zwLL6^LwbF?lAX2Uk?X;u-&T&ZCxHiP(%?%E2&P*+1IY+e#Rq=?Pn}|BUs<+^A(;+NxH{uij68}P-}r=A4^a}jWY~4RCZj)ZzXSN}6@=2kG|Jr|t@B7#ahJ8A zcP*B|7^3@}FtF+*d+nuW1(*<4+@sa1_sYyL{apk@Nbk1Qc4QIZUIb&I8YbV*|CQ8pc;J7y&^b z3`C5{UKYsn^GV^c|Ci@Qk0TV{3JI;B)N1 z(As~5H<%xQini`P@Kx=D31Q_x08;@XdQ6`n@ly=sq5%=%jt>*V*k#sMK z(~7MuomB60SI#xW0)-Vi2z&8n)5eN zBv1SZ_(Kp;(o0o@M1Xw4YSJ)VLGROhEChRWcO`->cxliWOeS&peex*a=-Ml16)PZ` zgfYb5$;{={Xkx=s%T0i;)aJ)N=D!or&PLgxq>}Ok1A(uP_WcOp)<~Mr9 zwV#1CQz&JB7E1F#6{O1)u%)5W(k9}}@#j7Ds2D9Tq@H(=PLIwwEd&b4s9|bgjS}Kg z!tp7!2omJ63Lo@faK!5u5*FkIV&)+*2{|A#!exlh_;zZ@cFt@P7%!cLq_Z9cz9csM zb%cC^lY>LM_uqc32&TVwxtF6k(|)MM9Q&`1juRx#Y&efla|!l8M!qquS&FrNVc`}O zIu($2$5WAPJIW_XFN$SlHp5VZncg#kcYYenVqj>=kfM>fp)oRi2r@TokXHJ8HYhge zo!Op)8&qwYMOmg%EN#a_dM>je8ywpd!4ZYOJm0d`QP=e+1Zky%I+FU*&?=<3VDk37 zgJ24X2Z(~fWO-!}<~M$&^w?y@M%TYJ*|=|hnuy|Ud+Rq^96Zr^n@5gn~t@49BY z|5a|4v*Rk-bz;}GEvImJsILtpLCXUw?$>5@baWzr3;AyfG5YQEQeJHtUnTb!Kk0}I z>6YnQJ#q=Gz&EM|GPU3KneoXoL;$Ia{v6Gf^)vtFI- z2gA9es~TO9Q`#BHFw?Pp->%s=Swc2%(tBtGQrgL3Eg!Bna_@F>eb3Bt(b<9I1$`ds zS@RTL**P(Y{2c9PTPh4G4kyJS0_#Sq%8 zh0#J@co|16hwJ79+5vW;K7&h9E+_Cih}{k_9~?x)RocE$j^JLzt^`rRrUO z=g;>Sw}h#93_y(HZb3cY8;B^oLF|Byp`x-@8yHvJl(uq|(dXhTdR*{VDBz0eZvT(m zD^V zXniBh<^Hzj?k^{@Yca>LY@}fNK&Ar-7wrk6kdu)HWA~+X=h^e^c(f@<|2*+8=*=sD zNK;7@P!55}&_i4fhym=%yg|aCe8invU>g~eul<0dCW_{5eoUhche8VeBn`{wK=^J4 z=gaQOa%M=KwmhjcDQ$^fr*0uzphDCT2R1uR@M*uf-|0eQzaL(Y20oqN@DNQ>5l708 zkGLcUD#kc4>~2DzTpuA?k`QGwyQH<(b`BMbgGF|=8vWXYgxG-MgESnXUsu1-=&BE# z2aFPb|44`x5<3lLLIVjw05;EzDTEy(52zp`#W=C6)5RYe-SXVq4A`?uC6QEUqHI$& zyNmx0Cj0)}M+PD-3yIm97AsDJTbJlb7VK!wzP0lpv#xa%P<)%jWz9#!aKBT;uch*L#P$IxEJ~t@(kx*F++_wVMuc>ZE7kCE6!4 z#A`vDgH&-0_rKXr8XLcTJvcx&z>I>ej^x7(pRC{@r_s#%L8-sTliM=`({6;%*(v2~ zsk_@tGb}_x(OxYTBRz5v=zdsKyRh>g=^Uia>@4bNb=5zDi;(hcBP^Pu&guTHYOHGA z+H=T@F7M4uNX z(aD->h`)a6+ULP;^c%Mvjc_DaxvN2IydI0P|6usEXTjP(Vo9(r;IMo9c8Xf@DTDDe`%Gc#Zp*OuCZmLGv zL^`pzL26Qa98wI(J)J=v!3R9U<}S~e97m7zR@wr%A?Zbp9qz|lPQG5A2d{UEm-n2U z?0wka()cMLAf_j6jxFmWd4xKwYVZ{x7q80_*t5STbsy1nmv5D0n3l;z9AT039u_`w z1wz!hu3U|@{CJSQ$#i{uXmW8=&Lo@QwT<9XO0>t~IlVRL^CU+%xr}d4r7oAzyn0Y? zYS+!y{YkUGor}w9h4IzM>b*~HoA1_$*o&yByY;TWy#cpz_qC|IZ^n10tCz{fZN670 z=(VZ)d8ykDv^jUDX5rEc{VFY}>=(nuxbWt$d8_DIhomT7ESiib!KivTeftEWm(p>v zTS5KYP}FOq7Cl#NlZyCXerfL8N$tGfNIyzcmS)CY(S1w)4hHJ~LQzGj*Dyn1jsXD+ z>G!S3L(c%Z_TX`d^3i?uylPHX=Kxn$|(*byJq55td7ozBy2tb7-6 zO7}*(jlVul5*0b$@25bJ7)vY8Le9VD#ux`Olk{V|SS(IAx{t+A2vqVVLNo&G8y};H z>dn1G7^pYj8>zgs5M(rN%W^Oj`}^w^o=dcsw!4^OPHHDt)HKj3qz{DyYKLdnHl7uu6BAO$eVgb$)^>lY(Qd=y>FKG* zi|Z&5CP~EN=KGlgcSfK6NwkQnP00Iycgjckh}EmV0R~+k7y#0L$tsE?&SKw^spx;eiS@hX>Hiqr@aMdMV^iDGujg~j~QDI z7f!^?UZyo~o&~Ewn^AN1=w{f*H3%Jjdz9a%b-7_q9 z>Kf8tY`orLh`XQt4vEWF(07p4?DF5;_{=#_xYrS&i$csWLr4pH472?;>HnrZi+L7W zHlnv)W2pCyfkV2 z^Dn&B2r^mOsRLAuqHI~RluVf6^WN^t6`ZHZkKSw{+S8N-XKPX@C!USZH;m0aA;yHR z$rEF+X@`Xg2a;)k6Wiy;>nkIHBe@lEJb1HiAK#upXN9^NZkn;~&6!oeJIi+@85C7G z5NH%x-fT7{2xeY7<%HmACCB}KK3GdxGmcjf^%?G&s*_KYM(x;MyKJnRWA6ZT4}|F` z{b+T+8;w-GJveSWe^c7oTo7G-bS^NYUBzF? zmO?}I+o}r#Wz;A!sH7`L2!|V5>j^8ty(UDMnC#4Y*a9Wv#-7HyA^fK95s3OoN4^D>NdO`#h&g1V ze$tPg;rV5th2h?rPBFF~D8_tzaK0mxj)0_L3KEUN_Eo7i+ zh*h`kB8Z&~KQCzEyDEmXycT7tTmJETzx}=Z1P*CGCIH_hIc~<-e?82}7umyftz_k1 zE7sP%5{W|8xori1shd8aoCl@7N}V`IQq@%wtq?@4+-xlM%C75nYt8EhFD|g7bQWxn zes?MLD|k>m#TboEp{{+XjbS3XsNIE1H@<8+|E6Q)wN4*O0Z?iIVh^HSzWGet{J}|$ z4U==0Ja82f6pE0iRC5pak;+FrICTl}4;Yl|d;x^5FFG;KvvK^JvY_ zzd(f|ID~|%fqBuY(m?pM=NsK2wQMqYZHfvd1R%wskbl90!o@oB6UhNg@p)kJd7{`X zxY(q8P-|!(#5=QzQi7i!Pn|La!fBZErtIu*F99#BEGS5+@~>7Pg54}262Dv)G&Z9DZ!;=v)Hga?}hW0DsmxKci4L-K3Qfxz!TnQ-~xe7VDy7aoil2-~eJ z49v1ObhK;hXeIc?XuVBaocSk-1*!oB6174mOM^QsAoyjYLEmpL*+wgTh=yO1GVu#L zGjbeggJ630fxF4&hVe~qobSm|nZgg-MfWxulAvYlTlnj^MBVT_n z%_F$pW;?b?@mE9VlXw*?Hb2eIhU+}%K9c$=s8xEm5i$StG2$qrlvua%q)3jhU`hPW4?U20FEhdQFRtk#eu{7Cs>%$(k#-j7iep@?ch8@`2<7J z085Rig89x?uiv_ZVn-ZIvTDa8LF@x@FJpTERz-E}`MB53?#CI3RmRg%*{BXN3b%SP9ILC8VuKLs<7a69JCzkJfeFh|FQ3 z7%|NCZv?dD1MxA2SsU+45VegaF}#fg#>*Hli|91Nc*z>7?hN+Uk#_?j69)cU#nDJr zwvgmubL$^XyzcjMgHZ?PDm8D3gp97XjU_J=RQ<2-?^ba+@fJg_&bqN|D%=iwMa;-q z77r&BUbMO&-v~u>G!AN$80a8k8?$-I)0D^q>)L2Pyb7TJM{=|JZbZHcIPJPxMjMv~ z*d1)p5-lB~W@;W9-%ftZq_?At8fkdpQApO?A0`jgF1Vf|z0-CTJxJc71b7CxDl5SS zXg=}PmDoo!4#;|0JZe1}Uu?U6mvZ+IXAk+UF*Nc6OY8}A>t7ca}v!xuuIcPFL zgvLSWEI30qMFlzVOkotuJ(WBmBX^G@2$(~En2i3&FJNwfn=9au$!Zhy&I^7Dv40Eu zPD902<&@knQ5``H>^5E4lKy~H95TBaT0|6H2-InFUxTb-8 znsa2_!Ub2nqCUR07HmGy8$zK00&Df9g<^-X0`00^Z%M)M28RNL;wUW7n{+FkhYT<7 zrF@(iofcu!S9b$xE>(?f=-^nQ>+(bA-H`Y_Y09Hv|~xN5=NqG(v)QsW}?zZ&D>{w6V zhh;9)Z2aV4VHKDMDUJSG?tD`{=l3V^gMPNK@8#vO<|ns=iK;A*o`H2SYLDlsNs~y) zo6e5wi<2UnY1qn6mdjfE7%bYYm>2Zk>K)2eoM@0l%K0egD(uii(oWFD5|*Aj9dv?Y zB&^IZ+7$i{`+582+5@A@g4LVk<_lay_q!oKl1j%M_Er&?8_r|aw8)`_h4O+SxiZCb zE{=QejulR$s}Y)h5f8LaU&nE*6T|43q5Bp30=h|`n#wfRy?1nFbuSS5yQ6CtQDJm# zRW3V4CEn`%uD%vERz(|6;y(|E#1v*i@ptqIGev)Q*7XbI?0XQ@)i}$)CyP zH1&uKm(HPd;$cnDa0f^!XI-P>s{rCvfTJT1T?N$LQD55@q>lBp?pH7}k;y+JC!H9F zOmo}NgJ<>88ReBd=>b$Zc8-mWo<^i#O3$vZ&wiX`57iceQ&EHvu+?@YRJ@|9?>?|3 z9(`Cs2oiW5!>lxt_-Gb`+4SAJ9*@8KSuQ-L1f~kf^|da2IWe>eOQT!&1f?E6rhk%Q zfdY2$ClqT&v#L+Ex2~>H##iSPLs60$SHc=q*?VN!)pyEhDd@*#n`|q>1HQ*BsfJHJ zfbjs1m)0jNiEJ$7^<)V_-POM@+Co-(Pd3J<&&4EBUR^wK&L&^HKeT$aPd!pi7^{TK#p`D0#noUv2y>G% zLCJj!B%q(O3l$P@n$RYBTWhP&B<4TL;*S3Q7kn+OWm6qjHlvm8XzJX~ni9bEO39+} z$_d!4&%p@{M1#d2iMqn!XgGbd$C1&II6(T&5~2YUkij?3sq%?b_`7#{W>>A~(e=9^ z`g!{wSqNG{I^lKb!uXAP_Q(I?#C$*i+tdo;JU*Idpgf@KDC@_i%$@#}k57i9A%=+2 zwBYqhwDqGx4k%ao^H}^uB0UIcF)p514e!KB&Np1bjY@o2anuKWolRvJ>;+~YoY_*r zEuH2SX<9<~m?j%yxNi+eOAp^EFGR)7&K79Y)xINho)Io5=M{4YKYlQ!_D0=RmICK1 zb!KLg@O;)sHn$g5d)@EpC^%juVD*ra=jSL%x=bktzLs#8Tx_YELZ;LH?8ZhujVk^l zXX*B-0^2=j7+^tmp^c6mt~A8$apr^z1qf9#l11O95~MlWyZdApANG3q9dUZ>OH7E6 zu#W~w|AJzY@?TTbsqBxs?)8j)ikZ8n_{s+Ple3m)CHGnRq_=X*@?{`9);0rq5G}{2 zt%eWdACo2CL>&2neRhkf8Crk;k?_bB|6uMo+vkB4{st>%aPr+QiDUe7V*?24#MN<+ zj7>j6?q?FcV*8lGaJC=(U^~6}#4y9^R`!@}%)jki`-@)WPtn1d;|L&QSc7o7N z-(J8;X~6E1%lK7G?yZpOeYjocQF6^quTClAZ89_Ia=`tq)Lko6z*qWJ=i?{TT^knM z|IXS`KeyNL;_3wx>(q|w-Cpi!-M*`?0@@GqUwku@J3$G+urf2)V_d}<(m5Yh!vt_ zvr*Gy)eE_$+O_~iQf=dB@IL1J>mn{Bg~xB|e3JX_)#yF}EBYyYMXead4X`n?pE^3d zpH(qsl`deJRa0?i98bWYYxl@2TGwny7_#CpmLzf34wN|i>spmY=zPxKwUZT+`lZsE zZ)s|_{e6%CfAQ41_tTxAJX|a2_p|f&)i!4`{ctXj4+KxMEP)fBFoc%;1yxI5JvjlG zhSxWxYTsy~&0{C{4L3tgO`M=mT=rbnC;c7HZ7MgdV_JzqMP-p6a36&nFKNt`ErLFA;?GVzk|E3|KJVRCX|&c zloe5thVkx%rFYG}JC|wku;Qe*vtw%8*<=m{^(r^}nu?}}gYNE9-ln)8&e=LSz6mTs z(-=crSL&_eTpmipQkbs3<9*wGWfpUE{~gcxkHe~^t;foH6-^7+K zR$S{7LpfyTeY?ods(zv&4FZLqmBde1ntku^|;P|sK%@bdxEJo=Vi)D!fz%u z+$K@6d;Dd8f_v;}j+b6}DY373$cOUD_D}Jw^mNfbKCN zZ1pU`jPK7>0^+xoBbP@1@Ry4vThbEtncD(1JzV@REFMp5vDUea)vbmuaVhpnOY+O{ zE8#O^@n&thn(>2!X~!S;;mf92btZ9Fjn)=^Q>w7euVl0MxgZe!S~obm?Q2^>l3Uty zBf7Kb!#phH9@t(DoGwvI8ySRAYi*Lop@ahk!Cn-VP>udnf@q~uQ47wze03;3BmYt| z`gxx%2kYsrq_3mBKi^9BWOqbGJoO@WvDMSXQ+^&7_xIIT8tL;1g|7}Z&x-(xunZ?K{v*SLoO}eiHf_-D7R_Mj-ZT(#s<-vLVKL zdg+<;p7(Jsm7Y*lD?0hcx27 zs2A@Fq10nxR*2*_v@%)-q*snxol*0{9|t7TMYsvp5F2G%FwA^BGd)u6 z=fa34n=0MV=ucOFn_3~E&w4g?WSN*el$G0Ff`kJfl?xn*d7HA{i7$C2YbD(ENU{^) zP;6V#gQ50hS`cRWxnc(%ZygM(CkBn zN3vK2Ln*4C9G)CD5O=5iF9wrs^cbbwZ_w6=IVsaiOL>|U#$T1~=pG6kwO;4+QN;~OFO-pz=$+6@&DHX%>6JG3iqz76{UNao<29$8t|}h zln4TQLQ|_ria{MB57UfCAo^mblk&6pNO`xsa4(c50n>|7D15r1nzQUs9L12kmHhkW z#vn$!O0~E;(K0zPomk|Uh=x3ER3OuMuEow`cA4#C!YLZ7o^3=8meoHJ11S^`{2UT9 zOHD6-OcvQ^&k?s=I&%`YzV4xI{q1kRN?dosV{Of_;=@>b$Gcm+yAP|!X3=6EUPqC_ zV}2!Eqv;RST(-wwix1cjg12fWe4S{a;0XoI;&C_zkJjW|C?EZpM!$^Gc)Bfzq;?$R zv$*G5%l>3}b>EbpWGf(Kp}4HpujSJZ6lnlHURjFxs3?RjoG&{{k2sn`UHUF_SI4&T z_ti3yW$}>SFYHtKr%|R}?}8%RT|^R4AJg3r7h1l2j(6-HU3~WLxv-}s=@SBW0J*es zd(FU4o?GwZ(Y%PkBPEoo;i&&#Fj5N&3Q66P+^=PeIj^;&f9Qj)z_sjXW%XX{*ccv~ zpZVczXe-rFP)G>1b#wufq;=hXjaH+?kWO#7)-|=ZxEwLk(2CUIe@Jt9N1w+(mKjy{ zdfcnbuG}sGpP$k~5R2dkPkwI#t?)O36lz2FFqUST4R3u*uLSCB#~Phiu;~GRQ*B4l zT(Xh1dET!ctxsEt`minC_p{6}6)3)2L&4JYPi$YO{hm1QK>c!QeCo^W47SWAjTzMn zs|y~b=mQ1*G_h2#LhRNdvQHm;doxZgtv~!`DxW#1So&q(;O?8VV>Z5=>?WTI1)vsYnF-f!6ijaLYqpjm}+j;shusj`(cu^o* z57tO6hO2yJGHTnqlY|p6Qeot3uE;k!7N-N_t)#A*u^&vhD{<%Yph2KO>)-nRgvnU1 z`7x_owrOv#9_8Nt8Dp#1q_qlZ@v_pBc;@$MDU^uO7HZGYH(2O6@b|>=^@w=%Hz}Ck z%4rTNhTaj~3v;4<=Tj#z*vnM@~QXe*B(b7S$ zyOMy@`hpCL`PswdhW}zTO^Gc4HA#;;ocH^4gJl!H|6U}<5q;Hm_o%8|dOw(*+j2f* zW#BSqcCLhN#+GMd4rC5=D*?ZMO+KbJaIbZF2(E1ia)|nL;20<{|ITvD^~WP3mVv5Q z%4kQ#5>xT)*ls1Xm%`LXt;Q(p%7Mb;g$3t#Ht)QSyaZOt5P7`888h&Vgq_jw0UPr& z9E_G=^62dc&B z8<)0(4DE_)Tj(WQu~#{#G_4Tqz76nt@zyXD2e*0M|bM<}LnI&LC3-*Gt{g z!`8u27N5DVH3ek)$n25rgPo_3&7l8y7@K5K$6|yRlZ^AXeX~na>(vva2bEa>lfIoVI zLY&jvR(@SZHO+1zXM|%-QCE0|CfhwG-70y@sR`{ZR|Ex3gBW7 z6{p8!2_ZEobTUiy-kr1MH%m3pt)#V8q~cTDdkL_AQY()kYZB@c3!AWQwjZDqkSu*)O5CRdy z9Q>Jdv%97DiX-%_U!LFC3j3_*Bk(v(gcX?;5~XjMlfOfM)bZF-J+tC5U~2wxta3u7 z;O9d(d_Jf}V(nXoGndHmLBvPraZ*YUrWcaJDVw(C-v6cn_NAl|;rvckXb<$kS z86M#O$JAejwbeyi!!Qn|xVsl9PH}g432sG#OL3P{+)8l^Zo!Hdr#K}*DeewMgHtqb z?sLxbU0?DqSAOle*IILqHNTf zoa6(28YVVuxen$0pN~CJ-rzP|%XIVmoxSWsj4g#BQI=WojFOb^>{NjmJj|Uo!Cpsu zjyV#S=g>?WuO&Y^N$(^wsvw*}193p7nPfkG4V2lt6)cL)H6d^7{7FuJQf@#$V<}>+ z26GF7B!=MPksP9Py5Se<9vUE;%Y$qSme+p6mK!e(nAi83pN-SseJJQkTdj=ORNUAwO#3vlV4nZBSTY!j%>HzTFIITSJF@+#n229N$9Olz%jegP#+98I zcZ|1?Ov|n`cx3yhFz*C1iT{pP*%u3-;gzOLzG*9;+=j)FTeCX6kuzp!hDgC-Gj**V ziIEP(=>S&nGDW5%=+PlBXko`x3Qj^0G3B!nk-Vgd=x3;y6+N9ojG%O@k#@f!|| z|F~gITE9W$iO2yuxiEeuPt9TU0u|4Eu6i&6?D64=Ac=tAY%r8Jni!=Da&*U*klYxx zq>+DgZ3Zb$E&+UMLkzy#f#i)p3%mOOM#$on)fs+-w>Qy%%q9=uLwB0t%RKFK{Z-5C znd*i$?7rTJd+#CZC33tj4lHtcp&>b_&za?>d6 z2`<(<=~`!R=)QUb!};I6I^Vn&WLA)ux5{-Guts09zrSBT9FFZKOR=d<=Pm5%`Sm{zBOV?TfnccurRlZM=j4XJ`Y zafawI@Re-<25C)ZMkc@Vxee~P3WIvtG@|ABifyaMPR$fifL>D(m<-n-!JV?T{Kq*k z@&gAHJ206kU#Z&Blr zCfmb=hw@IGkNoPpVadh?YL13OSPVdPLc+Ql6C3`WUuKJb@TpNqsIo-zeoBl%6Bop= zm$M`dJf@nC%gA%y(5s{S%q=R9ArllCib=p9t~aJYQ8>NGqW&VU~ zNF}`_*%7`Yktif3GI0(l9Cy~%G=afQVDyOuu8AIdrt4&;3;;4EIsOvFO!W;u|MDjR=ehw_-cTvyR?i90l{3^5JLoJYC+R+4uT;yvE{W@)}r@ zKCNE~;y(gW)D;PdFV!89esAThACc|dV5k!eURiT50K&ef6Bh(}MfP|F;4nh7V>yVE z#tXkTCsIcRekfpVp5{9=!-TR=fWrwsAQK8uG^LA8ugL=+#1D-r#PGZQ8vke;7GIs3 zfhUJJqT0G@d8V9-A!2wwLCA;s)AJK=3DYLM|{kcQagr+ zz4PUp@uWR51+IDCkre?U6d0Oy(Z*QxB4Ta%j^ZWox;+$yy(ILNZkl)AgM!YxUy?tH z0P?5!Nc#t=Fv8IhV|hL!x4f^F&c*VY&B-X6U2?jeB-qyFPPK}56}9G(!^U-DB-BL} z7JDNT?o6?~H%9g=nTlM@nlSo4SxiAPXF+h*RpS}n}$k4yDWQQ-zJjRef%^&hWH2=q+u@5Q`nx0 zAAT?Dd}Y#(AecE{?}9S|v5VkcMR~b5{qWEB|Jy4+@zbQ(Go?&^B3GWTmZ>`erRIoa z)rybi<~CF&&@2Ok#!5-wz5?$zvi1Ov8*$JBx8k#)L&@ zW|@&=WB5amc#BP}j{8&dcumHsTwDIxI-+(UHWzQ^pp!UFiekw^q2&07*?IRXOB zCZ6Je1UR{jcWy-y36v^cOUl|0320wDy6-(1-t-xsHw@i@x>-ncbcSBZlOMZ=(fwhf zp|Wa52|%TozgE8uFu4<%AXXRh;>np0r7>+&oy6zY3tRmqpQ|E6jn7LZ#j2HW^##ZQ zFh3~M)XcAzgz!mmI%^D*7T4Rb*tnIjLs-v_vym~iW-$p+fvx0xtPgwNajIR1^3onadY~- zAu9D28>Tn}nt69YTo~kCG^i+QI~XgiRUl@Wd}7v?dma7d3#OeSV(4FU8F$iq>JOHV z48-a1$t!!&DJfFl1a zls2Qxq{%X?nd&DRWn-Udk;dCt1&?OeT}vNpRDAb=xN1Z++t?Hllp~&x*T~w0EOyWk z{A+*ub;LfJE%-0D)Wx_~@J`#R8zr_9ZiijG{EV^B;kW)&7j~u4pt>}a67itG74QpC z%DRF=BO(BDT6{ep6u9RR)TjfRDDlVrmubLS>p3vnQ8m_ zKKiVGCn-z&C~+2zYWRG->i)L^<@-9LkkE(C*HtLoz8Lnh88mw5vBeipq*Yf!pfInF zEnf^~8T@E6?lw-VwHZaBZY#=}V-A>C(CH8O9_gncgd#tcdTn(#1ep?vac0dHaX~7Wm9;gI0R8~RUO%gmD!_09!hTRzDN!^ z|Eca6I6Z0Ry5#!CbRGjpua^u1;7h-9(`4Wh39M+{A%Y5-1}k}e$~J63%+ zqHPKzNtRd)pXS|i0Cs@yO#Km7Dpw+$~;f;gH46csKvhS@QT!>I~MG~7$ z$pr=?LVt{{dlRU9$@$DGGH|Mv4{@NfSGTgBaX`yPG5`>}*SqHbfbGa}jGjEU@ z^q5Ofd5AjNIZ93P{5JmYgx}l#yUkeGb-O?aPbvTD&WUs7P z8f?Gcdo=2S_uew^>cCx*dw#!Fo+l`5JWt!RpkN34YVRAmi||t8@ha7 zn#-{k{qT=Xj`3`M3pAP+SSvN;6_BflaXPqy{}0i!(bYP6i#|>hhEsdga3(a(D{zW23UHBtM$RTLfFt8hhBge{`#X)Gm+HiCE_gZBm{Fp60Q zK$*JQW-(IR@e`<;^qPcKMxbjLwd7i7gJr9n7CDz~OUD^-t(^f;=R*H!7v)zr!?7N6 zG6ktvVby@^7}I$&$PjK054W0HrVNM$gf)9`b&@oMCFW2}776O|GjCh4d>rgSQ|dHr zNJOi#AIOu*`fFRB2)_Po`%+}e3TfkPAm0O?^>X_B&7|_aQ?CA1#`I0oKEf-#S0;&s zNF&_p7%#Ux^d|DxtiD7=!5ijy0y%G#U%}VJU|{}yb0w*esFebwf*MhQsRNa zQUJX_pEXxEw++geJn{SU&q(U(!5^x43*2fqKJ7l?n!O}F^<8$k2W|%W2ht+4uRog} z93FI0f3BnI_SoDRDDA>loSPyE6{upn&bi0c{ohV#S$&pYjM9J^6BDf2LSAJ9dOtKa zH*(@UJ1)$f`P=(F0{=Q%E~i9}vQ6EP6OyO#47C`v#~mUS_r?mSTF(iY;?2(Yo5B}U z!UQ%H)v_`zO!5=s>+;Y=-w&LgBq6uP|%K?C5=DH18ZRs(Ta0>M~rtB*DY9)Go zpQ;ll3Tp>Ikv#+MVsx&h(Qjkzrz~?ip^ttDx>&Y)TgwX>4$KJl&7YIbuVf~r8F=(m zkCExI`#aO)b8Kgt&$ruj`VS&v->ja>r6s6)0e}RE)aAVpz9VEgs~=>Vr3q54;VN z$oN%nzMI+gO8I;H4P1#!aeBB0*k&)=ik=Y-le4S-FLonxVq|LCb)77B-g#2rT#Te% z_eH-!a1oD?Hz&uYK6-H614Y~$gQxYX&2vePNbph}^G@L-+_psgCogXra^p9z4MHKU zt$Zz=B_548RLOBg^68$`RVq~KNcwJ61dhNAM8G>ejj2MQ6FB?L1tbx8o`1^PiWe6f z@)Lw%#e7If`=T#F!TTGl&e2W*)wMzl+Dzhd+y0wi2BZWr;dj z<6%|?5*wbnzRW_q3C6u`w*E+T+|X;ULg)TF>0WMZ*L7w4(h!8iHD6Ng_PRZ>^@5H1 zw*qReJ^Fq4X%c0cxe`>BpFK{BA#F}-Ajj6U0#~p?&K5lImKR;8`G$Hy8$DK(Pj8kL z6CR1=lqqs`>hyKE%1H-%2+Y7nv*v$}^hchKA@@_fBK^i1m21BEZ3k|T`|g-Ickuqb zx%ZhDD^ydqr%@!Q7Wa0=`McNAOr6L9>A~o(ig~;JieY$czG!P(cgvhX`2PYcDVS3o zQjddh4+Wn^SQ_+SG8jDd9QF}FjKzye=S1LY65Xk}&M6l7Jhwfl^oIoI=pN+i?Zo#$ zEF&uq%+GP$II`OyRL}W|;yWULD$bYBctK4ktAJZwAfFmuyzdh~cSvjLf6vnGWd?Ai+Ynq*~Jw*~nnrTyg!c zZq@_RLqtFvgLYg6k^=_C=V-RMj0He#WE9&FTdZ=GoJd_wQ?07#TR}unuy{VEx0~Df z@S?fj1ZTUtkRZ*t%@JgfZ#f^Y3W=!MU!&jM8G(SJD~nTv6#+!--uxwFZovd03PW!C z{!FP-B>?{81Y@M~JO^MV2u?-r0F_-7a;O+hFhOgw|X)Cf-jahHxq@ zKkh~H4*53F{4QAr!nK~e96_D$oY^sSy8NJyLVeh*9w2x)bQ)Vw?!vdCs)&pQR>ZA01}ra%0;6Sz=-|e1nSMkg?`A|$*ZABWmyKb? zMj>aOEM!ylF1jFSnzK_Pbq{|fJy#x##MfBGtOMXzbV$dW&;_e9r}0oM6lYWxq>7uN zjzPFX$JJi{6+oZ2&?SF|*y8$i_M!Vj<*=IFK)hRDA<;B@h|M9EMdYh_n762H5wPuk&H0D^DqUOC)s(VfiF+`M%9mnZSh#f3y)#3gE# z20pe2p9q;>-PH7c);dZ}wObB&x(~S-Ntxz`aC32pAE&^+>}|j!bGrPr`ZmM5am)Uv zE!~fk-xCVoi{m~{~#S5v*v_=o`-`xsh4UkSDcuNl{4RlhiLa7JMrvo zx{8ofEqLq_+=MIxFfJc-cN#Et4eAP7Ja2fUy!x^?A>TwL?6GACTkm^1Z15lM@mr6= zbI4o%0=x zUrjIQluC(sMN|i4Z7$*>yh?;&=U`43AiO#5uw&-w&j2J&vg6G0QfF=I#`+eo6>CRh z-9w|eTa6g5nBm~WgG7~@^IloY8Ocg|?yoc^Bb}giglJ?P#I zfx+|TcG2>3uF@jpcAj9r89sE3zV5^By!xIKxPu-hf_gSeU)DuTAFhh?E&Xoiq0hTg zp`&6Omrqdt(MCq4HlZ_`Z|AAtE)2EHbHr>&8vtQK8p)0h9YPmPp&gD`$VHa_bLWU( zHPY@EfyP`(4w91wV)bYBL^@`YNp(ngek{X#E15TV0@E#=RoculKMoPR)rBeD=XW^R6k8`?b+0kKVwxZi^3DN#H;>S-!#qy_y;^LtiAPk@1Uxa(Un8 z^9_sx<9tqoB+}sdwJ>^uR%+U4_!m%bDT;BXu@6LJ0XiDcb^u3BXQ{0BN^(FSJ zm^CmL9`nK~&Ziu~>g4bThm5WwF$Y7YB|aBtSj<-)oEe%iWi*PFU4>{>A;ZGB!z#*k z;*Bj0HnCkB=PR?4;{`ARwMdAFFNY}yRaz3wne++xc0e`;b(1_b2(HW$0%VcmPen5k zh^G?v(B{6|yu$15Lrd?Os15s+YSsafcK6MWw{Nfg)+Xg?(#H4p#?uhsWSwu1&LJToUS4UjcW`L4 z{MJdt>&N{@kmd6ZDYE}b!}G8E-c!4j`|V(XG6iNrnT&8ZZmBkrjg8}_r6pw?cKJX5 zW@|nxzYqBGK_r=efgT8A+5M(05I-dP;2X$54+Pp*RLJ905XfdHGkpQ)M|WnDF)cK5 zm2>Gf6|#=$D<~jh`(Pt)2F@lKhO7%1nuXqqxxcz!u?VdNO<91vjNP@dNCIC%+c%GH zI~Dq*#?T<$Pro}hM1X4#S=rza5WRi-HUI>di-+9%EWWI)Zidck2)P2n;ava1zOyzs z8U+WJ)NrT+30?sK^4!_6aDsd5qD2rq$u)i~tI21jms<(<6(9GUL=w_KL-?)h@5258 zU9T1Gr>BHK<*-=@&2x!^Zw>cDe)Hxx<9p{-Z{R^xR8*z84*&p28*ixv^YgC_3>CP| zyuWg5*yQSkAA>XsZXNrXVYhNHIMsYx>UF_ga=%*3?m+4vEo`?k?7-e4@a4Aem9mdl zNXQRv#NK_82Wlv52pT-Gyk1$9+!zf)!RqDc8Hzd~Zu7I>_W5s@?bWlY4LBz;&Xlb0_~#23=p*fw+GkL^=6;9yg# zXQ;R_hhQ@*&vcQTWCjF&YHAGKSsM6NKbh3@*F9XqT4H&P=iQ-j4&4AhrYSseG@uixg3kADg{1h0jd{s{A-i1Fnjxr0C@!z{x- ze)?|1lTBM&Al~-fi`2(wwD_&<=*)Owa^S;&zghW5&PY7`Io_cD)Db7q0?k2xVP9hl z?@r!$))p1a7F!86-YTc6N)yfU`iV;i_#Z~n#%*;o_ig!e)tQS!<=v#gk5Zer_0;U_ z+(F9|&90@o@-1Po*G1T#RxjMV{l_g|;W`*0$qEd2sJ&nJ+jI~Po_DrrenFfp0yF3? z-m8jQH5dG_U=z+pu^dto2<~IEQ`x{Lva(!%I2tsAA3Gi ztqd#8Q6;SLCH~zhCGhTeKTa#LL>`G?nIe!LfmcxvwTNK=IF)slxfaRG$B2Gd16F6y zikqPvv)|ojU9VtM6Lx0D_Agn0KU7<;$iU#2HLr>J+W<{VQv>AG z#_G>Z-@Had4kJyx?x^0?d}iS@gy=1>K(VIqvC@%&%+ctQx0hPIPsp2h-@@*SQ+oaG zMc`hcm+!i`MCryHK81F60Kqxa0&}`Ji|#!VwVEuWV7>c-fq$S94<8XpoqUeFhTBZE zu&{|3IS~oiN+s9Xs+tP|pD|z5Fv`0Ge03#g&!Jc0kATB^^SuuORq^1TEsZa53E(X2 zKEGyVW4&Uj&VNhGRt>c2+^b?p_TYiF6jSo0?~2e&)KvL&c&|C z5g>Dykjh@NQ>yE>`{c2R?QHXF-*O{_<^n>@EUgmOgFxNZKgd z2hidNC~b%dkdY2~fS@mPqtK`R$<3?W!oPPThiiTpf871g*F<7UI%XboRrKS47d_`z z0e$35CwO1?1HuBLP(N%y`1*c)B`zCGV|jhndSwOE1V0iRS0cD71QPxPrd}*>M7_N8DbIIxwJl|}0SW+LxBm(-6Rhb{?w+zbJ5hS8C?IL)G+&*XKl-N)&u zA#!}eARbEI{;AZCeChlTbiy{wjH4Tsb5eK_`HY@i$b9&NR=r#4wr9aSKRDDH?bGxI zai14A&6j%G+yB4@+g}C}EM7Xz4=q8Hb?SmjK*b^XbibftHWtbg<4U2vCM6r5BDP9} zFwiyi*tJjpucRpR3A>KV9@xZ5yhSlEHkyOn6G71mSz3|q#*ZWTu*Tx@2=}!>m5wBi zcX_T#K1s#~Bh3;1%)~+J6P@)nVAb_LGF?~$X42CI1^obd}&0`U^@cngcbd{sA>S8pGb~$2A_Dof*ng= zCbF0wOGZgYV@6OgsWAu3AG9aaB#$8}om- z>J5UQn4sW8kb6UGFSNev{IOK(c`)o+PwHjkzW1KEA$WLbXvnX7?_D39P$_)ad++Mr z1y`yGxvY77dSS>Xra=9F28|y0@O;#x*@TG+_MT8!wJ8U)Y+|X-c0Neh$LTh+)x68s zENF6`)R6aLs9JB>)iUH5Q4=LA%TQlHzH4`?D}`F>wVR!5v(x7!Z8L|*vm^}}OKZW! z1>kc$bQ$%~(Zo>$rmC;IH88MmcPTJi5^T%F`+yn6M8=rUMsMvC_HOqv(N?u(K~y2H zsEid8xt64gpOE+~)32F}x3HJK@xi5s;}h61Ec9NZA>nIo8yea<7dqp~5C(V>Df#dVZc;gAAlL1p7XW%|L%Vh^h1=u*B|C z>oC0yBSeb*;@*015wf2ucK+5bg+GCpqK;y?sWzT18LgP=7Co|r72HH|^JHfn4W__R zD&~*_GzEeUhzd0A;ZFXA|Mpmtsm0nHXDe7}C}>1H_m(aRgYKc0eY}bZyzyhnXRBdb zF`*Z|LC}E3hTfAisjE9U#8(+Jgon^#Qg;F`*?-f8`_r$wu-8KKckcaqHvJ6Q zH#ED9zzx0l??}BnTYG5kyLihTaHLlFOH(q>fynBA6|8cDsBq~Ri)Q|h-6^s82MtQW z(~X|%qudYacDKv((=6O+)kovzVt!^WuQ5%ZK5jQ5XGzwr_a1_tG7Sv?Ow&!Ac|y~0 z>ye}N?AI^Ct=~O%{#~-v)&KF|SsKTt6f^-4MgH^%2ymM{II(=qjmt^Gncci;(<`t zynBloQ1+UzRHNg>+)Yc^rqt_8EBwXot*Ng-)XINjrz&pR5c6h>r^~gpU*cazgZ{9# zy#72EKLZw8&-{#sK2fQT4pAhWGl)g64*(D=u&Pnsk;w)-2}na8480-(eA{*p zoiN?F7!leCI4qF5EQS8F3_U-Te4I%Ek&D92wss!(-Tzlm?%Pf2;S}|{=3y=LSR@+m|8gXLo8=A!=h`o~xtekyh2oA@D)gC<7B)0DH`jKyI<;o~*u^m+=HBM3P4=s@R}fuNi7Ez0EJZb5D*r3Xu0{nnChI!|<3%ae ztJ}Xl_rbStmd;7WVg`YG7!19>=RsrD*WJ?OsGX&fxe^#Stjh0YoB(uYcRucRZw&!G zb=&dYWog1wXgp@mCx8_u*Vo21>{Gixr`LZfO{}~3g87zFPeOF4g({I09oDmReW?)C zzXw3?2H`5fz1JtSQjf>KrDvM#dXzXy3dUHEk=DZMy~2%{#cXoMMj~vb#{81|5%6@2 zr-{Dj2{^RZ1)J1*nX7T{JbFB7sJzVN-nhz{4n8Q5y5@uayQGEYH@bW}9vV*x{x?{l zS@~Z&$RKU#)+;(32ljK{=oWe5*WXTV2sz`H{3nBeyWt13giUU`the3PxraD|4&iV^ zAKdn@&vADIehn4`?RZKkd>Y6L+X^})B?0YdN;?1l?R!yU4*Z>G&VDZIO#!gpp6Tz7 z&FfCoKTdV=12l6iPM3R5-uK!fatz4`U~G>cE}-ZRd-~YfeRP{@H8JenBTn(`or>0Xa#ZaJDf!jBiiTWur37}S+upZ@=Wqso@6$w4vmAV6&H~cvLBh-Bk zdz!Hfp6LsFy577I{B*vtnlj~Lp1s`NY<8Lw&sq=X^OKa4fyXkxL0Z zZh#%A6+Z2;_gz<*2l?GD29|Dn@KZ$LS!0lZ$vE}xIHKvl2!pMSHC$J2=Ta7Z7A;|7 z(12;nkiT-c)Z+g-rb8D*gruZk_5X!Uckd9NTml(9XKO43#3WvZP2F^S0@%Z55-hLY z!W)|DzVptO7J3HQBg<=ReDJ|+;pK*grY3xN=-It(2z$As7Ly+mY5z1B9dzDN$u66ON5NO`|+QW|Iii8f2_TM5;W_7n|lacHBa;r>O}$XN!XU zq3#`jdGMzBr!T~1bAMqUD}H$kOSlikG4BxMA0mT`wayJd(Dml0oaxg7y)z~Fb>3I4 zo-HpL|6}fsCZh=Unwn-kz4JmLN@6QvvR`X!Q^B2i?1DJn$10f!#K`A6P=KSkNP7006cXr+s5kVE`52HtZD+ zV;1&8pB&Ke56!yPC9g?`MDEWmpIXUm0@a$u-P>1BOtW)x0!C9_mK^w-$eP8W-lEgh z0;xX#^>-I8{Sdg@yB0`%`Q+Y)XRFrYQtE`BZmh}07YN)P!9IMvwwjDi8P-eaY#Go+ z!D-o>*G&4|B8CPqih}%H(M8hdk$nsNB0O}-BGA&t^VNF}^@fK9U;0aeK5E?Dshlj5 z8G$*z=EpA-0O<_YqQqM=`dY&;yiJ1i2#Km-8HBh4g>1*|cR&*br!r?}`XU(={wf(p z;&f>NaC}nxZls-KST_l0-JjXIK82H@rqHf%>g_LkU3R`Tn(bSKd4*{vb59n&#k7tzRt`$1=QQ^e&%#SZ0ops&S-o3?t z=kYiur*!^r;5qY5yD;d@&o>AjN2#NlA(vYt6MlX`<^sZR4Bz#0gFhoI&DD@%8 z>ji5X1&RI(Jgitw35PadZ`&E}GY1d!G85O~*=TOM)2hRjD8uDcP}D_iX#9X)Bu%o7 z6#S*(FZFJmQ*q58=dw!5@0ljsHU~Z=;W))lv7GN)X;!i@B?sOdF|`=W^2o2!k;{HT zvsK9;h9qM47a;|{QPgnytv2V)i(qi`1*l7ITb-|xg=hz1pMdDU`-UTn5B{Z#a zSuv$-Sl>{{G z+X`M-Qx;fMc5Q51whT|^C)mvW_K2_oj%wvEwc3n|h*B4r3%YMSul8Mw(KU-}A-imz zO9Xb7y<@4xek450yg}D;L&r=Un{e|#T3cA3YW;>J&v~eC&h{qRGAJHh-PyX8!mJPh zEtuoi2U+O&0CQs04jk*%?Id;`2%)EYO_b2ANe%ilofOB=6DZElCOq z@D+eEYwu(GAIblnuvM1q5LbH%oU}EB9AW!ydQKqUZ#1`ct~j<&azvAH<{D#VD7>|^ zv$YcUn4jNw@ZXtHn!5YxB>eV&%D=<>#pCbAc4Q2WWv4sLi*NqMg;z+d%XPI4{!_>U zd%L;U?e)RI!RX+neN0B`%l^+DxC(#eVF#VmR=bh97!z$4L7)l|4e2L6h4s%&dj$`9 zp>jDntQ&k*>w0Up13Kaiq*BI@cmo00G`e(zMWkXlpJbm96g|pFGAZYa6ziO0QHmK3 z-q~UjF)6dDF%d6Pnr!KVa5x*U{HA?YI)Le`X&@Y0+PGJgZUpqsT}ISRFsmt(WS46G=}N?p)vP`BZMWcc$V~@5TpU z@oBP@m^55OE_b_8FPzXNU2y6#6bc4iVwV}DB-~SX?`lbQzu0BD|8RpHhMuJOSq2T( zXLVQgtx%H8JGsw6vE|FiYKaFepmV%{C57G$y-Z z>2Ml5F0ILON09ZU4Q|W_w=P>P$(iap6=&+PPLbP0TnRq7&H8c3921f0!&{3Nu&ESm zc;5yWxH0NLulR*6cbF|2Tw;vB6I~}(^!nNm;sd>#Jbb(m2!3nkoxl$_7fZ1L#-vaM z{4JJ4=jtg-4V%XMw(%4Kzdl{!fwite%`5`0jEdcJ?rEuB4&)e1!FCbk;h4R$z~6J_ zlTt zuB6@dW#5obaMo$`jTT}kCV8XrIuxaNr%th!=*MYB#=oJn&Z+5sYf)oXqpl{ayk`Rb zy@g?z!y-Q{k4%3QkhD9&sTzo(p(3Elwu3eHNaLjzNz2cx)45o}hc^q-k%T1n*&Urf|dYP(Y$u zK$C?Aqf9)j{`|uyzp8v4WFmZObh%hzTpzHezSf4{Cd=k6$TMKSsl9LePU>L-`#PvT z@DR5i>(|qHN0_6le)`Ano}E-U9A8S>MU6y#w%!TVaWrgrP1rxO;JB~w2#APmUoD(w znw#EP_>RvnYH4T{iib9l;kd*8grGx3LZ2Juh@*v`fBS```AHu?Alb56$YY?2Z;eV3 zWU$xw9kYZT9j@}3$|hzqa3aK#(c$s=GPC$u_&#h0K`la09ZLDR)N^JyZG!|Ye%@08Y3 ztuN2oVgl*{P3*W@)>s#1We|z6yi;#E7+4V?b1L2xJq8w$vtQ+l`~U}-4R#gf$`mEV zX{_JXYd*=nFBnmufFyk|473!5f2$Q|=uC9TCiC7`GpW$06P1z`%tR1ODorr(*|6Qm zVTf)uVM&plOA@2opO6Xgn`wX1M%>|AVQWtX01Aei{{}>+XHNHSBWL_^TL0H%=(g@v zecj<8*jB;7fs|4?T@H23wAFE~`Bs4{F!`4GWZJfE+(deYl{F?(>-m8eHtPx%6Mq`3 z+_--glX}g0whKxIiThmr`xNhIY=MnlcRqJKu2g$U-1BbIYf_YjR?`1!ED~wN;pLSz zvwZmbr)jtn{QB8}3M+cBwVV)_w&O(ao(lGBCTd{{JE;Bg(pSHBk)c3Z=R|@U=2-0? zU`7(ypE~t);?{kBK>Jwi%MSGwBP8Teo00y1TmZs?bNQNCc%EJTx~Fm5VbetZ@yhrv zsAAIS7plrE>I%Hl&7Do(?3betEs`fi6aek6>wz$2T%4FecyD9h`?HndHKieXHe|A* zEWU2nIcRr|(IQfbh!ex*T?80aiL*1BBZ8xre#; zb`=OH{Ci&%6Ux4V3HY!hjHT4|Gs(?OF-bI;8|-sWDn z-;}vFTJa_olA`lrP9}!EQK^3ab^VV6RPHd>AWw_A%3PY!R>=`%-2zI#h!1hnIv*6P zz+b^trd+54e8H;k>|`;@!fw6<*Y#x?=D+@xW4Y11K8KH|?bq0RE600!dUf#owd#(# zEQ?jK5Qt(V&*^YgPx-8IW_!2GN|WQKjzv@B_m9rK^Et*#81wTPA2Zv76lej^F_v@o zOJiey+GU>heQjuD_1Zs_q+jFCuk(~NVpkXImhfav6umz~0i?Un z_0)XLUbyQp=|0P1iYTx+ty2BA;~&=k=;(xOcv_H@UsK35OIli*aV95sgSZ!}^3DY& zEKr3Rlk|!ze%rzKx4A*|`}PBbB3)&KeC;oa0>Y*C)Ls3`LfP+UN;*f<#T_WYR97Be!FzpS{h>%3cpD2c;Eif z_bHh(g-R;mcsr;e>};}G?7rb9A(JwFu-EuhbK1dv=f*?_P#&dPfD1{8OgZ=?d9g0k z+1>k3E6B$2aCEcGbj=85g>V&BWFZEj(@W3&bsK6b+2aq(l5&(bPA|1)I&Sl3q5T0H zD~-XydF+`Fb^r9~Qk=RYx>D{xpoq&FZE*VrqF_bnH$%@*XHc^UGZ3%s!}*->Vnhrn z`H`9iDHbBM|1dD5_YtWKM?LBd{%pcTPHAUEyW5!CN2&sR zeO>}2(Ki*b-aJ0B3{1n$cu7o?L`7Z^5p0eXgXL_=yz}(b(y`2a;Ww{CRbbv*S4`b$ zd+LoMtRh1C#obq3z3Q)UXPPWC+b>9pYK!Vtu6YQF*qXDTT1)3tiX4JO8-DIRbE;b# zk(y~uR3oBcIa~?-^x^g(B@h~$=gm^w_V=*CTkfUakf3JC+x-0!!q7K}pNGlh&dqho zXDN^`o=@sm8=>K`gg#|5L_Py@fnV{6d{nLw?ML2YsDyOqR_LdqScFP7wD9@zy?vAykh%#4q)GtaJZxh4He?)w|#)H89{9~y(s z3pbjfy`~j@lF%p;@YEh;L;}5&kF2(S1`Et}?HgDw-m`PBK6*}7$a=gNXX*1SK;7s5 zjH=nr^yx>)Vq5#`818E&cc}08;Lk(fIp9-$RwfCw531eJE=-Z6Xs2V54#Nk%{7-w# z!2IR!ig538fih67uvbtnN4B$ti zZSA0zuO%pdTT~GVnBX&C)j+a&cqRWC( zF~abb0V5pg_DtH7T_a016O?X6?8Qg?G44nFwy(OxHKPyWH@jt!M9@F%WFpcJY!s6; zfet>_)+MQ7*re~-Bew@2w(jL0zV;IvTE0ZLzi#cFD*Dhcaf1CAkWAudD3yM`bxhO= z`M_%sD_wM~8#VpDM8{mR{+uu4RT~|RVMKdGC+@hdwEg^X3H{CzcD3xfDrD{%70U$@ zzWW^#Bcu+$-Hd|1|9*FY+#bqHWide`6A(HM z2HF@$Z;bC=&a|GcbTn*)+U|m=P21Z4aCvateY^0oPe+-4KGR6*J`os9XUjuASbN*h zcdW4qi-avUypH+?F%*vF!vUc#*k79z+Y(?y@u%7Xwk(W7Qxou`2ZBkkmk@n}<4|L+o2lvIdFnpT32ymY)y!V;SN zM+O7cn|g-fErVTeHMLT-NByw32T5E;7UVK<2N*iVIsogRniWyy%yb6TR@tgy2-Xk> zHrd=5BaFmvk+y)hQ(JqRn9*6LWgG$;wKvXH!=)cO&%0XP@RO8ZXSC+=<|vP zEIqboH9Qrv^*a#p`9uu|J3W>Q^|*ap<+?Q{kSR&#?LV}Mkjt&pLXQ6xIA-zq(WI3T zPeVc8fe6>gwH*~5VDiOb!ExHW%U;P(z*O`q)$e740@l9ldQEw6!Q1Y5lFV+&)Be$! zEaN3KXW#Wl9Cnsj$CAWp!}t$zGLVTE<8p~uaA7ekI8+Kmf#n9f;)KG!AEeb4nA(s7 z^Yd1lz6U(DjV9N-EPem&6eMX8WoGGVO3SIN7Tfgtx@7bYWX$I+jriJ++kMtJ7$XI@ z?iS40|Nm$@3$`f3tqTv`T>~QBozgvYcZW2H2-2W*4c*734N7+kNJ+!@dd_$L z!Cdb%PwchVzSr}*nVT0Y5g)IJ)aCr>tN_0ehE0IYm5t56bhHqEaGk{SmYuy?IL90J zB^|!UBMUlsY}OMD8<;XQMyzan?p(6md#VADAWBbr{$F#H6ycTeap|#Hy=>SdJzday z4WC-uqR4%1a}o`Cs=0#5eTZ542O!rDq`5&`Ueuq4bL9U1^0Z<8h9=<~Vep8+;5bb9 zegcCw<;0s4Ch}_cI?A_Y{>41u&Rq-zRU zF=i0}BJo!!*i36(^f`5=8r=bmGy#|C&3Rzs5sN9UV4X$gYsdOWpM|0vP8a8jY}ARpgTuU+3?Vv+MR&qlJY;KRaF)88>|r zH5DuzZ3FxnEkqt}ZKQBwZTP(S#vclaiw(Az3Y6KJsCnN+xaZPyGc`+fnfwnr_S-J5 z24?g7hPs|Mx3?Zu*LG3jVDVi=yQ=#TLqWC5|sBgiE@V|YLz833M73#P= z1sLqQ{A-)uFND(ggRaK!?T11B1@`e3_C>*QrTCpZ`l;Sr6Yx|r#l#F0QRTUs2wFpO z2>3D-m6|Vy=6{00#!)7g4p%ai;)?rh2C{>t`^6bab8+xRC~~c?@#1)RIE~_}Of)ir zFz`53_~1MRdYs`C35oZ0-kcHQ!woWQJ8m`xO7R4eim+1@h^^rI3%2xhjq%N>XjlhZ z{>b4adQcWE+wZzRdIKV&_%>@JN12^hylt39XJ6>tI4s_#GRdF!SUSYeN{aKk9QkBG zTP=}L;~B7V+}K9MiZn~}&am9gd$BKV9!(DnkbpJ~jWS1I(#? zuTCp}<}IEV)|Zzr4{iO9uIR~Lo=VT}GyQ(LPwa6UHmNvtSvn5A%wdrqE2-E3qM!oy zp_#oS)2Fu2-#s7tYu^I!n&6#$QLn($(xML1lWwhB#k2V%;{s4TXfrCALNH*8^3S@i zPP!)SOvESK?;o4h{(lwj#gTQx;jL7NtZnyJ`1P+)AbvUu|t@br|Oqt*e#$jgL$3m&(D;AjB zX`&TejJnvUK)m0GC}6tBD-p!!XyKI29VC?CIZH&TA!982cAw;t3S#am>B$1Lit!hr z1V^Zc&MPfLaFhu?u+rkP{O|s$#J}?^h|Hqd)GK3M8uz$uwrEIz+(MVN=#6-{QWzX( zD%A4IFI7aR!}HhjAu#3{JjQk6@0Gq1+u_F@)42J}Lgp4B1o$w@S$HrL$7SL&YT5`) zgz?Ld10Jn!+SZ~o0nFLYtEUf!*(~U?duD1k5k1g>p|kea{%S0;r`eAmay#lbL_FIc z)iu$!M_GSCHk4(?KN)$>oR~}>yDuoF$ak4?S&BR6RjcXwkK{QK2X7gt2hZBQPG<-PphzrpB&quDfQo}}s zn&-9zSNNQ{XB6gY7Jrb55eibW#Hbe{X${rI3%n}1pUWm8tj6P@k*PU|T|AW*q*Bp~ zZBK^d{&2xD7n9VFHv~LE92eo^W&&9wPiBMW{LJQgho&5lbL7p;TNPoHr(21EK}3D( z{$ZNjK~L|_{d^b?JAP+KwZV|}U~(iPb~L@`Facj3`91%kn*~o~g|*vibR43ylKvm- zKV&?S5?NRT3j*rYq{OuFWvK8>+v8O51+dif0tjO~CZ$Z<6mEVjtg}^)^?XwHnP%aX z95Tp=A3kWSD@}|~Q-Rb&mRGNC$4#4TZVgR-iaB5IE@4)aip+FUNgGuo9158eMW|Zo#sshZ+R6z}vElgInZzxG;7QoZaT{TVGKj`1Gf5 zs_XBv3qC+k5KF(Wh^U(4a_TOZjrF}rBwz9RRU7iL%_wJNhh8clCa-l~NkX004w0a& zqD(JXFr0rDly7@{5*$v%%^$9pG4O4v3)x@|VRV@?QvBIl8gfkh38!3!I^n&Wq!#o> z4ce;RuiR42zR^^^s^3vUdb1RfyneY=+*4S3^|pFo2s7b3_7@$##*7)Np3!i1VyR$V zE<|qXpN@^$x0D7^@zz%23c1x00ontLBB|($I*Wuvd(2I2?A2dyc3wH=48ZR#2~&L{ zVFly25bU0p{bgX@0r_NE=@qj^QRO!7w|?~D;528?)6X)}o8I<<5S+mWf1 zS*@}0O1yKCDD8QWqJs+sW*9VdY6&L1stc?vt3lB*`{1{fdGs(>@_W$Agx^YS3Uh7& zsid-Vr&RG4ewVJYIB@V zkOEDO za+AS)nu!2Bpv}ehT%Mu=w^j55{rioVG>!%XTOg{Aq=rRANZhhI;>ZopO$@3$Q(DO* zLoYrpmi*WTK4&-#-Em^PvUed6SwD&T&lZ=n=CSIf+q9CNks&A>abj27-0ZpC4<*|0 zw8*hKIMaWyYT*#!4wi&y8sOCD{HWsv!XYQhbco!0^qDMG=8EhEIlm^3;tErS|GF1M+j(_+r6 zRll`G)F;wnM|+&+m%yK$iD9HpR^NUPwUPO+t!NT0;wP${IyzfHP~5;YFv9ndl-|mu zQQ@Nmm6HLj5dJ}h?WDXD2@EtvqKvIbLIMUdo>w6eQh;Nw5)^JlQs7lcB9cdCy${*; zo~$VgKzwg6PMZ`}ULg}c;9&F~KoY5g%8E~;MAmJu2bn^U3=|0G8G0K~*(exwRz`}x zTh_TtFFmvzf<-_y>{)^d(>VT!496r#o?fBxX{5`Vh#EPb)e)duz9=^)3gK z9}Sy)-`w`I09N3qEm^V-%h%4Mqa&9G*Lb5-EbG?n87F)T{BY2R4)u%8cv*6h{d!Ue zKB71k#%iZs{@Q3X!x(mSVNc#6R>fx?npByA_Nfwj`o%@>KHJ8~{W~cB_0fZ21IDR8 z=62TTsK)Cxqoy0S;1ZP(Y_8SSWU`fZNYWCMKw&wYcs&D?*Q8F4M@d};dhMTYa~cmR zd=N?Df?E~VgmEr#HfXxrc9K$ywbleVfGRm3J-=E7vQSS@Rc6Z>AqZ2a!-i?44^vik z0IcNY;bJJWeu`<`>m?FdJ5eALqCe{h={P5>!z_qh@4qHkCliivsFhunsS;}g(^!SA zNxz(xF(~*U;^r=wQHd9ROyff_mv{N>-=ZH%0paC?Jnr=7Diulm5*08rT&2l4fy@0N zT9Gl7VT0cOaSF6Y5|S2|$3@-tUuog{leTBqq-moY=GEY%Tq%g_FZ2{YqFB&b6OZFa zUg0K#vKBP`MtImQ!!hlv4!|(>sB0C5QYa-kbQY+cuypQXJ$K66Ok2CMvT`UUH{3ea#Cs%VB6F%Q5wTwI0*gnS5)=VMr?#eZ z`qOTLLWBib;IT<2qHtMBqQyZjW?&|^8m8%xqRTb!=D;9N@$3?)7-+KG<)%A#rx|5K zAiq3ZPfMb;346HRKua4}1w2YM`28LDZ^bN{WosqX`V8rW5`oHz5p=arDQKp#swxAyB;MDvhwD3K?C8S=|qvt;oI?&<`P@{?9=j26Yt*_t?xSM@-P0M2RG^$Db}?UvqV>iszOeGg5%cVo>6C9F$SajH5aR3P8~m zg?Ja^_s-y-NcocAl*}3l?L~F?3V%eELU2k!j3yqeIB@=Of zf^afTUP1Ew*PzgBArHs3y5coa@(v)CX?+fR1XnFCPtvu0v#3#@0md_r2{i=y5Tu(M z3curd=c+SXE3bPwzpW=y(L1A*#Zh8Vij3TQEQIP0o{h^Z8t-v7Lzo*SJ<7r^@MmC3 zD`kAEjjvToWyj9rrb6SRdJfUn3YiR?Ik?`&UZe1jO7v36Lr(E(1!vnwg&%d`fKlWu zdBm@TOF4pjE^!MyP8U61r&XW#eEbS6XD&~_ShwQFV`BtJCnEa={BH$dM2^hX3;3=A zV)kK`?7m?hy1?KrAe2&;sJajoatk6$&_V`~G2bc3S>;ZWmDRLayy zp*8!hXkLU(1ltSrC81;UrkLopqL~Imup)21q?p`!-T+7 zZHh9WBIBT?GFxjB$;8sT^^J_SbO|pj0_h0yHTf#e~YGt70P>p(Q;4jVjWOrtFQ% zbIF0A?{ll;B$yz;OKByqKBhEj=n-G3RI*gO|DF<#P)I!TSMLIe{Yd+;krL~s<)$BH@#Xm~_D<%C= zy$f;u(@-h#Aw(96#>FHPkamfLdmHrQ!BR^7fix7Q_+2$zUq%^K>Td8? z1y_bKlo<*Q4=san;FqfHxpJm|(I6eb78%Eh%BRqfA(xJpkO)EP@rE%{nw=&GF&x_$ z_5b90kNSp3a~94YWgHF^5SKr?NnNj@0dMZ@Kq6dKOgE@_Ah_6|;d4~nAa3g|R~PEF zO{)XwcfTMI;DnhhMi@irg_O=sTqP=sa4S|SzsuRUa)bH)V)M4T&)_AyTnz)CLa0#w z*}2OC6q^c@{v%Pv%niLGJYeUBy&D~tR`WV|)RT9-00^3$KK`!lM#b2s$_<~UdEV|} zrH>;w6AY@bZShcYoTgGq+s)HF^(1B-rJ|TZ)|$!kAGAg1lo>U1i*s|q!A8W<9l)*x zQ;FBx-yd4|z1sL)|H$<`h=F4lcH1TUVHgz-(4CPgubdA_Iten0=l;oBR{;=;h?ELC zb0#_iFHY$N^KrGQAB+?AG0Q=6_81!6Hv4vL8CaZfN&8?IG*)II9rr4GLtDdPiv?6| z=3pJ-ID^sahtAVoH@~_|uf${ZV!l9QTby*!RobGJ`z? z6aKJsS)&W|Z7Qp@+&t$YkJ+5|)K{-m*gtlUJ@mZvdkz9F4~?wb*tP0+Q%gP7(Q z48I}dWM53R=Fz*w1~X+z7I$7;2o>djz?m76(oK{o#S;v`^Rx<0>oHK_f|kFoLw8L& zmT1`JgXF>qF%)3c49eaXQs(K}3BahOB)fd8s@mqyAw!kJVS$g}2+TpY(oX6bpC!~I z96D=${`7LKy8Z%8F+^0FW@)pkXZimAIePio`7B1ikGrt^zqJMyPdK~L0&M)KqpKBW zwdK!z<}!67kep^l8NA%uGXyWFsnrJ8dIVvzcJ%m3TrcCWvT!CEF$7W^nwE%~pI(Tp z3{wP^xC7y-zcD?KYt_&*EhDqJX8fXmYlwcyUUVT@}i*}D?a+s zpL5|l!IL{^nE1nV;S5%j-Jp1jq)DX9VIZ9A^#vhrINV{Y*h-Y^xC}wdpXgq8bBRDnjDZO)Nsv?}! z>W8%);3Es7%s|U=;1l#5e0d!6WFL6a{?^m~ zALuU1r`C*!Asnc@U%y1!71gMP(NHw{!(xZX$z6G3!z|H1_ZJXR20Mi|Kr*L?YN9oX z7-tbB7Qhpw$s0p$DT`A0!Hw6{W-<0Dg9warTRum}{g%eyn67fGH|3n3MGNLZMXSB7 z8L25%D3CP&VB+~aoRghM`T2AyduA(dv4)(7!gN@uO_wN&v$7NtpqRa(!sdKVd(_B&=fH3BaD5ulQ_^GHWI8 z&hPFjn!ePT^DlRNA_w98YO%SEX8#JE%Edbk$2dr58T;Y5_Rv@;tBcqX;T}4{3F?1% zGR(c>|BF08{MB`bQXKUd@qt@={lU(oqwdzNNYK=PQKP(x4%UFHP+n*FMz3LBAn`b{$1kgsny}-R{wnT2Q1-kfk+K##GRYZzB=O z84hxC?1+a%rO?5J754PcU$c_G{s}lS73i?qS^ndyk2o~#YHRfU|65z6ec^i0u?F0U z`Asdx$@#izrUnPi;i}#5k&AL>TAZ3V;$v=bV7NjrH-atgpamUJZz@_MBUj8 zX&a-}bWD}ETBwp3)X!%Cs~;8BV-^L)+iB+z-i!zLrp5|;5>vo%;c~U_?sb@6Dthid zOUezC-kJ0!aae;SyZLEg-URg|vi$m)@KHa3_x4LzMg8r|3%^^<@(&uc@2xBDtdBMx zy1KgAhPUnu`ZhHkgh~KRewP%cbo47nbIw`7{wf67tYkhAcU%iHH($BaUn|opLqQe4 z-Q2NcZ7H)3698peSGJ-=3z$`y7Pn-iyw1wSP}4*d7Ghl{NDdE#=l$HDo&M`#dKyao z*g-xW^r(Y5KZnR?sP#9KRV4}iI|OlD_E;znlzb0-|Hq8+Vf zmpC<{$4kpAj-I7SD|&}fvYm&?!l7Yd8_2>7`NSWTQGSwqW6n*+IN-nxM;uQ=Wf%2Z zaiYcCRYX-?O?68DdYQPJCTbId!omdxVQ9W{ct$)PO0d6U-SHxFy!58<3e?a9ME8kn zF-W3q8$e7%9%hNN2)=O~t9*>^Dn|btCw)P$Q?2u%k!0UiG%PF(%}^U8on z%87_1hcr0cU-laGp^F!55WjsZeQu7cUjK^}4DQYvdu#}(NU4NDLn9FQeA(YWZuz+t zHXBAD3Wl8dlRq;AIR}-%vg;i(lFXEB0~X)Gcb8bz4ny|aWo5IZ90d8IUGXP2{V zbm^fykqQoEFf0qIf-;7`#bwMD1%A&(quT5hHE;JkKM`Cxak1!Wa0(UYO^md*aTGEa ztd}(>uO_!9Zx9p}G^C=9o}&0ph|@%otn&%Uw=5@j+y)c9(Hajk6LECv)*LbdQcU7E z{Ua(<5*k7#2Ms|~=Rq*z<)(V?iSPy;Uzj*Cfhip;{-BHoAyE?ws|+`vmCkLE9E@HP z6$fMu2oy3jI3>Y2&s%cU8q{*Uom+5=;gn!^6FJW0*Sju=L>NrtGHqTMur;^A=gnGt zlK6JEWolQq*Q#0<6N&cM8&f+N&lNoib(m9kl3^z>VBT#-CB8lo&Dn8sN? z!7}>?5`sD}v=4=Y*D5Xp*V)F}8u$HFs#w!b29YY6(BJ8grUfe2k$afN+v*I&W>DM% zv~eT(xuf*-t*xyPGDT>J^luwxLI-_0IQ8CbIP-cWX5`;o3q@%(V3=u>uT^64W*XW^ z47K2abzv@UPsV=Ps{UCqo2_CLrrz7(aif~^7#JplbMyQdasqp+QKufJx4Q(mb)DSw ziek>+^-w(&9ESN*h$HU-yZ|+Qts?v`wlI*mLlGi)95OuQg@wbyfozFRi#;wmW!u2l z#T8c@9|)cA8J4`%LJ1ag+U#!gd%eA4@wsO`gHf{(`v1S zEb`W;mxr43bvKXtUr*5+PvjHUF8N_kH2&da%U!RkFL$xPyqNDp^{1BKbz_n_ep{xZ zujy01)^jDwpM2*s!&0MwuoRzj@1?tuM4{a0-%DLDHwz}zd)zR1X>ubI z_W(mRk#-Q5mXI>dYh-vBn0ip0(M18N!Jwkh5GTUITX2JaD!oO<4qG+UIenJFUE!&s zpHEWbyjcF2;jOhS$NgD>0u?1t)(Kg3pC^r`L}lQEoRkjtjYv8}rgtRO_#yt;gN{3* z&ZU4eg@!rpyJk`a4%zK^dbLnb_^@6Htq~+D)^US=N}6GfU2S+Q+OZA<@+rORZ~ezs zO%cMJZq6|6Y3twd;okeR?9);e(V&>KM{tfyXjl^9A<0wt#(M_jyoJo$HHp2<#QI(q zl5ceQc&vH?Se>rdU3#&rBh}bkVU+IiPOp`ZuTQGEom+$Kp?|JtFdGc3{n{=}#a?P- zl~t4=2hhGStbcQMoxnJwB_&c`Meg%;so2d-?7H_D>%oO%%P=aA^`dz`zHetW*ZS`W}$i;Y9~n=Nyy__f;w?&83qpJ1VK1b3wxBe>-?j) zDE)LjeYof7*f@wv516nA9-k~EnShFStz3EapTU{XR$4ixC*7o={)Wev^@+%$uX zA}(bTq&cJOp3MxyLd@bQv5i3bmgDmuka^ss;RiI~-BN?Ci(grBw2d_sH8OUR)jrN& z;Css-fT$|8D(#9tkNO1;i!2YB=W%k(kt$8DR5Vm5sVcWgQ&(v(TtK1Ek61hz(Qi|Y zcC&r9HyEAQrybrcRhxe5IBVuUB|IO)obLUTh+ZX)GHt6;xM{REX!KD?Iv?@otoxbp zx4<>lqG>jB@O4f;iHP`VQc(^X1`{&da?s$5EgZUp);wvSkc!BGM8u{jH$XY`YCNXg zUbrk%Q>XP0k8aVZZjclzqw9wsbqTP+NC=zelZX!1iFEaW$D=!lM1oURRmL0MeR=cR zC1&7pGi(7{ znO9ZjLo2cO3gzVY*jRFi^c38h+;I=)voNBx2wZ`^NqL<^XUG&T0ZBL~z7!0JpV|Ac z#fxGH%RjD)kGhUtghaz7$!*JH9HaZ=3=|yxvi_h-z)~POSjvi=t#bR#xNXgx%3!^1 zB6IMa!_UoUVr%nKu5QIFQ_pkupLH$2NDn8Ka;=(L9NExO)iUd?XFkEQ{Dm5OmHK)! zy^Cupn^&*7#d6l~rI-JZ?G?Nt7THfN3y+2A)&< zU#={wL=-NW?H{ETPR4-tu#Ai%rmSYBxhPv~O1dE8ENK6L997H_xMPdRbhkwNpe;ct zE?rq!ML_282YcJ)s7!~>B8Z6czu!C9#c_x>b=766gIOmE6BC`~+DU;0Jwm6`0FHr$ zl{dLPBS>i^3Zv+EUEpweY_d39xRg@Rp@>cSP$$T36Xb#&)!k`*mzL z{G8^K6bwwKRX^0)x{O9ZTbH`@VfN4xVU(D?z)4p&YJJG>(KAUg9R82tAgz& zXw>EV+hO~AvwRfOK-82POt=rE1elp1b2+&1`LZSwBhpqm#ioL4j>UEFY%K(f$a<8c z12&N5s2OX&jEfS#vN0vh0s~>R3HxgOa~8Kygvs_Ghm2gey=75p>!sYUvZX9@PWMja z;JmvBIT$e7a8xiqxJPd|L63;`UBqXd(pm_yDJ_DH$#5RX3x+*L{wq`(ovuQQiSyeI zBaHUf%>bmKcQMJT(f2(+2cyMa@Wfsk4ISfITx=M|G;5NU_@3s;aJJ1ms()hQzvsh= zpMeITkhUFr4~T$r7;iA)iBPf(uH~)icwLm>`K{@q)vx<^-`-fP8MDmYObs}cfFNiV z;Gx}YG^!Y4cx~R9b~s)6g6a8mfg$Y1c}+T##)LZ(O%vBW4K<)uB^-{7;u0=^orgVV zQpmD6Uurk(!cD#X?Z~a>(eK}U|DKJfbAhEltwNS5{{b+;_vLD$>G!@5+p2qj%bC%l z>m#GyfuDb=ERZ|nDo6=WRiVR_Y=0A_K}!)l?buY$!VQFsWRxT;4EW^Q{MwyQy7hH( z`qMDw4-}pm+0~2oGq9q;K%G~VP&W-rvXu5(qPM)X-0ll;0m)%mX9cSWD~3a z6YKxspt9hm(+KM6q45sJWz6KNlBG+2?|(kw^f2~|rL^E)PK`nMJqNC-D_BO~4xN)O z&ME&@%lfFeH8F!a@<36lwgg?;vSmBU3|X2YpNmtDG)$||R~tIsgTx@B-7XH)8nS7> z;;Chq*Um1j#zuc#J$3u|J>S&)daQo*y)`~Z)!+9Yk{f?)h_iS*6%OLHa5t}o)jgy& zlK6vcJs?ToFPDfMgXWu;p!Jyccr#T85Bdb-l|`It!Ld{i12 z&Dy$xiR$3{hcA;s&1Io2t1aX8TsN$2v@k#QW)zJ}3mU0gk&xqY%L&|F{RQMCIq|R{ zwT~*o{Zhhqus70Atz77Ys`;Izr9*TfQER!jLmSBaBEOm;}ZF0|d%GS(id zM-}M=_!31BlBjS|)3RoOq%z^(Z`Knzs? z)2-I9d^h3zE)M*BpLR!oWJ(OzN@O`9BHR8JUfZ76c(o;EW z%(_+WKn(oDGY4F>b+OK4^~TF-Hjpg56+$Gs9|dXnGEs5$6=(8oef45M7*>@@z4u|2 z^%;$mKzvxbGp5DobnfmfXBB+XernZ;gI#X-f^dWTlSLX8k2}sRbmy?qM=zU;K#oct>`zTWkb z@0;{XVxC+>?k%Oa?bPAtK>j=))|fglS>gfX*xuT88Qpk-p{+eQ_5qED0Ny%56FnI@ zG(}(dEwzH^doO1xhe|gkVq|gFI0BRRNjU`}A!FaJ$+G4re+huB7cpV|C2|-w38dCh z6>;Ao!Mj@Y`%HDqz=XRkl$f#fAUjLHOBI%=)ilaI6UlwZhX2`m8rbx-3$P#iYK&{m z5!AghjobfI@LvT71O(Wa{C2sr^yV2*qXug@B)ZI__A+2A;cmSvra+5>M&q6*O47*#MkGE^iOWzdPTRg{7 zCe&LV?(FGr#(4$8_?;*$tTh8_>&Ea-=jGe6%gDqP2I*8r@EBXvNMi%@L)9qdn++xY z>=!LTi8L2cd+2$1sV`f4hDqn8nbkE^ISr-}EMR2O;1EHC3`AdpMi;s1LYSiR$ZGp? ztClRmC}}N|T!k-Hv1JuGcdUzx~{oqks;dD+(9#&S&<= z^&FQ7_kkt%3Vx4c-KyKU=2^lU(hI}m$QPVFJdn4uUq=wKN_OmimhIVwiB_)txr>TF zeZ&{u+u!C)q5}0(NfC-JTLdBJLt|3sgJew?N25dY!t8Xxj7M^GlF=V^Hs0Tp}}z=5T2g2 z>rB?y@@Terd5(|E#h`qA?dtAgr|aUR%lYySntNBy_xgM4b#-_+{1;>0e6Duo@%}{S zQjNaLT-WOmaDC}k8!T)LjdyxqO@v{Qt={8_iE?mEFMX*P-dE1d@fjeY0SV^bif^h{~>JHWC$>(M?AAhyYpXGv|8Hznn6pA{O2(m9PD55fKoI`kXdJ z8XpMfS$^3$j5RzVETt!fHwO5N$>BSnDI?}P`r13 zmJ+@t!oj@cEHS%g&lhUmg~Nb8(cAqXClH9%iQoNh3rSTc$H`vRKO8_&P_-Ty-o6!b zHh1WIxH(zWu1uzXSQrSw?iGj_nc@q#{rvf}xw-jsC`J$*Tx2Q|?xirP@b&Qg{B^Hs z<6LjU%EWRu@RVC`_quv;J0aUZHa5@U6cl_IB!8?8A(Q^6^wGkxsGE1Hm+LH58@Jgn zRA2|fs}n2?*}rYm|JyBvrH>4CAp+1_@B1FEj6qSut;W%R-`j*%th>%Bx1F_K9iKn0 z=RO?en$%g2=+hPU_4RG|Ox*h3Ns&JcRyVyI=(ZPhm4-jf_-wR!uPqaG{t0n0e5tEy zvm8m#eci5k$j+~N7CvndmG|}V3@x=(rEazG z7>s*JU=BcBHqApF@);hLKsm5z&LkA|x$2ed8LMY_3V7 z(dWR&=8c%g@-SSqZsE`%bgp-SX`HqER@Ck^Y-FUM15phv7me#qZ~@`G+(agAOI_{Q z5|&tZ{Yl-~X3G}{L|dC$UBG$Uvi_G|llz2#FPIPu2ypSb+!f%>%dx?p+3E{BZ$6nM zf{l&$Vt<#WpJN4xi1|pLz0>rIb%0B{dB%3}q_HkoqX6hxL?-~EPA!O{p#O1qoGRC` z$xwcF#!Asc^kmkH8;+x%mB^u5w}SkkJM7z+9yGSjyY0ErxaI7>%C8rD4y|qg6uw5U zcKi3x^}4Cof_Co9b!pdiF}v~Y^9K2eMgR3bj2jU4>$kvc+5)hSTON@b9g*2Rd(ccS zFH?bs;ma1VyM2$|p6li9IRW>?KJ+T5bg9=_6_}5t(>hbH7l7pnUqqxoD$K&$v72&Sy zzf+LHt(NCXONgW(gBgkI>tLJ$H}l}%xdlx0gwGGii4)3>W<9E%%M};i5UY0;IB$Mr zesyrUBs#I}YiTc}3T=HSH&V zg;cWmYwZ`9K)`#fq~;4kx7(7ju2(~660%p$o8OH92&`-4uIBt<%|rAyg85s=-(>`S z{3ZHtBFod$n}5-ostsBSOvEA&c;(ww;DZK+5pPi80%%d3g~UhmIhuH4CbKH!fsjQy zsFk)QBa|t4p*q9GDL91MlD=@#_%_vneC2!oFH*gRf&uz| z^EiK4j31h`|MLQH)c>1c{MU#W7Lb@S8fX9a?QKXDiY1`9kvQv*1cilH@~>2gh=}Wd zxy7!2CT|^5{?O;OYj~Y}}RM2Ch&@nKw6%VE!FivtG zSDDY&>kk5u$ifX{0P56Djj!9z!;KI?_`Q|}_x<>|;=3zrx*^Bxchz}IF6imx`~%EO z5`7^2Sf~7Eh$MPYUq;XJH;e*e=nXXtij2KU|3SiTf;%gYf7E~x2QF9%7lR;i{t`8W zM`Ogctan=+QHKihMzt=DSb~(4xF?N<(zyuTnKLM0o9Ow=U+{6B(mp?p^lJ{T-Z%=9 zszQo&ise4M3RGN%Myc0QD_mtnoPrV+C5qve^ouYK^nhhc*jfKL@L)5`Gt~!of0LhI zM^>haZIMDh8;`9bq=So6ehanGBnn}$z|qa(b>OB$!S(FQ`(Skd2;+F}Ma!JnFL)9c zx#=E{y!uoRf#L#15yF4&1Wu}{tFKtX9IwXAkOueDWmE4V_U8?Nuj%(R^?HPH?)UoW zd&gVzJOo_MqS~6gIL_LVOdX<*R3BXy#}ldk!rj$9WF$4E5N= zdcp`(l)%^F{K$^4>_LH@HXkpDnsb@dk29PFMyhr#TAWqTJ>h=G|1D@oBQx1vv7%ll zmzQW9TI(Nug^Hl+Mf-8VNQcsyE(O1R}E z3*^X@YcWNRlC6!Gl-hJ&OsoJn`=YtioIMS&1j_b!M4UVKJL(DMY_%hW;+DMT&O50iJYHfS)_B~__-0$9pODvSmw>` zLy?oPm%dC?A9q*fs&r-f*n<)-&OvUz9~>VrVC2XqTWl50SUr_7wFxo)W;gT&bCP#N z!kopaf;7Us1dVc{&R*z)Yn{x>7w7I?=fUnl8q(wfbqvLeYYHy9xY{yJ|E#z%CQ(Hl zJ~A`0HObk5rWtAy$>yucw)2g)ngvG@V)6js6DKjKZ!%@?LaA@Q9<<{@?gXv1ETV*&p zI(n6U{r(Bx+Lzbo+w*4EA-v^=v|qr503>ja0!%-T^Jky1(9pB?lW+0y@kFK`*)C@+ z{m^i>uBS`Bm!Gj+w<3ObAG)rY{T@2IY~N+Bxj&BhR@?OB5k`z($M?ySE&G|>*A){v zwwbxQ-XD2b1UG!whmp!I;|6(IAe!)ugiCZ-@@j_iV?v=)*c!6_wSfe7y7CsiWO_U$ zqVqzy#1xqbvI*j78!DQig8Y=2(oB>$RBIN?l1|bql<2VXZ8{$U-~way`#F&6$t-w2 zuh|kOih3;;9(;prWRoGHet-&W*lS+DWiL`dN%9kn?6_;m6%amX~0sBDj=AX za-T5jpp8J&>A5t_<$p0;)Q>&E_rN~!;0hg3QQ%~Q$-8cW3JmxkBN+auGHNkbuVzf* zuVFyz`nMJ{viE{se3G7j{mcn55(1TI%O1<=95?hV&v$R)7`K-w;@nQJWZL6 zI{+QFUqHzx`*LIQTs zEZz(`K5b*X9wC|3Sx*4ol^iF~QrBPJSNA?5vDaeue|zJ;1NNP$=>7Cdm@{IGy>)$k zbzGS66c(wl>)mjC_SAB%v%_zmq%?6h#E0JDq5>JZWFyFVxn%L$d5yMUoEO8$&A!c~NeA>9-94FZiq2um`G zLoz00R#&hSC3XgHdun0kd}atSX4C{f>XvRcWI#b zRjvf_?QOfc@1L?|l z_lb;qN-<8>k7q5C$Uf(7U2BfF>15odKZ zXBlC#6G|694~N)t^(oK{5L!W+l&SC59ZLtdy)*F#ITx||Wx_eH;c1D?;5CN4;zd;z zIuxkm1LOvzj}a{*mgm7L9ZD3POj=k8Qt}RXQeUwkJX6HtM(t3J~jL6=8OrENb-AM>+zj@Gi`Gp zOHl@T9jXJu-MAa?(B%_iKI-|geb7cj&^~oNo)Su`thH(!LVXeI zq+f=Z>q8D-+w^|&*3*A5PGfLK05JpxPZoVi_i?`-6uV^-u|{a=H<$V6e@eq574m&r zH0%P-oxT)S!^z^CVWC?91~29_*qs=o^WpFL%im98_ZPAMc2(-xsyswCmh|~&m}u|9 zE}!oeUz3BtKuGwZSl1=NjrC5G-$~QUrRvLdAwYR}Z)UzFeX zJv>8~bV_%3r+`Cui-5pTk`ht^(!$U!LwEN`hjhr$AdQFvNTWz2-q-tkzdpYwaQ$=k zwa-3lt-V&@q}gYg7JC#~;oag! z+GkhAM1V==tfFYX7sLPojkKr=+f$^*AlJ8uw!K@ z@v&rKE@9VFYja!u^zO0-^8h3kw6XYQQTzU)p;G)<_}fYzzh6Nkh$J>Z7@rStPyY5= z>_begO`?GIBb1Lgp@APN%vsZ6!Zdid9Dk~d5HmSQON7Cbu6kyRv|LS%mT!`v3 z@lwhHWy93}W7xV%c~vj?SW8q91{%CIPd}QwPgmo}?MJ109iUM5-3#Ub=t>eT=d|Zi zK0nd&$m0(AmFvS`SMyXkJ3G5-$%U1bbwP9i7)X{}65%StNF@0OBUa%B>Fm6`y!?EJ zF<^(OarqEE65WM^^sX@j4#)(T>&!2*%f6Au6aP1~?>r15IXF1ZfPc0^$1YdWU12P+ z(nrAb`yQD_THo=mVCd_AkI&VTf{%U_f>KQ9_d{mzzx}C@wDMgtNoM>GL>qMj$WFG?wh0O=!ntZjm>`2M?@G!bk9vYYvam&)8|>(sl~wCiz-Fs+8Za?} zY)U2ty6cu)>dg_O@`-#dPp9_o677y8llZN=#QM%NYt4H9P&9Vjl*Fg8CGv95bUm!P zj!9T{T+Fxdth72UAHb;_r7%s@% zasZmsEt1Wl(Yxh2z2tgX{JmH$i6K>b^U1IP!@x*14~wu7qHdjrkuemtUA!-M7MTCF zF4k>Ds?9z?gW)$dSOqC0M5c)Rn~BeYMwa`10Q;H&2$#Gy>+6@6l$STD{rVy1!zd?b z1kR;DCP->On?4qY-1$|ve7Do}DUjyow$Tj_Jw4p_*d)QNj{D{=+8ZgyIamZRlR%-G>2NsKlnz?*(wVZYO&&4d26#3a#q z2_}D9r!kCF&kV)9;dg&BH1wRxZS}5<@nO=sGtkX#X#9LO-B*$2(68Ib$Os`SidE*^ z1%QYz>-{QdRgf{+IXO861xXZ8G~pbNpyC#r|vF zr(Nu{GP1(OsG_}#x{6{bGk3{9w&G7i=ws3ouwkDhWz>PqFrRkuPFE6o>WD>W_!G~v z0;pOcnApyQ(*|33r$|H6crmY<)i8e1AfJY_&q&YFaM^(?7Fo0hRcQ_tqaKq~?HBTh zc_(T75|VUszN!zPXk!WqYy`5|#*>*-71UqI%}% zG?#-3O@HT8X!W)B1dgW%MB&o9M9Zij3G`InMXujWy!`^yjs@-1-O7hcy}L2KY1G|e z%cES&XYYSE{CY%rKk%PXZEpI5L^oPpmoY8c1+2OPOp1JL9kGE(%Ajj`GizUm(zzEu zzsnh=?B4=e65sya7XA%8TH4MNb(2tsN1oUa;TnMoqK56%qs}UV;12>t6D6;I4@ozjdD+QD+S$ zkqFd4oPxq(jCM@o{eNjs^W_&`I}CQ#hZdYNn<20ffYL~AU(2Vb3T=l#-`h9>%VWSl zzuMy9BU#`O3IgVY|3-y?b1@wNBn--;=gItX_k?!(?Wk($FY?%XmSAq}5PrG+F? zuc{g{&~)_AX=T3Xtoi+n$}IcE>}@vxJW;KkE)WPm2MxvTM7c+dz6s;QLSt$BYw(~9 zPt=Ltu0O~3Wh;oF#?~3`u+A~kUzjOt$Tg%KLszUT%D|{f?WdrLBIdx~>w3v7!U2=f za}*9M#=;_JiWnVavPn{|bCsd&XrS2_AfvJm&KTk5rlk#!O)xh9j+T~?M{Qp2GcFW=7~}a{Dpr=l07ni-mJbKtS=C-5_|JOn zes9gRz5Ld7*0;KvHL&yTY4}QWb#eQnGGtns18r`ubj-Bw#cp=*wMH6)%-f&EF$|<6 z2ExGnVoUr)BZqXn8C}V^l7o{-?%_PmVG_u9D_wPypmk<Sul^N z7EwFJwkw3kHn-z(E*-f1U<(`erC0uZ%l4fb+{nF8HyILZnmgLdfhc$cl!y=lgQg!) z$_Av8RS}a78tJsrwA?NQ9^rrzMiNxic7{0&YC_Cr6VD&3&#t@RmV@nmp`D}e$=AG~ zgXDdY0d^#fsBR9YGlrE^CqxpPbHWQ=3bUn8a@TT2B`nrfz$>h@M4&1T67{p zA)?Rsn`a(L3E9k(A|waZf5|uxok&oe|u0ufLm=d934F}QPs!KuR^V&e|qdMy(|Y-svXOo+{|yek4)OJoK>bZ z>jEnh!qRXm3iZPSGZ>Cg(~qioQV*OfjP3xz|D$zjsT4F9F%@sXnStt7}Z( z^7|n?mQ!n&4qEHV9Z z4L0n6yRW^L?jILPnxIiCvcTNIaP(sk3yUD}_w;P{kgGAv0D-;~hc6%ZK86ntfsS-p zh6#83I74x4?}u|J-TKLnwzwn}dw#*NBAEWFI5DTH)-%hnfhpPu1%JoR5r-c6a#0bt zcVxP0XXzwkw%0(C8>sefgCGl)ipqOhiaH8kPu{ z5y(vfvaixrrV`@8MN|e{A{RaL5UnnnqWPCEF_~vTc;~tVht1*Ke+&O|LVchrQ^j{_g?yBfo7) zJIJ4%!w=FsJ;3GrRSv_^qcsaoBPxA{-0t~{%(J_hpKG2~y*^v@S8YYKP$VSFFR-36Qc{KWYRZJ)E2XRC!1Phz#J#$IT zs5V5M^xJC*X_Ch{uD(WZ%+04McLX-hLK=FOVH-9Z9Me`yW%| z)dv{fCo@_L%RIFs)s(X<)~%Y)WTU1X?}rLhY>|K+kGY&AbY+xCBXCzeFJ6zdyDaLy zAmG@eHYH!!#yKqViVq(b>*vIYl@1dE;RzhN2_5;?Q*&kGt7o%iZ5yJvcL{S+gv`;v z@W`Chh>_oldGKU$RS>RsVtAN6hOt%qpsi{5U=oP;FvVVRBv90}DGV$m)|Dv&r@{2m z&N3V=n{8SIuvyd|@|1I-+Q-DqVCMqNq@EbMZ|2Tc70J!ix`;&77WUak(+zPoq_3ypN*T{Jo zT>l2dB2QyhVj~}J0io09`}NNNq;}V8{qKxc!tHhY`dR3=`@VMzQ{RG4uKzAe_7uNr z1j3fi0C4o5Lf{Un@!{IK8wf1l3q>}U2X3yl0-Wzf@S&)Z2@#{hL*n`=APcyhb~=%A zXBX1l+z)k|QLH)yv;c5wMm=5%mM@6e)3;by*gtlYioTCn=c?%-s!ayF^Wsm zG7=efVZN5LQH&MQ?H>R(aIj)N7(ZbuER)(z(wZZ$*Za2vrlZn1-f2e!V25KHpysA+=*i)S(^{IhU&PItxG~)!Z&Gi>R@@!ykHQPdY^$Lt-USbe>Gj z?#=0o9_iUSVNP7!T}N6vZ5NM|QhW)RI1fVB_R$q5t_MWsNv!|7~w zSQrk^Rin-6LB#NR+3g~3Oud)IOsdkB6^>icvL^wFu%sEl0r9A#&EKXCk++2G>l(cbws?rP=yr$B>%K;1YgXyl$YQ! zp>9vwH?LYPKEL1e6-*j-4u(E_5Dd1p_pG}3+CHjs9nBz42;8ebfHl+02z=!NfNuuE z*g{VW|J|l(`9t{43-8pRsQg+i7a0u5RwgE3 zd^0AHB?v^Uswx(8^;CKM;$fRL1{fA9H>VM9o}NvH^>F88pR0s?f||dt&6(+N2TsG8Am9$%~u zt719~Y%OjoJIwvPh}3X;SfsQedMxv{5jG|e0Y|Q`AqR^IFr@bG$S{mxXJdedg>f4i zW=EQG>oNJpLv;^ZW{{XtA4K5Pt^*F--tr&V^Bnd--dRF?*`io9bk$F}TLgNt(V0dQ zly!KrXt;_~n21w`o`^Yqc)01Sn?EHqUjz83S~Cu#Ws>txV(Y~uWhFb>^3viCEUcVP z9Y6I<%9eO^RZ%6Kt6rQwhF#u1A#^xR zZZvTO&SGrm-0M&4?xNzvb?U{(S~6C)ICv?0fm>5uC8VVfHlxTX)z)(_W{`@KV4Ace zOUgB7JTNdGzU@{_6@Cc}0hjM&tYB!mCDi?qC8X4>n6Sstt1a;tSr;{=mO*ENqP2%| zXZMGPe<4}XV`&7cSx!RFa|g1&J6scgiUCCq*+5IWX)2s&8VhjVAt7Yjr&yy!qmEr( zW5hy37;h!BW3krl7}|uf+^p8q)`@!0?l*jNFF5dHSheG2_w5D(aVfwK)1hD`%mRjzGsFX&G!)h6V_Pzlip;BEGGHkmM=iO-tg{ zG5Ihl^JpfxxQk@B7843JXFp18rJb zUeqPDlN(mLY}Ik{8b?-#X)B*_5TIc)_Kjo7y=m_2>uYXP$koBdx}h7S-}{}bH48EmN95<{UnV9_*gF^}Le)EWMZ_L<|NKu2&@FcH5{JYq zg>Ebj`u1jY^xc*ZSKPyMlDJ*ZGZAkNMi>G{J{(oTB_SzU*)2QiP*lQ4ZA@7nM>;o; zuNi`&O;`qID$dsRKk8yGsc^5U!O#cNrC>BHP)BZX7|z&AeWNfHiwI33j#%zg`s(4~ z%hajbzv+7+P{P*@zo>+bP{-*#DhKN2B#U3bc zTbF;aAMXnxD|2lMftxyNob1Dn>6Hc+nxy_S3w2B>16_>hNNU|vc4R8$Y#cNy;ByFA zXR$sEN31_@T#iR799LiwGir}A2tDTTPpfNkUPE$(P>mnKe1&(aX&OaMw8htr&{ zI_ePj^>^QjcNBZ8*4y%@9KYsMT+@~oJ|217Lp9xLCtJk)jqHG=X{%*lt26$H8K{ku zs<`NNo3ntM`;xEx=4$m9?~ssQoM`?rY_RAP<|=Nmqbf6q*wKeELh+gt3rotTKMZU} zX}{yHG?4eC(>OUnD)btgrK46_$ogN`^TKDQc>+PFA7OMLG-{8chna_R*Iuz@DhVmY zfqWbJK=gD`%khZ;LhP4NP1ta&QmhDtBj?WFaSC{(yy|v#WZJWdM zgDWMm&yT{OvG5Ie7fR|>P*0QV+PZBI2ZezVAcXIUP0eM4=a`a;EqU^j9b|03C9C<| z>GZ(Z?I^!e*`@=H)f*E{F7TrbBEmQ<-C*i#7j;!soGeZ>ZP?-yhzpvE6BCZMja}Jb zeVBL(P27_LYYTaE(V4d+b(%7UWY@F#N{@`39K7XzEAQ#f-z5pnzDv;6_-=TxzNN-2k$`c4lBEn6KYpL&U3i-60QL#L)D!qHD4oI-8qm z>|7nW%j>{u}2fGgi=#) zhk?F%sq*>FJ7aHgK+Mj=16|VNLjX!}T(hkstK zjf?vgTvUOa>_c-`mqflUJ<1bQlLPfW$~n5=vT3OJnW>0_kEm~GsB36QQe6r*(BhI| zthUe;R!wZSGDUN|%ekCsbDt@Y&o!($8r@8$lh4V028&hM*sPPa^^bjvjDUAn{xlEe z#+IWeAn*j*7kUF5ojp=#Bw7Z)a!{;)_>&@@rJjAz#m$%W>w=q5qIr9j^tZqBNs5>- z2U59eolcoB;gPr)L_(lUTJ$H`-w7g1!>*0_3nR&xPTM#IGd3rLKS+;*(3ge>47vbi z`SNNJL{$KyS{4?bp{R?Q2kxIzIt^SDa!N_s7?;mZUQFyVronzWAsQvd`K9-QA|b5v zB9_S$#2$zlukW|zF0lb$4YL;jMX@$h%qI=@WOSia)w_c8z+tg z)Q5OjJ)WtPM?L>&!g2t?+|hgKdv@OUT0ASlLuIgNxjSf|&G(Fw>OE_xO(Et>Q*Hge z&)ukf+Nojy+O?f!@Fz8B2& zYK0w0Q{$46NzaN+b^7c}NJwmmQ7I!G5hwZi)T}ZrYX|RH<~Q?$C2~XV77DjEH=T1- zm0ws{*rgu7J>kXv9;XmBdLhaY!Zam98PMN1cpk3sf42xJ2Jg#UZSfAw%bJSWE-XVY zyCk%9vRa~VEx#md56h*&ni5mLD4gQ@NA>hwpB)LyJ(S5MOf3|kH0%Mjx|I!U`+R8Q?~P4jL`C%FbZ7b$Llc6bhcr)QyB>7Q z==tPvlM?pQ#vXz~4)lhR%|^JAvzI>=Xrjm-nj#svkkWmLrJ*}rc8nKb!iUx#ZpY4_ zDjEor;uErVjvY_g721wYJPtyN*r;k&yXU;pKYI)n^qFJF`pK{^@ma|*;n-Ffpa6e_ zRKFvPI*^#Yod()T{z-nDb3=E7D}kRPBu+nSJ3oSxh2<27IlcMxQMlZPYMN8$_F`j^ zkX}xTA+d6yx`xH6|IaV+(-(N*&F)SY2S5v|Q=}~RyiQDgB9T=#)H6h|ZL> ztzbxn2;9!!iaOsT8Va;% zk*Z}FQn*IEbod_8K#u!1+bpU3FLsX6{~GQ4GCD%%nVQXB7mYh>bYJLcE(5~IKDy-$x< zt?(7;?#v0ZQH~IT(&1&myzXFG>l}EzewP& zJ^;F$_|s}eRd(yr?LOQ_F9|K8}RckY(jA%uxj2u9YG zK#dpJE?38RqV~T=#Dw$8cwz1?-8IFHMbq@tNu2jVT2b^u&VkIef$`QlAo}vALR`PN9tzpy95OS}YeF zfAWkV;UOCA-*|L4VN}^JU>VDOskwr{@S#ms1*j~k_s0PZ_1!I=FA9@a^TSqyg(WZ8 zam6R6h^518eY6}aGL5V8b$+osS+xuoOoV5H)KdmSEKRiYN-ckj*(4ZU zrI1zAg0<<4j*@~q2tWY3t!Ep) z^-m?X!!P2Sr1PwC5pF}Q*43zXazoui+~wd!jInoq$ws>BWlTw|yXqKl#kxuc4B(mPd4Aa%QFk<)<{n_ESP^=;m{~{7{ z#dD8wK@xW@>D}L!J}1_%0uIQg!lOJtZAcHt+ilQkRZ+eUi)hWrPt3%QKvHm(njE58 zQcrx{**%Fq(ruij`qDJw{o>?n+Y}}_LQ(S-O$EdUiq3O2A5x-VC}%m&$e$E!do6_U zT5Zs@zY?XA#Qz!4*P@W$WJrqtg|N&uN&+eam^PCwS9i^Z^UlJRAEnf&$GVyP37iSlkbf9~kto5{Lm#LwQug)bNIJ}k7 zwn>l!2aAul4;n54UQuT5##{SkLm3E1+-z@aKU5ilkYa#D<1tvGh=F4rN3uZofQmvf zdF*M2og5!8`flQSL5jK1wM;=qR8OAAkMtzg!|CPTR&n8(&?l;%DiqFK%xxCeIO=M{ zwFRtyP1v_IH$VPlP44({Ui`dtt}66tu(_$NBWju@$k3<7`71VF$1~yoUjJAG9cfHB zmCa({Xn*ptS|LeKO$rbta2j`&>w>iPUtPBr88mfsP4``s;2#(Kd~58`ly|Vg*9~F^ zlaz(2-qYnext%<-3UGdRd}Uw+etcbA=w!rdPQDj4NM+*owY~3G1yR8^qP()SSsJiT zo3m!Hyj>Y;47vHfE?F9*$R;!tp+x9S9Eq`qgF6fwnArS|t4htSIgq+-^ZV6Rr{(~^ z922G!I$eGL1ap&IHcq>8{>Dm3Dxc1hf3TdL*hIqiFi-K6SW~<;Q$M%bpb#gE(Z{do z8(JOTqkjmJrUFTTjPC%&tt>;LH^n7zUeAD4qOH}fz8}-F7p;rSA)Cv+`Q_xTS*=+pl*0HzN@rK&x9Gz;|^)A9hA=ao#^ ztZsiJcZ>>wPJ4fu+9MT%tiKXgZ#~)~_h>Kl+}9IE?fP@uU?EzNX$wEZw5;Z;{)7oP zoW`-1LsVQxmZ6;Kd;gxJ0lCgX)vBQqaunI}>`AI3L~l zIcZ0kx390eh&gVtr*+dG^NL=$s2PcXs8bfa&>oR}iZVv97oOTVH*W7E4u&7K5~j zDw1i~-MGxIkFZ+Xo}OiLAJDWP9`&$SJg_8I%E;3!AB>_SK+IbSh1)s(fPH?PHVR9J zrBZv@vv+*))u$cuiIfc-Fth5ROkW9Q(kIY!X^ zjdy*NGbQIy*DG^#`FDSQPEYHeRw)X8bztzXZhqgmaZq6Bmg8u!%*)FQRAG=L6N}NM zf>=dqCVlDUw%N~*pP4R~TT55^Z&WnZyZ2AIlSe+}hUZ1Z#gmOkq~^xKM7SN$98s^Dn*)WCpi1%-xF8Grm<~lyO4x=@ zkA*I!s02TOCv2w-mEokp_s5apO!L-TgMyO-rDF5ic07JwcY1G!l8%tm=ai~$!ia{S z&Gfr*l}Mg3zSO`(oy8YF;&fq74vUxaOVLQnDn+d@zneAb`@L1$+xoPy8(ik`Z~nfopk=@;fE@iwG^gTLukilia@jfv_4E5*&y#87 zSQ5kL*4E>=+P|I8J!d8=29{UP?ZKYrKavXe_@N^(}o;F0FdeH@Fj^#yiDwBh%dqL!WsFEVELwE#8Q!wmnBarJW8%tC@s2~FW`6q z6c6CA$(KB@^AESPqArmo_wPj%n~w+826iX}y^r93pa`WESDvghi&N8{$f_^Vm)bj%GfryUvL;1|$1H35G@rX2R7`m&Zf zgy--a$vJ{?I9*{9$r6z#)#(t8@O%TeV8+x}pR6N5uWC)xi00Gxj@?!JKxME%P9lGc zN)LT>3LRy+20Cf8-I$?f=;g2EP(Wqh^LTgEcd!*S3h_{meMEEQ-Y)Hoj3XC1(<>t(%4#k+6 znn42myK-q9tyN-mmo84VH$xG{uK8QTk1+B!W;~{PCR(A^%6Z6dO zh0SOkX9qLFFq zOkLypERq%lLn54xI5BI5|L@O5J)(1s9F8q|Q#=HIdfclJcvKGx;n4mi+Fa{I&P#3`kn zCwDPAeGR`R3J|#Q@sse5@bWeo9;8Qmp|88MsVOAA0r5$rA0Ie9MU~~%sZ*9DSITWU z=ngx2bUFx))bQAui#Zyq=MFuiC-28_(v;5Ky#GGDe>D=4^=tMy(ceYA$7I^0qwCN2 z%SnvS80;Q;zuouVpMC!4{_Gc7W7nC2Xt(F%;OCoY>ww?C#zGGn|NU^9200;C|Ngu0 z297=Sm;9UHp?rXjCLgKhEPUt;z49r%`&0S;_G9Sn-BBY|DzH8l`RqFB-^qtuj}D-f z16bA-kvsKy>-WLvdh}dcmFCY4L~5nK_$4<39v`Ah)sigzG*<6ZB}F+!5OVZtr|;jp zy81iqkI%81Q^@lz=clj7YXb<3Q66L z+Li4xrHT7=W`A#y>1ZOjObZ#v4pSCKch4TLDPGo>Z%$(phttu{jvBD#q?$a|d(Pqn zGKD;us2Q!nRK*vd)Xpk=GLsCcr8c6;F+7YY)faKPB<4bU)s#h!o~8^sk52&Sm~SrD zI`0I%flp~)lvC3+IM%%DtTU_Ot`?v#IIYU<+RW$oFEn(4mTCx2e#esA&t8syj!oEc zR^79X?Rm{QmZWgC^25c?L3`w*>OP2=ncc3U&3VSU!xQy0RX#WM_)^;6)?}6(t`4a& z5U0_DYOly}nwE{NP5R`Tq!SW;o#o!D*tr05 zWn%8AP8||O^CabL__}=yi*iVOh$%;AtXipod4{hQka{~&Q8-~?k0iH9Hr0S zTg1)IVz|^3)8?*S@19fPEFnP@MVwteGdKa4%!ncVcw3l{PcI~Df(RkAl(P~1e;pmo zYN)3u70Ao8B|rf|i@I?&-8W3wft;Q+`}X8g-E4xmXr>aZl)^?Lwj#ol_g)`bm|a6q zAigSujI{D#3*DC}^?pa@@H##3gN6`oQkrxG;+;o>lcb&Gv>UO#z#&ExSl>uO!by-7 z)Sr*ET)}`LqZFT(z`{4o!6{^lqZ8mpmoyZ|sGGa3GX|&kv~%eKX1$I8`34$J9vZ14 z7M?n*2bzkCr_}RT!IY(yURICo0$ZPdi}Z90QsR?T*Bn;+|6Tt9v)&_kjT0O?(EkU| zpw1~y8}|5he0^7mayN^PqY~!Sq{X`gX*81{l?jxbw*|9bUnIqO*&#O9J zQ*Q%EC8Y>F*Ols0>}lecmbceT#W=;aADlFr6Isk%Cif#AD+}C|A+tox0yJiE)$Xn& zfnS(B1X5y!!C|FO6LB&mC+YM|>=LZsk@H#AHM`p-Xc)yg15aV1zmc&WLv>n_)0K0R zW%-|6BC$HG|KE^nGamsxw_#EdI*Y1h5(Woi5Q3z_aVSBOWB~B*>DLso3VyEWDbDVo z8$IwH4;!9c1si}x$iUg1~ksnd5TWRW?4XP11_f^tkpXhoP(T zY$?8Pr&stCS6|o?NN{qRv?~su;-w&RxFGp-Zu#!%+d|$PhGBe^3~B|M-rlC_Uxb4U zCNqUFZKg3f!)dCDUKk9`f=q;7Y5RoDV7T}_KHPRS1T}ossoWa@$An%Xh?aaqzSW+t z=l&7eR)O*Q_C9716o=rLOmTK1)xe%t$Ez8J44B8|Jp~w~yIFo9mX_Am*5+n#Ol*g_ zW;G6`l+!=}!|n5=IOeb_zR3|NGarQ94hqFv#Qt>dZ7_nHCV%#m#SbR6KZQYJOR^{T ziAuSM0iFPhZ6YQUtwxKQ2q2Jzo@#Jpl?n4E1}z68>pXI@ci#FhPf18hsFZzk)3^vfD zF>`uGygn_lnUgEdHv0>+B*rf)@`EJyr)kkqZ!chh9Snj4i<7##4h_TwCJ)UOn!$pk z9rySDZj${g7wpE80LQDw4YN9?&w}2S5j3&=d|KRY61nBss-*^davO66k5d_Mlun23 zprm`m$|QLGux5Lo+ZehWQZ8ZxldOx|Je>5*%(leN2P;UniZ`y>sYRs+A8|+sBS{oZ z2-|^(f#Vr`-=G%>0#k7~e8I*HZZytj|5jNQN|Q7HR>FNvHW}K&R6m+_Df| z?yIe3q>OBr`7;42n^0SuFyO6E?OCow7>6^lIzR|ke-X)fbYIesm)YY^`E#3q8WvG% z!S=-CIA=*&)t1LRmKD!lx&o81$t#L$9JcAxtQ;FQfG4T^*y4mfK0?RjE$MBCH+kla zncD1KmnR+{6!>lU)ZPY@t|aB>QyXxF{muX#gry9Ru;I958V`$0dN=JEHcj*MMJt>& z`R8dV-McU`|mdN;m5N_SbOiumRYZhwQ#>+bay(OR3ph#LnF7%>X+`7sQ=bc!t}1x zu#4Z#`S*9P8XM~=RG0@n^`HITd~)fFo1@Ld0mYTpt9WYSfdwTw_(_o}#NTRoI0P%; zQ2L)1z$q)A7{Z3c#SQt*0Sf!roVQ7CyDa~0ij1@hCp@-nza;QlPdG`SFgAPMO-4&t zU@xA`%$i=gf%t*c?AAN1N!Gw$bOE^Pg-6=l#ZK0j?^F{1tN8QaF@@Fzxic@CNMgD~ zO@I0C)AqVHm6luBAp7A7?y&EwA&dni+`jk&d()n1ymutZ9Ru7!vc08x7;!0!nU#o$ z1gTu*ZW>A^wFT4<5jp{^(!4WV5YI4(?lviGsO$BNLLh=Rr8w9QU(fTmv3+h@ybOLb zS-h6_S1ltbq?3D4Iy^B&Z%7I2Q8hh-Da+S{)Ma}YV$31L`rY_-daK~<%602YTeTxD% z4zpowm}oAotTdDKFlK-GlD&wOU0}Hq){z}nRX1)y>8u@Xt&@k9BJTF}m`uH2891b=5bvuCe6 zgkf2>!sbF5_Nsg;IKB%Bs-=RhnF5LV1>eTu)BKda>uucZXgVBr91@5Jt)h5P?_0Gc zOP^F=a&uejat3Cgx1QmrTK`7|>^)g%@p$JaB_%E0lYGU7&54(q z5|~3quAM(5V)kIpAdA6uA)rc$o@krTI&QmoA=ku=9Yy*MM!IRfC$H`ov$uZtpy$MQ zJ-al)dKM=I12ikO(w*_NWYRu6e0DMs5axKUrzr%%Jtb4%yOH{W#p8U@xG{Ka*AHZPYEvE89(*YD4GKmVeA&ehO$SQCVHYd>%17RsP3bTRjujb)gH zw1W{1BOGQPg)=;ek(#0ggpiE8%9wLU$@>2}o>!w46{Ir9LA4PqG8>(|Fg5+&H9V`J z(7I06>8u-1@*OA$a+L%x8oVyl`^C!bj{9JRc%Y$Ol<;xz@*>M}-hFYJq*QStWoZZSHGriQF7IU1E)dE6)Pn_wWN`!ns3pXLI1`!|h+wjX!ApP=hgQNr|t8w+%Q_ z+DFSfE0hJqp36`*k1f5P-6Z6 z>#d&uX8@CE=-kVh^zHx$rS^WE0hW4Vfh^41*+?Sr&FR_g={`QLm{IJyDMi?H$oI%Cz9Tj;Xq<{SP8xtmg8{rCKkZ`{HW!KtRR0Y77Fwhk?L#dWNgC+*`XN7MK!Yl3T#qp`2~W-tBZ-%>=lZYFC-*9+4|k$Bc< zV()7PU`aM9y!0i`e1}6OADLV~O`T`VML8&Q7m_DBzJX~quZ=%#>orLT@|B9(4%!t} zORAYrE)ib5_wi|x=I)|re@Xg+b0>onn&m8ZuDilEpBIcSWq{`JWFh-UdHTe@Vjg#i zv?z}51YR+hK=`84Ts(eX*Wu*{I2Xf3yfJZvn)#j6?`-YMu~GhHxa*pm})^p9)eW1wUjUe`(tul7VtUW{=cJ!PX;v$^|5VuHUqXZRmAgsy0cyUT5 zX(c|)rD4ypBF8XJxIDvH$1Xu1W#RB*q2OS*{{{<$rwk`qNVWEK9{$n4C9nkyC zTpsig+W>oJGQNj@s=Lp+jwVM-L!K~|e4OO}wy<&i233}Z<~BMP*_Dm!Qzkd6<|)#i z(yOuWHrBVOmL63>EWXzG#=|V|3`Jat=go!xyoCww zrz)zMOPCx#ANP}3Lrrc#v--x(EyJO?wbd6OtBopk>7@c@wJ$uasIbzXRo!nzm*q^| z29kS9^*AHyo)kyuSg`5OQ;K^~St+Po*84p4}r}(G8KIWA!Kk z*ra9XCX9@eA^0Z(K#A^e5sv>@@7)=K9)77Y1|460-017<3=F*fmtT7wEZN(G)qV;< z^-IbvXiQKii5>N{STc1OdD-x2nKo?o?jMT=ivg5fw+ND^PRg|#MXesemcdW)L}RG9 zoETQBo-y0<_8$o+l+&~XQZ@`@+Y3p9C|(FL1Kuwg{hDd*unbn!30UH|qN=?$i*ieN z{W`68iE|lU@EVO~_rHxfU);SiBh(9HCtai}Y9j7yoN9b$;=V!>!_)D_ffphCpC6A7 zXroZS`?Lj(`6w^Po<05|3cVT9llukfiwb&Z9#i<8njCy=$Cx{_4>GUpb9rj0#kIsRf zDxB+FkbtFcQmVz5bpM*_w4+eSpCHlP1eQ|$KFKZci&-G&r@#V4WKK@S=|5v}XU!a_ zrtmHymdR2EauJ#KuJF5k&C4tbMP!=q=ipiP>&f;%vg*E8f_w254JN*JcB1O)YrY&c zIXRrZ;#%AltM3^e%;-~ z{Qd9nbij(C^X`yrli;o&t55>TH`*ba5A^0zjfKfqS1m)>M6a$m&x;bi$pnrpkJ+8o z|GN|I=x}A0mekdas|!}@YJ7*8PU;$wX-`00jv1Y^$lWhHhg3R6i&OM_BCUQ6`9ND% z{wkjJ>n=)tOOe07S~NAy_dpOsN|svSqrjVS7}<*fLe`EUOkE~SkRM3Mo2Zv@$)}G# zugAj4QZpDL)UWu~`FDz&#=mT1sjNIwn$+6(j*PN870eiNHL(rz;LU5Q#=e3iyeHPS zdQ`Hq>u*Bu*PmT?&H(E{XTg7uto0y_ce647Ijy=SjQ-pIcOm=#(e&N%RKNfG$Ce~B zgm6e!_TCw9BP&~W2w7QK$0~d8krkm3va^n&?7g?llX-BA9FFt5`+OfikK+#y9?p2Z z?)!c|uj_hVS6V-N>FHkQO-TF2D*WQH{0W;p=DbdbZ{Rky~Hg5)TS~zK3_z z^Ro@~7n^uCVsc(~-S&$Y3{NKD5sniquV`}+c3Bny*B+it1+({=u3w(AUPfAo+OrB2 zW>u8YfsK4SxPIP6&OLX#^7%9LCNRVP1*-MYB$<;wkpBkEf?9VIz`c^#yWwyH4H=g3 zJNgY)zuUL9$WJH)lPzpCa0L|s%xVw8M3d$@G8=tFA^-0d!H@3K5?}e&QhWTzHc9^P zm_rs7E?xo0Noox-vvj~I@I-?v{&G|nDL#5Uo#0FRNUoChK};LGdGl7^GXadbIoV=^ z93A!H{z(4Q`p#LQ#fRczGFvuVPufzC3zk-6PL-JW?Rvp7 zg7)!JkguFAc*YdnF2C{PhV6*8Z*-}T@ z4m_Ac;3v?9j*!KDasSer-oO*v7hAq{ttUL#WqTOv{{E#@?#lyjL93~_)~ei^U7tRz z7y5Lk8GEY3EdBZ@3ve8zz~lO)qRe%%wHk+7rFOqzZhrn2YkcoUNA55J)z~Qd((OG* z&$qg|)CjF_px7{))~`-~5g+%fYdObXD97%~tw(g$+zZ=@Zanr&$EuxV<}6S9$TLd>x( za1!$GP(#yuD#yIZh&$DmKa7`Y60IVG4rJ$PfA~mmt!(00@pva0Z5*PS5?$M_eRC&d znv|+mf^i4CTQMDFU$_y_~vLX^M0xYi`^cKx|io5F?MA`+9Z`uFD}`OE5% zvr6AH;mgAtFwcx_Tg5EP-+U)p!j$?h9V^LScQ-G;VFAJ=e1>!CD(KK3U0=HINMfl_8;^1=Ww`$?O0GM4~J~%k| z1#9Z4mo>G>8AZ@G^C$M&`hJ(C#gtd%HrGy<)UJJ%&^5#S8kHC1cQ=uSeXO9=CuS9^ zqQ-$de6d}}tFNhU`;1x{ZsH<-usx4*3i9#s^?k4RoOid*T(|JuBvGc2uqv3za#Kg3 zF1NQ|Qji#m>RahexIhd=r?W+7v0!okdQscf1}aCfw<8GDTrdr(t}=T#(4eda&(>TI zjAH5w+mP_9>^AwUM}@Ex=4(u6$bsnW^_`*okId zy?}>cRxUtRX95I#mZ&CX>~UFj$ZsuosW+#8lt9$NHnTq}_hw}^uy^#vWn`{$4}BMV zba(Y{r1)l*hgdFVhe+;gTZh-?+&B__hy>Dx8?bdFYC)+w3k+s|#!$&0;mHduuLN%b z0{8T>yQzhRZ1A;2Xj&occgRiQ&3FiAVHUo2$6dnre7{I3im#jbP`LX$|PyvbSmEBe9hJqp3kDD$=Dbi_iN{M=@xvjwPjUWweVs;LUvI{uqCk}CPe z)F|!}R%;?-e|6i;jH^eJE{lB4Xd$~e;lH0kxucBmwl?XUFF(a*wDNN&aXd%aQ;5?) zDtj>~n`UMnjZr{A%W*;hQbGz)mEoyfUk#xAkwupG)aV?#w)$3uH zu^s1cn%OavJyIwgve^fG857IqDBb1Iedw9}nY~`vVnTxuy%yLKrC@(`ZxrUPK0r39 z>0e6u9xnA0{Zo}@<3Gb-=cJK-Efp2Wn#K#RNyNxOi)f3wo4OmN8e90vPen&cKb8IH z2##2i*xxAPw-JfdrIjYkx;O;Nu~XsNEUdS7S{^p*$lD`3R^-ozHYssgWzsi2;K`#7 zhdEv&`yfhr$TYC(?CMtjDI0_6Ij|N{g zX}|Xy)DlP5_CCl%8CDv}UhUV*V|H}T;w6;KYXi=jN9C@D++l1Fl6XpSfBZIvpJWgn zc49$_tPtY*pBXIhYOeu?#2vJJ_@PN5>r~*7uKBk9?N{7gsXrekAg`BXDwDGBGqtT( z@R&U}D@_mP3t1sR6k-nQ9fsfgfY_atz){&8*v;>Eclkt*tDkph2wm?Z$^f+N{0v3pHQT+>H=M{-Xtr<`*G?zq>G z7*c(v8<2=iKO%s#X=fN_ByIrrDAFX-KsYVQtjx8eg^Gy2c!n%i!<91<#W41pkXqD5 zgW~tMi*AJ}FOcKWcjN&?#;a4I0W&J&p44Ba2ZlMpd2=DgRzn1ARE6ts2o< zu(6*W{|R}eBY!y+f}IVKy&mfZQmbWqWAg``z-GO}F2*JY_`^zy5kexJo@ZX}*4eLr z+qj?m{(RBBQ~u`Wu0seyT5DL#ciG=T%k^N%A9X4o0V)15_OEp`;VnzLNLC`tS(!dV z09T;VptakVu$v!5HZM;?Hz5-5Yk8eO-1@-X+Z))3er|1jm1HW+O_kARxpH_w4)5FY zT#>HkW`~YmOzsTr?k_a%i4Wz;1+D)y8eC{vHCrs_DGlfETKk$g3`4C1h+o8$CgJ1a ztX>3-qGb5fG@oa-T-;pE&Q1&W&^h!aM}M;+PjR}RX}=2>f^3>Iz}cXlFIjLMBH%Aa zS`tYbnLpg<2VT-(@EUdR36uU;!eL;nnds&ir`V1g6-A_u!!;qu=(*kU0IL1D5TXn} z62I6Q(#1XqJXK{23q@Y9$G+b&uJe;2fjmEaIveuJf^YeqaXe{lS=sp}f5>I2J-^c< zMJ`xrdMdlm(cbM|AKB4iyZVBS)`F}-dyC#PS#TeW`Ygj%JSKyin*P;rTpyYcQY z+moqshr*z9=3wlVPRO=!q)mxlc>;qtu!mT_z-+*at3^0eRTnvQ?kOrmQ-1X_hoBxe z%Ulgjs7ah6RUcS1IF5r8c=n-DZ!N2extG%Fd(i?*XveNV(ac+US8fn^t}RD z=Heo7H$M_ns`~tylRg-HmfZr37mr2V!7g#Jj10bL1=#Gt`QrJ!L*Y~Y4sWosk=L&N z@|>!n|6Ao{nmIyke9?}kMvFhyeMB402!Rhoq}au&ke&1-CQc7sy@wmB_v*Fv>n&#< z#7MraXDwL@(1hL0jAYx4|C~HRg>{bR;6;qOQJLDzVYUDSf}k#&Qeo z;~(mm7lnoS$rOwt%zKAl3SYKMyZ^8R6D`r7RaHo$!_HlaTswLtsi(9;)jUQhF8!Ds znS!`VO^R^!X{tCHwmF@AG@uhgC3;*v-}v!a@!#Q;mM9(t#VbQ&l;3(4jMxPP1~|WR z=B}&|DmNIhZGp|{+dy`aclnnd-6P>*LJCHzTq(u$rKd{$9E#t%3qR{GASGdG}QwLWaG ztZsi5;Crzz>D3@P@Co2Kr@|w2HAXaX{~ahmD1egYuKelOM?k|A+!fwi09*g!9;DxV z=cbJQNWz+v}YxaNiXZ7p4_db#8v%ovn<{x{mE+~)g^{V~4O1W#f zQRIzxiqq)^uIl}0x)^1}B3fdh={)1oFi*^ z%QJCud|a+EsKP1xmouA?oLi;%{#%WVOy$&QyfEb#q_rO&zH@J%a$kP6v_?+h(SyTE zP14Z{^M^j8AdAp1r$+EvK4XpWmhp9Qp{5{xcYF0BLM`cxwZ<>lkher2|7l)>iAUnE zRVqS-=!i;Zbx*JBXKXJF4Sl@4+?HE?5)nLlQqt-Qio}l!M-fcD{ejhpO;o|22CK~M zV>|VrB3Z)KwaW>jFGRYgrkBG=*wvhEV#_vdCrHVQd!(5?2EJBj#eH_C^nM$>Mk?Tk z0$;mdkMfSXZ;vDyv$uZIS#|#L_PFhUnQ`}EZ*PBh;wGvF#0|uJDnL&l( zEL0s3ZHw4IMM+#<@FC|gd0~St1V=7bL$G%zev1~4%GY~4xx2fI<=V#^vQwsUXuBZ) z_}%Rl08cdGP|#m8d1;;q=_-1yr$s2O)D z>E!3i%6zF7*RJqe?jhp}ktwgqMxhn|UkfmIfl0mfQ;e7ujYeyA_iZuh{5>{txv@l1 z#o*hL-li!q>y}~4N{{94C3+{d4uu#A1QV$QJma$FoU6U3qSWgir$}7NNk^KP82`lt z{^F+nGShx`W@;PNQmc8N!gkz5%jXV`ef|8My;-8SKU9bi&pE^hs$NUHBIK=ZBRL~G z>$Qd*BXZaBbaI3;yqZA9jf<3UdDXCwMNjsg#Exc<2ctN06XieaQIZZvJ{|R8oTchQ z1+8AB!^8=Nqa}bzJ5P1{iP@^eUZ$Db<;n%zcPd4-AYj4C*wTNCLY48^GYaF_)P6f# z+mA+OHt|ev=89-BvmsVq(}wbwm!le#ypT}HvF@KduaV3Chgq7yxRp2OU;ftf_wVI> zCe)uZ|M4osUjN$|Ks<#U5d89RbBnnyc<(yM%ll$6=kvaWzJR=~+kK?@ceeX3zeQ`q z$NKuFCNXLfV3)V#lef?+#kDoa-%cK<%&-cj#e_Xegbadu>}Br~_B$SUzW4GWH$?O} z9BKXk1iw!+`SJy9a3SDLbL;Nf^t7W0x}g2%Kn72e)b3|6?cpa=?T)KgZs4px z=<$eGZY`W@cX#*nRSo=Ppxg?xAi0WNnT3M}X47YtHF4wmCQ-WjYKtFx`5n(|dxRjg z(Rl`BdddRPUC2Lvv9D{(X~qQj-kwc z`$Ww)>XxR8ea${jBsv$Rkb!Ae}eB3^aIJ(5f&ww^b4+j6d{ zvTAm_u?!?|X%l+T;F{(&((Cm7`wZ-(5ySMQngV_)$(vKO4%E=hEGiUO2!^|dJGo4MNFn*;t3i*~=`f_jJl!3t{x zwAX91ovtoUdahLs%&ggQES;fo0h*`BS?7xKkj~ksK(V$ zA4Q$^zGZ+BS(V|MJrW=`IMz>CENO}(S75C&8_?K8PUJS|A8Xz85`$?}h>26My)=Vc zz5iO}XEi7bl!%3w`bo#-!=^-vC(@0{(9$YFNrc(5^i#`%2qo)G`=IYASLIDm5hh8t;vANR_F`P^h+U;A~BeE5AeC`95|zYyK86A~L86ci+Wy}pp^-tKgB-EqF` zzIw5ls;Ip7`fnFA=1*ELlLK93y60JiVdwQ$jT@NqfUm5e_`fMsI{9i929H0a9W9i{ zhG1i*RanR+&}oHv3*+Nr{&kjhPLpMwOFpv&ZRK0uIYP`2%A7cQ9{zVjrSMZ3daP~y z(lIAfo1|mfB5gxLvbXkepdu!`1+~3nCf$=P$PUq4K;qCrg^aix@k2d+WqxL6D~7%Z zUqC{9a4AC7a9l7gTrY9YYzYWT0hj;G%y7jbeeKJW^d@yU za>(-46|j`&p5!N)|YS3v#<{)-=X&h@U-rw4w&!xoey8G$@k%Ix})wDAY zTkYI+$9BjcA%UY2HU%#G(XxaZzQE(gE&girMnNNrRj*O)K_MGhvcY>4=Mbv^3kg2Y z1pO!IGaI@gRH}vsi*78deja@&klXgl;YOogL0rI}s>{P(ut>hTBg5vnQe9c^B~h~r2|neqvc*Wh zR`$}p1a@}u?5s2hVKR#yF|nFLNi=H_^r13`q=-O6k#CR=cgDe=!(_N;z6(c&I@#SM zvO59Q{9!ody2U_TN)R}bW2~=_>XflTCY$p$+idg{6v#oox(534p8LtO=vD9e7ntem z%lZsVned{2h>K=i%E#=rI?q;XmFf{9s;C|r85{3yfr{OErW)+iiu$!Hw!`m5b2MM> zPL)e#WowjX@>^K~YzWwtG-qe4jv0lM^yBLV#2HslXSU`MxU;J(NFR@SmdFB7f#>mNU& z7(M4~qHrLH_WF8Zxx*-P;$y&)*w>p*iagRO`0`ZbDj*Ov5#MIt5`fnQUR~nG)a;9MZ&a+?ow@^6J0`|M<$HjAdGgT-Vckt>N#N9MMO#&C8XcJRYN!xAB<@V!+ zSeilOFRvLLe#O#+DX^rdiHM3;nYW~}Hu-v|zgGgb-^Ml1r@>NgO5oNn8@ftBUdfuF z8~^KzlFjtR!;wf7mJ#~Ga1g$9^XyyoUW=uQ$}ezxO;6A41ggD#yA}BCG-8L5Wimuj z9jD(8IdDkrV>c#rc8Fg1zArPSi_fWbX%=6tZ0*EwB)^P#mB4Nlg_nEAOW z?`?7TGc*;&-Xl$kjd;K+*C=tSzkz(6lodz8zxBVheS)^2__%@#A#11kZ+j>6kd$uz$mL+(=N^FApv!+T<`L?EWI}h?1Wc= zo;&G0EdUFft$K6fCbiMxww4<%wKt;BDZm3`C@nlNZI*dH|2$>jk+4%+*$gXQboyx+ zyL#!EwOX`-1}-E8S~`aM4-7XE&B$GieWd*6^bRSNW8mrX`a_8AXj+nt_`07t7g=bu zG3$fiA&)}YE$7?YNcx!Y)z0rqT%r;p4eN~=8Ury^RWvlUp3Osk;pB-ME-Oo@eXr3* zt@m?NOD;FPQ{CzQg>zqRy8pTDMaka?W({7#<-s(OzP98Rz`L4UrL#suFklY$#dtAl zRGyi_Vz%S5EcXy|wF-{cRVTAKW2+z^FeB5v8sPl&=^&X^bo9hd1OGK>ld5TVkx1+^ zlkXDf;$=HJTFei<02{~kDQ{w8fdqmH3IeAYKh_gr(XY91fe{{+*Z?@*29xC-m&FzL z)gT_Km`-3Z{+8f&@%W#L3?6x}E^OQWZe^kj+7Y@?XFn(kw({?IcS-Nuz0C^$M-qd% zFyg50Q5n=w7BK3tx-07qXa%{yV@loK-4;wth1hl4B>5Y^Aa}4_eWx>wZ#LjpdgbY^ zrg8TkOC6j}0;R>-!(&j<1fSHUv(+_19$U_c zlgWkp0eY#|7@t{nR>V-w$MglJN|)$9pJiRnpAzp5oU&Mo^Rjzlu7hrlj*Lw7WD$xWIb&yjYIU`<_lxX|y9sl`e-@(~c{}@>Tn|5V%gdG> zr*eO7l>GYocb+g*PlG;E(6(oYA9fsfvFf`TyET~h@gqJzr_rIbCUN<#D-%^+M!>ppNnaDMl;2-fb+Yvfa9;Q7(MeO;f` z@mFHQ=ySC;Yc9F3<%3~j);rxV%tZa4`V54|r$H5#`zyLqzNUBmN7%P)uC0Nq@V0oB z_$_V^#qC&cjezPjE&Gj(q0KTUC=0r!J#Ek*ep{pVZ8!xvD-C6Gyr3@rgfHRM6*2FK zq&O*`Jzvg!1||=bzcNm!a$XTMUz5msX(Fg?Ld$JsO1vJ9r$Dh0*{{c@rcgql;2 z1xJ#cRY)&_u_L`8%dCEV%S0x7P|A>MS5m1keM*?+CxclorN4YuKlB6r*Oc0=n)ZMn zEvwkMUNZDR`6sx}#Y2s9tz7XMi)MJOjbf0+@}b|Y;7&nOHge*hFKR&?Q{&!@y=TkF z`MGDZ`L;!xCPycFx+b7Hu>Tirv#)naYX83p#s+QxQqdR~nH-k% zWkk%Fxd$EnAOcl%@pfkBaIScv*N9~G9_CLMGkxUocTkvsDRpenS`xs<^vfHVzWVOI z)ipJoma`w&xGS3{El!*8UyIF@sMzik64t|ORAEiW$*x&&klAd5)4WS!XhWJF3pp{t zTUsmc@gio)>)Tf7)V)^UYoNqv*-ULxPxJPVcX|(=D%LSU*Y@)rAPg z1_q3lImuzBCfSs_dxKBX0uLpn=}1Xf0S;4Kr?+a5e}zFlUUFCibGXls;{9@D}c2>}^4fhRA_d!Z$)F7j*7Q(Z604N*ya>{KQ>lp8PbB zVj_*y>|Uy7{$Lp;Eap7(#ZhEH0+ENO+C%@!Iigrw$HT%po{Gy)Ni$;OFsqqcCP@dv z{qT0o&#Gj-feVZ|-=pw9I|suEuYNmEN5^PtEo6bEu^Hm_s(@z4$iS@89k+R*TAy{$ zc#=;3K_Y9aE9wp)G(M`n73E>zgw=F+e%~W^b$Er|odyL0Jp;pS0z5rp*3#q;=|`|q z=<8$hD59uWuPS4C?hOdykgG+RXz;9}6?=F#poQYDl^jNQ z*~6%zY%DC0DPi*Ph@Cs-C9m`I^z7)O$g8! z(8cxk%=>|##v>9aj2d2Id^}&^Rz~9a`K`0FEp$(Fn4pn`1rtexr3JkB(Zu4!k~v@c zW7Hui%84HMZ>C5e0?&%1;3*L;==-s;uONY8b;Y9>{4V?RmplL{yu)52{`~puy2z8s zKZ@|YeRs}%r+zf=Z%*3D<#nAs|7f9j2q@Cr8$%M0X60{oQdA$XhQj3JeMj;DX7zfa zL_KM1sJ;r&8&bv2j%CpY2F zD{TQS;grt-j+l35`B|}MJf%j}CKL)Q^V8ES<3(BN@F&$r4kPc+cGBdkLL$MEr2;TW zbLWjKP=KU3HdIvXQmHZ)QDqw%8ZzbQU)&tHTge|x=|x;WHclDJ-ws~ns4TWoUuT*r{vVW$A{+O) z2WrmTLAMK2sMP+L(%$Z#=H!&ut9aV>MW2Tb9?QomOslPGaca~FjLi&@8Dh54_#)AD zS%E&)rfaclwG_SmSMWmhPpHJSemg>R^VH0=n5fA4>A6Xhg}z1FFoLmnEiX4yR7mQ% zp<#yR!)8*KnBEP24jn#w+(x%w+8EAsZbd2@8fFl*Yw33!aZ_NKCT#Tq%2lct8;(?e zC=1SWa8gHguOSNkn@atAY51^D@9~;^?R^j!-o17proSKZ{RXu?dNr0|{6=(z50_mp zNzQLoAKSV}qMG8Nr;!5PB_l@=KgsU|cT zEdVEIL{}NTeZulpLSHICyugQl4e{Mh{~lSZ^`2Q@!#?EW%hWUlm)?Y#Jm=e zfzY(0lrW_FOFDXX%hNJ8wA9v?`ADB@)7tEYMc8 zL#qyj^InLKW`rIwu)}}9UAFD{_k!$JgyQh97K51Em#Xqh7J>(Z*M+Qwqn)Q+aZIkR zpvNfXivtbyzvH`k$#d}NNUgZe^M_?1W;=5c1d?)db04-`9b)cEI<8{Q+sUhSRqT#VaIumo?w{<1;M3Y(NGLR0)cw$-m$`7*?%&|ND+q6PbW{uZ zVO(wA(o*Ao(0T^AxKD@ktL;vcW537BhI4lxO^xP=U(9x5hA&1iD@9<_?kkFFYG~Lu zs9wClq@=7Jn%1x6Ns5qe^w}nXf$osb-`BUvq_5eC7+-%cQBUis`Fhb6QEEDeZf!Lc zc91*Ur0O@|rc9t5?@3@_zPjiXcU?%=E)}mb%^ltD(P?hh$rlPniR-KJ#Xl7?FfwF% z{T)aC?~l79H|NcZi;KY2Cq|8ZX?*;+kj>AeY^XYB=GS6^g7U1F)}USVZi3QmY5|Bj zLp<<8P&Z)6=^RSwv@7qvuohztUfIE=FS=3Dxt>1n1wp_#OHKif}R#w3fXQCHO08b*K2ZE7+U<2barxUat*Yz z`*{J5Z(}14N>Nc!bVGdQZyr)))e2Qryi_njj|nLKJ$fI*(RDl}QxWAF7bLHOluOg? zO^1gQYHBQH1w>A9V8kwq!3@4<)&eF4>u&dXW+p`na7E2p^=`|mp zt0kQipEfL!qbZlqM9)M)5@Z!h{}mT!P4d#E$IHUb(e$Ot6p5-**y}kmg2#(Oq%Y|R z5ie-1U12XK2q+y0(nGG2!S@0YlSH0Q#RWLACH!zIq zQBPoq9A8-AhFLk^^47}D{9N^~(nnui75X2xPytneKWh6D-U;%)3kn|Sy*gh11^JM^ z05a4az3R4qIh>--vk!cR##7Y7y@G!~A;RqTFgU-eaBn{@qmuVoUqyEKexkk)aA!-i zj#o7uwC(<$|NbzH=;l}_q@uj41(;pP-vE#^WHo5xqlEJkzo2-$8vA>VvQz3~p25tZ z%fV0AYe^wM6G+75`C6+x+|}(4Wk!ZHLyKUKw!~VvWW9q`@Vq@H2m^#a7b$UxE^cls z<@x_q3$o$SxM2$R&}Y~uw|;jRt8rP(0%x!se&{O~m+L>O^3Sb|9l)neXlq_mW~+kF z(l~vt!1av0DMZPZh5DTm#&40X_FEM-T>KBh@wRMx!m7$>pk#CIvy-W_ zWk`NBfc8GUX#gC>)}Yn$#43MyU)zX@=TJYwb@6cby;xAd1qgVU1CP16-Ra7iDl=me z#0s3`^bWn|h$O;=5iqVZ#USnMfWhH;6B7v`bj@18n&{mdPC8V*WxI&aRlLK*4x^`I02??MI1Q$9SwJM8OowAT_xFT>uaD~|Q#gmUT%$>zQ#$)MKryVNAhp^3qRWS6m~e6wK@DveeX z97%4tq2w~kmce0JJr*i|_9)jLLMT)y_%NKj>&zUY=%=)h&uW{8V_QHuZ-*Vr9Ouf{ zRHGp2NoG*g&{HHaRTFv34rPfcNhhE1QkLsHZWNv0jP8&4MZ>iwIpNFXcBH_`5)_l? zu|4=9hIURn=v2FESZ_;s|&~eJ}4M8;HDuZa9vy(-d>V3Abt0U z668+XQkj{_@7Jc!V~Fu_GYkzGX1{2a={=OT7)2GpPWl~r%MAJ0Qu^Rm`+?J={Dm_9 zCtv7=Tie>`ZSxP90F!Fxqot*S=MJ2vEwxiO$j89Q z2pmVX*(qayyeI@4sK2<_o1~%h#&hHX^veKvuCk~<2Ww=f1yLaFoFu!V@yCTBU5~%> zbfWL*2#1LA>+-1t0tO&fFtQN@;^6r)^P?c6Hn!SnQX}WP%Nu8$j6I2tT(L&29GAs6 z9BD0UXa>*up*yqK)|QqWkKn6=<{GPx?flL)f)&3ArJofQ6)LK{t;gHB1pz?iHv6UJ zsO$FNV`lpSSTtv;93Tm_3Re<{Gwl!Dnjbb;2xgnsztqkX8E?WPrJ$!QSG2hw3RNsV zrlDF;4nw^?HhCseYw+}z$xzqMx?c6!V>*bioB$C*3)7j6Ygw`UYYdM&USf%u^@T{$FsnmTKV>kho6 zS@y=`@Tj$`)0^<=pjNlU=9p4}|H~baXv8ZZk+pPT0Z}TCRaUY0Ioma?JRSOd=yQnm z@@pf0?d@n?;?O};^^mK|TFsA-Gc1&ZbWw=cEk1E8_JRZ7K;S7PIhrv#)T5M|WwW0C zH>-UrBAmNoz1*gVn)RMMC2wCg?{GNh&eK)W2rq@$Qy2*@T_g>$W4){bi-NL2>&`uj z6eo3ywUz?2j8T7*XM#%iU$Wfa%B0aGO5uW#DGXUh$CIacMLM#mu|8{|p|K$~u@o|7 zip?&giH(F=UEoj(VG;~V(kT;Y zMbpq<`;DJdTIw9Vw^#Z8(NK=~Fe=Ym%FuZA=)v~hiT|g(?G;mUK}G;H$0v5KWN_6p zkw>c;3#Mn%M|vEw5?T37XWU&12?5xX1Z9dIpZ^JnclGSwv661AtD}VQ4odwF#qh)b z_TB|izzv6o%23vDK#=rW0+Qq~@cYg3^xQ2rzS5{v-DTyd@;=xo_&F8!Rudb6<-2(%##WKkJtnkRyzc2Kgb7zP9k?BHd{eA_X9Lmnje8Ca20_(mb zj@|76J3F%D_1efm13X}FiDgXRVM;T4h^Q~!z=W~@KQOq}pGmC!^bjdzfwtao0 z=FtZ3a_B)|aWNGB=4^MjwKeeOe0HJrpP}Wxqyw4I%wjV^4D}O0Q_R2N&OeqdiY7M| zpkq{jID6+ze0nD8&fWok`!6NyQnmop9ZCwIYvs>}ozzr!9!}fWkcT2J{XwfR8>v_c zipjR%Aimte&AOmpshL7;)Y1b(FMgCv3?d}NKU;6`J;vj)eR6W55hC=N)79XQ&9m=x z$rJjFdT5PXgvq0lVb;W#bX>T)QZ!_mMEdImgQ;_zs80*^9h-IR9| zDpQn@??j5q5d0res0mN^ZI# zUmy7YwE#_}B?cPw{^D6a|1tKeWQ(b+*$#a z!S^tWdfX<8sR?*r6?*j0gJuq?Up@uqE71V~H66PZDslIMwi;^o_UUb1^uPdEiF%Uk z`P@Y(HVE=N&)3^Kp7c%!*Z~p1_9)Tv{0?nwQ&UsST0k7Z?Lg+a?K?3-BNTPPNUZjT6*zaCQ(U-GjxC2Y~mu?Sn{JD()xY8Z=4 zkC3s3rbyiU{UzEc8ZV4r@;1bj)nIbZdYn&D9G|j0l`x)+nj#0PK-m80_^7On>_t2k z5YII+5l1LK`ZS4o_pxT&aq_zf!CMA0uO9q?Rx~BrVG4(mm|it*ZKrR=Ye!ioG*b5Hw+8-FvKEeed2!lzrtKi-$WxG;MDB6@CR z-eYL}7xwQJChWDE#?Do6aq)|Pim_e8%k~Zb0{#Ip(l$=%Xh;U+q5ZM#<6CrsR2h(- z`>)uZ#PO^#WD-D>1ElbXlkuF`qPw(91iH(R0dW4hoYUW#PskK0C|MjzqJ`7(87b%} zA%f&Bnr<$3-ii!PKj`?gp57%b>rGYEusDj5($`iXj<4-Hz4gqqA;eB%@(0}q==U}F zO-d0CKa!GMy)=qI0|&tY6($Au)6!|*oXJZ{sK8gHXT2T)M(u|!{-Zt_xOR+T3L4}O zxXQzm;cUO=bdf!~w|p+mM}+S56024+^s;iLd~IE+D(I!t5F+ zO5glN7qd`7XQrn1eUE+s@vqC`W`BS>pwJi7xw`vnoB0RXi(NQ`Z}=+8%F5t2UBaVs zx&3yOF+Xd2nZ(Ph4tnL`e|23MJ5efNs`U+!S*?sXh)mUazw+_r4Dy?al^r zP?{`D`0kmZR)SXHRTlyn!Hh@tKii!K1mlyC5G=hz!DYElkjB%XNW~)1 zM9Ah2TL#RR);jLDGw01tO?cki9T`QSA~p;MJo1h^L=;5kRy#fC>n3t_!Ju^yy#ov= zWw4mJ4Md^uN+e|4&F=;JdjI?ZEg;g(&7^w$CGOmT(h z_Jcspd?_DqZ;`A)G`t4o`|&^T1e(I@xw@3T$j%4wBZg@zr$C1nxdJubW^Ip2pHM)O zi|4(z_v=@KLpqVn$9{PpFJFIb?sWIF+mw}kWWN#!@EvN(Ynl1ls_JCoa1Gis&k=vI z{2}{^@qyiSO=4T(=uIAx+k{ypbjDqA#^Grnzthz?f3DY*&+W&huvH61 zl+S$*!jOnjQ3vzDT55P=y!z^5o%*&XnQdO~O9ARcV~!UYD0AcFqXzVyTUI2-T&rH5 zzppm!B2@!V=Ht_7=QW$k%DBl%|HAnjYFKetvLj2?xE@N13q(RbZ=UuuxyDqGOxAU! z2#62VPuUObi^OB0xxb7J#XFb(9qKB!naAw$6X>)&ev(PMcVZ4)3nqRXjq-P#BC;%>KlhsfgA)PQ^P@qB z^@UeUf3+0Xj^Vn?Vs957MNFnW?)Zw>;!IW&f$?ksocNdD_ zrWm>>uwUy-)%bwBoTtk);8b>wx7SNp3O)u2KS92?xNH-%k(~Z9YA9(J0gFx0|4a z(vdZ47fh_q=Blv+V8r$E`YhD!TtDcLgTHHtF>WnqrQcww?5F*8Yn{|EtsMc>2fIORfz|VysM)!qH3{;O&sfavf zJ=2wlO_7o_2JFi$cnUqlp*Wlng`RE-n~1k1C3;J!aELA;+dG{4hPRZSi3C9pwWC8x z=}f|O+l#qH-xKygGK5@3wAkprnm#Kd^cjol1AInvGUtw}evFHh!~004uWwn+X5*j^ z%7mN`33fJ&HE^L}P(o7D$tKxHTbmeNnU@P<(EEfmuYSaoa8cYojEDGC#f#ScPTrq|tbwL6cKnh#QbtjoK)58UTAf5W^`rFPx~!0et0XV*BHCPiLU_pLaxgtDJEjF zI8`!f`b$UHRw3f3=G#wS&oDLf)&k^H))J&-NwOfsPDJ+w}Onb=qR484Mz0QZS>JQ z5GzoQeN~JXoUFSun5wZgX*znAepG6}E&~$uMrrxDRJsfc(gsV@(+kq56eEkr6~;X2 zRk??@IBz{qeZqAsR3X(1kAgle`aAi)!iOavBXHfYwrX5wG*|Cn<3LP(JylcqUX7iv zZ ze{)4Cn%MC4qp!&|YPp^{@BPG_uOh9m*IDf4xeeyC_U;P}L)G1j=QxypdM(wXmoq~4 zEQ*+M0_D)Km9_rmRQiY0p6n2Oqtig5M1@cwUm;PIL_m>f_>e=ra%ws*iyh&sE59C6 zGW_qMOE8cH%4>umdTYZ;7{{oqR!W`{?e$+Dak3gc;cTJqiM^Plh*&C=kT_4+K$#`O zTL!8E`7ZJ5u5x5(9xF7?PSv9XLFgLl%8{S-$q6z@ResWOtK@yWH!-HhMQ{QTs=jNe?oB7$B!S`*w}!4#>CdPo?OoM3zP!Uz915B!YkM4>tZ3s zbVj`?gx7csRJLPsG#l3sn%FLi3%MJlpj_Mm&sh+kNm^(K8I{&va})wfB04%;fhBwj zsgz@p+?)WRD1~xOfBSPcS^*pNA)2*i$AyE5->yLyM_{fZI1Z9Z2T7)O8@WY*`(3~? zhh>ZN2?U=&iO8B5LbwsHhI3hFKQ(2@wPx0oKZ>C5R*;B}zctG9X6gP19x3|Wco}FI z<>pLcLP>H?>*H~HCXWlREiO*TibRfc>C zxL9SZ)Su`jpJtro^wP7XgTs61d5_wPFz;dmUL+8cJ)k6lK!r$rmI;EaM<7p9Q}cu$ z`{A`smwx@XIlfU-b#MTJbRt;c?9$RTVD2z4XJbL#*M6I{`!u4nQpGv?kN=9_;^_s$ zq=>ZCBEWg+9Ud~vA8hGT_R~rJ#z+ZqL;QAip8xH5JD)@^mDLi3yY+Zu)la=0kCHTOaDECdcl) za9R(GwvVEq5$XvoF_^eezr-gc#-U&rgtFsSm*93=50TFOkhqi!voXmN=1BLJwUTIk zF>O3y+(pxcl2t`ldz3`qNlFRQi=@5p#ZF!%V4#d0rl-e?;@^rx3F{r6B16GP{D8m z^?jA3`QMRmOl{+xBtuHyJqb#ypr&}DzV-luL%pM+fX@y!&;aOFMQO`J${3f0ug|zL z2DeB-IqgJ8XglO%ZVDG%d^rCM|FeM<(%4V&DFa2AUN|ItArS}i+C^e#ds%_AFPT_( zpepE{vRWTKCw^gyH{&b`{z+n1e*jB;Yy-PPkwY?ZjvJlIFZxS(q34%--MV^ERq?E+ zkA&wn2_fnv%jS=0{*1EV;^J}Hdpf@MvmTt1^r91o2*}nwl$2mMCn6c4Pz%@N?*9Fq z-a!-REwx#IxPiDRo4Cv53qppuCGojMHdvurN_t7Uo?=QJ`Qs5fDvi%!k3SZqU3l59 zz2+q+5q2xGc@?Eps_R!k5F7RcjG_!uDo2jw<8p1aA(5ub^d;$FPV+fmZoZ^52+l9`!yoxYoHemXL$>~XRuwlrHw<44}c7x0l^ zQu&UG+_5Un`}aZe)*Ebqid;;@l_!Xmu1Vj2+Pxtgvm2}8*BpKZ9vE8 zOb$ivqB9&<5-urZ)C^mJzMC-aPMmr>^!EyDLG^_KCN4W#-2%yj1jYa~7jdBPCo+dv z30xE&MgqmKk?5zyk|>MfsI$>@`F=vl8jR^V41nS~4ACGFF>Q`$qIWv%l8<4r%}}W< zsyAO4pa>X}5Tk<(3&MwxR^NW#Ln;+TpW_S1)h{Y|L>=sQ)~MjPSxTPi@)ffj8XK!% zYF(EO{Dw5~8x%kJ6tLV>MCsP+3DcPO)Cr_X*)7*uJ~$Lw-7@NR?VUMpXlO| zYM)3Y48IK4AL1ic>Utx22&T_9*z=WkB*f#^+*~hL1vV#2TmB?j#dB%yCxb?2CqbZb z@A5zobm-UT2`y@G-gr&kniWmZ^F9M+vZ3vrW`ODb@FA$A<#$kyTzrb#Y9gJ0&3V~} zf7K9pA#as*81c;1fK}4O)O>h@lzsK?MWLSF57GLE%7+YIc1*||V-P~CLd+!F$LZER zRc2r$nqXya`Q)Kh3Q{g3KE^%>o8rhIeD^KF$r!36yRV#Ksj}G>>;EcMXGR$Mqk`H< z3CkhApkl~Vnaj+lqn$u6M;inWlXNCiV#n_((_d0RgJRS0a6?eRfh!oR!j6lJA40iC z5A|F)05bOPUP0jS&5kvh0t|;CBfuDQ%6mRekkbP$!JVm#9d%GPaqF^2G473D*RpjaS`m<;RJqQtR!q3 zD@{(N0}1wxOr)32{U|PjfQLvun;_|0sX7H%u?!HHQTX?m14Qko3xcV!d2A%jsavVp zV&0$%Y-ZGm1qFI2%z5T;KsVQ18ju^HG|IXVBf+L8lMlO%CnTI=k*sV)fDEO<6d+!| zko}AzB9M7c*T&k;2c-mY!Z0GF%z)>O!k-~Spy~buX@vob#?uG8683*Ye0kJt@qh&S z-=)14`1ECJY^r%V(M(UTvZmN(lu*;TUMD*i$RUhF2S4##UD1UiqgBSo$H{J!5otoT z!1ggPHk7Bo=HZNK3Plu5BEjAE%|4zIxcET?gpNY2$^GFhFOymMfco_@NLz-rQ0ZED z&Yno^Liu;rWjk{M#hmWw8q7!}=GCM|bQ}IwQj*p#XWO;gesrP$|ZubpY_zUQH*rC%h72w=wh<+d|^P0Jn#i?>;GbnA+QK3m|ueQO%?Jz@f)r4&Dt8WYV%^rpK3}emT$_6UspfG zqoFJd#UY0hC8qx-Gn@7(J-RST_c$;{5J6>P54>06CcJiNcAM5_8zywEyhOF4hVMor z!=TydNkO9@KfhRLl{nK`y^0s=wkRBeKyiJ!pvX|D{~6AdX;_q0)&@0Hl||V0X_o0+ z2OJkhju1~1L7^}prc{31vYO-h92Yikvi`hgByXzk6$=aRxL{1M<3N0eA5=S`bMPVE z%MpX;E-O3YIsLwPT(U%va^5^_>WhcI1{%Guy@$?ZZO08XUtNy+)V2HweW)kSb1*lTAfkC<)7w@``*hV?PSTy#j0dIc!iE7Bj%z91H2aT58wV*&P1m@P#LP?tTFg;M@N3FLT5})0 ze_RyHDU))VG_FEjfgSZD{u!J9x`x!|X_t9Uq9*5<+BY1oE)zl?k8xaloHE3b>FAvL zHzkUY;oWMvoU8OndYZqI8QbG;aB*0n$bkAqv-oVRIS*byT66QDazAGu;`DPgEHV%- zT?DP&+tK;E`bHP0na8(|4-Y>R zLjov?N9Pz0UqjRE&;R@U`ju6iYxb9?yGZlkCoqzY{+N5S zT@Zh4rwzgzDm z%KEQw*wvrJFoCxec3Ckl5iVo39fQ@fV1mPO9kwtiD6ZaH%U7#KyhHxq5KeB)~( zy9z~Wg~g`*uB2L4!4eC6lh*vj_V-%O7J=UPsiowY?| z75A0h2-kW-e%_d_(x=rQ-ekxM5wyB(7AGr-c@=;5c_gB0N(dM2D;N&hS0!YBL-fMv z6=kP=N{ZL9)g$kNPQALnB)-%^eq>J3s4c^*Uj@)BvEiFZXLW|zIBd5%$Oth`tej#np=W6FoU}}($pAF`N|i#68g%Y zIVfX`D}yv~5(m(gW9CwAxQlpDG^~}!ijmkKTKSPSOsZY`c8GqZXc9&~#^hHK#Ci7F z)%NP3kdR!=fG={5p5#l{Qvq9k8N)Ct)0!^f+*TZ7^2jSjGrl0W~Zt-;(aC)Ex6XV zQZZe=!XAPwK2qSkN3Q`>wwjyx_aQtJv=w6_ln6$Uw#n9yTJnpedWcS1C8*dct~*;A z9yAc({O9p~vOca+C9r1_$8qh=idEIp*X{elPA!U{ z3}jBV%Ofg-8ze^KlQZnJ?6s9m=Xok;jweZ`k9Al%e}s|OJ})nSS;^ZHl+2=fVJxR? zp<3liN}(F(&Gqh$eP^6{%2|Q>-0^$HSh*aB9P*$XV5ZbkKS}_oiA*mEd~S{lEmel< z=xq8}2`LHvy9fd%Ot(LDphie#H~le<4CKxIKo?kA9nJ{A)HU8gLdSrF?mq$#di&@xWf{l@CyvZXY-H6VZ(-utDvtLC@-aEYRd zV^4OkFcgPqpI>M1OeUua`x=XV#fHSNWyV&sO#GobiS|tU-?K-^c;tRXk$&3oArl;`{VPu(=EbEqhYL5m47Gp-)Cn9vbRxj_JJ7Ij zR1%}0d%P;plCP5ASmv7bE63C)$e7TW_OnVp$|Bmt)MFs1XFxP=O(f1`8g&w2p1!M) z*#7L+Xq4CAhpHkSelxZHE{9N&hZJz`Z;N2WbTrva6_@2l_E{B9SucLSdbde&nFCs8|?Cq>eo_de#}*xY{r-RY;XEpsNdNAiOv6b zmwTVJ(tauEAJ6G;H>21}>}wWFA$ui%Gwz5p2x1O#9#m&FhaUte zW-T{U{&JQbxfgi;iWKhbdFILXad}K25{sLfV5?;n*`qljL}dDR!;93*=N@NHD33+b zxuZ*X)GUK5a2GgFdw^Y;BZ%}UR>Om|Gcy;fZFZi%Bi1E9evZ2=*xObXq7X|V4im>K zmypeP9BMmdSb^eFr{VL5aB%x9KE%O+!issu&~#Rf&cQ8`(7f#(NFG~D2DIu?T%k@p z5R6&;3AGsC931&FaZMU4!2n}Y`TRXwQ%YPK8=f&O@XL-IuV=I)J71nzRg2Kz*L(3p zQSw%#MRXZjDL)#ysR1ckIe%wdjNdJVe((5MqH|swe=MyH)Zv)o48ulRs zLIVjc<_Ex_1_3xkL^ic$A-s- z;@__E;TIkroGT7Zy1V90p*qv!4B5{zDgH*_qrF}$*&XmjCaJjE(NlseWFJQ-3-C7JizcZcpmAiDP`C*6p?Uq)6upZa4}10NB- z#}SuEx*r>U`gl~xtf-gMC@LEDx3oW5Cz-3z+0|#QVWEEYkJS(mE0hv172SUS{a*N8 z`hYDfymd6K%w4s<3>Fr=yOcN*1mXlZ)?wpx?d`W>zC!T4GMF=$aTIl@H;TrDJBX=` zP;yg3rZ3qr&>kooSrlcZ(Iy)6K?eoFSWjuvJ*Cy%3G|~U5n`1HxJ!)}tm*69=CB)( zkFGZllcy*nLS_o`vl#uw&*JB%4di<2N9@7+s_V0y;ET}#{lq|gJjyZ%F4hEdyqKHq zA5DzAlrmai_L)(}Q^$9>g_j(Wfh!5Y;)SC>mJJgxPP&gQOiv9JYu5s!PNP%H7`6^b zJ_#A!o&IKK-5bz@1^t$D&i+?nTuIN2lcYFOu*kDHzX89Bqh;5pIM-QwV9gX>jfxss zF?*<2ZWzd&hUW{6m#3@Aw$oMi%+P^PZj&C5nw;Lf`_4_=wpaB-p=G~-)9cmP34Q$3 zpy>fCzT2I>O`8 zLx0{@wx%U6oJ5VJ=!!@e^*RTwgZYyzPFe__{qCypZfL{-VkbT=ZW&*RJEov@RBHKHh~DJ=NMQ zUk%iK>y+zwpozgTuhy#8+6Mf({YK!b4o%;4x~x*^+a4my`h_r9n7M;``eh2+7gt74 zfCmY=Lo7B)g62&v~t;n41<)&R(*i! zDASVvp&FSI9If^`l0_js-x*e$G(=mPhax3|$;8}yDPf4%L|ge-#C(>jf}kL6WPuQL zEV;{;pe6ssxyMD?sN4HD<4EJe+%fo`__n0a=-58df4;NYk>E8w(|2e4kCO>(d%*v z2o9c~Tpm=7hcQ%ZV2t~!@_~hA6(|)Lft@&XqVc%8Ves1P0)S4B!681qaC6meHuM(! z)9KB-iZ>hSqCTU&tO@-q>R@RaQ<(POe*V+kRC}r7>8IXpr_b+(12fY5)ksvoAQP}L?^~D@N0gKtps3pbL2^Ru`NRvcIH7lFYqvw&Sh@oV{8amjwas-k|(+tOt z!OY_BQ*H47{?NJ|5$XgwU(4#qThGm>a-m9S>Q)@1RGRx+FgM@Q@iRBSQJ6O1IdnQh0I4?wOisll##7h|1d?O`gv znmsO%F+Ib)*xo;@tq9SGlx#$?k_dOlE~p_Ok6NfwPs8MXullwuV$qh==Q0P{E3;tKpY{i^SbC3`ykp@PC8m{E_kp2V4AKi*rXZ4oU zm<;CS>#|v`4VTT?R}t6*6pvwH&v7}M8!aUzr82RzvF9iAs#hW9E@MW8*B54DA~*gA z_wGA}Vy&ktR&)~HI(!Sf*L*Q5*T1q4+~R4P4M1glbA3vokf+K)mp-?rCw6m|D|)rz zs8+OBu`5D_jhD@-ZMxcao%QZcXue!|t?;~Bt#I3E_V@4K0IV(Na~dz^xhAq8gUJPg z%v4Tw?}Kz}#USjEUj z_p|+}N;6l5e4W&g@o8;PXMbSy+|${0SEmk2O@9W@cXrlsnKA)$fk8m>{Sl|GdxmUo z$H(V}m?|vx2-QyH+hA1lE{i_2th&q_HYm8(PY}&Po;BwlJhG>91rN z-lzd#1~#14*%zr-V{sVeq^ZxLPz5w|flGB3QXFO2nmtzZ(=tTbzjgQP+;PYj%+HVV zNtUl9o|#vdW)yBL;J~878_P_)f9v>Cx*NQ8QNwvRZ5c0nOLSsrK(ntc-qYxFsT{t( zY4QV>V0Vv#0Z>_Qo(3=BNLvhoRKI}Yce&psFJno?O-HSlrgMV?Y_N-Ug$=Bvavb-F zSqu`AtCj_XaG<}BFJ_bT1dUQCjNBr`D!5%ke(HfTX7_%?^ZoVj>*nz$R%)f14qN4G zDIO&!Vs(xysl}-0roGXCN_ZE7F~0W4ul2m515|-!P`iBf@K|kJ%(L@3&~AGE{9tvE zj+%PXB83A9oD2=;f2>43$KKS=?pK31j*U?Q`A8{1D4+pOfH}?m4?7s;HvMfQvHNN}7jA;xQ-gM#k+R!<$N2vOj?%5-6(wVtax+iBR{ScWNpL+PR%a{s#J zLrKf^d6}yFV)>iG`+CkB7xT4F8>6XGy#p1X605!bt$n?qcQuwN`BC=_u&pL{oy5N# z_$F3z&15**k~VvP{7IIP+DhgRb$d@AHQ`0mU|!p>JqwFX_)+~DfvrbnK;bp1Y)Tu? z){)c2H8CLH*XT)3l`plCKSHU`Lt@!4g;7&z4VPhAya?$sFw~%jh6Uv~2!$YxY(7^z zy8Vd`j8hYbRb}2Krv-#@2Rq1jSr4xlaGLuxF5$Z^yM6~lV!Oaw>$RTopjMw-nQw#3)_)g3VF;jJ@=1{W1l5SNlM^P{5) zCw28%^X$PO!L{mGC_JSP-zLfz8zxivDxqJe={aRAVJ>|iDNDbG5<4E)G)f}S(xkFk zWrImG{7y%Q|1A*y)FSLMfqZYa(ZCZ=p;(nww96l*dZ|2WNu=N~6itRE#LIikJ*-w> zqpBFt%Kx-ISs;*2Cgm`kF1H=M|B9KM-M04BFMZ%|uypTpcrov|@er+~=b=s6eKPO3o33{;l5G2Rqu`ErBuriGFGdJj0+6)fXt_!t4*YNK{OI3J zL{Hy%&g|oIl`D4DeA0Z;D$KPR@R3`KEZD zv+uTS-AbikOX#2JAAkUtXhEE8y^5yy_`cl2$vkuTvx-8kxg%Jd?8*^Pm(JX=ZCF_? z1=Q2Ryc0IT)@QEA+@&se)$*n{R}JP%45csr<3k<_Jxd=xDE8PEON8m9oz1XE&vw4c z^a`41#GMWc)ZOd72(Q_Ed|(_CKZjxG|*}3g_cGPvTfdnzF-(XzsS*X*#4NH zNr=Xa6u<-SjtWeED^6b7+nqmD80)918hs}+w7~%k`RL13176~OT>r(`aq;|)AzXcp z4V3^ca!aRi(=NE*BUk*KN4hQ3Q!E>Z{vu+DoH%*I0@X-qyziR&rZ{3R4a4vg&K%ZC zN;sl%5xvY(XjG1GB0L2Ga{dD8l#}qXx#gck$Nq6b9gLb zdvh+(;&wRlGGeY0`_r;o?CWy0!1d{Ey^B8+1O$X#k9fPdbiN*fz~f!;c@~DvQL(7K zg39JAUd`op6^L4w_QQyrzt7DzX@@<+`6TMt^rl9L#Y?vKqSk4KewLu z$?ijqy0TLlEC_vy2Y7A%}#z70&J#p$UmthBP6?syho^qKtX1nrjm$ zw7ku15wQ+IVbvJpVz2_+S>cmm5<5N4d<}uY*6O^XfkdKm>}{>B7c4+s*S@phP2m^$ z#B+bK1pkEaCJ~C|t1l3|&wdgJ+;_MGZR5d4E?b{K5k6IOG_0{ytQv`(R@>Hf>QN6( znxCIu-z#%2lBMd#l{JF-lcBhn;2cx|8DwpbNv-DQa>_ckq~q|Y5ajuMGS*47OGOlB zyjENyW)%b3U7ER+QDgyArQDyNFw4+?CcTO`nSkm&<3S(Fl z=TD9fx`ck0A3S|51u@-<5wY8}xr9YIofys8lvKfY9%eV~*HtN)gKO_8+aHyOK4ker+2on-JIz17> zfi_gSCKE@YS9l|@eUO;U$4b80Rk%o`q;M+&!+>jn3dBkzd8Ss62mI3T8^vsozS*mg z$AxUs&!FUAql?DBMta)5meD;S#x(2y^dW(TK>T^7J{9u}30rxhK5cUpXzz&xf$)mh z>4b)&&!2y-1oZr_G{xxw*CEmEZ}fxy1n!n=5V+9E?ad=BJZ;W5UaHq(GsAyF!dGQ8 z18UKazcVu2o0=`h3cw!{dChiQ$duWgSNGLH41f$6zA6?~Z@=hGsdv1S=+JXpV0N!i z@45hN29gJlHYe<+>v-&zM!x#!w`zHuJU;>D@&lP4SI7KpIrC0`J7tnYuh+8z8T7yT zWxjnB!3f+y``adO4sl-VLfGBH^*#7WiB9OZ^&66Ya9W@}YC1UGc4BomL&d#ZV312{ zUa=G>2fnkf7|e3v-hL`9Dq))nZu*z7YKR?)N80X78I?I3l8lAEM<```M)N8f$v!$0 z;qREszdb6H;DHK(_N@1qN29bq)ci}t`WaZ!F5au#^@UVlWE&5fqy*1b@V#{w*9Q{0 zA%Ko-`BY@}!A!fDb;IkBNxoEJo9NzG8joVgG(W|vAbi=f5zt^tq=k-(f#znbW>!1m zJ1xBZF=pWPM_(;G%5oLoPYcenR>f2oZw1N836hF#fr0AX2WYT5^7XW1WJiyRo6}El zXmLvR&^}~BGFeD2e^kHX3-*<%K*`5oIN#(u!-1wF6NMwQ)N30d;9knXd5&DT$U*FDMNRk7VeeyJu^3`u!Blkk zOz9&StB2A6P`=;>pkS?KzaW!|t}>FG1H2LepNrZRm9qi$^m^m#%Szp&0`>c@vx?rA z6h@>Fwtp}^(Tkp}>(hvv(+;BuuPp#~wSsaY^Hit9AG+!ilLz2b(pmX6QD8sE-nRvde>M1G?1Ln0^=wFo-3RZ>7k2kyA z3*NnqlJ=yKF3M8d56r&Vb}t#cS&w!_7`TO|M~=G#yrHA%@Xq!o zNxOb69rzwUK_TJB-EcdW+;EC-aa6zGNxr!+*F^g*h#$^&G!JMm(>xH zDj7)pVxS^a6KtdgUs*n}usV-O9cTJnqt|&nfe%HJ6NsCJ`g9S7fk=w-n`REd$w@i9 zy5|j~tq3lOdI2bwLL~q@uZjtV`pLZVGRNDO33q``%0O^o2K16c^<}D~TIvNl8|(ad zczrQ8*zDN5+=Rri__mQK7NnmBL`lm^{?~&~)9g|Nfj!XWHCd<6`8s)|5D4z){rl>E zjZq1d`XVz!MX}^H206);LiXFQ36yCA;WB~|R*MWL2nJlibOunH}!H`A1V6CGlf&+1Q8AxA{C8UK@M6Np}_+* zyQ%WR!wIrEU|6wxnC-><0*K~`r%%XU0F!@76p3=Wm2r{yruZ$1`vZYYxURbA) z>m^aQ*aWdSY#>#{bz;dye-)r)cfMBD)}BlPlTi=LUt(R|P&$E~KF-qf4MiW??!S}s zIptf^OKVMx5Z|s>N9Ti0aT04Zj2QNu{W=A9gCG|n^IS(_PfTsQJj(n2)P%-4q3H00 z{p(wiLucfMwyaSXi8f+3Epny?@hJH=M8|QTG#e5xJFe!J6AaHFQgca#CuSO2oRHK}#>aNYG<^zUZL9mb{v0Hl|)8xr9n%03vL+rUk*0*Ia&_cAh?7R;_Gy?qf1E4w*Bf%hnvKwL&#$fRB11 z`OERQEN5}5kqRvYpAru9#ahahV37~T$^Gm(V7Qp>p#?o$U$(q`Ck7-tt^``b=&h@r zq!k`B2lVoJATG9Nh$%B&K3F@9PvMp6*9-S{gtQJ(01iDabEY6+8wT~rk*vsoUvs+5 zBDy1La1<3B!_}+B947Un?maUupmwUibd4U zb186{OgF3hk#TjCezs*6ry>)5IhB4zLt<5&knTKQ@mg^zowbG#V|?}XC_AsTWfz?; z2Rd5uZ??=SscD`iZ02`HM$!cSUJ0cpRq5PWoAKz1kKaygDydwf(rqQ-Vw=1J8>uj1 z1t8ldP?Dd4BvOhQHA&pP7wRaK*wilLa6krBa$)U*0tZrcAO z*_8b=7W-69Lt`=*Csu8Ix=dBJa)3H3uEx695tB`M#%tX0o>)Ot`WDYPTTVcIL+uHm zjJgl!?1ES6#nF4NNweclxc7jOz39{15IkH3YF`XJgvk!&jV4bZkWeM0 zs_#iVDW(nSO)EuDa>f=lB_x68uRy{bMP4IbAHd{5kSEPfNzltMPc(U&-iMNX6)#yl z9`GX9PX*D{!p()-=I!5U67;arxlNOnCYi>FR3te&+B5~F$y?JNc8FlFz;swP80M;S zoPDY8`o0I6bTbBfOtqHRuj`9k1>hu~tpi~hZ&O4phf=PrC+5xh(!9?%K*5My1U7F` zxBX?1Aqc=WC2EE8slwIFD))kZ+m7|#fr1TYe(uCjqL(T)rKCJi6M#UQKS%CKUz&MJ zDTC&oKj)Suu`e7u2liP?0ovV`#gMt3Ju3kp=l`6R|$l|A_BqoUOFa;7V z;?0b-O>o8a9T$f3K{U*ossrp5I9KR!LLn^_UT(;Fo&o&3{w5m9vAn;ZUj<2;c6aiZ&PQ8+)z{{$B@X1Nlur1;+qW0Ti( zl|_qz!vOUGh@#WxX*sFrchTWMx-K|Rv=`og4oF1?`V%Xl#uPCf`1Ch7q3LGO=fA%| zZURR4*3n=5RJbztx%>$wCo5i{xt(M%$Yzbf+IuqEllKu5NIX+zEq0X|LIP2nJgR8i z^vDly|Er{6Jm(jK7?^gueG%te@v8JX#yBV|A==)47l)voV5e8$$Jgxnk+^=~r?sg< zy=oc09cq$0+E*?Y!>3>*F)C}4$b?(`;>JB7)sYOMsiENu!PEF}G(ZLfE~kT476_qG zzI2PM%#Fx(3?p8Cm_FLvmqLLQ#{_mDjTvCV@M6T1ir-U5jz8SyEyrDRaUrEewKdJI!lp?YYCJ-#>^_2mKDZP1g)U<;2ea zM%bR6Pxu@lV3300=M<%}5|d#L+F+DQQ5vIKtkzA;MMZhJQ||iUQ@L{rZrcDl&q3f7 zj1u_R^+z!ACV+cVlfft7_ShH#V=^tZ*i>Riia+jhj_XH|=1B*dlQOx@$l)-JlA?d^ z%)IuapoI0$_Xl(cq4ChW>N0Fwyg%A9DG}JGL&lnxI3wBlgDNpJ4w?RF48DFUbOZ98 zr_%A!onz0_Pnv{Da7?R^eb?84Cr>ntDm$`eqB{&e$33EH51AB#7*o+!m^QEg3IU6E%JZTts*z^T)qE;sWKsMYCdY16#dGrYW-xPKXWM+w$- zK?x_OAkz5i~;~v`u~1B6Vh-x*XfO1bq*@4?bg;-Fr4f5xx4_{nDk2- zGh6QgPq8hn>#`WnPRFsA%R+t(3CJz|CpA_BLdWY3CErK#CfkLL6zyt1fQ2g?+oavr z1Hwu8kAd{wC2@PwZG@6%cOeqhW*Up_k* z=1(vfhl}lF6MuYB0D?b{g)hI(_S%A&n`4oK6(b|(KdjP+Mz{77d07>cs42I7z%4mU zVQ_4M!tmLTqHsFc$+JGod5GI7v%AU(5vfFq7q%Xn-+VLiZ>ZR8p1my%^ zry;Fi6Z8lWZiy&ZLg&PgB{~hqFBmU>wFQ!JgX3`9au^C8hU9;wuSg|6T~2U0=tD=WLGGd&r>&$6Wo^=JqpidCI}wY< zfVO|J?(-3=&2MM0YFc?#c;S8Z^R?C5U@GWsm)~>WKBoJD~Z?K~1@wyS?+4@UBWWqu8SJ-(k(J?mt`6Ki(q8X&wptF_j{!_jv z7g?yWnQ`{9p9>13E7h?NSC82H7*u0>(QkEQ_^mAq&`P$_ZzhJXf64ponSm2`{-kNx zC)q^v_}|>-eS)6-HQoHXp%ALV``XT(E9xmASyf%nv3lYoK@^|~%5ggH&Yh%`9R~be z>Y6(}qZHyDyHBX#+d3bRkFeE!q-006dA0M zvd8fyGq<-#O;0~RV#|5Y_s~8usF*pvzy%76yq#)4PLMK~Q33fX|WpoX|<;R>6q%v%eiNrGooCGBGUM z>h;QSxI#4Ex?7Mh!~iz*iKnSHw^oInQ2brl(Sy5`l$Uq^{!Ds0;d$EbUuWOm74`eK zqWAgk7lqV6MyTQ=6UMp}ED$|AmW30n^u(%YI(H3lGM#g9wEr zJ|ajcj{*BuhkAfU>4aVVS>cJ;yPJO+wRW@ZUuV}_yu&F#H<#e`>(+|H*#PhGGpF-I zpNk<^KtX;(5~15O0Q3VVFH4$NQ$fD&uKRFAy!y*V$ntJ`Y>Z?C2?OJ^YX)vmR^ z>Hu+xi9V;+K6*Fa-ZB3)pv3xmRcM@6oW~FxJdU495a05L{{>JJ^l6EZuY4m77W_S^ z&EIXGjr|0J6ghWk*o2N~vduB!501c9#N)HYeKotrX;id4yWsf2Q4%Q90M+{LC&4=` z#7mU192ck%-H<(2}+3(qvVV{m)P><-)0u7$7S|g^!{v_>z?=H&p6)4D`mZs&f)bQn4YWlw-eK-0j{8bI+;=DQef(*Y-ikEwr7%_Xv`u9r9i&$J9PZxyEpNHr zj7fNy#SoVCW$=?dfMK2n%m)xr=-!+=Uay&nHSEsoJ<_cL-;VLR+sAscaifuBh>@P2 zG73QBfhgq<{z1!r3`h|Ig*`Y~QWko5Q@xHCJ3o3&znfz3w>?kr(QR@+3T92y;E22L zzW41PsNLw^TLcokgTd{+W#4^0mn+uvd+N3%-v4`rG?2g2hVq?wzuT&Q9w-@$rP$ag zvAs`I-Nx{g2QTl=?Ob~mj<`$FSMfZRWOBD+O!4L@`gC+SiZV)&>|FVOc_Ro6RGMWX zA-8gflnNpExEKhrG-0+J2OEycqzD`yCB4x)qj!F;Y9_D3$dXfQGyB={b)Qc4cn=gi z$;Tu)){KM1FRq)H7R2^d-&a5%k%fwQTIOSP-Vpb7;6A`n!7aG5>_P?h-KrJ}Te&lT zQMl8ryV*f=3o^vhKpK!bm?Be&lFMSVdb-%ddcDXe|3gq=5hZWv5|2Zd#T*s|k4f|@ z`j662g?d2f4;Da2!5X9`a`-Gq9K)iRc4^otCKLTCSvaSq<;M3XzVj+y+JqE$Z$5CA zHF70Ba~o}#KS;BzwhXNY^j9Db6Y#vWyI!U6Ibr86Y65rB?)8kT*x~OxXK{CEsO>69 zA)n@qBE)LUdl#7_K@YSuECIri?B#n)dVlPt$ zB#TVNYVR229Z0Hiu1Vsv7!6JQ@cgQS!k*qWZHtk9Js=g>ZaAP}y^vO+THCA2&GFI} zklX=sGJNnMD6NBzm@eb?_7@D?8~;R_{#U(eNObAgQz`CODZE=yxNj`hB-2uH!kjb2 zWdN6{RoctR$w}41CbTyi6^>M~9O6`DNO1`mWy*(OVbYPI%v7=XFc=ml!^EyaEQ5oa zaqQ!Mj{-*=hQ`CR&XRNzT41r+I+HpKzI%~I=LC0x|2P}CjK^9%7q4#{7v>q8$8qUO zg<_41x3bcZ zH|7gV@F=P`Q;Jqnnf_(58koFCqwG_1g8N4$yVFkxUMt$nRmnuFrbR@}{mg$It0E#l zd!Mus8*Mv3+GI|`&c^niTU&T4$V5OU3E1u6uce-}h+Uk;4{Cp55VirxE_I*v7Z&t4 z0C}A#Y82Ev5Z(E4W+sEhrUG=XZ)sI$YOK$)T$`5&0ciRqh${onYs>N6dj^+t+S+j> z8pIljJq>D(>~i(i$8I1v#UY%+Bzs5d|ob@gRj&8@gM0){?(M(7iKr zsaqZ-=B}HF<0zqh@uLDgZ$!#qM81$p7%}oJQc)uk_Q?-l^+Fnnd^TRvc7hioL-#_v zkm8F~$3VTMx_XY?cg+d&Isq% zMsE5}kqidBD9i2?)_cdp2ggLG?;uxXbYQo5Fa@zjm`FI8~Ql#U(8ue6l}#XGIfD~rVzsn;Tn*h zNBO&)ZyUIT_*VA(6!=mcrJ=X`!(lsY&X$atPEPIU&L;sF?VsA61Vt+6%`z~}Mc5@)M za6Ms{UbdC}&3*~es+sU*V|`s3h6hYUL3Fn3);Y0S4zuOOZ0EVdKG(gh>7?Lq`lDn* zd5n&WfW~qkpq&9U(&u*<9iv{gS0W!}yH&-bDhYI%+IHfH<>8LwD6kdJnk^ZGX z;Rw(@A3e22O+{Z22>5D$#S8t$;>7fA_T6o6fq($d>?S`{qd2xpN++LJJYq$D+B$Q_&{<98(^i=h?5MU~d zx>6~=pvts+^J1ZKSn{~;*V$!{4Jj5(6XdgB3KQ_&OYo`J z;L@_P`?~SPqxra6?7Us_I?PLGz?(lQczuohE&PLdsaMsXHA zCA(uWy8s6Rtj4-Ul@c)@20wEpZ{hoSQN=_q+rLmDfma7J82T+9S3*sfrbHp9(E}7w zOf(FFqK(I%O&xt=P*7XEB|Win3}mm%qU^-8d`R@tyw$6BlNY#;{_`OmLz2z2%7knL z$@eqEy0FTik}2osJgte;4ZA_uWh3_ypF`X6-r~)dDsD-+DR|h1o`RCYXKWK%2?B@6 zC3*jYi^%khFStyub&nzwCxdd@&93m;R+@~dOpL80)#b|yh4fkZOY@HX5>V2ZM%PN- z4yWJ8mpa&(1kr|0#%&VBBX8I52uy+{&;?#YDtZFJ3l94Het*AD^o{J7mi2g^@h?=9 z3-7Nr+5^*tYduhaT(bvVab?u;hpMeCU1(WSZjP5~)Q>Y|X%ix=)XgC%c@8!&Rlp%2;xW~}@38T;1V~AGq82-)2JtkD1gO&`SR2X@FX_;dISXp5A-{F?s;pw?+9Aod;UuK7d7!ppGBlu!;LV)Cx5hVjSR4KhI;%+$ocxa(L$Q^(F{WD@(JOKv5waJ7f8C zDbfk%S%>sF=<>F-pmGv(@)E5QD_p5}$s(d3aVs7iqT>52NCH(T;#n!_rKpdYEQQ`9 zRn);xJs>L+WNEojX?QxcC8d^PYJ!G7H(ljjjBX|mZ|E+&Df<{k~Bf=%d6!eylZc7_IXmQ`V8f{b^Kyd9*Le-l@ap`h&4oy{QDX-RHO<960at z&>itmH5oE{Fc^BfcH5iwd^p?beIit6z1chZeF1~rVeY8eZeE|6uO7I;@`<$9hcnvj zou)gz1){><_*L2|j8WJ+M=$q4g557|UC~dRHo%fK66Ubhw!QpXw=G^n7q5R}83Fvw zeeUUu7%Kv3k4{4(Jz@`+DS`q6pD#ooYC3NY35c4KfD61&v3WOj+v(TAS7m(bKdj|8 zGE-J6u*V03P_xZ6x)XfXAZzY?uo`bUexyc}x?m->&o1W50f<{jGV4ne9M?XPF-hyO&;{v6%09Qpt;`UPcJX4|DGl zg)r_v^wGh|s7mk>P23s%t`IK>0vWp&L0xFN7J(8>0gfSJ5QY;USrmjBp7Pnfr6&?v zFc!fonXa7-RWd_hrtJr5d`yl}_9*iT*U7C#qGuwcW~?F!hH{x3jj4B0qRqERp(!1KBB4TSJAYkin#uk`o}b^g%TNRhtI?=ecm7*eZvHw2 zb?GM2e!A=TAE|cuR}zTz7VvqUXZ=9JU@tw$wWU8kH*^VcFk27(3uJEd+o=|Gj?-8- zB$6lVA8NQzBH~*UnPOGFwr+Sz>M&0#sh2J+Qh)aB_h~VYIlr%wPp@D?cI{cJ->r#m^o~ z^pCc7<1{L9LbMzjbtv8~e?b(o2A$qEHGA3Fp~Gk@by!(gct|I=6Sj34o9j5lMYwi+ zB}5tab22j2=L-r7?3(o}=YfFFp_RM4yO2If-8Zv>FfyPxeK6gEcFzj6)~o7&_Jizs z%_V3zyKmyXXarxDZ>b%%ZA3KW&elWR~JYSsQ4$3P2|w&%QbKC>zI=M;HzuAF7JngA)Xp}aP2;>H_J)YSgc=|#eNS^f3d?yag5z-Vt>*)ZMZ&Z>B&|r23PH5I z+EL;ze~*HMdbP%I8+n7wnC9s`hpcU@+)Du6`Lmdvb}vm67I&B z*(A*vO%ywK&2_*8v{Lt@TvgNIHO+$;`C9w>aCNRiNq1A7fU$d?%)nMMiqQIW5M|o> z!?Jb~6+VJSzIEL#FHmLw3hu`&(Z;5wrWRV!IPn@x>fkd}Ge-ZDi}+oyG~S%9EWg)R zlSj1S%`B-o?av_m2=q+P$EwdiKLU{6!b&YbX+RM>kBPyE5pR1z0WvSxl~h#3bgk9r zRbPIU{nH~d$p4vi4!m3pyj}#nrvXOI!zMtj!zL3rf1g7q8~g8cM-ylUy6^TjPqR+p zhPaDnRUP#8$XqZdAyJ8pP}3BarBK6PS&Rr(TTms3FWjaOx!%HKJ{NJj2W&JV%IlmF zRLaWZmp1b7syYY*UtPb>sD6tX^fN>_g1(x@JhPk1Tn(_ze0es@irgxx&j z5?V0iXDs~~%pts*NS!9rRdHIdi?;mdt#*>0`B2+7-Gbgx9*(Ixn;Zwu;)~m9UnaEd zZhg{~B^wig=R1fp-^e+B$&E;@Ltv}A7xwfKp|`}%D@nou-iqEF1SU1} z%2nMrc&V8$*x06Dv4DoI~TDeNsa+{4gvx?@uZ3XaX zrjyG@Ek@psU2kNnN8eTh;Md@=Jg!Va%b}}7=RFFxXnoM(xuisqKvVVG&6UPsK4&`? z-AP?Bhs5K}))ye)Q)j-Uq~y~ZUq<$x+A$pjI0H*{LQ4jO=)@v-kQP&d zgoMr)MuTz4RQg*Ty)fP)>)4M>6;gwq8T3d|8q~wlA%6L9`*h^O=ZB_^V+OAO#|0>U z&-t{AN>tH6ph2fFS?Kf{hmeZVZ!Aq^dLHSF8Lr0WJ9clquzJfvZZYk>HNRHaU&-Rf2io|u~)90Rbccq5T zRk89CT0t!iM*DITn!{^0);BxL^f1R)TbAD9GqhBCpMOnTYcriqJ>1bKm=opa<_{=t z4RZPJ`qk@)(E&8`B{1aS&(2G|&>GC$yDDxUopWWOM|1B@k@137{p$Aic0iXm<&jaIvnG^a)AB3x*alqqxlm9BVaPwHI8>(akcXyEQ9Nt_}q;%6Xwsi-%}#2Nq;oX z*aq>Zgp1GS1i$x zcPNDMak|D=>38|=eecuhB1A?WLyp`j{t*qV`^jZ+*keQjLbia)b$NNo@WF82?phd# zjU&)~@3Y;4kyokE|9^!|HWu#_65%c_VKS>U7TT;vkf&3z^?77D6=RYk3a>h(qWxS6 z3{p?Bvc=_wOH8Djj$f-0TaanID{XZxCC)l9)s$vx`0#}%bvEr#edoqA+H6>E$Ub8E zz`r$uC4UHOi9)t~7n(7;bC|+9G=5;7>3*h%SjS_Zvvf@k?>uLL0!OPR#{9;#t!|ae`!CaMgK_;|Xr^_@8!`0FC_O_?{ zJ{!aL?J)9!W3F-e@O6j2ut<0P8{0~w)&=Bnv&!x{nCvx7=br0Jef3{r0bW>_-ps}J zIVq}1RPygXM>W1%-C1w`&b&r2H`B!@T2(L(>RMiE4H7q4wP{Wi2(_DW;H759aP3;~ zm84hIfuxw#e+VUgjUEo@=9|s!^Y&li{r5=$?!F@}@`452b$H2!g>UmKGPrz`EE2|y zA5LeWNavS$H;!;dNtZdqGx>VlWYP6gHdGMpM%V$L21A8l4E=X2ed-ALsGNdWA*%|u z{Nw}@u^gLk$@S1_8pG%wNagp2`Vt=wST!~@gG92wCE zelB{j(J~mZsW8${?HfPwcWD2rnpRin)PBasHWRG#kJ3G}w96r+1hT~k^5 zb50JZ34+(K{Vjw5^0fQf@U;il@n%rDPynh$zs74~g!&Q<4#9Rc7R1h;>tAgxJWZ!x zWqTg3>z1?`y>*dgp~d?4pgLD2sAPeFr^WO4kUotH1{RXy84Ax2IgP3*9{yqt)+cyuvYZ)E3`i-8S*>==WHT8vLGtLS| zYd+;aL1ivJ98>de$9?;}r}}61pG>|*35c=gY0_t)Wf9-nbDKN*?WOu?yH_!0BO)m2 zLLLoebc#*jLs`92YJ+}NPOp0TfRhb9%2sC}@ZRi=>h*!|21YuXW_A5}b7_Kpetee? z|I0%=WQoWM@22)$(DLZ-(vrL7_PdO`_Vx;?3ew?ZzXyb(>J<&|62DF9+blC5-;jnT3@C)YVYuG*s&_KT7m8U3hTF_V|5SQ78~Zor17#+gSS^AJErAFXA>PVc z>x{32-hUC%TrMTMYWtES$B5zZ&r#YB)^{r1Tp#Hq90pe`J!MV|n>0Bl$a0ev!fp4t z7N4n@i5w_GBx3uUk%pTP2Gti8UFd->XS4c=^Cp88mA&g=A z=)p3>e@kN~4gU&GA`FAhyS1}H!n#?k3!LsV+u0~3(W z-mtcC?ORHrVn%B5sBPA-OA|n9Y&$d$ImA@mbd_S31f*qVm4FK8xh9~;hPQ3mcMUi#4-n{ zp3;jpE|SvLPu&buoEXI7A(^n>0 z4t01P1G3YgBc;PmfmZ>;3ySO=ZkyDakHWCXc%)-OmsSZ?Uxgksft0RF0U4 z=%DlJP_dN06y|QYo}vH_17;IL1oPb#?e~XbZMPS>AqfmO$A+xn(}@eu6@*xD%WQ6B|lTs#%X^BVEML-xArFh>7>QT1&*`Q zj%-8{32}CaunFB)L%~Pj10N%XMw6CpSc!iDKb7c5(@a-hd z{ohdX@BDJ{;<0+i_=26YRq$UM+9QVICQuO|f!n-L&udgvW2=skHgCe;qHD(NbPi^=nAeiITU3wRgoEDaY-Sy-hbgXTh;s=Y?M ze8GPhe)N6Gmye2@lN;Ybs{AiaovNp4IcH6-cFw$J^`w6ox^{CRtr^_nT@F|H zcXe6tpguS~U}XJg-W?ZvK}W_F+XxSW9P5}G4^tj~^m?i)iiq|^I# zJmSKe+#F=7og~-#YK%xj8o08};mZNoj(MV7`)quje!_m@O$7=PsE9eRd~P`KXgaCW zhvgM_HhNOoFX=4YD4^yYon&YsUsR#q4t16!>x|ptH8GrhbtDLkW6z4?76%5muDUL#2*3ddw8)Ym-d^r z_~kP2d#Zq?-4wipw)=hBKhOv(n)_r`aKtsCr$kT%gz4oGl^CDc+cHMItP#{H-9ez? z8X@n+$!bJSscq>>oHcXzsoME8?Z(mhQrh~D!@iI2v=zzFGGDmeL!5A|Fix__(`D?W zO7ZOzR~chW9r{B#k?XFtv(PnMVa^C;G29z5U#+L`&R(MVDo-j)b9c!i80LvZgrE*M zwid4CjKBF**~7wkra4l|c@sL1m!e#}J7EP>e7)J_n?@4i;i+ zADY3i7Y^SnPsPZSP>!Tks1q}UT%u7x(Dk*||Jvj%H(V&s72icL@;AVN_`A0MazXCh z%^kHH^tAYLo!a^jL4H(yIgeZ1bem;1eu5S8NKotR!y2}0+ytLo4*+6VecGnW!06~G zgZNXL^_Mtf_mgIT+t-CLKlG2wY}-)Ypfh3vuM^j+u7-63=h zYEw`)k;UW%A+p81p(4vW6EC^X+_ zQhKFWQdr@bhm}RE?FQ3USK{@<0lo-}@!@ZOr9-yh?D#Z!qBU2-+sw{#b8dMGt=*b3 zR>cyzjlx>o)1M4SNGun!Z;Xr%4qk$QLTr@CS+xhz zaUNo`GWD`JkZ6vkop>wvjomMDQD8B%4+y*|Qa$)pOXWcpsQ4@_6NF|DdR^U>^It0} zYn8@*_J~n$w@a^3sOhN{1`M@4ZEbB$P5YikC;VV z%?yRUwotGGYTXq6=P%XE?Uz4j<)vDM(swaO9{WS#!=;{`_C7!unTV-yBZxF~za!(N zynmOY7>q+lpQdsqd}i4hL!x0x_}A!_SR2xL+|yT7DCHtcygZZV`_g;ThBv`ARGIEc zcK5w86g9j^f(&J)%dAct^G*hB$A9KtGYIV(SrHNhp{dj=HW~C|d6=OJ~aO z22JdRx)^jss-21$#u9|@a!AlakVB#|LXjk~aPU5(6*6jQhuc*Ow%@AbA^)n0M(gL{ zjQonRwEiX8>$At6YH>-!AiAabmeMfPM0)U7mJTThh!(60_2F8t#N)pp~X;QOC@x5749ggVV$Q z6C0V^db|dTIw0ljTxH<98@V?-QF^*IrH4RA%EB#&=+=fDXeY19TX<`^?|dW zi;jx(Gh%YfD2Dzo0f-tAT=5tb9hW+iCGI<7!mhcI#-)?I8#z8B>$-c2FFL(CUFA>W zB0p`@9BW*r#ls1B$0SCL@^X$*U3_2u(xQ()$F3N&Jj>Wbt{dH5lU$gySB@U-EAG8N zx4)BZ^*t}b3dDaGQUeP%^Qk=9^+ws4GMU)8P?D zv$;f;S66iYh=fH)AI@BDTUES2J-GaukRDke1*J}1N~4G-u&0wx#&XCmhv_j>Cqm`S zwC$7H02@60N!lm}?p!eq!_3NR@t~?116$yIY5ZZ=Qdn}h<1kmnOXBWs+AhpUz~26= z#C?|gb~At<9NNR$+_N!H>O;|XUuxtIv zE(Its-{i;_NJ|e4r+>zaK6I#tR7i`&;xXk#fe`xN0>t z2PTt1O*G;oy+5!OS;)5USGP%0zaE4`m+$sc}@yd$rJ%9R5@ebp)&o2X$4wDNJVf4FAK4k(+`2NsY zWIDU%!4-k%B-&Wq)qfUe4+Z*$?*X=8NF0g6YudqT(`1EpkQ_^Xp`BwPb#Wmzq)?|& zpo0I9P_o@5ow8895az0?8;6DjPCpK?*7S}ov`CUzqDD)kdd&nlPPjHGO?JE zL!Mhp-A1Z#3nn+G)S|^`;rzPZm)bua7#PTVjOihwpkPlM4|?7Y>b?%eP%_!LiOthW_-gX6-z&p_HaR_YpuG9u zvbhmpKdn!S$nZmef8^j3jE#lmc)iv8XaNI~GIsE0D&vztthJTZD~jBzg(I_*OA&MR z9~_u|z8yMov9Dge$~}yuVyege_>S04uFu3SvnJ|#^4XTC5{z1w0CBV~O4|Zao8EX# zMN`@Ff4^L2vx`igTl^Y4r=MzxgBRlJBaegJ zYL3kj9b-s*)V@DQkIkyz9Q%?v=)+oy)IUh_s$ssm@%HqNvLPD*I1zmO6b7Vdgh$Ok zp5c&L+1O|kX)E+k=`406v?Je>DD@tPO0c?uIOgbLaLX-u)ft;4O~CIHlQfDrD71XX zOKR*qD@;hGk+8J<6bcee3Fuil2s)#ka)wzw8AH$tqZrMQ!M7f1pK;jaW)!rDp-=}z zBvj%7c`e3Foyxc2e^O)E+RywpLz(SqS?$1-Xmi&pP|bO%m|nF$mWsCmjfVNK4uElr zMan18;Qc`E-G)+oS5I+N^-HmbGWH@LP}a8af9-Pw!ZUi7PyRHdbzvTa{s*ZLd7&)a zP_SHW!3exMpDNLJT>twnMZx(w$HR&$y6{^?h4d%vT0lAv{J0(TR|!YvN9?CJHS=}= zW4rRLE&&FTRiIc9Z_JW!mtarbd6BHwt5;V*8drrLOK!(3=Mqy$u@YziWEVE@R(Ak- zP^b5E^4F3EBkNrh?TBdHs;7vntXIbI(q6KpZ_M<;}qBmDe7nK%j;&j zz(b^<8zBeL$Z@;|(}(w40r|129kZTRy*4XHwaVneig20=2kkb)flQtu9U(q_oa^1v z91{a3I{ zg<|L`);Axp!D{|t1E{HoUB5Op@o;eD!`$87f!YiZICDC!dve`R|8@Jbuc%4Lh}w3d z$6Lg&z9V2e8S^&4dTLwM80!wQX@BYYP|~`-ubh9SLe@~Y+L9~I$2WXen_?X)5KHlQ z`{Nhi-O%d&&cCO#A$58zSeRF}??gLx3qEZpCm-G2i!oSYhi8~42MHvUopG`z8j7B9 zK-O+gyEK(zi{W-Uhc2L=NNLA4ldiM<{f}K2L(qt)f2fC`;QJd&nol!OuA59?DgPYit<{`C zS6FYEW#v?Q&c+nW7$`{t9A<|%AlVxlY{sm!j*=OvM;FXB=#xM2y^ax&hl&~H#6j~+*zfqcDk4~DUD ziNeFgl_jj~DE#s+)T$q_`|zO0NB+~N;h?AQpWXn<3h{@tC80wa7c(*JnOS*x0v;cHt?1>CF`oS%K7WF66T}Pwj3@7TSb|%7 zb}d9qGjcSy>w%DvkgfA7F$J8b2}$8|6gn&TMDd1%?0uK-l~z{)G~3Qf%4{ya85G(! z+Wf|Yy$`9%<3Y{Ie?Csau_Q+{ijL)FcwDNSk@QSvEG z1}qHZ!C{j+xQOWL>XFp-^0W#PQ86W8S8jzJM5WG_P4D?i<6BMfm+hXrBJ9OOjGq9feT zqunLFFS%AN4s@U4iEAp_0w26L_*RZCtgI0pH?=zPK8@}BP-~7_T2i|HTkeQd#{=eD ziE-5xzV1@IOTKrL{U)GdOXXAj2H$T@ZJZ+t1K&6#LSA8CY3kVwUlO`7qw{tB%E{A= z=L`RR{^GU4l0757`Ko4D8v!xcHBZcQ^2uYF-)AHfKEXK6#c_|EmnSTEeI*?Coh5ui zh-EJrX#%k>hQQLRXYq@a_RyCl2y-;1jyx12!Z8s#^<2$1M;C>U$%oHK=juQO@1kM& z7za48dU^+%4D7LXwu++`2t@Cdy_zGvRQI*Dltvshdhn+Tf~4QItUC8Rmu5xCzIAH9 z+XK{90N8|$iTQZI@a$kQ4-+}(2D%Sx^hn0Ivat*5zT@Nfy6tnFiJ>l0HrIzg4C77! z>B7P3sTi+z4kD6|&ThvNoLLkWgG_Tx`E~*%xp2?ISS=8 za{FbL4bdddUItY&-iOMMD0|v%%sA7Z;UM^f2mt{{BO}&(gw*zF>k?`h$tLMbFl~a8 z-qM*o^8iBdqS^Z5`u#qE3+_954(^ceHAcM0V!q%Xd_JSFQPe0#;YB_iZn^M`FnFsv z=1k92r_wMv?do1fXT17?Fb5D~7__T`*Cbi)(9CdlGBux4XD*19agL+NB*}{QkjsbH zguC7TZ1H)2^ZjiE{}j2HUM+7b3~!qUt)dM?LIA9<^idk`9J7ypQ72W zx^<>=249O>$a;79Emr8_p3{10nwJ@h=vTJ>a(^!fuNAN> zOf4~_cbjOgJk?TR+lTj+Y?0m#1YH|kJWJ!%o3?v-zY>#%$a@{iB{$eGo~SM#jx*B~ zByClF$zGwh@`l5HH}`Fv*G$jNCNY;)`kRJH+QuDL1!Fk_wZ9z-o~#^hRT3fy$iFp= z7UF6R`Ng`mswWqZl;Ke&>>#b5MJIdK67Sa1pl6rk3CVUTdNjVWqQ zxcSeR`$xn5MIrnUDuo9N5;TS>8czJfTeaxhv-_#u)=zxK7k^GR|GHJo<)~@d*(MxpX^j%x?{Ce?BetS>EL?f2^IiJ6Z1Z-h6(VFQHRsC5SOMw=WV{X?5OQspl0$_zz=| zjGd#Yu)MXll}64&MnW49b?v_H8LHd1+bAqtgLou?|ngisuWsL3<8b|JlSEp$iFO1_70dLeQ=S%4sP>@mnNgSIp zCo3u{auqC1OtyST`Z6N$^kvm;;8{I94TE+86Muhs3r{!S4k7U}YE?S8PY3tG#i70} zVju}gR~c{GjwO~Q(3ENh3F*5!wfhkFS_%>~{EKn=I0Q?ku!4!@sS$~GdY3z+ zMmazSk-t0+g*hd0xR4@naR}^Xs>{L5TQg2jEy-bUq=dy1sPMZ$^o`g(M@D|F1~Kf7 zk#Q9kl7@vs)styaVB7o*w>Z+(P_TeX;NPuS_JCi^d@5``#|`#Ie-gI~wjY4>fM=99 zZ99L)*L0QsyT`kb3LU)^a14qN@GMT=ewPA-r>Lb3OXc?xGD3Q^qc1#E-VG5jBm{wqHO-qI{zi?vng;Qh5=3OiqH%eOjKYqDSTg6HQI^{@o3Jv@ zl__UvIu$964Q#NgLO8-^#E)NeBCsftYb;zd?k>wSgzp?@G@DWe@FD_mRpKwtR+^6v z?Q7Z}n2lY12k=l{Jx)wNPV_upii=OO!61dp@22pbSKPyQZ2)Hy!u}dcmNW$#`;q97 zjJ#a2^TFrkflu=*3_-Gbl<=5yQ7(jITZ2c=U{&~a)^9G+6jbWYV64>5z2zSW(h>f7 z@~_d&(@{Av8A7aYi;l7?T&6!tfL%YU8z#os^*Vg6-wAyy3DueNuJ)k8*EWX|e5d39 zsBeEkCK1uiJ1cf}YYm<)X6Yb#sEqa~JzC+=vW~m!d`B~obA^DXp_`}|<%oYIMVsQ* z4xgUV)RDT&Sbj(&OtIX(+n3gJW%=4^^)T=VP$#Os$q*9Yyf_~a*KhQ#>g+u7!2b6r z01LhgJyXqTP2O~Y*qkQ7Ab?3|NM0I_3Jw%n=UK`}r}LVPC}j>gU&&wbR$-o<`Y0-1 zqpUd9Q%jdBjqjru#s^uBS)J1yb>`FjKXG-<8kESPO<8#!b4fxN z<$mDe+erB{Cj_~B8X=baId!;EL@KT-zLRhAwvNZ@cBU=Adyg~oddmhQ^>7BXSi+j$ z;;GoEj(b(#vbs~lGn)-T1UQhRV4>icI#cw~s0d{I7%Xj5c`Cv~RhyHUADs(M?iP_6TFviW?{D*kBj#qMM(?@o1uE}I=B!ivCCB|n#)gVj%2?^VB$>C6Xhyk9U6 z#V3&#q%kW-+$^18eb;sx zh*bD~BVH{QW%bG~n*^s#rx{*T4)m-i!z`9BcW%(%45%M zV)`>_kYCyN> z_ibL6BH*M91l2k?>H3?f2xNMqYylNBBP;8nHR$Dbb>nZuy!}FUG>OtSF2Cf*B0ujah){8GrM?Jz4CaX6DAJ9b1detD2V ze=aiOQ>L?!(g!SaL_wH(X$zy~rGlk;BLwTs^dxCvW^|0NmXq~AAbS^s>2F?=z3O|Fz8pH7k znD16^2vA+PZv#)>P&;gNT&D#dqyfPUs!o_?7^)+n#a!O*yT?n4wdefRNY%frJWOfk z@#T!f7)xH$5}^2|L-r%Y^yptEn`qz(D58~_N>-;3(o6v2ocOtsTB}up=<=IbA)Sgt zS}2aXl^OMF>O%sf6g7yRCsBZ1;A1)hA{nweZY5VEK^9ns5A9LD3!d#jlua$`ChFaL zz040kpV?K(+jjPJV>kV0cXCJWUl-X9KYv7NaS%xB%r(cVYn|cd7Imx^<*jxzO0Qd( znw-47d9!ZXLLf6?5eky1oL{;4K2TKow$;cb5R3@WG4S-5KfR*Z0NTgH`J!r_rk5xL zgr@+&Tg|fltA_sXz5gul30_e{(#9phDoSK4b*4`MWE(>aDGm%h7-TaGx5qAk1xFa0^ycI&qw>hvcJ?P9(mh5d^4=~h%JDl1L$s5ZrgOCC_nj?P zg$v?_D82+wJ^xYR`Jshy%#&k9m6tiQsDfbUXO{D-RPt$(q6B`# zs0A7)lpJQFunMxGv8z^wM@Nk`H((=>535F`thB4LBYLZDCZ)-O?8;nEJ$US2ifKiU z4;wshHsAz${`D|=_YygN;hbISW+XJqBviPT_^SWTI4R-U~_w1r< z_YV&S>OA5-96UU2{bOUgY?+gLGa8-%oGUA83`wa~rExeCW?IwmSbqB=2}iq3*{Q}l%sT`~EWYMWZ$EA+Y4AGD77WwP#& zZ;Zynn=@?Is+>$36}hEF7ce=itdC= z(nHOe&O=p2>OVJmkKZN@TGU{O&8pHCp9`$Ze3Zy@A6KUX zTY_9%fIAA9T$J_Ho{63XI0KB+#Gj|N{=d4NgKia#JN;~IPgu1fPOjgn&j9I0 z9U#%IT?@FSc-p2|zrQz#Vw6whR__fGLbh4@`sC=`b4z*~_>#3LLQj!)(=WrYf`L&e6t1J+kR{-4Ca$ z-2uYEtz9RM%so~{0ij`u4GrPcXqgVu`^rgmGBbU#??>F-YPiGME`?ycj~+%Y9rw06HD6rvA@%<+IJW;5~mFTNQ1FDV6pVZ#x&_YBwlhI&A-T} zW8+e)DJeXT;iVNdOM)8{NSOtqJ9vS3A~$Et?&s$P4%=H_yw@(2;#}~nn&VE_D#Uv6 z0Z;;VK%YXd+33yBdKKW8d@BYmN@-lw$Z-7kP+;GFXpPw%- zEmn;aG{2smeMU~!ei({XHd^Ylu+oeX6C><>+OhRGX}G>_ zJ=ni`AVoG3ceacta{&$~T+pMa_qyi^@8aX%BcuO#YJJW^dGiU5FlOjq zhZscu#`onRDDWZn6RN(5ie!Ff6ZzNiJBx6sbofd>L=-S6B0d6<)j)vq!@c#Wd(U7$ z5&F{jr4sFN>f1=P0#j-^qD-p+CO={{2Fm;@oA0*q&#YS7;ClNvwP5C0uZeqrb61SUYIr&Jv#gXW5~;KhiVE*yabX7AFL2EF}z}77D#2J=f7Ls z8u+`2V%hEaZhD8+PY549Jf_9b?`J{|w!>z(&ur<2!Vr-=eT`DKh92{^uj77EXA*7q z;TSXEDU$;j@5BkMiLe1yAf=@(44dkQw-LAJjT#Oj`o-_liV4#7ZFYNB_ z=HBr(_zwc2S1(}iaO{Wo3D7A46OdoW$e*>~jF|9H0>4LPUBvfR`7m=QO4Fmecqut8 zB3GP{Yf1JR@=z;z$gnbpsP|42p$frR#X{NPl{81aq0T`XJ$efRO-||etBNaUczk$q z%#kJs*#^cw*+z?;H(WX2!zUwc&sG=Eo>Gg0d4Jj=6@bO-ufuia_D`8Ql@#;8>yTFj z$WJH3>)UsZ{VIc12n)U|s;oRp%DYdtXNSx0>=e#w2{$$UVDka604pjg5`SnEe@Nxu z0Io#rH7VcH;IOOzevbFXMJd1M8<<8#n5i6;f75N80LW0P1~gf~$vpFl%yx!yAt|u)2|3zn2U=>AjLf4 zG&i??7 zx7;8+_TaO0(t!)6ky*LaP59)SWrR6x5EsjPo3dzm8Y5a!8U5^^s$(Z8??`)N_h%nT zKTxSN@$SO~Lk8|gF(|6HUl2wOq&4{}V|`)w=+c(oxsBjIKmbqGh(>PiYDNelI?VUH zH{{?O)81~7M!Ju`|09#?K7==eeW}B9b^+tG>vlu;>z@?Slw8lF#eXX8CwB2$_ZM-$ zeR69VpQji1DQ@@io9^)j42({#FVQJWy|{{6gL=4lGGFMTqDu8NjyIPyx}yS<(#zAA zz8s|5u-IlA^U!m8X=S3appN&mt)AxiOx-Vq#)i7OFna-EaQ< zhSv-#4Y;x|#Z@&q6&iyHtFM9h0_(sOsx~$pD z!rWXsAV5YYeBWoqw30Ep@T)Q9&gk&)M()ObUXW?4VOer=vj2BxUvCa~u{;#e^ku}$ z+$J&(F0R}558AEhkWh!Guh*9j{h#bc~Pp6%y zhx(0s>m=GvVGex4R>$dg7<;!@S6bTICq0{i#&eisnSqZ483&9ge3XftqPCkp~_^IW_BrmFgSpk&Id2EM^We4-c_@ zSqBolA3w}rey#93`Q?+#S=v-=ah%TiP5rbo60=jn0PrTT%o@7<3V79`nEpKu%H4Ea zG>ndk5&wV8z4cp^-S-7N0|N}DLx&1ONJxW%beFVrH>iM!v~)V8AV@bN($dn6bShoa zjda6%e4gv`eBbv!c<)Po6lTsj_da{?wf0);Bn`Mz@$A>F)}rGzP92u>4HtCp?;nVB zSRW#YC1}KvTTn4LT4(Ua&CnoCX~x!{Wtvj_kjqS8&JK*nFmaO*SoAav>05R}Du`IP z>PSB+^(QHAsfbwOYOS6O4N0iWYjQ%vQqJavHx~nmj50K&rOQrhDvuI_azA}#50Qx8 zmckUXu4U@}m~y{jzx%0Cnjm(l!X!FGajc1X9uke9kHv4Qxd7t52i1&eLQ8!-VPRqV zKf;Cg{11(Rxbv?~s&eoS{60jbKZ#>EYTL4i_8K62WH5YMM47shu zQJo|m=Ka{;>9rg!WOVyUs{L!=SB|nQrqBa#lkh~Lmx~G|^#|!|#uLsx?1@hA^s&z# zkasm)jVQ2axfXA)Psq%BWJHlOY-J*`xw)}}j1X2HK@v0s959=xm#V!aRCWI*%bF7Y3jPAE#U|q3DiS_to5uIk`w=0YeR~= zYI0^as;uNYk}Y4ql56sri;{=f#Oe%b2~_l<)(xy7kknV<4|f@UyU)d_h)hmQd~dM^ zQPlmoay;dDa*)%}+1XiNUmqkVy1I#%JR{szeL(-~qmu`K){I=QkAK}O^1ttMwGT!| zU)ar>IBb2*j!Y7AFDpl9V`k=eA1l1hRoc?28R5QX{)mM|mN!DGUHEhg=z#6*?(Smx zE-o$(vt{@8^4hQO1W1u&WZ5#%$%IeX&wJgwcdvTbXNOo?E%tZtntKeRa!Qj)3lM4E z3l0ue>sQ(ve-m9fh7oTU;!_?qq>>Ab4jvUn(QrBkr0KQdJvxUOq!`@N`^TFNEkpO_2q-iB(KDqD4Z(WTOPv+7^I-Q(Oq;Q zuaYG%IF=fWgx&tgL+UsjsChisu!@EGcChKsVnUqS?UTHKJrt@hmCrcgM}$qU zRr#LNI0`KoA5O8)8YC`XU9|q@0t=R^q_Eu8Np3%XA0bI)_%T(JS&DkIPni^?yXZeEm9~iDQ11u#Xqr zW{1VmNPl>ktFfpu(^Trwiv6;)70?nMzqOTN!00Rl~RWH$HQ>$bT&j9Op_YevGA1<@ zy?@w^8+h!f@mN8cf!*U@bFZUtin^V~OI~flvjvijN|%+MPkjc)#!bSW_jCSP)-q;< zn#12`9~B&ogukuv)OK}ckMCVO?7MpX7`b}r9)5AA1ACrVv1X@kUyDF7#VFq!#49Rl zV52qZg7`uvhTf%3%1Ln3Mv)Vu#d*F`8eAW5?nOrsqS|*Ni|HO8G(1KQ@CCsr6q$_H z$0&@curzglrc-P&g`_TLQ3!=>h9-Ebj5moxrRZ^u5Y&xn-JuEuQjp(n(elJFG>DFh z1kq{soiTJ=4rWM-cu#Jh7(rP})C4ZwDLD-)U@_*-NQ;E=qU(|jBD?3aZ#s+H?gO`- z9BpNxo2B&IMSkE$5=O?+xaZmgGJO5Zi+6)f3uugJAffXbvmTgok2id=m5(VU^oI_M z^b@Jii`>+ixRa9;!QJoXn?LjP9Vzz6lCvRo|2zSnY0^UGp$gAHA`;FOa%EWaHfPP9 zgoGrS76l;kCNSm^w~}vD>@B#rMDJl2z(^cT!lHF_a`ZUzevMrY*Q3AZIIEscDpomn zbi+wkcVjg*v!uianA6(U2l1WoXRdM6;CTK@=m<|<4;_L-E<@DGu*~g-4H0V*zl~e(8yJ>0 z6QqF39APa{&%80uTzXNTs)RCofnOIhIA&3l$D|175G|K#!Y}>O77z1baZ_3uF+Ui zbLFR$z5QM&35(3*$5C7?+Qofqhk!k&i9uIMO9&H}mHpA&?7MgVr1Ht6Ew6iiL4nQj z<}WrjHbX;0VVm(WzQ<>c^W3#LwY8l!!-YV)^t{ZH>07?}FCeDc+uLjN>J{*`nwuXN zeRae%PWFiQ`udthtB{F>r650l>S)}Q`)^ijT>?doYx9%qqeDa7n zm#x9w%h|m(b=MZBhVs%O2|9)OQHo(kXvTnMTw{q|@L2@2M<$P;3~w%yl2u+r2i~5cW0yQ9-^$ zaTpn@4Qtn|I3T%xKIaEPv5LvD|MHDe)fv)3R11b=xIsxvq?bM$iVv=t;D38#E>ymj z#28~6@)_UJP>Fn2I`cOpfrk-O@dKXMkELO(PgP+dh47#;qL!{24ZI9#jz%L3^8i|3 z6k!l)r-Cemh*Ni?nEPCD8JQ#{m_WaTCf-ib>dO);Bb?FKWu#_rew{_g12i87$8xKx zPRxJwdH(tRUfbE}=dWKurr({qN04^_jM{YTb*!mv=rr8nv0J$|wfmaD!7c>#-K~4^ z_VUJA_JP+C|C%=!{GfXN-E^XLn)|2{AGPq|3t9eH`9=Nen&!0}u?^cW|OA!bECQ=cJ9$Y(}2Osl{wtmlc^}dON+VB}RkxT?7 z2E<%XFYV&TsOZ_;ak(;oPE}PLN?G)Dw-C*=Rw=vLk-Q7sdp>)kX$VZ&p(Z{DrP*Y8ffamn| zI6gLx-X|th?lp2;bm%T5QIR30+g8P=?VtOByO1V}P5Xi<8rc=l_3eU{ieUcJuZWCF z%nO_OK--dJ2&`0jL%KhL$wWe2tUAay)PwVrN8Kp2&?cBddvg)ujOok7H}?R2Vbd+Z zUe$bw6b7Z;uOCW?3d)MbieE<5eQTE%g(9rXVTEoGrq&m*kZc1n0tl)n8NuA>Y%C0+ zi5p=zS|a*hkF)d|HLD>0`c*UtNw^m58RUQ3k_haHa~-{SG3Go%1Cd#sU%q&<^Ko)= ze*d1Jz1GK-R(-i!rhm@g@1wTs+#O>Ox%ISM zj`|WICPj9yUI`o@sm%XbqE2_*1=nQGE{@G1y6>AC3^MwG^Z<@KW_EUV>W(}VJg<({ zAGl1k>~Q|;QY7+b{yJTBEhQ-_3Fxn(h1$Nq;6$Vp^7);zxljGSQJu3OCGduff zaBVhjR7LbU8~7w_zRb-TeF<6L+VTM2hI_ZOdjeXnS{fPyLKo}RTE#kLFNXQpYv^AR zJD+!8Dh?7Car;NFm>&o>#6WT7xmlotDnNBS7#xN zynK9hP59H()AqL;D#mW-pBir(ZFxQV`phGRHoICg+jDPjPK~cG#&K5%2QA969=NHh zk9J+|`7GD~3#IkpY-qFIB@iFDxzKLXt9R?3s+=|Nj1&fKL%{3Mfc>oU5d!h$kF-J% zA|9(Hzc6?d?h?M4=39&z3deXNPh6#F^YAF6peK+DC9a((1QGsm0`!@a; zM_!)6Co=m8uac!Nv}Lu9mFdrNMmCPqft>bZ9XwY8KGfT{gmf1m5a^pe5kYLgbU(kfAcLa)G< zZ(@B*%a!=XvyQ);R6Z!;@uvj~7#x-N#<8Uf9JeKV?deDMUp)q@9x5NF;;ROe`Sw1? zDCdJDO`i%hIrzw=g%fEH4n20yf!#v#fJNh*0si+7yeE`^vud-~DVtG!!j6fk)8)s9 zWS$$nMRrAush$UAIXl2wa34@@-=nf+KcqSLFy}edIvY%r0kj4v{j;)ptx>Fl?DGee z$99EEe|~Y^`A>Pq{&c>*G6jx?o7ycZ&xM;Mm8YhQf!OgzE|dLybHFTQ?ZkL&ZZ5s| zuhZ*VisOK?;EvNq2bt*pcoW0?a6E8Y>Kv8@9`Rf0*E4I%z_4Bxpo;phYtN~DJh;{B z9oGhgZ_btk1q77&EyrG_-y9VOd#LvDU+SZQQY z*dY?;XoIj$SQ^>2z2Xa|Bc+AJp@gCD*;yqtYU>m>^+P;RwHM(LE{76JL7h5TQQ=DG z=*%2)?xsD1xr!o7E9wk?lopbQ`21A-Wc@OSPW@x!Pk}7Jh0&ZFl)^^Hb#};&rsJ*< zhZEU>q8K?P5n*t!grpx=W_phY$%CqTM^&Nc_p!w9^TiVSh6N!ZQVjEhzsA{5!|}I0 zSZ<*ZG4}Y&HPIWj=g&VrZ6_{kixl(*nr_tqq%JHUNaA-~B~lSmJ0sGWh+T6xveDOn zQREReH#zAJ5`hPNj#fas69|dj{LWK%Z@_VJw%e)G%jdF+XI4L%^w@h3)*Qes$@cXx zPnp&AIwRd(`RX+%`Y26|?dJ#gYI5`Q^TG6%y^09`D~r(}f2s!P9#H z3J)Pt{(d&10MgmQ%7+~tf6voCwIC^u2<^qCx(diY?RY-$carnGTx`#d6gp7xxf%uH z=3DnDPuMt4y-G4OO@X^sh{B-Y!E%g>k@GLjHRCsaYwkrwMOezob2V>&(fN25W@i5W z16(|>GG(dUw@ZQUa`xxXFvyqf+O2`Q?ZrzGo;}dYQ4u}<833BNP%Ns1ZVLecf#UC1 zq4GqGMyJ<%)e-lwAVuassBVTo@M>t(;bMsYIRuUbc0I8r#!kbiU`z<71(5z7xfQzH zo&ztOJ4eaiqKK)d%75s-BPJf*e zTW5i3EPpjS{Ey-Sk0q~7IJuJiz9*4ad%d+7U5xv!`~itH!L5=lAeKa1xTl;bR3|S? zxOTZHahebvHJc|Dg#q=2VoSq@gS6X;0$Nc_LhBTg2yII95)}x!MTtqPQJuhA_!161TWN&I}stxqK#+%Oj!ExKKZn`@5DXz({FWjD;JJvGcAz5e^yA@4y zXGrd6*DbTySbR7RRFV7p`?vP2ioEta$ihYvRZ`rtE~_Zazfivsn|xQ&;Rhx55&2?-kZEgRm4ls!a_ZF35Ck%53*5sGvQ@k{ zW9*CEZ2BfjUu&LwdQSqC+BjC-TBn!5A0$6A5`ari0>Z!q_&t^Py5RiHzM1Oj2?hfSFlV8BTz;U%N@#6Pg`)n8ef9fNqX{^?b z#&6#RKQJ)~MXhk!Jx514OL3!-Qrc&kK0CHhsEr5R`2B-{;tuBsoG43#n9NdfhZzJT+N&*?-bsXg;5x>vf0a@d z1CpX;fntwVo^=#lD|UEZ&-LZ|ceg#SlSJoD<~8pV#{vNXLX5L3 zpES_DY%>^K%i^0m+bQuWAC08Ww|@aj24FK{G};wS#Gv>`s04`V9FH4KA2|yM%`*a< zt>V^*&II7EI^(isSADxZHj*FOa5`!2#_-GT3tHjV!g^3Rf&Q?dpkUKs>fQ{u#|e1V zW8wvA@Y)_KkbbbeuRA{!W!q;}zO|JV+S6m2-c!~S`uXm}>Gj`4ShTR9 zq&gG7ZJqJE*T#s4&wdyXk1+*M6KH-cZ9XXgNe#?5QBb>xF#00+qCNO0`O>A)L3vXZ zXoeJcoZyQ#9#>7zklO43OT_r5V=eOFwl_!WfA0%oONB$D0#SV;(YtvmPted>+cVd4 zW}1_eiqV!cxtz?RE4^?s&xb=!;R` zMOk3?-|WYt@DB5qp^q$a-;k!h@IZfZO1#UqScMm|khgESL*GKGMUg0z zl;cRkc(znpV0+*ns(D?5S5o{iQ-UN61Kko1No>r&$YDb0Nwo_R4b=^ab^?1RgME8^sKtZn4J;@Wh*GnJMGbeHScb4^pP4QE=X(kel_!4z?|zyE`A=O{B6tu9KI%KQ75 zDyxg5jT(cSlk{s_hs%+Budn0*N`U$~K7PBx;p2XE*XIQV&uXI2&Efdz+~sTOVZh8| zdGzRY!%D8^r%&dc;S{2#{?j6_etrd*z#$+y@gIisOixYCt>{)0Cg(v2IFtM1KK*@C zkGfUT-n3$aB=(5w$Nlm~%}AP(>LxyIPU7ko?yX?E4iES7Pjmwxk5BEuyh~2C>TNr%I(*$zEd*b} z{I|JjRa#tsViG*82%{_vxXDZ@zlCY3yke+-IQ3b3;6V6r_fr^@+O|1OyuwTjX~Avb zMF+=&P@o6Xf5Rj|u+jL!(L;Rk@&-(urqDJ96w%h{a5Jn?n{g*dIcqi?D4IHXO+e>9 zp_#3k<@>d}6HFwCu@e&9Sn=~Ojd|3=j}PXIZ#TgY4zO49*e(4r%wtXE{!DA$kGz!H2DN&X=j11CBZ^=eH05cZ+pXfJInAs4=_$?!;25ib>k$&Q@73h6+~quiRW@m>t{!78#E7%G zxygRf$;W=RsSPB0294Z)2Q77eaD9K7_cP67=NS0Jf$`m%wkqO^M4WF?UshM+O3kT( z69stP3lE>2H;OupwDZk*0(GCO+{&W*H}E+&Cpr@mK1ZQUj5yPQ?DPi#!HmerNIo)lMRlj#Pnw#OBOh~m<9_}8 zX?u~7_3xGI^Kfh`8(`S>x7XsxPtWiRP$>K*t}}6sb-Lbdu9&^|kmf!uR1^hv)bLtQ zPh>?%>pFavK8?sxe#2IEN_xp>H#50BEbW01-28ln!W2qCPYgxEAT$f%WM7ov5Y(b% zml&kkmlftqL#O&85XOp|gZF(|;sg1t2K600m>Xhb8-wW>6mw)+!Ne~tqY6S=)c2gB|b4F6OwzdY=x25Kto~t0I zySZAMd~0V|B-kVT#H<}<({!2YI6X~JT2qsl$hh}iQeB-0f*AgJ*XL|NaL=j66`Rrf zKwb8}yM?-AxnRheyKH|#=^=aF^4l74YcKZ|2ntePwoyk4?oRv`x_>Fc)C_u_7Z(>z zLN~b}s7p-ZLr~v)+3OUOIDc;z6z3P^@&CyP5D*mfd2@a2vS3%H&MO7VwBd=T_Ph0# zJH2|-deY0+4~l^z=Z4e8@Ap(mT;?*;(j5V(qJOHJM7W&O8)h#6I0@2(_PV`B>w`Nn zfIlq{WFVT(&Knd+IbObw^kx8k#Ymw=R6$A2m&W22YdLLGhO-IFU$Z*j45uh6h!jS<{1w>$B1KH~#Hw#P$u3mRLB6{^KObKNfQoA5Cx3eg%P9a%tlXmT z*<9);Po9+9*Q|g#O&G+BzbX2|+`gnw?99M2&jGHgr$-4B|NRh93Cg9_g!>Qc%S8?o zS=gJ*rYf$%O%95AzvDxQ*P#827tJ~pq?Y9!9nwMWNgyoCpJZg`myIxYZzd&yLiMs0 zmm`JS5{KY{=YpSXzff&%wRQp&8Pn}~*uygJ;_P*J&Ptr=V$O7{bB@T5(}htq zlkX?Mb%fCTR8`xZL(vEYB3^~-giTIaju`)}vt`vo!@)o&4T!4`?&x@E7^m*8P{Y|V zc61c`HYzf{sgjO1JFlxKL22>gzUXb@V87wh+bJ7BL@sHln#$n|=vVX2O?T+r|3Pg` zvh~uukBeH+YGhfSZt{n{)3JJ+pd_V*jWBR)u*$-zg z%%pj|E{@{j;^=wX59<{;>I&<{R>n27eSoruBVDr8Q8Z9%;cGfql9iR^O}2aaaszZ3 zYs@S^!d0Z=eGZdzQypZ+lb%?vtbnxMI^9`IAa$S)2ME% ztx)&`6&=dd7>UV?#MFi0>#)d0XX2v!%GzQG zFAz_uMsB`3LXt$2+#20RFaZxQ(ZqduY!^UOUIAYIiMPx%E6w^XJ ziPVKj)#~e55&&3rx39`7=g=k&%<~jU9n4J-u7bU2@#H*@s&sa?PIHh^Q0N`2SmEp3 z=CNxkF*-U1{4b9QWr)BVo*O0s;RsZaG_Mr{ZFPrU7+1Ib>}%B7nfZtGKl?;h^PY#G zQ?@U}A^%S9M5T&;zMLMB^``=R_=Z+4u=v6B&ixWbUB}i*}9U9-h{#sH}Sm@?6-^qFCZhX@dHYj>KOc(k6 z&z3PR?(-?$zgBu33URwfnGfbq`Np7Ke5;~|hs7sO8t78rWCBAU2|iDRTETpyUP`^R zcHDTT?N1lg4(Yrmg&^AfX-pjElHf2x{{m84zdt4fci~9p$%lu2#KOK$IS}w5U;J-% zv``&!YP$-_*c(}gP|3wPY&`ZMC|-L*2Auzd72yj8JF#0#3ei|qX&+=Z&#BK`>Wc*| z(z8H`-l{~o?|#awDSjrm);vh2*`%rQb5u~(B0z)ui|;IjRMdyBl*iYd!Zdw zIPoI5zGT=tY#IDKtfyZvnJD9b(tOAkCt6bLkNF-!|7al+3^p%AxuhbeoH@9V3j z9gM_=y4$CBg^xfVa9^0iWX@-*qI^KW=32MW6ql#zs)q&K%&^djA>PXHG_OlLP*-Jd z3jf%El7sp)Vv^_g`XY(toNt)Q0@IH0tBP>i zo5efIsAHneFRb>bZ)FnwqFV!)VjkF;#=<(^*WqL)U-LBMnWX#z#8aeBi1{1=j5+kP zF=HMrx|x{7V>A;#cw$h>eM`CLk7icHQe4<{grNw|%K%ae>hjlA7YYeJMeq-}Fsn zb_I&7M`61VOH<<$wD*dD=@n^23>A(`$8wUxfl*6MRs$h_B7Gm@2ZDCV$Z$~tIZPH? zJUKYTq?tiDXTNf$o&>pkXi|uvgVsL9s#dX(*ko@D$(KezTfZL2BQYmu32-Bd3`XqL z6>4oJo~IbV;r?na7^LC%AGL)Q{eHfA>Fw-%EFexWjgZnXGBPUeO#A0(UTMcD=Q`Gy zeD_lPfC57&$HMjsUN@0=7F^xE=)pti#8#AQHJ(30`NEh6#o+8kG|bRN)ej03S$ly{ z0jPR9^sl-W$p zBVTqSiDnsv77O8SZcZs$ggD=Q_;zPOvl4x6Pg-wDHM8h_?YbAb_7C5u>4(|8bQTpw zp}lbH{zd&iF2L-!EbbZdMt+iiU#*_8&!0bkcht0&l$`yx>1?*@en_TBF6tdthy#@$ zg5#h=GT=mr0N?!pY!Zb>U*r8Cc!j05o;5=s#cED)lwmp2MI9$Y zJLR|^))n6iW0dr!u*G`N6JtfINh5}i?TMvBg6NQXs&_%#z|bN@}v7p-u7<=J6! z;a*=8KU-V;(CGU6^=3W^-sb&qTCobL@a|(ZPa?`eG+j2p3r0`KIE-q0l?6%cGCx~FrNS(*VGwWx6Irp5rHp2(Lf;7W zKR*?=GMA1$vb)3k3JoGP>GPT{6n8%W(GHo=NlT>h%G6;ZGi7EXGBP^NxAseWT2Eh8XG@R(q#mh) zKHf`R1fY1*|MQGVP7#7+LiM3cU^#s0x&*}4IhO`e0>0&L6x+*ECeS0C*n6^+eQeYi zLu6bC_X2V;vHk4GXN(n57?41?+=S&71u?FPh3b?z;jr%nej0>Ej)~lVoX!YSk|mam z2<>=MLnUG0Jp=WZr+e7 z%B0Qwq@+znhNVkyak-YbAl<@BKtb${FEMDaI$j^{2PkpX!Z9L>^|{<4e~v7Q6>ef1 z^{%q6rh+y-QwSZfzg(@w#IPrE+rxlxFQj~&(c3tIt9>l#33?8?*Gk&46k-AeDT*Ib z^*uvo_QoMGAp~eP=r&z@qUpAd*gOW=PWTn|lT^rMyo})X_f<_@%dLP+>`M(_|o^YH}9X51Aur zQAB~eyi1dkmJ^vcs{ce1Ir4K=u+=`p&P&?9S&QL#T2fO2Rh)|l@9X3;0McYN ziJpF-`>ow~>>UguasOSysUeplEUE#&F<64NtIJB&qsC97q6^l=q(&$hLt>GEpdD0F z9`N;LS`JMJ9N_KT>F@=k(%Wemj0{R*+vTP7^cDoFC<4d~mA?cUWP9c5=v@XW(f8iI z%fUEM0=%FB)lLjq2!uwx9$jqPI~z{{P(J^SXp(>&`SWj1zWTNXw38ce{EA#&O2}Dr zudG-mI$3QUWxTWSGM7iNLZCcQ?r6?$sBs?EsTdYa*wRV}IV3^pY1HpVLdve^QM6mp z$KCIgo2AYD!ZF3`ISCCRNE)Q-dJV540%j)8ATCY-&+3$ih&$-vW5A@Fg=rx);#@)e z{*W&CZXyI`UZRXT5r;w@`0)wd<8gu@$XF~0!9B)10zpi^5DSc;?lLkNH41uPQYD0Y z4h}r1vmA-qMcl9G;%XJG5q0Z48#nItDE6G`q5oX3~xV*Z>_0uezbu2 z4&!A;L9(Nyo=BRAA&4#BUZ@PA`6JO|l9wERNMGPfRtF^{&!{Bd5FhRz$5Y&kqPWCOHWZ`S< zn#7=CQx3~Li5cw;9EWIn1w9e2{PK=V`ei6+)BmI9u_eDaHxST_ zWwf9bTL2c$h72%2`cMsu*Z;4DY@aM@_h-%f!4>u+u3mu zP>Kn-E&+srsq4)L>rHr+IQ-)Xwb)g2S(b+}h9gx|Hg>vCo-Lp!cg1!{abdG_ zycwe4xiEv$bNVbXdsC*3_ufU{MH+iHzeey$2Zgi~n!AY{;XQ z7BCXYM zot$t|CdEFB#KI^j4Gz9Pik#4#96BOHvhe2bT){tSR+%9kc=?2-kfwyt-~Nv!XvXng zwmJETB+KKwd5i3=EuAQ{GSx#NQnMe3>ssk=(S5O({EbYD+XUIUL;^~Y5c+-WrBYER z-n7y;&ZDS%cQR!mh~TeTHu}QJl>~d6ImtU7dO=0MthhhKYBf z#Azy!3GeEjFi|u8-;R+5ca?NdH0y-1c1f%Yh^1PFVf%S;Y87JpYxE4dd&_x87LlFW zb>^}tZr%$A;BSFCgfrZGZ8Nfr`8hT&dxi4&Ba*M;ki8v2&e%)YjERcHYCxqM)48ruZ=V2sH|k|JyBf#5eL@#MM)o z2ZiK;UyHb9Ac&A4U09+##FGOly5LE^QuO0GKAAGOQ8_*j$sm#vt*emvQ-QS1NS>|q z6TxJ2&a6R}2mSuI(&^e`Qbpfjf=Oxp@0{2KeEUpt;YixzSa~$K9E=7@ZV~Vsb@TW$ z@A0c1Ey@2jC)ErhYp%&P;tR)JZX@QA=4Od}B1>2bZ(k2GW3EUOCm?dmOX;_yty~p) zQri5bozc9NGgRQ{_4_@>PEyFT7_?(@KE2K# z&*^_>;iLI3Xz2dT33YIPgVJ8ZELKL~<1>tRw5xq-ZXs^(fY9oSiB)S<1ia1(xn|O( zCuoUkh_Z{kejJ4P6jqmPS9Hk2yQZIIYx@8CRCeC|;*$=do8G)E!E#a)dQzyY-`R=6 z5HVaC-!5QPE>0{3#mR=&x5tcDI!F-b-hoIK*f~V7Ctlnm_QQC&t)|T=W85OZGL(rS z%zCyHr3!~MI~&RqSu~V=GrgOQxifC23}l0q=HB|r+ZNv5!5 zAM=#m4Jj|V-E;FYBD3{EoAwnZ9Jp$i_ncnXbES@QZtB^|p|*Jajn9m%xR(Mp;UO`m&Mi8LJ~5X1BcU+LL>=PkQgHzw*0~rGM++}OKDcEUjS&0g%)bN{9fYU zv{kJN7xQTXwbL!5!A<&&<^yyuBsr)XF)57@B<1 z7K(4==B+ZZdcP3zzil;f*tHWB<=e5vK++;*aa>aAaebG)XOxI=GRb2*vpx!QN2u4= z>ZxyMPhNE}>68C&yFmUmjr(da|DTWu0%KW2#{W`jfLwe0w|0P(a`IpK2gZ$dF#bQk z;eSC4;3rjN|DDj#EL)EMLJG0;q|tx1$^ZZV&>U6+1=+tnAZ&-^JFhmD8Z!ZJ%dQsC+$wZ)D@>b9YRxa;o0*=MqQ8)0tIoS9&J-<_)y< zJ+}9MXlrN`9&Ur#p1)JQ4ojU6JZ2p99X0u`fG_vERp4#3!l40uE&AWGRZ-C%07Cu@ z;52C)IAB12#>KAKPR!108yVd!-Fuw?P%r@ItODOuz<`)HsQ6lz|Ee#6Yi}!mKJG8( zNy?t`^yTwzLAE+DFMhG-<+C>HBD|eVZDXb^y;2) zU*8u#w`_nyqc<4ZUXA~QPcOSCq0?0=G*_O_=DnEAeMy4v{tgX+3zs{{Zw-xscM zz0caH0pxB!*X>v{qa<3hzwmMt@bJ1%T_^2j5imfE-g=pvGBP*U$b4yC2K2t$@rB;6 zyUzuuKaV{nDf(Z5qaOkWMXms+G(pgQcO~A?dsWvOFrNvdQQM_!fEQ3Xes0Xa2fWX< z07b1+n#_H!&O7-Ltv#D@V{P>h+aj&!QlO;mpPDmzzVgLZ@c&j4llGvC?!(O6UN$m7 zzd9#N*}H6i1Q>F9WfBA|nqbcB)s#-QP^n*5&%Z10vL0IzL+Y-((5Y;*IK>&GBmQh4)c z`54c6AM@X>PYeyEK;gFR!n7O_g!^}p8Eg|6sO;_mRC55S_bUp_PL0KNTSzSfX*}@D z_~I(7-;19CHfym_dFNq0pplP^jGUf2gL$OG)&8xWonzr9OU2%c2cIEBzkXFZb$`6M z@uq+E;_oxDAeB?;0&q<*-XWLs9P~3*R#xm?he5CYVHg>pWLuO?0&xS^Z3oRNn*Ux{ z{Qyu=z6Xl;%cxGU$3oFQ*isdjR33^i?p1&F+DPGd?5wJyG>4dMjO2LiJaGn$4=`9D ztFEqIcFR_7ZS1jAc~|5tL*2JzAd$yrjFtH7>#w&P+xoB5gaz^1fZw&Y@`AIIljrXg z$7i9T9JlE#R9;8JK3CUy=OqnRAq5Ae%$vkuw2O~tUWBQW3K`B5kgmhKlWg? z3e^?H(daa@|3hiszKQyJnGt}tvKl`h#Zwk+T}_+0F%%({=K0=n9WKFi#J#H7tsV{WR;lpofESa>~H7!SZrk)?LG*kA0} z>5Vf*L?%DpI8*VwB1%7#$|SX11vA#SM{(&QfJ@qVabZ)r@+rn;YJWYE2fMpr09za( zbly%RdO0~br}OR2%E(D=bVQ8n#gO#;natr=wPXk59?t(uKA*g>x4)fEznOVzb@X*O zoA0|Mz_MFp@87%^y>)20ItP^dZ;RC;lZp(f%I2(r3`$8(V4z_3Vl;j3wiz7^w%D2^i5L4Ag)~N=Dh5-2Fn7s@$_S~^C)*o#+2{RVrBaom)gM52! zo(mCsl_#<@y+h0ILMZ#5k zTtGkJ{N{46X?ZbhT5r1X?VR>2n=P#(z2lgB-cAE+O>a&cMANw~L#NsB+Q3LOQRfHI zjn6R(&z{Ax8GG-|y8ewE&Xtw2RL-$=%-W?_o9@6$h{Gq1%e+%J{aO)BD;xq?sa*fH z?o)g3M?4l>;Dpy*Y!rB0jJksp1P>l=F8KYt283zr^R{9g!cC+HWbn%+6f{e07mX} zahMKq=qawNs;q2iyGAGH4qN3oJ1W!-q(@>@OMosDCMJ&Sz}jKcb-z7ez%;tfp8ohi z{Q=A)XJvYiG3R<-CfV3GEV(e!fsw4HvkneQb5z&P=m_^kg^JGw;3p<{H$#gDNA)fz zvOnBxRyXkBqbgm9@z3v?*#e%P#w}8XeLDwI1b6-hZBkxB%SnvaL1@#YOg*n z&0m_ztnO*m)358OJZ4G{*9JURsRua^>lzjpmhcT70${f4leTK^x(@E{2R>@L%;z@( zQ-?JmB>xT~vl>X@H*JNXSYnEnI(MF$j;P=6?Ez#_E-qU6_V#2~gemke68&sFF%cr^>^YrYssmhYAdRF}@k7Hm&ZAD|G@JL@y=?mf7N zy?;XR2`D?$H?(j9R$1HS$$4!)Ae2)HyYw-`_ij#R6B5Y(=|8=EH?}?5iA^;7y86~b zG8V6U2#m1Q2?$E7(GP!inrNX!LcoKE5od|*Pwpfjt>(E1QzK?0O{48bb;(`0a|pQ8 zGbih0^Wi)Fr04nDn^2OQ z7{G43xVVH%h`62;eY1)j*rn_aEC+lAPQ3f*!aEj2ZVop)Pc=JoB{x8RlVKecQ9 zKt}lQR|t}eyhlP}&Xt_*vY6hx0_-y|<<<5vg|jt8=Bs<>`5xetYv=vKYkPV>GLxSq z^~(kjfnV@W1BUG0mYIP_cQ8d*=DnG(tM%#OEdAW1$%OtAH1D*M2 zsns{CaVx&Hs*`j??K~Qx@6s2s-B7He+k39K#Q>d<-9XV}`@`XZgIX~c+i8D1KmKfb z{BEf;B1T<3z{U)i!8E))0W`P0B6k((kD5O|sBlvPEuaT?WQ~mG_=?6oW7-}kb*(2{ zo(dSUkDGIRvXqEJ#}Q)ws3<3QmhqLz{`{ap(3Ohc>Fb;0%|R9xo^ozATmc~y>VH=n zBSI#o?#!;5UhBTV%;+f5n_oLF+Tgo7J38hMg9Y*mbDmq_PVVTroTUvl({_zV!f#am zb93ON@nZ@5Yk5Ru z2*vf=)`s1IxH!^Vhk{?Pc6oXFh~o4$A8DGInSpe2^NEeES5<*_30^-XGai&)?C+kC z;}A>t-=1ITI4TeBNwQZ-DuyVq;%PvYZKjOnXO>{=T8#{I>`a8>t7GT-@S>dolW$YeoRcBN5EpNsN6Spt}vrlxblHN*9h zus3V(rtAj>xP*8n+4>*9N2>pPOyhp$e{SPR-D2KgS77PA|aS%kx-oBLU@ z2M{t^Ya9!-me*KyS>>NAIrlfWdD|_U=Q6l8^=FLZvYT$ju~p3(MJ|o-aHqM9b(DvO zgmm}!&z3oF-J?jf8Tb0rQ&19^|Es>^?b_~aVP9X~%a<_mZ>*Q2g@rLsp7>n3we@_$ zpp00x^0=(I;Gs%HUJJA^ed;l0HPpK;sl|Hfe*Vr=Z)U5k{W7A8cNO}ZEn611t{;h`rVA2+`T?I%%RI{)3xovT;uh**5_%;|G> z1s@#3)6*aS{LI&W*xYwvz?oUL)sNeHZ*R-j*3sEwEd$&qIGsV&Gf3k_sl3>1D=V+A z?%le3!dAy_%?kDN^NWg_Ro^~i$B!M8CQbVE_v!9!`Tw8440c;w7#SD$YKo>dH`lwe z5*88XW$7t@>fYY+UAnaQxm4PjIUBd{`IE_c;qk|aHDUe7KOad}R|(v5OD=j>h=vF& zE34b$jk}hm-Ts!lckf=UFwvu~ezR;Wi+`2e-!kV;%yx};H+B{Sw_JZLEWCW_^7QA= z-|OH1o*TV-<>4jQU+>MHZ8i6uzIB<5Wzfg#pFRaIf3+yNr3z&=>Hr@e=tkMCBFndc;p zE-r51;2wXthKPTUyz_J?{f>~R$wnn{Q`23&$v&ws_94wy4 zjvueqb_H&9s@toyA9(Um_bXxH;2<5F_eHy>@*H+`HRKVlC|aO%defT{tIB!m98IY= zU%bfhoOCA5*mIKAT)&ssmxoMCbrg_`&{?EXnQoW6)<>WPxUh4=gb6QRym&BgPTB6e zNgG#$XwCH#|Dd`^!>;1Pfu}_iS%B#)YVEYt$oQ16z5*xL&L;J_Kqw;O@CW2*n%WH MUHx3vIVCg!08$Sgi~s-t literal 0 HcmV?d00001 diff --git a/media/small_objects.png b/media/small_objects.png new file mode 100644 index 0000000000000000000000000000000000000000..ee8e29453c53f71174f9a0dae4fb3fac3397d155 GIT binary patch literal 117472 zcmZU4bx<5n(DvbkAa^*y2^#cpg2Um5b2veBxCbYAaEAbg1_%TW3&AZw@L(ah91<+J zL-3E^_tyK@yIWIJ)w?y*v$NIx^wT{tS{h0OcrWk(004oCGDHUeKudgTvbg9^lB2m5 z)u-;6o3fE706^ILUqk!INk|OL2>}b4<1XQ6viuuS&==_n z$$-KbWm(dk(ZlMe+ka)dWxK%~K?QQ;Cc12yzW57In&g-A&Wt~9KD znAKc=wtNv~@%+F>#e%n3k4y)P8a4&|u7U*;;-7^5NlW zzUDsy>s$AHT$vPUE~lrQyr|}&`&-&;m2!`(0nNnDn}!;5af!g4Wz>!nD--0L_c6ET zNzccXwL@ep%4OyK(fxm~9e)^KY4uwV=vSmqdnF()CH2s;@)$nedD+tDb7UGb^`A~( z!ja3JkE@*Kw>OzVr)(}L|HDa#i&|6I*!4lvN{i?ASVsWw8}*wfm13oZAR8Yj@>deq zOwM7G!&lN?ePjlA6;}L+4bx*KCD_&&S8%NDe?rp} zu;E;%!L#Wvo;n88`Tq^k>1|pv{@;@6(W*c1{n}7aHwJrx1pr z&l!VhDPYGzT#_(>P%Bp$Z6KCqUVTY{9zug(Fb3yEwbXSs{lhmn`Fs9{(^YE3@9wWd z6$ZYk>vL_(a4>o?DK<`#95W9Ah@hbrgTb9dg#6_ z6cocv%Qs^uLz5Q{n{5?(EHZL7DXcDaYM_poDT#|aGj&kqe)de;t3WVe#=o}R zjiGOfb(^}oz}Xz>B+b_YMk52Y5^QjYhw)9#h~KtionS`en#JysdB#W+_ft- z+Qv}UxLd*-cNbr5A2)d)HqGzUf=^~VMXdj!UHw3*HPi&%-anqZKK2A(N=tp>{XtSj z0c>B?+0l9y7x(!0V!b14YBcV3%(Q#(GGR-ihI^3N;EZT%(pn#(4| zP3vwPjHIhRTNf%TC$jOKvbEQ$actp(VVB}0c2K0WzpZJM8w+RtLH z(0(Z``(6GXZ|}Tbm{_^X3BKQcJdhU8Q_l*XBQ8tw19VhYoGz9;xjyi*O5HpHx=6{hc1cLASlRENF&Ln)W06K&Zrf4*214Q*8+vBql585K=r zjOgg-^KT%2w!1|*-6~#-3fZGy)-K{*>hRuM2phz;a)I#StU~`BCgS}%jQZrzi}|aX zWe7U1kr(eF0u%%~HS#@52Z4 ze^)_kE4do1D>V(H_oyh_&b!CEGxO`wm4LuT4O~*a=OVQI`I6L{MulD*oi_{j3h&VI za3XO;h(pDp9cIUWZu&evs#P7fDMf_XdF@hvVPMA>#j?_B*md&-0zu(jdLy_N6w{`R zBfze_?B07meoxh*HRH-dO<|?9w~wUX<0<0qtD+owd*u#EBbJtMH}oq!fvo(#VVOu= zbT&>Qhr9KKD4o+?}z-0aUGF6S3I~L_>we=&EPhY?b9v^9}N?{F^`|-Emrta-Wll71db+ca`+ z4aRD80}T9#(XF_?KdXH2P~L4~L3eh|hNU}CpvUy*CkG?|p0?vy5bzdUASo&JaOty5 z$T3!b zMMdovt20JQZ7C=;HOGI7@}FF6yNrQm@i{+&ul_ z-_MqB-5kD<@OQ*4J{*MHaNYR?8pPoiRC+Azgx@Ol-WaI`U0LYpvfnQSAKN~xKmMt? z`!^m0j*!-8oWi-H&&|z!_?Hx{Ep>=UF~2D>zd7zZIhmyV(cS$(uY{zN_B-u-T&Q_m zrVsS$Kp~B0y?QH4^rwgFsXbZi;QTB;0*eY=F8OMQ3u7pRven-xG@0^-nb!GBuyR_q z*%_|dSl@_LI)31{B*DV9)4XA{E}w8o&?;nu4;^jF%bnl3&3@6l+}=7q z)yng$bc>($E$AZTR-p3gO z;k_4>xeRi~e{B9}x7**1E#F)Z`3CTt?y1`FOh<>cn!qqfx|cZn=0-iWt2R%`Nm2sb zsx)5qIdMU4u-Vv{es`gb5S|x<1fDrmzelMPAfnT>%KNL|S2ISFEX~U_*wIK<{j|v` zEpGS`YC$T?V{@-HP^1AQl@%>8U&PTUDvhwpYIT>J){W=uYS>>t(UDSTil-}SXc*N&?j%}$SlmSXy{SAdKP*vgfNi|KY! z#V^}*q&rRUy-3iRntGtn!PyF*Y3~C5x&WLKeZKxzX0{)gCHroI z@T~iiO%pdk18)n`QrA>6eoMZJdctrD!@4+_Y&%oW< z>S*@X=*4jpDD+}9N;(v^BK086{il+dUxH*7inOXjA4FARY15KFt1yeee4edqHCdNC zI-Sb=PR1<#Ywc>R4jZMD3QW)5`e-0^W#3kTxF0)unC!ePxNA7u! z^ShpV0N!AHA*QJ-U|RXvo~2J^F?0x^YvwAv4wpP?J^X9u?)Hl}v*PURI`BmfIi{{x zUD{b(5T)x<`^nO1j^AH;slcgsX^r;l?_S6f(MbmRHr_48`CO5oH62PHOAu>AIeP1< zPM4RLt)wJ7n?=Q?>4m8Qb@N<8&eG=;E$>j6UEXbZ>)|98!S)V|UMDldHm- z^NJ>G-DKTaaZktmyPJ)F%?W9Tfr=l`x*<0@rRq!M4dHOX#xoR3UYU-%nkfnnQg3n1dj~p%wsaL5&OVWqlS#2#IG#=rAK$f1iMXZ=nBIQQV zg}%=S&Fmg~arH4Fr5b0g$VRZBx*OAnw$#>888@GWvRy;Hj;TNo|Df7k-i(~Ov(3IC zj}E#5x&kRNDYN_c!c7_TbE#!% zs+y3O4-+}ugNO+#fnSWsc>${B1F$Zey-T)$=UluNN^lqz6G+L~&RuMDUKH*lm1C$g z#S0(Htl+)xrD$ushd8>5?5#XhnIHVb;pO@Fq3=@h1>u4Oi8F13KK*;Hx6>3+84mhr zx(dQtFd-lG^65V|@D3HM-hKXh+p=l(f+k~~cr(B$gPSc?EYblj8j=g$O=u`RHIpc$SI>S*jf_16Th^p z?%@kM83^)teQ#sYU|jV$6a3f|^hosmk4&}KNXtrP(;jTddI$@mzBqDqS(+Bp7R7My zJ-N-qA;bur*pwihtIViumCiv0J$Uc34##bNHP-kt*=X-Q@!(%4*4YePTNH7nqdP3f z&yDW^TG{2mr3y@j_NE8t-uu-`NJ~fAM>7hK^1(+-oL>O$vu5`$PWPdx(zw1u zZC5#9QBa-Hh^ znaf3356W*io2ndGyLot6vjTBT1U>GwuI!JO)(!0wb)I|=Q!O`+BgiRsob?#$!^`By ze=C)9zIbrW+Ig2&(4F8ZoNC3;mt zias^Q&*n@<5Oy8&Sw=8t9o+_(M(V03KF4QRresRT5#MsKg+V@bo(s@0h;j_d9~*2;w%*I8301pazO_Oti! zrCx{B{4d4Pf{RRK#%QDt%U8(EF0*?@MnwyiVED_6*UDa1r60S9l^x$U>sS~tp?Ay1 z0HR13pg@piSqlzfZ!{PeOGLAq13Q$m+ha&}fw`on)ELvvF=x<1$mFdS5L6(X@cP-c z#}ouIf^8cD%6nf~s&6!xK9!3eLxlU9j;w`P+>%{6(|X zg+EWD+->Kk5-7XDZ9WH&p-V*8b^RLYv-@d)QwWe!YJn(3_yAhf3 zaa{@8+|0Cc=scTQ%$d|R=E|-XZ}zTAyuQD^GWWY)cC2}SIO^Kr_xKQg&?qe`vDD^` zGMb8-w=q`bZon6FrIX4XqY!!1+ylP&!gi+8v=c={CvjI!fBWMJC7(WVXGSAe!a39P zJM()r?RQZt|7N}#X9v@IvWaZ?>ETMg6qO%ouMUs|CWv$Ft5GCF!f9J16n`_%_DCj53Fj>)`v_McLsL-ZG(=@U?oq<<1$O+E50+=+#j?x?OwMJeOas`dLVgk;?H+tF4}jyGrYK!#%CG z9h!x7!|A~KZ=;Lcrj7^M^~TkBWYl}!gK6`X_D^R1EN)sA zA{XtvST@hYo3CcMWvWW&Iol9$h6NU0d^73*Lx;@ip+Ht;EICH;?wKFeIAZuhA-xW? zQQb=@@W#ny)ppRIvzp-g2H3@D&3C_(cOQVO8^lZOvB@(GBO8p$;j6Mb4mrO@KIf<} z4h2f(jaH8mu|);k&JtZ+U0z*Yy1WrLG%$0)vBW-eS%(PwRE=|QDWx6SrNVDf?Fr+w z`;x)$eCwrG3L2H-yj>?~4oA1@<^{(Vg!eUn*zh~c8A7d~wJ~6@GBMimYPqj_g^{CB zU8O#kZ4*@9BNog)VVE!^k8fr-!c9EhMv75!3mNb%(H+qDm1IJ)$s zj%cJMjjCov2#MbKZ+=u+lz8vYkN;jIuVlVngJ}HL-k;L!|K8Ufe1_k9O!qDy+EKZHYXruH|`J4|-Za z!jD}GrYM%ko(P3erZzqp2BS;t^Up637@wUj8c^Bf1IN@v%m2n7&K}+P_a5w2ZYZc= z1Uyj4Fhxnt>;7HZs3*X5V8~kMUH8+Pionf>P!3)fe(iwTE<3Y#oR6|x6m&k2`_%fT zs_A$yPGMpsCO@Cob-C3~DL>%qLAR=prA3hT>nU{O2c=pK^P9#m10`e?aqlZLmX0rd zr@hTy?D63PiUvoEi`y%TK}J28rJ**AgX>4q!bTF01NJEAOwe7#)A2p zoS$g(rbTt_N#k%#AKR@`XXlZI8PnaJoq0Cnw)Afc)uVVY{j!9HsUN)#s)}xG+=@kg zBdTOCX!Q_7xpsq}AlX##(vO1_sqS8ug+sAIcdo;`4RX|w);xTBxWbH!$b=2X8- zNPJ=vtl)4BXf_&WpR68gZfaF=LeN?SL)W{4L1@|Kl*BP9Mmg)>A0f0Dpc0%(=tzy; zaLWFpc7OMh4z=XWYtiQj1O=Nx%ZshJX0$&zFM#%Cu z3bz|jR0`rF`!YGX4kiMZBzYaVw+F3bPti$<+3RGDl#1*xI5g;#vU(Gg#aqL$zCOW# znT4yf@Sf}CwfdaA0tvIc{7T-jww=#;qpDQg6h6{oV%PVU%|2I$qkBqqJ5N6Lp?~*I z&?`+4@tIYf6$S6Oz7grX_>H1?)9xu!vW4N7TNRKFNJ%z8sCOrnSZ}3LX)Sc`fmxX^an^Q?5Nh=3?3YBAb?R+C-H@1v=miD@0 zYjq!Y%({M+Y1hpS26P~i)2DFYbDGI1&cP{=^^~g9yD<6~6KydqiutuJ6y3zDSWd%9 z=vm2JKhIy^hj$zm(+bNjsw=L-d$l{QZ9Wmdx6UO-sq+;M;=ZY+^4rDBB8?j+FTOdG zu)Poo@3rXD7|+xvk70JL=qQ$f;kxC_{r+$3lW+RCB_PMD@#)`Pp7@t9Uu=gP z#LA2%j}|GJTat{`6f&dN;T_Jb2k^>nl5wlzo#>pP5jYQVw9x=ard+7^iGI%d?Om4$ z26+OXAQJq0Q&xpO%vo1{q=Xch%?i@yVTs6UB|q#Dl^MPBI2RRt{SIeD4i~agQ9rHS zUi0=i-EPFXa{}0`M?7N%<-?j2ienbqe$DSm#+#ptGojNRNmC)3=Eq$(Ly@N9{wsa~ z(46ecpu?9_yJ*4J{IxZWoHlQ%>IK4p(KDF}gWZc+8TOWYUUCn(l*OS&dW29^KXUU- zE!~}v(X->B04rk(eh`f>29e-ypliCt5vwqy#yO-nzJRP^gR)WqP%VKkte;4QMNm}- zuQ^Q#^f|$+Lvs=HAy%YwRB+bU#`u_79HDvy$V+>oNB<5&NPrT~)~#5k#Ch!yILV9B zvz$?A)JbaMb%u@u%hi*Wo4-6etLy0L$vo`Ha$WJi`FAqOmXs$P6@^o{*KbJ~>E4EF zKN)rX9vpnL+d&b$^(FXp|L(5JXPHXl_S&k(`6(%qq2~9vmNvk)UDI)H6}>aswBq;g z+$p#aWg~^qc&Z$;uE)1?7m?VNR5%T8n8m zo({@t9K!1i@Lv+*HjPC{i_zW7uuiI1`LhIN*3mZBptZF7OdQ8r3R>SH>UwXgsU> zMy!$>?PJQOenQn9vRY<-Kn}l~R`;Ux3N}5m5T{uf0-%JJ4IK}j0y}3<^MakUIPGjX zKRw2=;&cn0@J~p!eo7=sU&=?v2IU`^HSY_~J(kV{4GHjQ1c%xbwrvjE@E;9T-`bBv zqSEsXc-7tf8$Sm-mO+uJ?7Lf^XE{ZDodX_Cb!MnS+iZ7CHg4WM8mX- zBV9CXnx>}=IwHGdW&s?UzyG$JOP!)a8bXfI=F8$^SZVx{iuz;9t8_93pOE%!c?hu* z+vnB3c$qic3fdz34u;XN1S;e7=+)g{nm$LHJ3~0G!2@r63-h4ajn0!+ugz&L7tiX> z(k9amPQ$|9)hX<)ibPu`yh@DyD#_u&cjD55x+-gOO7&Ep9?l>yV;O5 zV+ic>IR2p-+zMgj21JQtg%2Cz0Yi3s8Nx+i0(=T6e~bMe+Jt%nqFr%~+QWQ5FF6ka zCR6jxX*E0+H*nd)w(Uup=8L-GzP%K-)@EOsnfs^C^Muueu$Dc5W4oYYi_h_ z@5=62nzcXyDfgU8?fw7O0^o`e!EJCgfzk|b3=wE4UU8m>3eeB$Yx_9~<=`vx@W3-al7A?zRH_bm<^bfkYc)y;3E47j@~D-*ocyYAZ4klg6Uf{(Q2e>o4q-$^6ZCj?7>s*)iVRYHh*gz;qyp zrsJ)5xwRyZ(0Oe-!g;E&m~9lB5~IH-1QwAk9Tmhi&v+Db;GpYy_qzmcUZENf#*Gd~ zOuvqQ3F<4oDC~rKfFN@COe4P|Oi%gFwZnRRF4HxMPF)`CI{c6RZS=J%p(>yEI;j#1 zxW?ded(@2W|N3(nz2UUw#@hfWBqxg^4{^Y)FYU4(MZz^)VAD&VT3Ncxw5D)%hB&Cf zRMF^jfaD5&4B7A&=?Z&xBlTtvQyk-$rf&Nj)zJV<9I+0s-?!yA;FubZ_`UZ7HuZ91_F9`~7Sv?X@$^%Sz-;k0_5AP=G1Gc4Wf=FYt_JqoHhOr%=b?hND2s*BvwD}|Z6MeB zx%_^_gVATztfY63u5GKfY$QH6*;3|3S~>15?)V6YZj}MY;&RRw=yA1*>NJ4D{J6S z`zql`>TwpkAgDg;Ju3S1%YFjmPfp&BuMz?OexA*`paQG)!z)@Hstyl7#_C@nUFz#N zU^<4dsuDScA_7qqRr#uL zQ!0Oi+gDBN0+yEMVg}W%FipuYiLu3VKXd@YsSZt*bT80Vq4?xz&p~MlAJ zO0TzBBw93-%zGb3C||OZxN>~rgQ1gT$1Jt(99k@!v9^SNSY<$;z{NLVA@AZ)N1=SY zylpHP(GcibI5NzbOrp`FKD<5^b>qm=0+=8hkR385*PATEBaj;UdM#x_$+Rs>yJKv#!_CfUJ&5tZO8=-}nAQ&+|F&Hrgg5 z9XMgAuFYmpJ!CqT6mC0ZKTOOS5W&ZL37@xXGb)hqtGvgCgCo6P=LqE)^qA_19}F)3 zN;jQZ7k0LUTid*B(6mYIqN!dTYJ9*AYWMPQ0F!~ z8&`Ra6n_;g2MY*=2Urj~5C1S*>{=3x&=g0DX*~qw%zO8og*#RgHm4N7(5hFRKxZ%K zY{|)PHNiSDBsknC?%Dkn@~tg&4OXG=X?|{9egyo3JM)>y-(()q`88~3tNcoBw zf_1U6vDMBB749B)hWl@5XdZ^ z6&~n&0MeeV$%2*Gqo7YT zan%Ik0fbWT+xRyzV~3VMPf-dPd{!-o{+n3hc4(H+KKAf>Q`RKARM6%{<40V@UksJx zjb1)3toTg&7|EyP3^)$d>sq+dQ~h}bL)A_e2A_{A6umjj=(~O5a5TooTB-R=0o=1I zxwOlYqAiVwm!&E4$EtN4V3lZ!FSb)9zuw()IopKvj~IJUD!_Gx*tmtFNTB&j)vYJL37^L|R%f!Fd|8#H0IDW9$s5IKjT(WEW=a&K|!y0^0Ib~2l%TEk~|*zbu?$ZHR{${ z_v&o#5Q`au7)y+JGe^tbuU78O)CZ@A7@ejgP##naAs^o${HnO#81YEICXUbL!iSR` zJ3)W`c&4$@l7%FR1B1mesEUlOaKXJgd#&Tn$-jD45h1wxP3Zgr^c`gv>sQf8ASQ?C zSxJiChWzki2}fc+mN@ZJd^GPx7A|ueu~x{jWe7AgKrN! z{{E%Um*c{veL0pQAgv5>8Jaj%$*`@Fmo2Nc)hr$W?t(3n75Wk?i-{rH6`I$y!fA*b zDH_VT1dZ2=!P3}ZAtvxT8w<+#6UsI__GL(?xNuk&`C|>TfLne#_8fhRC(@KwLy@uK zh#yV5_ewaBwfx3r>k3Ck;{hesJrIEX(qD8ce6su`@Q-yNEXi^zK^|R%<5061ajM0z z^m*%i1M11j%B;fi&FZTqg98ixp4W#^;J|C=8~eGH469^iaepEH*kIkwUiQj46Z7f^2Q(ulIc}CQEL39LFFK zm?Ot@sB>omap|PWBD2Vf%dIer3aE!&RxZ{>*lD1a^ciEX<}%1YS~AFOLP9F&-O04b z_Y3QSfRA$>ik=Fgn9B)?un}aofXzs@4B2gd%AC15)^B?@@sFdSihQ-mEV?Pnc;93Y+>5PFkBV8H z->w6^qnZU;+tTp`drNqWovK}9bfLquWSKyc;$UBkn~2PRFSk{QyW)*imT2D$Zz{yh z{R+p0kCS#4T&Hp}d{TA$gUQ**sU5{P$eeW{=Cpz`$4-h`50v&%`C@NVPN#^{*t4OH zMn&{!$*@<6nEW2p8u-VtcvcWG&I}vx*EW5#d^I3r;jPV)`LSYS<(>rR)mV))J#9W# zn6si&fBR0=)X+PJt(`3?CT$YMqqm%U2Y#K##Ao&Upc#ST}@i*Kx=&MwkwZ#<%6A^-JhiHO$0q#zxDj;&(}Y&_ZtK z`kZB{q(zq@TdCr{M)Tzaj8Ppz%8<}DF>zKigXyWtXT)+)4rGrb!H5GK$%r}ZH+j{Q z75)`?P&q;GD%bH9*0v&y@wn^yaCxRQessVc%@1OLlMayzQTA|xVa-_-d{b3n%A<9h zXoo!bzLxUUZxZlUwZQyvt-_z!dj1QY0U4cj`ztSo^=p}u2YLyMY}yQ)|GE5moKQOV zz=%tdV{Q$&!|fX5(>T=7tCO97xl^@QNZ@Jj4!`03piq$A@%R0I zKmO76v1l-7ngocVX%O>lzaPmI=svo97#@gX4jJ@onvAd#NlEwhYv(Zh>w)diEO^+X z?gJJDt$P@7Ma^$s6PrK8<)vm%yk%FiSZfTY8VQ`$m27^sw1$rjv@<}Ag|^FtwNX*& zs_6`3g)aRa+P~wdVa4DTPD@O>9 zQBQeWmG6Arg21b6&m%C0lF_Id8NMk9D`a!~ z7$m`_g=VY7;agN!%Z|~w()(%CeXT{%k0Eb}DEvs+H1n4NY79ZRuFrDR&Y;J>&RF(YgenNcFyn<1z7XvPCw9w86CxM%yl`b%2UsC;Bc&{AZg0>o zZ}VdLbr$h61aX)aM!W!ib#Z!AXSOoY!qlsz?d9mlZ5z2L{ew3cDP`mCd>a}LN36$NHW$-m%cy=NMbSf1Pd8qSd#OY=SdN4H+h+FF=p zS?Q;c{nC&y>@;(%r7modLNq=-*08^oqzu@6r`^z$-11L_h=r+#vq{H6=)`qTWKRt6 z69AW0hVV0hscQ}8f@dg*4V1N-Lz zHyB7vUb%#bQVv$^37@%=AHxE5c=E*<=&^lrSIzMpOY2ETAUK#ry%l|A zR95&4??DLwvC&s!FI7`^I;QaP`$ZGM;Ios7lq*6&ypbmuLz`d>G_eu7o+n?&s0c}> zYs?{F%6{d4^j>Q+=!uf*rW990Q1(RA4 z1U6WSZ;Ve$DilhU`1U8Vi&G<1krr1D%)*!A9N(sN!nSyVlI7Lrv>+<`8A7su8<%Ax zV@J~37lLP}1=J3mC_U0lj_`{pQ^bWUmOh0KJD6;6#dmaM3?*C&?efr1T~IAzUxVb_ zP&Cq`p{{leMKo)e9=BDxntlqVos3ZES>g~HAgA#nbcZS~)>2shkBp#^6`aF@3Nd$Y z;xm>m38F*)W$QYUp2MJVpoq!ODkBPEBFQ4=l=*CazRQ+VhoLV-=5rjkB}p7Qc)k+e zNr}!MzKb@dgvpfq)0bmXyx0>E5`{hvcosbviuSVT*?jspF&u=&H@ey#0wOZ_JIC40E_sVN@2_^Z-(I0HsX#2fEYhAj7w1B_@}a`U~Cw9YI0T zaE{PxmNYU8k^8BLGb$R52y-rk1+2|42=SfQx8 zTpkv1Gy+u^ri4Wx!mq}}U}TtzOj|lXDPLx3Lm_$w-CzOTzY7O&amkLBK&cA;+JK|w z`!&rV8DpNYF*?-a-|(xI7SWF6GTm4k6`(RkHZEmtp$s2dRWb%9eHFK-%nv~BBWugB@S%|28+pn&2)OkOVeLBCEo{Sbh zPS;6!1#Gr!VyO-T;sMQ7i!suAJMquZi6I+D0YG3=VyA*`TKBTFk_s=jCw)|$@_BkL zBw^3%?!-Xp#rO-PF!Ucor@yWUm2+wUwZn z7{(7LVWkkA*jVH%hE`y*mPaC3!xH=@3qQMbNQ_YiX5fV?i&ifUF9Lrt>#UJG9s^6G zRirU)ry2RwH{TyG-*j0YueeFBRg2`zv>^c ztz*;9l0E~49@>EgHtZox(Q{Km{D`vX4bt$lF)&D@m;}EIg3qu$GLi^`$-`ohTk#`B z4sdxIwXxp7vWrg}rhrPv#i5iAJjN1sY=_-k0hw*eF0d|4q=zqhkWyFo$xP|;*ELp$ z``iNuNIB_CeXyCfO^2vrT8%_nD3ic3%1{+p?%78l*m1G(4?#kC9tFJ)PZDcSsT{CC zz!!*^Ek@R9b7^&jmYK6KxNqFd33Kn2&-R!uI5GDeA->(y-1+#gxD=W2wdhsC`asfQ zRdsc?_wwlC`nok-Mn2CjCZddZvL|mJyCc))>UeoGK$@&-b$=$aGFVcDOJmO21$7<$ zJ|iR-O7jhnRo0-V@b zgCwJ`;>EhZzQvR~=2BiwR(WY$4w&G=U-$5H_y5g3o;fgFd{#FzeWC4nxoKMzmJ z+NgqujHYL(WP-8Zrl?ZzUf*~a)-=%D1JkP=H8eAtcH>;gPOY_;fr@RW?;?37+ev#@4e9U-YoLDdXxa&B z3}i@@C(q+0H=E5!*HJAcU(fQ;p00KV%BUJ0-DXXW9z?cQw|kD=#yWl+T8$YYyo%4N zKt3JCDNbN?IBC4)=Phd|`)A(;K zoQSKO+@|u!l2<~Ui`w~QN;MfKK!1nEHF)n`pMcBN+5PTvo8P{V!QR5q(4@?@7HJHI z%m%(H10e^sY)VF8dyKB84Kq#~(Zs{I7gxh!pLg7MJejL`e^fdHY|CP5UkT4C2gFok zDK=4wTn=W822zj|n>2>fDuOs)joI^*kSdL6;iLF6a-V}3iitK-Xr{0;$T+uUPHl*+ zt#T@tb=4utimNFwQd!Bm*cViHu;Qdrcvn4R3>xW)V)x!1CO_R=zHY7#i-(y4FDkpB zfGcD8=C1i+o?7~Lx!@rSw<`cgCPWT5(n=Tz|9IfD^Ggx}z)8R7P)x+vji8jt+?Fr5saR#PuI~!r*UdP8;u{lN0KfU(z!(i|L zSPg^B03PH%7K()p#As9_$@jeo8CG2^If&p#3?ZiB5UpGnAE*+M1pptJ1K~DdA~9BtgmWO-OSmi zO()i8+3yRJwW_+AJO@V~M-%ZQ-gmHh(JSX*eT-x^l_Jav$+=C9lnn|kMeYvYcZ^KfsQ zQJM@1M~QA#+F4+h8I!%pqb*~>%Vk9p{wl*>B~z0pe>{DrqL|O(dC4pJ25sB2rEI}Z zm$t;Fo~r-EVKR^PkC^DJaNQr9XskUMQ_BE&T_Js1jhMB_nDwoO~i8H=tT`4_R}e4Gy}OlQZ_3IQg(V^_69B6prupPqM>qlxE; zZf2tm*4tV!^nMp1i86wy;N`qo+8NUr&lo;DFOxL(_Cg7w_I=&oc{jd;HPQArI<%Iy zz7G^EXvlwmkms7+ip*|xSwy-ll;U}z$kIiEA7)HkzxyQUi6zygsfV<>JRGh(5It

5BRu+c(>3!x>z@nBGq1VAG#kCi+E z0N|(UW^P3Td_+f*I*`ah(mcw5oWg)ghjc6DPv|T;#L#B2SO_`;fC@=9M=}1T^x{K= zki~g=+u71Vsl5XQ-|;Ucu<)lna9_IaM9-YC&^CA*>}&o~ozI$s#kW9BL#4wLzBLb? zq*Riz@z#AcrFS7K7-f^~sS(me+EuwRCFo@$0`KpI>Rqq4?_IsmNcB8f-qiU<3L*n- zH{*5VBmqjGr9Gmh8(Ez69vq1XL|nRIEKQ;wE+a!>Xbg0+^%GvV-Y8cle?JJYi_HHi z!$b@_l9$FWU3f6-HXCE0BEq0op8rSXt2q>^~u}_gU;$nbnPm^!7J> z;y(Fi`S~@s+MM19>6?wio+w9*;|XP2H#SRh&F2Yh?w*pwhqC*zN)X zf&Hy@UpgV#WNI_b+*Bp6)T5$lniMvP_jTHUG<*xcdZfx*SnElv4o#z+Gr$Dp6g*n& z;z;#bEzqY|s*%6+X|?L@s64prmPxK-=U$d$ZGTe6>lR={gs^up>w(!xzA6BsmD8+_ zpILoE6f&D@t;=WuBXqu{0?E+0wo`TMf0Pn}I+7Zd#R4AF^$#aR>zyalD;WmjHfMvk zMGlE(u6JA3k8^lCb=JC%3n-)LBZ&UD79cC!bDuI4J!?xlwckA8z_F(Nc&X!-=y88M z`1n5fA!=_L2EORBjwNLjZmJi1Caj*u_nBiN=NG#W*=LmrIL@;~ykrb6kp$&lmEWJj z4Apu69{|2ULBBv(9g0d*K$;qZfJ}&BW?BwqJ@E}wpKxlDiI`+!Z#jaip=3a3#Ha!) zRtg}3IzV^OPD29dzCg73bbXOf6{_mhSHG&L=<4QZ9{1yWAH0V?aNP}K?AnIeA)=Oy z(@;r+w(V4PjH8GWLP|;098bt26H&}*ngmf~tbz|d;3T005Y@@e91LPiF8Jg6cxskS zF6NbEGq}FK-tG6ZuJggGs;QcSW2&ow6FN!c!BQ!?6hdS|M3~TVVxCOXy~Czyu#^cD zXFBK`g7+ela~9Qbja5^F_rwUo!)MiiA*sLErDGn^mDgLS}}EIa0e{ z4=HE%_44SX>XvfC?HLRX~?&&X+FMS?WMs(%T z>LYTi+WW-&Vo_9(4M9HT=S@AO@ z=NynIyBdJB-i?An0ognDm3KZ!wv0+lMCcFz7zs6}C&l3a(BW|AE^p(pKc=?nTJM;c zo%2=I1m9Gln{`b$>)NiXL)A8Q+tgJRf(NAg4<7!X|KdCE{L!BuUmTr3`_zlizY5Ll zI#PXox!Sg0dEr<0o9$*l#4+yo53W|%*VotA{kUCkw%g5WvmJ*q_q+Xmw~jH#Tr7De zB7b&%`uzO3x;WcQ^|KE)o86v#000C8W&lLs1N@J6LxzGwz+w+D_21wCE>6XY8JOZt zur^Z!oI(<)OjggxQ$Za70HlB?DA6WuHak=YcwmQNa4?mP#sG$Xnq5;YMVR`-SOeU_ ze-CEW7YS7<#ee*rKRzaRv|Rkwx4u<(^~L$who9W9xoWCF#Hu<$NQl5h!5xeQObx&s zdjqJLMP#BKO$I3;RLF!W0f6@&iBe7_rzwy-=VMAD61?+nax|ADxfJP#sq3Ous1VT+ z$5M#M`{0;m%34*^Fpf70;A+g*$i5P}a?U59CEfEiAXnWdPD zJV609v)J#(G4)Lr`RUN6p zmln;!vm{B;a&H@jtQrjm!Hq%O?zqHT%~{Qm)4tcF!)7;LZkuI&(jActG3M;5s@1Vi zY(-2c7Bf}IgQe7X-^}MvFS?OItjK2PizTYd3|%EDJ|3$S*FNVu_>)DG0Mcg1zE<;f z7fxqQX|oM17IrZT56yD!JW7n$+nvui_f-fDNfw_C8PsFWQZS~RV|mhb=c#A!eCv1r zqvd=yuiQ&_j-EL?<%v#)s32wXGf)uIiAJ7^UhmhsSJPYt{Lg>?+v}_C8{hlUcmD8S z|B&AZE`TOPdiXo9ef#h17mKI=hyUq+`RD)SpUI*|(wYz%8&NAIBdT{?H_JLSv!h!t zztY`4bxrLZEvu&X)#B~dUH-yz4P9CGb8V<6gAuRJs{Sh$~jMET}m;g#Lj`5 zBL)Li%a)O-X=+BAOo+hDc{lk@BVtZzyW5GBDn%v|kt+D5+w*=H*kP!6(S!uNFS%YUk8a%|D^*<)P+ac&@ zOP|7Aj%V{ZcL7w2ZO0U4)B;U&q(n`90nQCBqRZrbbJEO*`5>3^dYoCR+R!ra*c8B= zvc?E9NVc4r)rE$Y(8{33C^$PlGUTL+sY*^!B$o{dqGK6gJ?^giTdJQARo2wnwYds8 z;5v<`qo&ep$`Erdxrj&{r5|HTX*!wItRKhCX1nO>#}DrhF#>a_>OcOY z?~S8;`)~ax|J{G{cfR%OUmbHUI;9^baqQQRudjEz{XVlPlzX2%=w;=u5q558x~Ha| zw^u7(v~4$A{8zvCwY!)7PkwUu&5te{&>Ii(8{N!-uQ2&l>1SvS&diWJlG8E*5F(pp z00JZgntGaKbiCdeksPKd$qq~>DH-|zrjwS)CT@o+vWJ>c6`=hq z`xt+X^@Z5#NNuRkUpRU3#TU0jfA{Vu((mJDofjv$Zc5JHhbmNR7MxSFSjxWN*LCgD zGch8jl+=`voO2$6V?G2FL=%ZA7ExxZd`Kk^!|1&Oq_(XIu^&eT==*-kyqt5hwk@To z8X_)dGb4&)oXS8cBC5qK_dPo|pU<3kX^cZIo+8}um>QZ7=3Fviggx~9gI z!3QQrzz{<1{SXsC$)yA)S5ia(BOw3IcI^U|w5R=&xEfT@Jr;Wu&>&utHnzj>yT0D`vzggw=$cx$N+KB$v$w_m( zc=Y)C^6_fB@6$LWKq%$bvU~OR>76^Lngs%1Ke#;QaPrL2+vWDp-+y;~{TLW@#E3~z z=L`SCpMLP2@BGEd$?>nh{_?G-&m>6|+&+%T^-{130LWvEU{GNbF_KH1qh-CG+w816S{z-xc1uK;F%L>OW=VrI&}y}WPy}q7Mp+4(9e1_*!f9CT zcAIwIu$-7|(6%yA{(Du6+C0XGW9(4=zd95j5XBZ?Y=B7D6n?dL2 z%}GN?!|HKA>=*=U<;FcZpgi|+b$w0yIwJ1x>7(%IXx@$e@bUfomsi*On6`b2agZWq z7}YeT5fC+J@;(}PgvPlrKXS|V;^nVab>jk^FT2-XfAt$*|BZP|@4xfL@BZH3eD2OG z0Wpn3PPy;x&K7DnEbc{pX&&({&A_o3$-1XY2C;41$tI(eA}VGOyf3BX zoSpX*$1<0U#M7t&$3(=_Ar*pm>_jD{h%jkav8t;nw561)sv>5`6YYg^$`joQ0B*(~ zU^nZ$^Mt4=BS3J@F{{~RMAi5GbO>~9S65Xo*;Ji#aTq6IV5lp{oKubfp$eg{cH5nq zjs2*lO!~p1GVG_!&b;^2Oj9$9DFR~3c^V3zOA#hhBcir#+PY!FejL@TZJMV3{5%gs z6^?1W-R$Q3xW9Afna7Vm*=Y0|_qA7Fe(L1bXzphpd?W_9j~Dl^EF#Qx67t*4grpWVH?8+Wmk!0zKu9_t66Ty3tu`75t? zZ3}?+KE7g)3^=Qr^W!-ajam1l-|q(pNYb1*>rixv<8~7t$$oY@hn5L<{X?)IT7(Rl~YYsl$Z_R^73)rv|Z~F zV4{F}=W@&7_)XWYM z$_+u;dnX0VjG3Hslao3CIOiw2d@dQWBE(54YXG~xFQVSNn6t>gp{JXYeDKNL*~Rky z%^XfMqufgYV|Yi>ltpDv!f{yDMV`VOms2&1@06;5C7xszNl*3DXFs zB||QWS@LGUBM9eh8?Y18k&6~VFcQ}}mojE~lB{kymbgwMf@5N8f?rf!SJl3%UG1H( zfDoNy&#YE*9Jl-RY7=A1CEGA)UAv~Tg-4Yp^)J8lmEZf;@8+ET+5h!_fA25;A74|9 ziOGNT$@RB>`|Gbf|NQrV@Nw+-i`mig>|z#p$<;ok&2wq@>dXIfi1+S(JV>dH9g|4Z zB3km0avAOV@s+{P9AVAjjA!?)-ivQZ7!AoyCJhrEY??Q2k`Nh84){CL!Nv~&rf_y> z@l7#7C(RxL=wxF7#z=r*I@vQ!{d@-qrZP?GHB-}a;G>eC+yoKJf&1Rn|0WsJUw3^m zxibIGuf5hdCqS3|`2C;1waPK6IRH$69&7+?!302S^SKlsLYx6B+Kj@Ceb+R=&YJ>4 zV@8NG&s~X>sQ7>`Ow-kK%7_qC1V9z3g70Q?6H$P1=!=w`(_x~F2qLQJYQ1LWNwZQ) z_C7RilT$7wjVY=c&t{G>mt2bElU!1&Cd#EqDKTdvQnURqILDYX0fe>|H9}mk zHYw+>Yl$g@;GM6k3K55K#EDmJ))#Tk&AZMaDgc=6#*v6bWRmjKbrsmP!2!}PCIbk; zSE1VM_xXuXWdP{l`1r_T-aK60dg*EJTeUR@Dr)$c!g@JW~J zv!{{k_hm&`wNnUNXyP;2UNJZPqhq|c=#xXv)+8VhRU%X?&qO{*!ud;0W zVYk`zV{%ris&*l`5SrRIb?E%OZR^FXrNC0kZacjB zruJ26PQ8q+XAH8Z(3yUI^Bmtg|N3wI#_`D#$%L`Z z_1C}rjorP1?SBpv-8Ze zS+|(aPfw0-9UmQ^oxk%S{rCUJADh5r`G`nnf=GxCOvraP2F(bQhYUF|u_`T0T7@hRe`#*Uvj8&&VA{{ zmjh80Jy}r?=kG0!*L9V$wmu*b5fDICRbuM*J0Q+E8GxxW5fd}Bs7`YMDyk*}DL`!7 z&dlN%OUYB3)(_(_4tZNjDaXgh$vb8@iDsq%XJ*bZBK9$=YCs2wV~SIzJB)*r($sYb z-g)2D4HFUK5aUFxnw&oop=lamE+wl$5fPDsxbORv(yZ%LqyX+Sf)z7!&a3Kbz1|PQ zlUbE_?$>_hYwv#i^B9NydSxa@NAvp+KMd$|t$+6RcUNii(w&!n|7-u{Y*FtvW943W zw7PoyXjKK3l3)1BS0vlj`kKb=(&i+Tpe#>k&t9C2!;ZyDDyzp=26{Z7zxe8_$L;Zy zH^eert+qMElA{2W6k|$5l$^6;K3dH0bgddZx>|qu@kgSt+g<^ADWX}OcZ)il96!VC zyT&_q22M#mI&vgpsy(4LO=kvZuH1fhw_iPa`0(U-QF7U=FNvIWv%0CB_b%%k>Y~!N z&2sUS%w-!>uerqdXuY}~uN#H-Xx2UVLYwxR>wUjYq0;5Wq6!TeICZOdy&JQvSJ*lk zYjio017BCJBK&+>MRnumopyCyxija;P@M;cWEuz?VgP8pW5hu<#hh{hRcd`Vf2O@S z>o>c{AAYjEUNQ3t0pSk3(Dw)ANnH}m7=gS6+Pe@Bi0-|9|_(|NDA$?QFU1pbK^9@nktWzc_#9^yK7d*|u%nHchCA zaJ}!JdFJ$g{HNdj;O-?!BHtjo8}t)zOy0ejOtdUSG$1-~W$+iq4^y<#&svNg0v1jb z_8Yee_8q7plbHe%kuxMSHIp08=j6iT5D}lSjr?~DJ73^u3~UfI_UNp3p>6=w0HGly z0`IXRP9<%3&53_ zb{bR384QX7Q@;U3CMrfIY95^uIi3e!`QVUeAxsnxLIN-Z%%zxFjH6>lM8~eKDrU;L zIOh<+`{2Bvtk!`^R82KYF*9a%>?Ug}WEW%1QUKue{1gzqb0R9GpmPU(E@E&lc*ou~ zZQIoKuJ8BzJu^=TT}lZ6j+Toly^1lhV`ir+6EZN2gH2lYC$9H9AHVrO|M~y=H=cSO zv_8G}J`tLgT^b(jF4^x^n}_eM$Ib5BAAb13z59=fWn}D{>H?PGmGJGY)~W}PEogIGi~$DC7?%hhfi`+iK7=dXPEg_E;oN@d(a(UQku zUU#$eMX|JZ-I!(5_lvFrv-NJf(e1G=Ti=va0uzYDVHmcd3ysg<_G4Rx&>W}7oBidG zuZ@9Y9@hO<29eg2tGWd?zAnXzm8K2cITM0JRMHTy`myB2@spQZi>&)zOjGc_n=NLI zvK2z-g7*#(Yv*h4*pU|yGc)surrM7Y9QokJt8Ks85V7xC49=KBm>6CR%$ih6F^Nd{ zlb`oXq#p3u=brm-|K8vG(f!@Yys4||#pC+4 z4V81mY>1NrL=k%tC%}%s{jINm{l#bg;9tJ+kN)ucyImp#nmm*z$qRb3gTwM9_X7X` zyqSsfnTzqMSclvmzJtsYn8j7ADIt={B<5ElKdCj%1WYFf2x2yK5EA~9VRZm> z1ZG;)7{L(%sDWl6FT{kz+|KGYgcGBjQi?fLK2)J38MTxccd_h-A*T{GftEYl`*3-w zPRKEUURXSN=dJBCPu)9zdT1L)2gpD);XzR_Aq+VRP#Nix_fb^Dgo_v(U`03))8{VK z>(_ ze(TXYmz$41fT}9hI^Ro~?>_waz0JGhc$NE21*Ee0=##tezx&ZX4sF|h>CTV`bze!E(4cQkB5Rr{*y+M0>$IuPNao3mpO zi#ci@H~p~Nr@rquo6Xhgx+Ha#KRr2W8rP3o?;so9{pf?s&2ETe8ng3$*0xO(>dK`) z-hFVFgWW#6Xvkgn!>%9u-RgMRo^~@ZOk?WziLmNsodI60F2Nbf6b+!Bck`wzVC!*j zz@lPtJXtRA>8F4Evp0YEqqqC*W*qlz*BvjGB;6VZ$X;3_O5k0}u&0$zz9Ci?1kpHd z_g7+{*Vbq$WyslF9P)m$>O_YLPY;FW*Fhl32xnYM0sZr_o!v)FaqE+jNSK)dbYou5{3|MdQguk5-b1emy;W>h&VVl&|cYynhQ z94qGCwzr(juplb|5FS1M{BpS*Q{0stBjlXbG?}m>g5eg3c-Azj$T$uL)`Y4KmGhp9 zFmqj1Ib}5^#K~0T(56ImJ{W*gDN;&S0GtZ9A|<9gj6)r&i2^nir&U!s=Z1brIZyPf z5Q3R9bGTua7LlCulXub+pSXnzJ=lJDoi=(eGHN@+ofc>4d^_{!?e65qZ@zQBSUmgm zouh8%9CuB7_WbEE#Pw=T3}7xN()lfACJ5)2hG^QEA|>`c%>f<&zkD$r8mJ7V>r1w#)hA)~%D^zsdwYRK$QpDhgUeuzu;w=lecKZQ8o3 z+}Y_dbI79oc76B#4}bK=TlbG1yzu207PDDk>if9b_s5Ib^UvPd?6&*Oz-%SStZ5xm zH|xCjMwYcy%$4&FY~1ZBct#S!Dukn>-E+AczJYwdVF?NF)NrM zCIfctnL|^}y4pKe*tyW0bhH1DxHs#yBv07Jfms=B(W z?tZph|4W1)^4#iS_Yg4K#yB4e7j@T@c``EM7r*7LS06I-pZ?j8Q)86UN+*VlveqOD zl^!TLnnY`z1DSySohs}Qp#YDHGo-Z3SnSE&@HwlLPT0i2!jzI#lfDMZ>yCC z4D`#UfC3s30z`!hDfW?3qe6p_YGn+vi<_ziV69Mqn(f+$UIY<*94a>NVkE7yIxW@P z`b-J(%=yc!u*0ooWFYBAVbev^bn%HJr zjV4o@7!H9YN}&57jQ{{307*naRBUK@bK@Wx?U^KTz3-Z36dQvB@TrPnba=D+=;rAQ zjFA;6ZOWohq>SFrvLs0ovSdtxKqx$@&4Y8U>pSOa=Um%5=bEl>tGe@UI-Z}{MUkh# zVKgav#~LT*(Sz&d`s(`f-S^&q>sQ{M@6Ep+ilZtH=Cwy(;aQj5}e?t!3cg_y&l((zCn6apy}l*uo&9QV^pIjyJ=% z48&uM1@%PV}#?s&tgu*O> zN+b+cpHV~&j;08wrV!l=40(B2r|u87dSE z!IHNI+g;yTW34eteg3f{B1MwFRlN1#`q_5dP$kTwno6;r&Bwyn6OT$uM*2P)gBn%U zca3*hk|udd$|9lneGGn*$@TKG(+P9h*1lP`*sS}k^C7VJO#o2I!Tm>f_p;O|$1IG# zcZdoATQi6)qjC-;tzP9NSQGHushuQpau zmW`q&mDt&QW;1jC;_RJw-+lG;)RuXB+4Rn5Svt)VnE7Py-pOn-F-c;Rl!i3V z$Rg4C(EDHDte{e@QVWBr2?z|1G2VA|zdXNs{O-q-+4TO`9?ee<6Qu${CP2a=3Iaz7 zz3-e)-}>5{^*_=Z7i>0}EEcEZ;;qx;*<_*=ks=UaVP^I|#2DJH)?`TOj-~b9OC*yo z_9y?~?>z$F|Lo&W{^#HM-~P?N{!UkI$Rd{%IL}d;nC^obUcy5l+&5(YFXDe z&t5!#{L%Jfy@98X+byS`F(~^s-$VJ~cQ~%Iy~n&Z4)& zm13c+n~2_oVU9NtD&0)qk&wTfMY zfz1I*Ze5^<$yrHY)1%4KsKF{C)JBt1LLv^gajq5zjrTm{Uk@j4=&A%2!~hC}6(S4x z7>5oviXfmi>du`zS*o2A6d;U4m@O~}iu2wD&jJ7_!bEf%W-Ceo6Qw*vXQCL87+FLN zumI~Qq6K#B-N@oV0!#2+OY8t%)N5v7g(z$^l1HOWYBeCy;A0JxCy7=hB8g2b5{C#N zO6efIV{ZKCg*6}&V_59(>D2bEzq~nr{N&lkPhQN%qtiPlr}s`WYhCc7C54P*%(K*v z6RnL_DtZadhv>y|krzUe>#Oy}Q+1-t@ifnD(_o^PD7dK|wwFx}YbU0TIkZjN_ibBk zH+9#C5Zh+!JonB;AAF1~Y)OsFES>0Y{;hB1nI=277&oi6&FrfWPv`Ub<@JWy`QH2B z3N4m#)qAU{%yK!p+ttl_Rqc_P6nTT)dRsSjHJgr@! z*2QQXzOZs_w(ZTuYCak30L&=D!wdt!EP_av*US2QKR!46$`pw;ThJGETVx5+plN3jCQ<{#Qkyi0w9aqa?rOQ*u2;+Ddb_Qz z&d-)NH>>69a=9{T#xV%9wI(koE$tS?1@5|?l`!m99P-&mg99Q!6p=6!2%yHDi#`t~ zB1737wAdaHZbb)?*$cAcn5JpFN)4d&TBDQ`pChB#x7mdsU7ga35WJae48RzxaOaY9c@)MY_n-qxmc^ ziY!laOPNig(lnTVb5MkpLkm8}aDMsXsa5;scz;}k*ssIZM{qu7WooOH1}?MWXn%gQ z+C%`ORTpBKnQc$L@7umE%5uIpQ&EC%8*lO~Q{qSaQ>#_%edin?j+E-Xk6Hza9Ac&{ zjj`IaqmlXMH{Q5et)r+ku~FFdz7M|ZUDx-nb!}6xw)ORL8TzhmoBMa~@)wj$3MsQD zv37{b5(E++T6<$`nkM5>F)H%Obar}h_vFsey59cir|*lQyeQLr)X$rBkt4+EXx#O| z$IivVsp6-rFfnRxIvJd|dN0eH<@1ZH4?cPF`02A}&tGgd8`pJpUANVyY1`;r9|CYl zluq~N7ty5Oz&wu9w(xW2Pj9G0!%@bjMwaOI$9ha_&2|@skim@ z>g>nw-mD()o5z&bSK)9C(mv+xDJ?O)^gl4J!&0K&*DM2rvtA+lxxrIbi?&UNi}yII{_vv);N9xle3h#~Ue zeM0^!U1<$>;{DW>k%B=LG^oI=MH4cSHfnQlQe9kdWUXl6!rrQlfCZQZl#$p%RO2GA zS+>mG7(8nXKxp9$F%XE@ zboF=s=+8Fwb~>9rcNtlg{=Lyl-2LsFVthqi|-E#bU;R z9gjYDM?rQ776n0q_r|JJCm{)a z+YwTkq*v>zt(!iC&9Yi=>x@M{rlMi8L?$5h-KXqwV`2!aP4)Eh>dEux+v{c3R>Aui897J{K?DeZL1|?Z zlVl|_j*bq?lcRKRLXaTaIz(Ppy0?>2>NqXIcoIuViY6yJwrL8G$6z?9;J00Kv)2^m z1Vg;KzO=4BfaiHOU&Fiu^OquXUKSuCWd00aSA@J9o_@a85YiA8fk?~|k#6r$8Mul= z{rb$iLMi$sV^tuaz1K!-1w-!J_MJJ?}s~bd_O-f^Erx-$s z$a!1LVP=y;ghh)1U?Kz*FvyGuDk)jc5jZkvr2vpXND+}qHKkdWq?uJpK&;V-@$&ro zlTV)bC|`Nwb(0(42O)|vkO%_-I04l=*Lxo#s)ZX z@4B{g-t`@WViyp@x88p1=x9G9atbG-JW4MCwN^=%Ef%p{-ZYyUVvNoiQGfy=IOj}e zSg9C-Vvc3$I5pFersXViJ+WxcgvuoD<=Yf-$_Gf9^!RY)Efe?ubaY zv0n%s#Tg9xHNZ9RpDTIi-=sYw? z>I*{u!3DHwy6e@GtIO@ST88LIJSZ!m#(8>te0*>?LoYYiD{Hi?L+cytqX=~3gkU}{ z+otKfyWTeE&Gz9}UwwP>Ee@e_lEg;aqOE1y)b(=ZZq`Jomu=^x1=%VA#=32*x;bB0 z*jIrSvKWmA2a|`deC7FzvwC@RcJ} z8H5EDtlg$mQ$~Rr-<7`|m4vzDrIJtXV6nSC{S<8qRBFE^3nbAkjA%4NG3Kn}4 zP4`*)Af0FEyGAM;_E^jgInkt=5PWEj&B`p->Da3LK;x@--}ue9f8*VEKlopN_ji8u z!=Kc39bymw1{OdiXpPR&L>rT&X_93+OLLp5EZ0S9(=<&p3NE%?Ti5k=(^qwKc7DFP z$xV_UPUm;u$dVYUb9c$kNs<-GxabvBf>&oRio9GL9qb()sL6arkfw=INrz;JY?>Yv z`Yv&L@8~P{{>%UC_y6U0zx$^^q!fK+;yM$~Tzb)qAtc`Tn@_N?KMjXS&>Si<1D zxGRmrC>j|)U#emZAAS7fogcqdVGDy{oIVzYYsqaUzV)p}iT>$cj&;GOdV5=6$C zos=VOQf1V1G@0)0XNJlwo9#^@dQ!$Dx-9Jb@AofWoW1}4kMG?-C9Sq~yQykzsdt_r zVvMUzUpFttMM2C_2G>*cLcZ@)z+yu9An;DJwCiBpG4Ge&9z4_?*61@By*NL+y1M!F#pUz!=S^gGeHS>oJ_2NiXi^M4(Y#%=X)}%h1+IQ5N%qbUs6?`*pKA zyZj{kaDMkBz5n3B>BB@r!_xNsIm3RLO{{7?zw+S0fAZV^WN&fsogY3+vSO@MV$`>C ztj*+~{l$|_)r>VEq9`@&*yZIT7hd92!%R0w3xPTAVBn#XqM=~nZIh*jk#O*Q2W@`Y zk)<)jKmPM~3TtEVAu_N801!su$S|lwM1(|w2q}$-21P_Ro2|7*S! zqD;)bzh}HtWCXMb*PZKH*S8Ib?CtH}J2^s?L}nHa>|z9kjvWAt$2tb+ql74Fo#lDa zJKy9!(+TqJ0s z$if5CA0!w>06+jJEO46!emfG1@Sy6?(xfO$YZL&Bh_J-S&c`msAY#7IBpYM@=C6J0 zmD6KwtR@2z0U}3cCr-!4x$9M1)m7#Crd>CycDZSc)?fYVgZoD(vvTGe_x$|)!?S07 z=TJ=FwT<&lRoC_Qs%}HGyuRERo9^!wqtR@(cRU)G^HFKiG*5B{;NVdqacF%cgv_YL zVu6I`%WK!P#@KtO_cs?;mvuE>uZq#Ms_Uz>%P#mlP3Z+>O%d1tEs3`X>&?2V+x2R_-EM;Oz4wfulu}xgB1&|& zcbp|jnHI&kGpfLR*nrH?wv9(?QTcfbDH=4^fQ z;?wQLg%1(kMrxN7c|JYX*61Q3#o}9*$f#ozuReP6-52NYfB50)!NLBcH*H=NBo`G} zOpR9ORX@$L|L`CF`)_{b+568fM~lhb`Q+i=XkMiM+26hRr~l&L{<%Jifr0#`wTUq*BGLwSaq9pu>`8%Hw8jvS2nn@-40j3qJZ|;ZKfY9{is8li<>|rV zmXImHGO$%Zgjo=oc_79jA{YdZqyV+nHcf|}f^sHu^ap3#Xe~}XM`5b^mYh;bwQb*3 ztEO7txpREy{#`A!*)&mtNFRd)1{pfI$Pqv!f?!0f+SW%AQXEBV!ANni1VaT7LkvyZ z^6mMGEQm-F2l5Cb5(m;s5i(F@9ynP{gNpffA_Sp<<}f(t%TVnoO7tNDfFe>mHU%RWe@BjJZC(pcRB1lz625p*5Q#+g8 zeJ#yUr`m#5lo$wMETd1^;Y`q+6gyO`i@)5+C!nWQ?;_77(^PdWCHrR&}EC!aFI z-IL?}y}g5jMV1->2&~q1Uu{2i!D*$mO>|XG{LN}MQ+j*tx1hRV-#uDN~{HA*(6D(Q&J*I z8`CEwK&7%#VXADA7^QT_odj_#e(|pR{=xpAAAjY|(^pi0pts?HpkM)UJw=0B{US>49}YibQ1aXaWGG zw8(Blg-Q=rd|#s4yga_-0Ej3c1M!ntfCodoAnkaP}eGyf> z8YLr>)QO>~HyoAg`!0m&gKw&>1b_d*$(?(5fpNXAnx>8{ES(P^AS8$&QIMl&VIfVZ z6jI=qz&(&w2pT*B2N2(MuI@Ty4lEc46%#NiL{Nwb!ZC_4YNH4R1{1QK$Cx03$Pnka z^O+K+ogH=D1%rx+NaQFCM1)9DI5-c8)+iDiS%P!xtdXBM1jT5{?SUg}@;?j>yi37=l*{i@Z#YPBSx! zW8bw}sowS6xpAI1Ra?PUK&(wk;kw`M^QcJiDPy8-1dhT!cx|*%CP1`?D8#z=F(Lz0 zRV~i7UEg()W1D4JZq$4_uU6G`IxVt{fI|qK4}I$c$Es=8n{`t)#=zZ^lY0jT2S*2r zvFiMg2n9$@bkYlImE|QNcD+}GAH4TNrc^7i)+`qDS7&?k*(A@3JS$#%?V|M{12kU;&C81VkfGhIr%p#&>FkwAj1+K!+HD^AdnE zZB5dLzPi3bZDI`23x`b~BgY6NBzSXmz5U+zp8xcxZ7lp-Wg91RaRaQ%?g~S zYCq#=o6tC1_tJ)VTqghdfADMnCX_2Th2KWVAx-39xovgrQ2yr|a0S&Su4$iy2yIC&J&dx+Y zDN54x_3r-PQziVTf9Yfg??3+N>G{>g@zK%!!~JwrmPvwnYRPI4haP)~7<(3Gh7i|X z8-nj$*VHxlG%u%}4||LK$!M$)U1ZmJ2IRmo1m}I@J;vZd@4C?TUDLLG-@7Q^I6Zmz z=A*^Y-t$i{yS~rToTH?$dA{>v};nDm~tt*oVpH`UViX;66R8JVV_yt8IOAapBul z)j98dMEk)f7Z2~AeB;em4-XawDY7S}T@XRw5X3w1VR3la_bom={SEhpVV07aqsr{4R|4zTHmDVbxW@0IT?;}J%+*V2}o#l!Mv^H7~#UiuzmA$=h z+&OvW-s#iJ=O29d-Zi@-Sxm;|YX@awiYte`Pu7)uieVJGws#Lk;j3kQXInc;hD_4| zL?56lA{sRI0|+%te@dC5P8nljj6<(F{8h|Cgv|5E!CC0v!amO&eH{BXVFy7?!ayG7>P8Hj0n{ z0VKx3=$&w&0OHQBlMpx}5kvt%3g7JzFut_=N`Ut`o^P2HpzVG`>t>M zK^xO{ZRbL0yVkk3X?@!{Yjvi~@x6IDD}3ikU|ftZuP;G7kzQ?TLsVv)(WuCid}A8# zdj@enP%&~bdaXuTxmneHP^8dm4FbInfZ~O1;`0LJLac>MM^zq$X<|M`ngpJubE&NC}u0N_9$ zzkAExyAYeY9(MUc1YO%af2M(y(fR&ZLo8+h@H+#nqXK%gn8aw{cJ3j_MZHz>SUW`J_ za+6qNQ;kGQL?Fwu{rU9K>AlzPpWZz_I@p^Pc}9S*-@Ehr@!1dGeg6;t;`@K}D=5aM8PDa^Y7@Zk^8X|HbP` zM5f5VV36oVd}JSD+x6ai@A{_g*4ypPa$Rk!)p}jkb=R)Sv@l7LnQT;KM-N{eO~%u` zay%LJZTEwJ`|guZ9y`whjzw$2B2BcWBrW&%r?cs-$o1v3Ww-90UtETWlhJ5Aoi=r| zuC@q(f=%a?gq!6}n&w%O7$tS*B1;SmT7gQkQ5HXy7{!OEk+fEWgIH#hlamvS!L4tu zmvuy?6F@~l*cx+kc%TuhCQK*g&CS)tFcUluGaAji8Y9n z*yP@wJOB7U`j7v||L(sHF`%}J$e08Wa+YE|_Rclc5S4}sz$?WHalLMuRxyJnl_b&o zezOq(TNFuA=sXj$1CY55+pej*X1m_bXN#kBF=3EC_S9iFqQp66aVu_$1t3i@6X7<* zaWVV*fB)ZY8h3VaY4beECtya2fm9<)EK)limnR4N2Zsmuj}A^2i@n*z8a-Ga1m?91 zf!R)HZ+!FZJFma~{PD*hzW=kIJo)6q_ulKamBgMoO7tKYQLzZbIQ3_Dk4LRN{^;5< zM2t#UfE|hreO^V}xB!1|U%s zQGlq;Xf!fY$r?kxoU-oDzQC+?|M>%gbFkwXUa|{WtIXOrO^r@ z2}BLzaa;Li-2j4U89uxU92(nN=kQj}_nT4#B- zw~%{q9Qx4I&Gpsh^7?xAG<|q^C&CxvY5+vUHQnZNv+dh@+jP!X%jSIje7$mQU-eBx zNG4T#v)TQ-$9bNQN29FB@}em6gh+`DA_9lZxlzCVt#2Ld?>pBgX_4jGC?QqknJtS^ zI?9s1@0|}n2tU3)JA3xg)6n`!krYLi&+T&64`wyOY;@{fNJlsu=bxTc!#=up?Fd!3 zyv~a(PZO(&8G)b^L10kI0mr_{@>I$(ZaWeVUGH0$8a*z{`Dn6PFVVwvGI?-%x~;Y+ z#}Dt^yMHjBjYcDFB8V0jSwNzX6hlB1PaYfRs;1d)w{_dKO}kxPd**|K!;|BKJWcke zb5kUFnqJh++2sWy^^rs0wRQdJ`DFkT!WR_F2t+V0lHdH+H$VR5-}}S=^Z!u7z!Hr? zQpBQDtC7Zg3*R)`)w1n64$eEzL;wu{5Te!E#i)r$8!Lj$;)5s&jED+RJO&QFt*hqK z7tPV}$*cFq(-GaGJ3Q(`IY-8;WvN%>9e!{>34qj zJKyR8sStdUq#<~~c zm54-Utu;gz6jVf-3ssDYyci{@1b_rU1U*Aj`KI=b4~RgBMp0%BDi%?JfPv75c2f-j zGq8jD5Ks_gu)^TTpp*b;A|gxyqCgNKL6#^e5CLTO#V>IyVPFtJWt2pYEIaw%EtyIf zK#|^d@x2e8-#eV{?M;isl15<}Tsy2a)=tOM@%@v#^NYQ|>OzJP-~0IS|NeWwC*tZh zf>NYtWMMj;-kUrejYgwlJe!Qlajuj`K~3m=9|R=0j-%o>0y;zjj)9D|k6yVSTtH(; z8wEv=Y-zz5L>3qK3RxHjKUG*->bE{1;&YYJ` z*Q8o8i0^wJ+Dz}InMsLsW}K70b8QSGqbZIhj-?)NoEWoM+b}^ltd>(%0tt4ZPT@FyRDkK+TN_I(Dwpp6H}Js*?3fD zC6H-+K%_iPm+R`{{CSAN!N(W~DY1HQI{xAYkZ6d=RnxNk_HX^>Pv7~AtBVVrrGbam zaVWfmh-y48%Ob1mcDr?L8<+(}kp@MgjZIUnwUAa?VPcgr3eXD&??EYLNR$Sx9pc%= z*=o6*9PBOj7sX;?^prspU~RPaVbwZR_0|zA+2HK8M|XbXH@x?Ck85Pd@$R;_}(~RXW@6HmlHg zMpH4KEly7M?%kc7-Z>bTifj~m_(qz~%b$L9d49&rrZ=PjP$?B-7<#DPu1$E@021wV zDgPfHUk+9mxH=E}v*GR{fT7a@K_nuOG)>a7AZ>O+;Nf*3Fv|eZ4OsQy>BT@I@#k+- z0oZQ0IxUn^D6EiDljV7ur4|vQ1IN)jUwiS9eT)dmAexlcS|jAC89G>DVPNmv_05fQ zPDDu911JKHg2Fs7>WMgnI5f%tFgz6zJVT7E20!9KQ1kNT?@E#&AP@X=_-v3ETp0#D zi$r?oKK%6j+1d4cS{}}4d6^lFNFY%dgb=7R$&DS9Utc^}*!S-4>FL4#qAW-GXq;P< zW>%496dOZN3S)2pMoI8cw{GbETp#=3ktHyTNbh|B*lf04-*1*{ZOu1ce`u{5Sv{Gg zH`lIhy)cXGMx%0ZcyJ!iz3-NnS0>NAkBhy<@$pf$smnZLjG4_%s+m+Woou(;)GF!u z#m(~=0-z|;+os)1ZBe8V7}gj(O9Uc939j!&JVGiUOj4%l(cwZVRDc8+BPNO3XwyE-udAAx@oJntE+mw*(_H#eOn{iEYJ34)5F8V>0~l0a%&T%5uz~jO|?aY ztV|xA9vkVKK8`2F-h8hpC)TLfUwuWZ&))*U`{DhXr{*iCcmKgZ{_TJIU;kH76p1lW z1aN0a#C^}YbCK(*$AXjhA?4fApvbPBB65#LIeO9Vr1`w_Yz_w z@#_4=$4cjAdGh8PZ@l(;94C4ssfX71ao#(294GD?_RHeifAj74E~_rYEK92(Ke?_} zE*usXK{P3gptVXgDWskAonVNe>-r!5?1LZw^k+YN`fRgW^&vFt^|q=)*KpUWELl8! zIDh!CoK21v^Q_3W8W>HgbfVM!s3&*Er-w(ItL9IB`1nW9>r^2E4Qx;5IKb+IbKYM) z>q*34uC<Crm zfotl%-jtI)rHFu8Ss&o0@iDNA!A15Q2XjsU1Ykuf)5;i4(Hm=EH<(6|Sl8XvYAwve zPLPlT5CAhO-~fmcg9vc&2+7V;Ymm7ZiXlc81_6XYGBa>M0d{yhfP^^2+ad!Dtv3&x zY}tWv2Jk zdc?$YFPl<)y=AEo30rZqoe)(J9qByA0Ce9vxI;-dJe)EnMFK` z02<~XjEjSV`DC)LYvGvX1*JI=&@bAaZ|ZtrEE3_Q$lmzsTW|fXZ@>5Ff0j&V4$&$= zMg|}iRg4g$7l^>#^&--SkOKrQsFWv-9EivhQP*({s5QnYh&~9r9+*LpIg-|_jbRqV z&^FKC`H|YR>BD2*Ti9M=Va2o5eVsSsylmV!!}&ZlPuK2ZwarsIrTpo-O*Gvp(~(ib zjKYz7@0#ANw%e=gn~y*G_?^d3uAaYey=(fOWAuI7Hw|#mCYgQZ)x8IAWQ!?F>eyY? zJf?`5Mq`v#JyDK2MztuiMK=1{oxMN!;nN>|aDGws1J`-Tm;1R$`d?Hu002ZETVt}iSj(pi+tGhE0n;Xa3}u7LFfCIU(d_w4}VUHf&k3CSzae; zVX}-tcY)oIgA4$|AfiYO#4bW0q{LFHsPEd@xYPt5VvHgZ*@gA0YP)u*h6Cy9<*+&M zpKiBz>g69tI525g;Q*;iWC*bHSI|O(tKRSmhJc)%C{uP8Ju;N7Ti&}NWI$#C;8oSG zs>WzathLrATHm=knufn}j3)%G4WeQRpa`v1RwOE|y?9>u-K#Iv+XLuea5t$U7Ii-sfpC<8`ikTGoL$OlArm`3u)D9 z#wm$_;S`xvL+T8QA$!?&Cd)@v9@7F41rbz2N|VWmz%`4ugOpIgC+u0bN}A{!NGJostNnW0XqtsJnxSdPJM-kSbHXc>*zxiC>4!(BCl?p< z`SSGq6T`}{EN8#^d|IqZTInej{Rqfp zESAGTmSsq^;UfT80_jnue*OpT7X;TY^K&TG$Bw2L&ySzxH}9hJ7^4~@L>9iDlZeOx z0HU+jBQ4iWk-54o6f_Epu!x2>ot~dFv$31sS3+luSO9c+r^k-w_2{c)q35oSI22fEa zgF#)@F$NVA!YXo7hrO%k_N4sYH@~$Et5(eJ_T=V`y@TDIx*85gm3NszR3KIs?idM3 zRDly?Zv!h5LI{aNOl{k)+Ay14oE;ypo2E;w97VY6;&3<#pD+Ub;ON|J52<$E<*G2s z{r%gwZoK%}58is+S(CdA9e@xxL~C=O6X<$=u{=BN=9hq^B9@FLj|!VW8w3MF##%%* z)*9!@I%5b)0n`XYS*N(QwSDLA-4|bY;l|7UH! z7lYx%53^Cd^}E0G^;cf~;;pSAm|{74;~zyoB&`mn>DLO!irh?D0V;+ z#gsZFV?bD$Nh$Z^8+UeYzqnW&fB3`i`l8s{y;*H<+rbt&Cv9^IbaA=>C!^7HYpZH> zII!9zdTEf2Zf@`IP2TwI&2Rs^ciwt(VKyIC$PgGH>POWoiH=IQY!VRQC)~k){qw1l zxi(aVzV5gJt9sz`LI4ppF*w=?g5U}Q>RTteGV!{uSsOaI{tOZXfC}0+&Ft)Wckd93 zoKpmm1YpSYGzbJm080eSt1fth)A0x$^oc{7l#{NOtqKo^b!I#wbiyhkDIyXWlR{iK z>y%R0v}o;Sb+R$F?RA2EwmeusBGW&wg4>FLRQcF~0uNK&vwmKChARN#12 zf6|w-?Rd6a4T`ZLCPI;PFdpvg?HxaQn3`6tw`9RvgJ{vZ%8lxJGN~`mE>=y0-U3-7 zQZ%4FdlX?A* z&Z2QZ4#*kOvK~yw^=dI&oLvy3w9u99>gv|cav@Q#Y4)*4km^B{QZN&o$)um{l>p}a72k6L1vH@YJ{0U?$kD#42j8oBimrMV<+>VFpA^2@Q#;3da!o@VY!Nd}fFQ)DRO3r;yfdX>S z<{bdU7~2q(Q;(Tx4_IA0>H!KW0eEWw(O65y7(y}xKnT4zTh<%fCRR}~768a3VU^yM zK@kmLFG3}Mlk&I?ruNxMk5ToS$3L~bt&yKzV(xL9)0*;mRT||91d^YxH%k8 zrd!kPa#W4#DzAKDU0$fb@zKfSC-2=j*hW9ivVpPI*{mq?E~2GWmBlc3nJq_?`q{IK zF5<9sm9uJ0qYwr1yx7~{GX$WbER`!3v~HS~MTSM*2Sx!oMKHz|)*&GgGO+hHptQ?K z1cp(7Eg41?VgVrpWK`v>Eb=U8jVzKSUsWZ5Tc6L`7=YPB{`IfFDuM^Q`_>x;im_7w zRg3+`KPID^fMb_pU`}n~xbDK`VtF|~zr0*^?K%WbF)Z5%NY)gSIxDJrXSy|>ZVl`D zvoF19KaryuV>~-=Z*5N(tM#BN71F_U^y-WE7qi);w||m2Iq(2TO5{j8XiTWfV*7CK z^z1l^uyGa%(V}x1I%5q1_9}O>l$S+OSJUmSt;ukE?{IH#Z#DPcbNAp7cx*fl3j2G%^Xk2O2j6@1 z@!KDsETZI=0zjQ%6y*dUo-tifFaMT>H2{FFpOT6qFYDS_C)dw5!X{xAH=gJlyMlhh zzuBg3YST4JC8`R9a81A0YZ>?1*-6*6Hx6$WRfP&7NtjiDIbD+@Bqnbxs4|0M><#+5 zHg+M9*_auss6hh+ObXmb01*+fg0I3W+HynG}+M2qHdy_`%x`USF**hl9+cDTj~65VJ7OB59lAysQkh>gvO0F9%> z;)z7rDG{MHke9B?D(=#{T}n_Q;G|+15f#ax4vTVROKuaRQf6EL*Kv-?xI6(S)tlS9 zN9VJ|ElQ@0nwSWbL=rN`uBS+)xNah+xLU4e^V#M6a=uuHZXOa4N|#KY<@-BZ!(qL< zy|cSDt%gJA3+ps?$++y34^PvjquI%qK67W?c4Sco&CLKH{ps$w!44aVci)^xhPJ=va4_v*|zpXZsYyv+>~ zi>#Yv*QRw?w_&|pwE)q2V}OQ(!R}~(YiDn3JUP30`or&i_jI|eo279FDaIt=i_94_ zs7taI$^7>3{N1gs?eBm8FB8G^U}rMgg3`{{!M5oFQauw#etEVyIX`{x;pz6|{=NI#cV8SA zW$yD=UO2pcxb@oGPyX_?_sTj9`Hx0zlh#DMcVe>CK1%0Z5661Pq7(GZzCJd@6Mo#3Mu@;5#%2!%d4Uw9UpgKTAwIag8eMM74)ce6~Qn}HK&AXqE zDgF470FPfw%cdP|dq0G|Th-3qXJ4J&m1IMR%Xyb`VS>%7j0y!wyj-KVWswc0!=kE; zF?BH&Hon~%tdr}tG5OpzSnccd%Z@?NaTh-uBVe-N8e74N$fiLQ` zxb)unEC=-f7D=72fG{O7DuP;gr=WqOZ{sR!L)#7p;}xzZ({Wu7LTuYbcl_k3@y-&K zo*1~y%DT!)ky(vF?KDBM7Fs`Wh!)LUgYgCxGzt(SY8OR-qoj5nQ;O@h?b_yY)y&T? zW|xcA>aq*L8^h=_W5-n*P4C{mb#rHXH!m{h9Gc8ZOrU}th*4FP1gbyxhOa|< zceb~7cDA;5_R7H^FEj5vIkHL?0TEYi(}pf34Q&@XA(IeY<+I^CWH!DLLnc5JBvM5D{cf7mL4q?ML}fU)vk)Z13NwZ`~ah)z^RX#n0c{{_c+-{^*^frsd4z zz`J!w5ikj?+w`|>0t28>euC7T{HAY1M zBIutrq9kHf$(WwifLE3bJ>fnvV?TxV8wTwQE|kH#?pF=)B69qA{@_Q))4hDOYsb?; zy+f|Z>#-@zF?D$p+PD;o5@U2VIa3A>WZd5F-tPXv#rfP9wQ+foITrEG<<3n8Be0ki zS&{7>z>Yt?^`Mw6j>P8ZBBipzNurb3dw!z>*I#V7At92+rEF zC>&@4a(Nb3t0d}6yAEc4F-t*;+S%Me=B)Rek{}tt;h?t0HXKq+CFU_ilRHcPLe>tg zTGhloMWk)lors8ZP1l6DUau|}%VxD)EEmh=Ds)X`6a{DfbW*yko{R>Q(QtcbcWW{% zvJBL)vIvLRDu@UJDU*nT{A~BUIjl#I&zDUz8P@AAG%Z&}%Ch2fFW!H2e71Mv=K6Bp zg#ey{M2)y!H_m|fe(PWyP0Xu7IT+;QfiLsIxN0~aOedMQh>&8^D6J?jHdM`oY>lb% zY%m%P@}extDzB~0oH2y3TsIHjeedaqA3S;V;gd%n96ft3sdLVq&*s1J8(-erKQzQg zN6+7S>&>ry{kO|JfBWsX4-fW-!_k8ueDCz==>xnmHehx0xIEk+=7A4^w;NH;fBk;L7^D{LI`JP zrvMaLEXe&^2bs?hkwCjH3N$`t))5&Lw5wIywQVl}*A4pg5tI$rR_MLm{l){20Q+B1 z>=UxD{y+j`xNh|}zMv^aP|(bi*-){he?cT9+Wa|J-V8=IMtTO7_3AAE$YO@_EAJl) zQ;bn(C%ib<=XOyR9&NLC$4_r{!`(Wod{Je-%oejb0w$pDoM*GRb!&X@-iw8QZtJ3` z#y%_OmzTz7wx|kpRpmvb9u`5!th&r7TdGT64C=DX!+crf&S!;kl67*!;cB@wm9Iwi ztvqj2ONd?97B*8ggQ}|Ytm&k*R1NdR87EH7MU$bqT&<3eFEZzfBIl5>$OJ%=6j@Og zg&GK51XV+*76lm@4M0@sQc7JE5kx+oof=bjp_^aKk54boW;0Zl)F{V>t$~;)`$opbODTCk>Vc&#xuo%1xP25sAg zcBQD6$Q5N)WOZGXRZ-h4D~8tk%sE3QC4Tnw!*?FM_3+`N)8psOx@nh}?P|GNuO)VS zyL-29--}>hBXU}(b_YU^=pFMr@*6XhohTebg-KWo=HEnxv zuwM>GN?Awfspwp5C>ttuWW>5SoJv}I(U>@;1kQ~P53{0dmY0D$0}2TO1|Zh1;gevE z2LVt`A%=C6)@$xs1eOG6@4vq|I(qibyQ8hq{!5>E>E8X%+#0_9X!ch>d9;Q^##lpl zOM7L)_i4_jDOJYM_HY0j!!1C->$VPwdKXXt&_1%_iYG<1iA(sIm0#~@)5}yq``l)mJrAy zWHwBzP5tUu-M#w@;l{BTL^svyqe&HE;|iKWupTzc&Aw!V;&nGC(ywxi_mYwd%asyA zRg}Q53lrQY(#St{6iEzXZ(C|YXk%>J5YJAae50Bkwzpp#kG6|?8^NNr-T?33Dz!1q zQK;HMZWh|AF(%I|0i&>F=FHP*Fld_SvMhGdxSX?)msL@fRhjjTUsVr9LA|LA1!1a6 z=gZM}H*@s-Slv(D>g0hukjp@U)`J`twqx#Io7{P!g1C*?_ zCihM)Fc^lS$n!}aE<@9FN?MRzLyT>kx`c*O+dX}9*2a^I^NaQJEQkjXk0B}z>(OpC zxP9~H?!o?WIw^fFkyVsAFeDWw4y+(RmW)A-j4Eo35ir7>0(Witg%io+HP6<8S&PhG zT&C5kDT>?@9d1oNI5|DIdHd}6`1$E+GRBZqCrMEfI+JIvNX!@|rC^M+4%ewWK7PFL zqbx7VVO5o6eQB*PeCBf^hhSXOcI|3DpPinaoIiT}q&rY8|{^tLE^!DqoU!0!UEPwLw{dTqd@SO)I&z~L~+}OW+@9xX5931TD zd46zkBd-UKm*>kS9vdn!GsX_BP_hAQFl&oY1D{vJ%lUHATv~wPWODrMQ8PR5Yypm_ z%G4wc3@&zRBndWwQvy}YtP^iCBFd3yJ)h5?JwJQ&Z2LblH@3I;%I@9)JU!w$8$c{_ z_cy3ipBAf9L{Oo=TJ_}ZzTf}=lIT_Ap`Zv1WbmWHbbYQjgMHg|{h7I{PkL<*BS@f1 z&MGqk6yA^OT2zg&0xA+KQ$IzjBP*)Xg%%BI?~B&Ea>B;bWuuVp8$1yp>Q`5&J=a26 z0afwJ5_)qHy<%pw9YnqMtPw~diimZNtdq?PUwI|dW;iB7v{rdzNP&H}txCBz1izH3 zzWMVLhtw*XRl9K38AFDg^Cm_(e;nt}PqWO{J7)K8KHVGITn1&H?UnUjK52@r*{HkZ z<|Hn)AxoLb%n*%L?~1Y%Z+#c%KC?uFx~`qKJ}bL!UDP#^4KZbHOsg(%%zf6io%jCy za`xfllbbgVh^UxOx{Gt48Fp?o-kOd^h}M|KI#(MU)`P?`s<49hmHHPd;b~ax&tL1FgMONm73?V8r3rk8VGD=is0G(f4%+F8n-hE*m z;_T$;N8kR7lhcb^_wTQli+V7)oX=i<^@~MaRb{z79T%gCBU99aoxPp=HxEu{=YRg> zgEn#vM3hepa}sQw4;3i4bQ@$@#TADTo2|+AgYSIvoj2d)xYo6rt}~N~8s9b`p;ZME zF-2~SHQqVzky#=$^Jp@8`Kw>~?ce(9=U;lE%-o~rCkMIt=KM!Lc|1?~er5dM0IK@5 zrHVF%Mit;XN(whkhayrB`T!^@TI_kCN{Gxq3#fnW+VN^++TiMapF_RViUHvMM}#!0 zN>pJrsA`g`0Wy+Aj4G%Sn=Zu=6Ks}>0$22L?y)JvUhqPMoDz~jB!?IYlIZ5bH{A3d zS-&QpD}W02nOK|cX5Su3=t(;UjoB!#h(OgKp+VJ6O9*5EG^MBjmJF)P*6yk}|B{0m zunn;Va^B{MqypYK5K>?Pjv>Y5y4GDhiO#R;F-;H3t%J7O&WfA{BfoW+#mJY-88%K0 zkfrFySeM1Y;bC6-BFlz@ zdbU_pSw+rfnH`nmWo!Yw^<08g2Sr&6nx<(N;vI2~D$V>&d9P zCeeBK(6o_Mz4b^i%&P6Zt-ZsY@pLq)Mn#@!pH(E9Vkg3^2qGkXhU}(m1!PqN zES+dfNfS3AM&`sEyKpg|PsU^BU*N0&2H$^n+HXtBJe!;K?DBGVdrLvQArZ)ScVB(= z)$e@wyQyv2WrEyBGDOHpAQ=E=Ys9fA5M8X>(k+d3mS`PPySzMkdUSktzP`LzH3306 zwku5#B8Y&9#)wEj*mJDKXitUrS(dDQ`@!4)!QcP=G+O{bp69V^AH4C#OP_mHMOK%W z@4xj{IUL@&cW*eTOQdQr7>)*ocizyg-QBj}qpYijH+)!|S zm}e1^r((FjdolYEG3z9mVNt1{4kn9sW(t!UkcM*b(uyR;JYx<|4@!qBf-!(XkVuNepb`^;Q(#sCQUnw=qKTuhNDN)m1(jsbESJmqa(Q+! zzc@QNKfl=BntU={8Gwv&KRH@;NxUJnFdUT6PA{h8F`y-+f}la%y>oB))`O#yLx3a0+9AkwZK*DBw&ngAe+8hl8=f0 zJ|P-X1rXQ(@d*7+4hf*|k1}UA)1@d7#KhKa2wc6Htf)rjYe>5nVf8Q5d*hL@NfP&- zpCrueERiutxXA}3LNuBZsB9W1005vK>=IDuO>E!_oB{$+Bu+`!YbwBak3FPs2mlNz z!j%)E0vY3pl$jc_?XRBxHkTgKnp~!e0APRwB=Z%5LlgqT5}U9p^V(T&$RZ*OpC7ds zNA1JcmcwzjdpH~&Wc99t)LY54!^G(KPGWw zUu3x{vT8gSly%u$Na0CV+L(4S8mSU5Q(hT#c~gdxa#b$&_Z1;a?aR0Ch(j<2KvTpd z3Lu(5fl-qt0x+GZHx>v~QkOV{5EFCam{Qxe>t?;YT%29ZW7oFrI;4cSSxNt*w_7d1 zgVVFq#p=dnq)Do(sMqaswc6ZlRj0bL?v*coarv!pJ$?MaT(~OAYB-T$-G;VJj0qD5 zzHCBhIWPc=Fe;~%R1z>Z0EB3)MFb@SXc55Xc~$saG%OaNYWweQ<0UjPwDHLkIX%TL zHY^pIGsTQ$Z*P}VeEj&y(etOn=@zIoi^a2d-}*sZ9~|7eb?1&Hg8&vWsS@INIQWg5 zyFWQPI$N!#rNe}4v~?C6_N8G38d+W^x@dH#EdKEy{3B8P(QB`{a%l5$KG-XrBNWtS z?y|l6H($Jc_jC7e-q;%Ws3(GDB7EtvF+oR#j`~O~M{&t-eU{h=83RD7s zE9)ukcVX8!^%bT4N@JsaKox+fd}LDa(OR%iGrl4v^+Zqr71^NOhB9lfNTQ-j1S%|s z2pH6f0))O$5%x`%5CT!}%tAy8qJ-93VonG`L?WO_NMxKs>giX`d$BgP4XPrb^o8*H zDgj^v&TYWDehwrAWp10bQ+3XfYJzC36(vL<)!xAsRKXws`9P-oYi|Ow22M#LlFda$ zC0ZcnRJbxpBBb8lKJ~NA)vm)3ifY&K>2b53WAVN#2X^;<=?cjA3P{E{$qJuDutfxD z&pJXtZhYw=Q53C<%v#el*s>OxtMZIMo<2Q#0hgrmBeFIO>fj}16wRG9AF{QPfx;rQ8; z%k%RPQyWt{KW&*cu}vmQ%Q3P>4v|!QB$NQb5L(v@w)#)IAxl}FSH*NX9oI$MwwKRH zn48s7nJq#`Ryc+fGz0)Bt@q;*jD{zn!_d@KnHR8htIquR(bLsBpj}E~?DEaQFVb+b_Oy|8QqmSh||F0Tm<(thz8;ch2Cr%oppXv~F1C&KSH> z*L|9b^EaV@ZnQ5*Al%E90Mzs)>tmYazA9a3)%Pls&3|u5SQ|MZAoiY5eG`QMB3BHn zE6dPgBcIyThLl8+yb%Ra1E?gR9Sd68AY~islOhr!STa!+4WUs8U=bOl-}X5&(Rpmv z{aVpEYph$ThNdA@M61A?tQt^7!=R*_;bGI%^_UYvN+~WES)LbJrh-wy_MZHfHW{d@ zz<`9A78d=l#;UXj!vGS1kz~lS0TU#0Shknecta#AED4Da3RX@Wyv@t3R8{e?tKTEmuWtkUSi>=#ka6^3U+`t&;c-AUvlCXTVK%q+sSm|K50#Ijr>v=gkKKb)+ zeJim{hSL)8?RVdQ{lPnb_z(WU*S`9dtSDy}mzDREz1`_}6xNs8cP13#sI)L_dN!Exm>;R&U>G|eS3TR=i}pk&GV`J zssNO%>V^k}WUd;jjfwJAAE^C}0Wv*Cls0||gsKSuEg8W~H7bZQqR9+4WKs&K zz=>U!`z#A>C#uvZnq70qFreCN@|Zx6)os{SeQ(&c9kaMB>p30PP+}l*h-#2}H!Tb# z$_T%Dhr20cqADB|AaTSjHz!by-z8x3j%(tzE5F0~q*RQ2%goxAjja4isF#@yle-+cU^{BAeM zedwb1I;x9@k78nRhFG)&^(F-O)Z~W!=+QsaOwcNY%0}&~LDnwAjAc(+8!B|2= zW-uL>lWA2BOh$_kB}5Pk;0Q3c#%7K@p}2B59PaP8%lYid(ZzBm>y~4L#GOLGt`BsJ zi3fwKOYvfUIZ-{1A5IT%8t*y9(CVBittN zL>k#$aK262#m1Rzww91&5p=IC{_}tM)idV?Q#YL6Mk}XLin6?_=*EiW}HpRE-krMt^h7 ztG}Xvex$nQ7?jyK$IRYZV-2Gqk)Y|9qh^V{6UeVTsM;ZdC0zMH!B}I2lOQ5!;y_4< zWNlKlA+iEE<1$yq2x2;8j3ML5F>{n8-MaG`0I+56vbeybS-ki_Tu#-5dtkvg?K-xpTeN{qcbc|fVkgLk8TIde{dab^cMKV3PAQawL6*^IG**?%MP7)C z;>coIRh>0OQRU9Zpx|unvJ@Ma2bN>o+j@_J;f*G5T(9kN3ytE}fBCA1J@ z+cizMZrb(bVinprTU?%A&YHz4b{%uFq)65qO+rzWV=z9OPR6$n_xAR;2lcovb4R|1 z^NjsP zS*R(fxe8kEC5IZtAYw+Ai~_I%00{`FAOOQgXUv;|i00ZV2*8LjD$Hz*L1U@w6d;6% z>(!tdR8_fDk(6+Qp#uSkVqXmtCQ>p00+>_@HoW+a=2>B*O-{^SGwn^cP>Fko2FLiZ zx9yi5RV9`X1+vyD2sy)?3}ygY`l?F}0XgSGN`{OfE6kBPRmGrrR;y72B%%y`mm;Pp zB3^t-$r$6USH;VD(=2)MoKN2J)il=oI=NAXf+-U)fEj8;HvH;WUb%UA^Z5Am!NYfa zQS9#=ly$+Zpb*-%ssM6gwHAxK^e$@}9*@U)Ss_wgR)~Tw5kZkxYc*)wdg#J()i#~? zrmhR)TvjxmjHEI+apVN!5C>&`p(3$uyU5GM>g4?N*^_6-C#M=aLz0A%GH*apf`D*B z1P5-icW|(~y|c5kvo*W23y}c#Q0zgP?RT+~t*`yl0{f+Oh2wwhszjc4_ zW^neb>mZeups*f%ah77873&ZWhUFIzMsFT3E|#q&%6#4?+c127>Pu@r-lhP+YPEjj z-S_{WZ+!c$_udodOo+3SlLzm;8^b54A;0$dbcV&4`{Hvi@1D(OtMx*ZLl@u*GgDRR z-FmJrz0WV|L3CEd4U1c@SN@wdpK9Nm^!~quz@pf1+*HwAkxD@Yz-|U)Pyk7+mXz3l z1+)NiMczaKR1j1_=;Myr00I*06{-n}7Ew?I6x0$Xgdk{uB_)xRdnZM)Ud*pdY2UG#1 zJnOoyZJV+z-ueD_KmWC_kG3Y;Te~rKsv5iCo$cv30@$YLGC!J*kKcOx^?&_mCpQnb zU%pfA?aF98as^9An%V}>mh-);Sae~x$aYFUUv(=EKBT(Hy9n=Kx;rZB%n?A0@%Vi9 z#=8%H{L=>yA0N+_7fsW)&ySkRd1zKeQP|<=Qxu&3d}>}5nVkG^Z0ia_cY1s*%zBjv zxao|pU@6rrE0`;0XCFUx4Y6O_5O01RdjuN+Hkv^MHH5;F0IdN46hT1h9okhzWaHY^ z=O6b9=&Q)~YZVLtV4vy@psK7N;{ez|C%-gc@Aij)hNzeLFsIOEp32;&*0x>j(@Fr9 z07R8GFRlt82v$L1^CAEMx}n80Dk%apLr?(dK7K ztS1pxW!L+g5)vq=s1o(x3NZ#}y{MA#x?A-;2Eu5K_124uh=ddfNmNC}8EcGbyRPlX zSOZ`d$Iza$D=;gen84sb-4@#lfF!HElJdGirOa6JKBfRGQp9A_e6@%v-rTEllNV(r zDP={G6{QpA6xU4_&|37RA?|sh6p~hQPx9*60fs2co;0#cd zWtx^5w!5uX*bXZ?9F`o>5em2az57xBpdb3d;eK$t>4%oot&nV4wl&xsTBJB*A^;Ku zG2QvrTsfVy_g-uD!_F*#04P$RnzSOYo~p7=ojkcSbDh1``UZARazaFQEGemXjAUR; zwjBJO$>ib#4?X<&hrar!U!=NjmX_+lfP1|`@a!Bgf)OJ)A|^B>a*T|kV2Ius0%asN z^X!Z;cmN|OV&**qH&i*(EFzL}_JBE{Us`TbJl;RZs;t7A5y=Q#T@jNl8dAGAuAkmM zI~)#8^XT}v4mFs$5Hc96<}ObrGXxGzkBIhe+}^*tQ>`o=U%BtX=`CxhsfWE#O?|UF z=^VwjZO#qrGt14(yQ4|h5kjx7Z%=d5$r5($(d6apx4-lKS6{oe-*#P|9q-?{(T=?8euHN_9$GB?VTf%|&+E%yY>EyyvuX23Y1!Uj%?Or@0Ki^EveV@z0X0(uq*Tqc4 z%$RuLR95m7NYUgoK%@dDEqxqf6fgBmsIA;JTA~aP+V+w7W z1y?C#j};P@3AVYw9}YoX6Tu zaI(jTulTy}2j{do-_Ghhf>%fS-V^XAm&Io}y*gI|!rWuflG5|u- z|Md^Q{>eu#J$&yaRSk~3cQK|U*|7s4HC-R{TEPAB^ymK0-~0aeULx<^=B8&Juyc)1 z$ZB9n&RGLqO;pJ_1~dUefSTE;@{kb;5KWDYjhqj@CqY@suwqiS40%XBq;52JJ(yYD z)Rk{lJJqghE5k%oIfqp+Vldp<-R;%&=l<>gbLrv79{bo6WDGqET4|P;^YQ3-xj(#l z^Y+2f5jd}D7EL@h+r8CKJ^bjUdoH~4+N=NRk3K)u7*+-=%l$!rB@PBV>+AOnS5FT& zZyZe~T~xDIUcGVs)fdONZ$-(XLz~__-rsAF4I<4i2Jf}4ApCO6Y3nJR2t#6Kw4hevp=G^A#kACFCk3anABln(ff_vz~*?UfH{MNt!4=;ZA z-61qly}KiI7f12!k~VJxiS?bE^Rshhk!|8>1`#ayBT>E_VE2$ZD!*hat^?hRYh)ifr z)iA3g0)ZSA%p8UkXHo~|P}d%MwzRg|&Za9beQ)dZHrMr;tuvSJxwv&^dueH9IOqXk z&Iw}5qCjR2d*s9+C?HvmLYyj3GY&ork|K}-u*g)PohF%1;T?`OP{6%bFeltF{QIY0 z`q+c_TsU`L0i6%ET9zDBDi*mZOI6{Ot&JDnxPI>5haP|O@Y!#EMR_>0Bx25yLu|Nw z@Q9Sy0~C@h0vR~aEG9_E1PEsAy+d$7NJw0{q)MKdh#7}XrG^HYa~>=$OPsy-^fQvO zNJ@D=j!*0{b_OsQ^x14_Y1odBZ+!Q;y&G>F|NN&;pE+$5gEhN*$De!ZbKm{WOQEXn zy?XT%AN}wH_g*@`wc)*E5k34ks(!KY*eC^gB{+G{x=}-T3@A}PsPdin;yEm%) zFLy%e@a}jtiqo;CcJA4OM9zaLuoE@Ovbuflu_u0Ud3m`O<)8Ad$_)0#lav!uRlbz{ z0i8bAyS6)BPSt)piAUr9aL`oVPUQ9$@g|?9$Y9P-SZXSOq89~=mX-m71!n5Jg{**p zsAfrH6>AJChJ`fX99c;{YG9UgMko|#Dj@P)oVW}b3+}*9T-OWvc)kflBxbVWAqWT- zyEvV+gJo`N$JF0fNih|GZc!+mj|_@3jG4{RSB9|o+uV8!9L}H803;@-2Humy{)dRhDL%~o0(z)QzY^UgiS#Jz&SPPKnQ9wF+>FHvLwf7>dcgh z4HILXBxcQ~xvmC`EShUqJ95sulv9%AoNHst#9&s1stR7sPB@#Yid4pA9NUyL$BB@6 z$3)%_?v>34nSzAcTT7GM=#o2nBh7ri{cOCx`&xK-{N!JMj2(eN9fD_I2VF-U3Z@Rc z2aNz4DnA)dZol#U;qs=CZk;~=nZNdTq0bw`L4P=K{bBILjsX!Bg@7Hhu?8e!PXGtdozVh5Z{>-W>GLjF@ zBD8HAkvw@(O);(yhnuUb-@m?d{@(jufB8EH)2TERHAjJvrLsQP3JDzo8z-_TWJo?R zd4`N^=8(Wt1Y68N0AT1F27-nvUlW@MG=aJZOMMPufSP-Q>R@;0&b3=Y#z{zl$f1e= z?e6aF+`4`Ko{LFx<2{;<_IIBBvoFm)^r5BIdjHP!+Uu|1y>sWm2d{qOiH|?}_+#6v zD}{6+0E~cOjCh>wsLM0SkALJt4?Xh0=fCvFFMj*`xr51Md^8%zqup+Ftdbo9RSmHt z!kh$To~KN^r8653Kl!)UPj9g&&EkH_#2O^bVr_1bdZ2|k=T2`oN2Abl9+>Zru5mxJ zacA?Yj@~jKG$_PCpvCYHz{=Rq7F!jZLzRGwUvrhfkj;t3at&feW=O@8*fJ8CiU1g> zO6iIvGhDc^!6JW@Eja?Bp_mjNv4Jt55{Zas7S)6_7kV-4W?kK@eIV~czuzC_V^q;% zUpSXcDDA0}J&_U2QSkF3)(q!TsB_v8nrY6oKr|cE!TRA*eRTPrt8ZU!1I`SBsAxdI z9RZhXOMc!R1Av^FR0&N)2}9NtI0%X;k&2+I2~w$9fC#*+RfU*Tbf&Z7YvI|?WhKm1 zHRjZ%*sB`H3tf`k^havs}RJUpEB zUY`^_{+#k`HY*}yBIX#gBP2>QW&|Iq)%9jFKB%h(onP7*Pb9`}M!gXFm8;0JbKo*& zWpsfN!I+uK%mavv@3qS)kaHHuDN0Hy<+kf$oK41)ySHx|`ElzAR>5^ z|NQ)|Pd;|XQU{2hy*gv2>0|;p2#!Q0r+8*Gpk>AOHEkwRYy7f{A6acitF&{CF>^s;TR`aQqHB;J3(H686uzbsleXcYn9$Jm72@|fY4AEUvN}I zGe9*nm&}M%GO}X^HIexlN=IK+5zD3y=U$NI*ZZ!EYGUX#lw}sTDt-|zK$29{!)PNuVV8pO_V|MPl{;9M0dvH|NQiKKXiVzsr#kJhYfY{NODd_Oq^5fRn^tA8&8i8 z2dnFA8(TX!ug4mY*$kqlgOq*fmYc>^RS~B1iUtzRa+Zn|ArOLKa0O(8ipWY}3Q2N` z1c)Jk^G=M%v#EGGyR!U=PyYO9|M11CX<8EY>}9UG^7Yk&Xxox4l@fuxvp<{~zO!MW3ChrL0?bnm(I zAARWlKmOxC`NEgKJU%{BRfG&8rV84XJ?UU|W%JUds~`Nx#)Yfo91^M+qU*iGALz%A z_wt`U_)FW{lhN_vc(UCO#TBpLbL;E;t(&PQBlByA$6eizTWfX2Jjf3=j=Ox$+WF2UpL-Yw6wBhEWS0W0`s1^%||#y zi^RkTx)6{l%pO>jxFvUrsHqZw^PbslZfv}5wfn>7?7f?|`!t^I0cQYG$wb~%&=&X|dvN{cjk~vQr^##_r?sca@!_KnU0q%pzHPzJ zY_4mlL z@a~!fO&5ugg7wX-{2+i!aH(h4|sM978-1*{FJ*Le&A9+MG)t13ffMi7Le0_y@w zQuY{=WKOfm?1sqpaOp!Id*Y4ne!t6|vUABy!DCaAcSF>qpqBCsfoU-Kzz06`H-6!- zJ@EJk`n{&|j)@9hx}bUl@Ze~C?dJ8P@!{6SnJ&(5?cKV#z5VEg%Y&*0vj|{BDaFIX zgS~0%n;x|h0CKm0eIQzvwbNVoKJnq^)aLrxEA^l*Y@Sfzz*pg?TmS~|KmFv#e&_dp ze|KNjRtEj1MnzRvIaT}mD2|Ns$gnv$I2a6@%DLcuVC~clpi8-M{L0PD&1ZCr%}puB zOiTIaKoLkyNy$iotTeO{Ad3J1lXnF#Fh?wy&MUnIBC|~POpCiLm?E%&7T6@fV&;zp zyQzXiD5AC*KmWLhC`4PyO`jl54UK$$=o<%PE$lA29>us_t=6o zv;aLA7;1`9ba{2<@})~}TWv(T`p7-Qdj`{4V)RClJZXxEWP-@qw8ET`0M!AQfr=#{ zi#akOfVL6MF`zjFfGSHevm}WSlO*VX$pe5R@0=4A1e|u$;DcwsxKzuciZ-52>QFo8 zLPE$U%$!orA~`dFO=hz?R4HZWSTY&_dy@=M-X%z`ssSmhI`qpc%ig)t4akV>e4kzK z{Mnon0>+%EC=(I^BYUS=g7+Z=GGdQ_$Oh3nHI-;7C(S8!xr=cUyU}v+f8gQozwq2FMf2WF7%;1$*)$*J*fmSb zZh2tF$tkM^B~3XQk_dP&sM>`H$pOS3gk)9|E1^ec!8Znk-m$Wq#^ULcS?QEi{wG2ey zd%cZ|=g(ihZ*^sTY4iT&<&_ZJVnk&ZR(iqxbS+Dn`IApR@#U|6_4>`5FMj9M`z~LY z&StN@ar^bVhwaQ)dhrM?jup-!?0rSNEk<>b~0<{-|@N9%N$(3*mOZ* z*vtznGf)Nw&|>}wrB|0CEClhkcv3H^JgXJYWI!ZB?@t@*}D*H*!#kslzz#J+HI0wZq6lLbZ zq+kdTWBkbDk6%20?wt$%z#~_#K6LRLU-}MLfK~zKxl~~mV`DIIMu=b$ksL$J2uO@6 zCqQz9m?a?+LhwF`IFp2>_l1Ulq7i|T88ZWdnB-g#4^Td5h-jt?7_+Kca3T0I_{W$c z6g?m_nU~&TrXmu|BhIbA5uosk221_n(lD#4*?2OEF;!KCM23{m(9AIx>BPir^&sa= zIU8Wrt1w!x-z*J>hAb*M<(wr+oJ^;w%OWX>jN94%;lb-Su3x`-^Z54d@#v_Xb|eY} zA%q;0iL8eH^69freDae|Jn`f^SNr_t+CTcl!~fgwf4NV|fS3Ud6xfWOxjVahXJ>h7 zK#1ORudb75&bf=pJ5DJRVN=)VPj5sOI)7pR&aL+PwbbvkX+-43oV%5Yv@>g$msVDx zu7R;aM~>7ivsI>|Cf0(wNDAZ7R^X?Ap$ZNStrAve3{YSCX@00(NWuWE6XeAx6d?n z)9=@fbF|bCgn-axxpC+2Q_np2#XtSh&FeSXc7~yLb(5x(ZZ=6>Ya&G0TVLOP;J)Rp z&8jz8J$LT(xpUroTC_er)BS5h{t22@@3C~ebk9AX{)J!ozkly{zW2)O&wcl`Y08ty zScsPWx(^$@+)S7VR}Xe>AW>DK`UP&qIW)}RCc~e zlBkFUg4Amo(c)`CT~5LIQdT=A0L)oJAQdd!NfC*u^}r%2_<)Eht_dY3!dmv$|@cD$Hcen!%=NDxGwq25Pc%lXQM^JIi1mFFr{lB7)$uqSFUX;t~9L2qMiMF7rSymY*~Gd?~iNn2}?7$92+l~yj~%xTtQ@G*yB z?Y7UHfAEpr?k$UOICc>$MTWsovo1`72AqB{d_!B$=QJHC3Ztbrg@gc1 zb5le^B%(6AgoP5$aC!Bg|N1}s@P|Ig?^ets;@Z{K!D`3 zWt9XjASwWf;sP6CYEsle70kPeQby+r?cb3HKtey~G$R6_V^_ddWuaBIj0j8iFPEfd zBDw(k7K3{Nz%E8GAi^%D0#5>fl=9K&`0mjg4?cNrX=P}p2*5;dk`_cXC&@X96g@=` zAga^YKK0s>Wq)RUuyKBKY0&Rg0ReML({?HfWNL(BKw3v~k&LS236v5%eII8!ASJ2gPDP7Tyb87F8^dP`(ZDH{M102oU!%4TX{$PRrdH()a(Krt=zEHgu} zIT@<({!~>}3emU>-OUU@rR1(c;5>oSgQ%#PBT6Ew3U4{y0Gy*a`pZBJvnUkk`@A_e zFH%iQkv>m|3pFk^05SuxoDw2^^2sOv=|A}=pZvL>bMMqnT7>uR@`Go$F0LHz9__w1 zQUD+YFtQLWgQ&B@&L)vem`w?gRI;gHX^5GrsY*swWd>9;DQ<^Jl4;2jsj#5MG)Yp^ zEIH+rB`3+n(|!)kFf+5PS=C}nF-BD@M`X!rnsXLW15GKZSWIy=ogC%64?lTvxH2f? zLNK#zhDKE8Du!lkmST)CTh7E(d0twnZ4i2m>o=it9IC4B^_P|ggW+J<)LHV4Yu8@* z=C_`C_5}kO31^AMo=#0Nk2$&Y{XQ@{9&pZe6_{KzMsIDP-c{@SoVXtuYvwzoF? z5BDV}qI=G6ecK?xy!&JX-}1KunlTV@zd=E2_*GLdaSA zb)C$r{%~@9eCOtMA1VVhH7(F%T~K-ubB;%&(X4F=q4I%@05oPaPy_-`DyoD5Ju(6z zBLSHR8e5Ke5~Cz_&TX98Y^j%690Mdp0RUNdN$mBxb~QQzJl1ModU7Ih!N^m?OK)z^qdv zfTWhq7!*tsk{YN=5xRcl;fMbD|M)-s@_+ZsmoHy_*E{^1f#8Ebe`)&zPh35B|EcN0 zX!o@l384~2un2_SGC@K{SAIYtivk%C7?VLVDXbIa*magcqDT^EX9{L!3aTbz1VBJB zcAf*y=L0xT^@srA953*21_(?Pa~$+~X6hZQX<=kjsfQ6Av#L(p=@IQb{KUoKZ~z9x z%*3dqc%mX(cFX9CqLOOcb*8pCsF#OL-w`kofMX^^=UwH4_l~M+eRK1{EBBvXKi$1H ze*NHPKl@YL+yChA{rA88E5CH*gAZ+<-mI6Fswxcn&Bofw>CKJhrQwfQZ2%&=aC+mf zfB2D4JbvZ&;hh&>-{~frkaE=9qxhkF*4Ee8E9aPy3EHkDBIheZLa@5-i5UXc!6z`T zs&9PltK;3f3G(SB#yEiXFYCb`)zmY_=vzYuF8ZNtQB+K94dgf z3{Y{;IU`m@VkBqaunz$M5y=5^ zh)BcJ8ygQ_shbKxGkV4R!1jHg{`f~Wdahr&LEyF8o$iIT+IhksGo`=}PgQSzF#+KD z7hY`Y`qHI)e*E*65RtCyj*pJB2m(+cVF00KKw^YBx)Y(0u-=(p-^JtTM@2y*>RcT8 zqqseqSEw8Sm-Lj`-$11vbnWZg;bNTtVth&8*$=(u#^PFs8hQv@@ zIMBdo&N(Lq^8|0JeeIF9nTSYpuG@=z2@X=lCuIV zFe->lWL8+NpsJ!Wnaono_$EQ(&C6gyDN_4@h^7XF6ubijF(fns6k-5iw7K?nLA?RZ z7a7q29M9AJEGapHHyaXW25iCrfyp^hiO-vo~cRBk@+sfm95#?8IG{YM^oh=1_S`bo6a-wbB%^?JQt z?=R(S@5i4XL=-|;TMujNt3T^&`L8hEWiIg(Mjb*O!l~8wuC)YjN6Yo@29HwaPqOe7c+ z#e~y59{IZwL_xp+u%LB4yTc7g>InSGq7iN%iVQph$?cDh@ zmoN7QgC99NKM4_;Oeed0`!{ah>QY38(eZSDXV(Dwbp-&;p!U9!l=F0^2;>7-Rd3K_ z=d&3h7dLu`z=Tu9h7kz@de2%0rnA{}Hl9w7Co#sdU}aqA9QzP_2u1HJrQF4=s?MVb zFoN&*P$9)w_j*;Yj%|0mca$ZG8W?1;ESV5`br2QD)C^aUxSP!~R?W&%U7@PY3__OL zn`bI)Bqp1K{JW91MqbT`w&yFE20s zIrz1|Q2a!x%FOon_nvy{ndhH>Zg+2IG@5?y>(9P)?TyA)v)l=Dl~RJ@X9Px|&iU9a z4~Lh}Zf%`f8w>_@Rhd~Uvyt6A+^U_zp zHR|$8ziE2?we8c(YeVYN@Yd~-*`fEeH0-S|@#+%$Ce*!x9bxAK)6|Rw%)_bBTd$N{ zK(dtNc>mz$t8d)Cu`@nAR1`oaFvwb0VRe12KdebXM8~7)tZl(VlI$`JH&;#kcs$)a zzqNMe)WOdFtIxjF&89JS1t=mpsae0NQj9KCTUW2Hu59eyywyhAzH+JFSn6UtN^KQw zy~oRqV%04HE*dv31U5{PBqmk$!EbME zUb=AcZ+zsVPk!`6E9*ac&ee6@x4-@EKmLg!`4vOarj`s&{H-`@W_M zNEDp!_j=Cza*0ID#08(oh_0#$K@B`JF?h!!W<<`1m6g@2SFSwv*rThf?;^JI7mc4N zRb9V%>;L%dXJ32e`-~VuaNgf{{>+{IJ&ke59w2AeR4C3+DrA$+aiF^A0sx3XHqEh9 zL=p(PM3eO>ht2^8;6#AnShH$32tDU2qJyL_A5PCL)mwe9NCYB=pkhD@ikSdRLaiVF zfbCCdd`N9;lgWa{@LyddgPmJ<@4oRLzxD@z@QeTK*Z=YV{J-=EZx^nh7$JTUuV}Ju=)lyR-AXH}2fLeKeg4qM43n?dXl`{ia$y zwHX}snm`28u0wzhG9Mf>I5UnZ&8E|wqN*YSIW{#mQ}W0pIU%5$O(%zO+Cm!{d31Q- zR(q4!c9Yh~j*ih=?E_W87b7;60-4VkQ*e+|21H;nfDB++Mx)tumI_rpFteFS&MAQ^ zn&q7D?CkFD96tSjef`NN9{cs*_#e)m-~Mw}yKURw{H@>m-QWG4>11Myy#uSMnb3&> z^@)@RsOcOQbpq1^D0DCt@I;D02&!|eae;!tVq<7(g?r7;`QULOU|5iY&JirQrE|nw z`A1bL41dHz)0j+WN5``^3Lp=cszJrxGcz$WU@=hvGl((8adPX+Hk$Z8@wCT01JMR} zmcTqH*4?a?S&N?8xs(!9v19`8nAsJBC}yrx%#sl~i#X<{Zd7xONyYYecW+(4_QDI_ z{>*1SbNTYUKVi0d?`ZYoS^LVZyY*msu)3CVZo4Qsnd#wV)XkEbCMC8G*_#?Lm(6Pc z2*E86dV_v16!xB>nhK`wV2>tKMoP)Bh73wQf`qA|TO%i+}kqzV-AsO#u=8ax*;`b>p@-=y#Lp(eB=KJT@YeJe^Eu<8f7mD%9g?HzCB8 zZ9}J%2{^yBGB6@Daz)xjb+k8{rnuBJgFsSr=oJi!*m}L*=H~j^)<$5Avo4iey;|Gl z>F8Ji0M#?QB4(-^xEQp2(R1_r8a#BJJ-T^j^_faeZ4pvs& za(|M#S=%KQG-1h%R>Yw+XAxD^6r~4-k~=X|L}C#@Kuvk~V0t`_g*(Meg(z!TO0`0W z&N<3rcc(9X@w?yu_Nxzm^nsQ2Wqh}f`gA(|?7#W!XaCQCHQ%)?^a!OuJP`naP9zlP zn;I(nts-7nK4s;Z+3_3`iB!Ona~4+7I|ESBw(VlqsVY16RUkxSMnobiKL7wAa`C)H zM4aotmSaq`6g{XYI0Si<;5?6?<+clnT&Q0E#@8-B`sleU zSKf)JR@LA9?ce;(-~LSpFz7cT;Jlk2&t}tUzqb^nJKWt*(`m7H7Bm#$5SEvh202Gi z?hnxUG>dn~YoTT))0D_^jT8x5$*D_Abu$cPYON`uiD}FtIn`CQys>)f%vQe&anjBv zvux%F0bn|rc5MV?Uo{Sq0b@#%6I2vJ1;+BP>ng&KDc5CELnj>B&ST0EfrZ}LPbymgRbp%4<^%?v3LkE8$eDO z02YGL1m3xs!p+olc5vej>NSsl;sfm7-X#=~uYc`p|N6848Wx)=A_B7$!-%q}QJHV3 zaIW`SDn43dMli6_=&?5oxOv~;OB^K*IvH%rQiEJSQ{Jx_v_W3uYKkGLl^Epzjfxuy;om<rw)P za@zr61TD*L#W@chKx8#m1W2Z;1|2x%o(5T!$gVb26X&37kt*r3BD<~~9Zjai7>c~} zb-!sEGjKxaQB}bZfXobBg;c5aM3w-6WJ;}?OH8IB9y$PB2us1wByAycw(vXu`@ekf z;~(ETbLMS-J=j0^lRx^y+)np*GZ9t&fzEP{sf!skGdkzI3n8~%0&vU*IvS6<)n!Q5 zL2_u7=W)(mYI6*nA&I3NeU&}=E+tXu#z`6!pumud7_%s+m_R6J^5OKQi^2KfYu9ey z-Z`F*C4-8#T?$zq{=n6CJh}VY>!Q*@oE=Y7(;<@_w_r*O7DoaF00iUU8^kDLIkh=^ zA3KrR>{OF#0t9A>X#zNi=vG`-0TnY-O_Q1CD6HzdanWBTLqyINr*Rgu&HIxGW|{@f zOcgW(5He#HmCPm&ln=O0!TBLF6Fj#ewyxkWR2=fJF+PG^(J zh#a#EO{nUgcMi=lh)v?0t&BvTOby(!IyTCs3)&?Gh)$=JrT~gKXCuBzX8WlGvb+9g z-+Jw-Z@n#5nc0`W@|ABq{p?D=5w*L!d&8VV(@QC(lwwM(Ku9k58X>2wMN~6(xtng* zp0c~Wzl$5&Ie5x03pf%MY!ev90mXBkcVkM^Sr#@^&{F0=7o}&}5Ly&W9XUTZwR%tG zmX?M$Z{EIjXD^DFTEE{vd+{tVudgkA=cyO*XrdfbN(R=>W=!M}vKlftV@1=Vd&68i z%2A?7%0k-iy!OgUm+JLZR!Bt(RxRgDOs1Bz-8-6CQ`%xCS7^Tz7z--ArF zFe}Z@MbRPv#4PYo0m3r(HUMyd3Z`bY)|~TKym$a&UQ8&Ni5C;*2dP~5&~aA-Fw3== zfp>10^WAYwbMb+9t2X-OKtm!Ts->1(i)bpvq-@t~=Nnjb*@z@(6Wz8n3Jcawy)Y^m zhX}Q>-_XM21w;`5C7Z$+CIC9+eh&SyWk#awIZ{mQj%yfh|+{zv%>YI`*Zm5 zX!FqHzQ2F_e*f#wUX5i+Q^{S9(K`f1N5pw={mZbG%1*P_COM4Y3K9bY0^n5_52YLc zI)ru80-!M?k(6>CA6F?dBVa9!=9-;DA_u^OAc7?VUl-3MVxkuU^ZNKmYrm{nh{UTLF@5n zZ}Oa_ma$A8{6m?-KA?)SiYdIkJM9S>f!U?Br!=ignTIFka#Oj?MJ&}A+`99vZ$;Ha z6+x;gkQkJ4RxAY?W5-n_6-Ve|xc>M_T(_Ie`o)V^<2YVkZNbo0xOn>H&;B`m@%O(> zx9=E0i>xm$Rcju4U{p}B#k>#&VG$uCN6w(C5Ia-Yzj^7016|)30~?Y<5S1#Xnv0Fa zMCMLZMZgRSAOc#WRi!T3ETt?}$hp%vjB_@C^}20amv(q!1u$en1nJ9E zYsoWK(OMhu7`!475*i>9R7GJ6f`Tj!1hWe4KufKjX)%8$a)ge^KoOmo65yhp%M1oo zN@YX+yZ%eCX6Cd%exccD+7=FIGr0ICpC9_!El{?*_8%@;5J{V(>@`*Ag_uCZOM z3-d6V!&ZGy0->^kQ9|;VtGei84412D6O2?Zk=7wpvs~(M>VtP7hHck?!JP6mO62^6ZdtFxoaxPT^sAa`Kla;ZV@^ft($g>^#|&V( z)>#Az zS+!69$&XyuzWL%6a!4tQcTj~rUw-*PR>FO(%&D_@zh>j`1KChYgMCas#CUFDoeE@$^fdWNCawgQ7D2X7nQ{_7FA7Z zg<8ZGFHkXLG6OZ23uHr(8Gw*p{@sgln7)y!-oAUAQ;x9#6U4>q(EuIzV|Ra4bG&ph$ z6^LpPX7=7KncDf#9}j(h+H5|MPyRu>s#1Kjjty&Su zdyk0T`zAK6r_fS}7jSd&`X!=qKM#k)DLM~q22e$ghhwRAn)6&035h5+&2G~zqF^SP zoz_TTAX??vJ0Czzq_B(BL_p|o)ZYp);UxorsnO%7V|@&wlxtRzeJ*o$$K?8?l2)Nv z@)R>Kn6D*8vqu12Brh4PI1R*T;(bI!sRhA-paG~?1S9}Ls47gPQc}rjPJhhJ@>}si zmZgYSmp2+bMAN*UtEFk0$Ir%BU)(+a{PNYGJ^Hghee{!`#LKHf?3@E+ruWJRV|< z2xhgY%t3iYxX&^OaH;0m0XiSRObJY}RwFP`tg67^OGPFF0wC3z1#&IM=y#j#)lP~O zsVQ4A1mIGu&9!QctFB1ZtQ4B{lc(hO^ZuR|Emku+&!#{`0GO?sqN$;Y0;W@c|JjQu zk9oDqh9Kre(2NO8l>x+5sv@u;&ADh_A^I;f3us*ygP33e7d)83l4NMO4FY zKWX|?|Kf}1yUiAmfZd`xjfjj!v`A5-_a3wog=#tsLkJ;;aNdIH1EK**7e6L2F|AU? zw3gz%LquDYK#2gLl&NVNCNEXeJlC8(6EmNNVSgObJdG)fnsdHu+EwG*wm|?D5s{Q~ z&sAJpI`E=GD24`zWtuFDdgBsw7C_)lgG@Rk>pTP}!9c>qMpuXiMHR+Med&G;w4g5V zOPc~9Vg$GBTnS7ShyW5|ASN!gsu~55TAlM?2n@)mst87eQbbGnhcr<>%w3t+LWB?fdlVw!c%92%j?HT)EOx*&$-BLQIGVK^Mr3Rz$C6fQG~fXp5)B z(kXbDr2vH1tb9_}!lc;Za&M_rP^kbYiUI`;tC9nl1(2Z#kbr2F?|3i(z%!gnqsrHLR|{VTn7M75UIePDsEVG^n<7S} z0BChQ^})IQIPUi+c8rM3{Qma-G|W{h60KIN-Db6JgT{w;74B?yJA22&+?7Nre+DicVPV5c~=d=li{nonCkbMo*x?4QCM|nzalr(`+%eXSjjEdBTZ= zCX8pmJ|iZs4SGNn5i>P#$j&i~sb40J@X&>`YKt)JhsFo)s*p8AFz|rE6jxqN$a`ou z7dIb0q1cfM8nlko01X_G7?_&#j&{3ty|!ABXi@O2B7)?p`O(vlAUwK%_OI$^cX$8U z?Ti2SvtRw~|M`FY`rm4Y+wFC`-CS(id76nSI+s&gcg+UTng~Q-Kwv{Z+|7LwP08JA zqXrX~LrmL8mjM}a(YF;17D_0QBbu7CdxO5kb>pkypQjhc~ZZIG*P`r*RIU zVImO#tByPn^6V6h0FjW17tMMR)oHx{;o%5uHm$DX9Vg z1+|Jmj=4%QIHsyhkv*6y*f5UsTw3<7b!JdhYDp>;h=L-Za`0+)xIM696T18SR!a@R zuUCGYrd)&%3%w5+#w8L3c5rBwAtE$8pkTB=SU!Vc1!6I_ZW?(6&u5F(@ewy<%^y7BB zzP!2u&{AqGiA=^}Y?{Ug#}s31X>pYfaI7-200AMJX|=OSu4-ZS24)^C0}5rDup(J3 zL-ob9aX5el)@r1RMBzu<^hoEs6yKHDCkNa~@JiA7$cs;`m7+d4H6V7%SXIr8*`E<~ zh@PEu-bBElsxmF3g5RmB`+eerQWYQ|DX8p&HH_STl(>^KMaQ#pJ!2JL?+C0 zDmgbXwCnZu>N<9O&iD4JCQCa^DwqY4048Cc-~aBOBk4#)uq4QrFC(h<&(4K0Bc!UDey&H4U8h}+%v zqfb9+nyzW$n6eYa*lez!@NwVP3`|hU@Apr`iS~2BJ*2;bu z4|?Y}O#u&Rp!#l%NA(O^iL;tki&hVyD7dIWhu{IZ)>?#!9VbEnF#rZuq~anr+qe>` z^J&gfCs&mQL?%E%c{jex{n%~RN8TGsY#PsKE5stH6z4qHCKgoCz~G!mMn_EK$f*_> z(jCgix{e)~fho#jN&%RY;$4O#H(KfwO;HV`ieUj^K{X;#1q8xlWUHN(q!hi*mCq2) z?_A@625gJCKgxn9vYM0wIaZN*o@3L*5STDcX&6Q#iZK$AngZAv?qDXW2H?DN&Z(Ky zY5<%t?~Ku96{ye!rv!nWA+qzTYE~DQOkxL1x9=ZN0e+CX za@$`1)n5&7Zu9=W47MO*6#z_i?k(k7ikVfST1x?ErZboVqLw+=Joe&3+qP=viK1CW z)Kca&_rus9kHcaAs(m`QUDE3czzv6 zumd7wfCU51(X0S6!eSb02ml#XD|1v$2o6g1#1);U)PQ?3er!1koEF5Qnm8)A^7c)* zJ=1I-nO)h0JzRnTR4nInwct!3UryVr;o8W~ux!K!e>7B)d7@IvH1+HP5|}RVXj4@v zidhXDPUgQTc%}V?p{g2?fryDHF@vfd!CXnjnAy;g4PPI>{`NU%L$hUVT z=h3;Q-So$F8&7THoDU9+RU7Am^M1QRk+hfz0!}cU@?gHi;K_VT>vjR`5FniI2P8lO z6#?}G3|tKj3}{g)S(rU`*1}h*#LhB-TS{LBZ~_6GDkw}~HV3-}t4sR}f1jQV0D##d zYO;_!>}+5Nq`EY}6ag5OaN(mG+1amQm9}F%+A{I{7M}HMFWJNOF?1bhQL6w3rb}z@ zoWIOgJ`A-I0+<@8EGA`OPQprBXa0=%M?*s={$hOGV;cPFEPC?Lr})--MF4x>zF(Ei z+9Hyv(%CEs7p5?EL4$U6P5XTCeHRQARxcuw&=JKB-M(hT1iMO8WY7e z3AivLB4DagjU7}mvr*^uW&;L}U7C}Rp_H6+8ODh>ygUG^ zR4`bc;woBIYpIDa#<0|{b>X@Y1`{Sx@`&=*g zr;GkB5)inooT8f@tATrPvDONx1+G1FLLZqpMpd*D!h#~C#!;vh)|wWBF$^V1cdoV|N`BmCGn_fxq$rZgX?OeT&Q z&7Aj+FvNzDfOw&=|52&t>+vC}$`HhbW)s3{y?yd@`tv_My?=Lj@v49KnxqAE)euz8 zbdoaXlGEJx{r!G_`~LRLo7el>yLa#2_Gvoa-M@eHW*oetI|XnA%sixge>!0<3I?JoiYg(7 z?QYX-cES5i%VQV%amvY>wt>Jkn*($LP*f9GF*HO&Vm1^&LUmxEAVAB213?K`7jr^l z2VfWk;EYj5r3H^{;HrdM3ku`?f)3096s9uSV+#^Kb&zb!b)e zOCYI&on4*HyfJ*w9XBq%K58<3?N#-NMFqe-xvDyp1OQB|%N7|7p*Aj31`sfmv*jx+ zV}4*ouitBdAznFIDu_t2Y4V*e^IE zLnJ0*zPSNl2!PJBDtLeY=I*e0wQAbP&W&?&T8Dm^=Lv}4y}zv` z^~0bB9snF4_6GnWrf4q~J>nptz4>K@?Dv3M+z z+m%se%SD#O5Ml*8myd0_kVr(LN zr)orG%4}AoFj{n7k)n!OWu6B$--x~5AB$R?kLG-I3?|;iY3#+UiJ@JsH=C|$J5b4` zMCW$vE~i}5Yzl}rP1Eh&{{8Lk<;|0;XCLpH?yB8vwpD-wbDjDbhZTD=sLpHUk_Cn4 z+riC?l7=Y?0iQ4GQr(~+EJj`kil&5I7Z9MCDb$7gzUZl)txK^p7r{d{LtS<;xn}p} zdHpgBOick6WdZ`TTE+4_`JvzTZT}2lq1%HQ@EKMFh*0o*jv5h6;L9)bwJ3Uiy{epN zL1y`kHHF1qYpyARM+6fzGy~#AhXpGbMRVV?)J20noP@MI*QZZzE-yELWJ(X)%7>Zx z(pnQmCPGv-M2byAOzwiq4(sQ$^~fW2L&TMx*0T`IR^#9(TB;t2xhi$JmH=D;zxkX; zLMCD#n7L^@0_G~?Fx8yR%oZZDDl#KNsdc#v2q8w7MCNf)J2P*z3K$?GAQ97Idd7t7 zRcr!l8Hdv>)gik5elQdA)P|7KI1URh70pyLXDy5f$VN1FQ4p?j^-@DbRbT>V8Wqs0 zRmuBOVifjc7dg1VA+Rg8$gK7}RV##29&hL())gl9VuqsV9c01A*;IiMvOwzr0SRdp zbSye%T1Sk|s@gG=Mx_b_wM@_7zIsP~({@jvq;1po!&qxUc3o_9lWQr2lxvyO{ErG& zSa23aR3+Ccn$tMX^KhE_Q{NvC$HTC{%Ts^q`-MJ_NQmfav1t;i22dE=2k{DsoTQRr zK+3g>s-rWha=AZ)3ssVuWzoxZ^U=-K?d|Q*Pexehsj9dT=V?yUTuK=cT{xVM$L-S} zwA-EcJk6DvT-(Lf%9}C*fL>l+yngxSa<~1##d@>uwB&vm#8jltX+k2m+lWZX>DZ6O z@X^)9D97RMur6`e>=+m-prBQN;;b(G-VGm5IMD*!}%}PLpF7LUi7F z@7Xca11}8#NljJN&cknFKory36#WSCm&?_#=3Pe>ikpk;x;`{>S=%`Km6I9LR^^bQ zD19?kF(Wx-W>d&>sa1-Il(I~Q?A(w%Uq>@T(-2+GnsNmsDfO&zhtM|OkW$J%I0h49 zK!`p*dHVS2lN(@v*x!;n%so952^vzG!+k=gaj>VoV^4 z4VxIKX{y*bL_|gmWU1FWDu+b;Fqrqj zfBNH(mHEZX*TX!EET)G_L=E|c6vB>4vD9Kfff;~#S)W9Nb<8DrYD4(w=K2)EGWD$` zMVxpw*Fz2ZF`W*FRns6lleu0Ex7&LpBjYg)-4K@} z4b%*barWii=5_KD{{NtzU$hpjU*|63!(>y9oHyJ$u^%ERuMm9fAQ1qqsQ03`uyd~moIA-@Dxl$egNK zq>41b1JV2aF~;b&mn1c!p_C=xbzOVIE}NU@X&$FK4dbge5aJAkt^WFU+-yg(mI^Mq;dv4agX+qoivr(-D$Me!0VYY3U2F!?7j7=_^ zrYWoW_OL+R!3bH^GJ;#A<-rWuKnanp0(f2ct_%M0e3rhclYI^Zh@P9S^WI0#FX(l@ z*)Lsx0PDm4iY^_XfC88)=1|{mUS&7`{yg=2x>$B@_J4PL`@a^clA_?*fV5Un1~wp4 zBl#nFM`+KWo@8@a|KO7!EXuq9CSuIA;IoMtwoXFXyWyH#lFiGHo;%sTy=p=5sVC~6cw!{>-)R=eoCvhjiF&r02JDq zy6)oYI#1JQzxlk>tdFj8jLtCU0>L9d>{czc3DWU+vRaFo3(m!;_s4y3f(W@H0)@cd zMKBaIR7pju_z?JYUNyMdv=Ch4TG#X(WWE58L=5Q3hO%f#U|=n>I`EULt(XzPs_Tfz zYL!Y>B&X~=?siv?pFVr?MM zN5tUVv&WBi+s*aG>a&;cPRHKN5*b$uL_P+svaGgTYgM(JnaDAxQpl`Zt-H-`9(pHb zcX7Fmfr2NkqL9;E0V~jyx6?eOdA!VNoaWkuZnM6+d9?02L;~mBYT@+N)A5*I9gVHI zylk3w?0Yf0*sPehB~58O-rw)Lwu@ckLolMtCy#g6*GBGe=yR^<0(!MRhi0<4)QWZc#Bu&hXe0f?I2*S6{Hh9lvnrAz~MIM@i;W?Ec zVDb61Id*x40A^}VU+vx|Km5V{lzy#R{jCK-6vz){{xWY8pn(3ap$o3&>EHc_pFO=hJ%0AXQSs2Ho9m0~br%|z#Lf|CGGCGi zf{x?qbUK=cb=-9AYQ4VlSYfxmym_K#okNE@r94j~lOyKss!>4&`|*#Tg@}x8*EL#d zu5w6qI_ytk!3U3~qU-H$d-14k8|OXLoKk;0O=au>HK~ZocD4KOf_p!|{YAaM4Rv6tu=UCN!j^HqBG6iiD=K_inYmNJZ2}K&M*&u_2&<7}zNS1HdA( zwLoOPw(gf7^lLwV8LKA#)1UmwvyYy>eD(G>&tD&pCj%8#Q$co1_Vdmyz&TM>!Y%|L zdVA~##ggVS_TB3@n~Uq+x>* zb4H#6c}clHT25(BMA$SDecWt!r{mDS-w$I=Wp=KTLn2zOIv|!>nW>Gl`<MeiR$1X(<(m93vs)LtUDLAtqC;DpIQ`gwVt$Hmj!DU9?@tY*cdaO%qp5+jKFs&b!DJh|F>4 za>|KP?(0=t!=q2)9cVSECBzUz z!%Q*oCPpUCrl;fn&F#=c*ES&)Ku}Mm{COY-Ulya#;uGB`e zs&j6EK9X;)uDgcOOtsd1pBwLT5kQ$!K8`b*caE4yvgT5>g4VRVytusFF{;XvrnLZ~ za{(zyKJD)*G_h;9mw_FELYX0FncnAeZ{^;!DDpxo{F+tK@5itsNSkk;zHto`e1`{@ z&~N3A?~|v#x;o#ra=!6-=318IxC}bJ^-ItY4&iw6!?Fs#K0Z)_k)Y`=6lOI0& z=m$SoueU(BAE)S>rm@DM7zV%{^ssUjcz4q5 zv;@xwbxxi0UDr7Tb3VlAf&DZM$J3!d91s2dL9}7s)m;oLl?pt{ij8X~+^B zy5+(>tnx4WAYZY3;Vg>ymGU8?W4_*PuXo#zpWXcIm%n-U?sgpK#f5{T_sZa?pqQwd zVV*vnrwaANE-N#Jf>hP!Va#eP>_1)q@cPkJ6M_&an2KqwB4s!n(>$qECZZ5Sy8_~3 z6oYe2nTnZQ001BWNkl}a=TU=#yU$P)pb_~Pd>ji%I#ri#cr9W^T|H$Ki-vbd*AEy4caF0Ilk1X#&;qsgC>SO%@+gWPP zJBB8Tic}GiMd}U#LK7S_F`dPHm);*D7>HDJAUBTZI^3=31aX+muWcAZy}X={>CfZ0 zDq!f*z2NQEcXbP7d54)yz^qnP(=lb6GqNK_M-Z5q*$2PS1k8+>Z!Wf1SG$`>Po6xz z=wk5Bf25aYWr4w}k^&lnO5IQ6FK%xIxLdb%N+qA7t}4jWf3myyc;!8Z5I0@dG)(j) z7khU3{;=N<{b8QU-RECSSR^*1LB6}~nl=PDC?TR}VjmGR!?c1;3RXV6ocDrS4_;jzPP&j5&VfPOm%_RZ{MbIAeC3I zUcY+tmQ8cX_qXo^XtUj|HmjSc9MFf4cwp>1WU1K7anQ)+z-YAUekkNUS0bXtWfKE=2Ow z$1It!y7u78R_XE6$2X6z+YsBfnM>(Y&S}R%VD1o;+GNA+XADci*25s+vkcVl$}ITuTk@%6Z>xFU-Ym z^X>Hyh!`(?*qK(SGt{}Hz2#%gdo7a@p#6@`&;lX;hcFWUQw##WZ*Dv3uG5vsvWHUD zauyDLSX^og6|OGhQ<16&XvlR`HXsxA|RBIx3%xh@Pfhn{4o-#E8gZMK&e zA3u50w2qMc_x9!e&iLR|#Ykw%-V?E#Q<}#)nJ{8-wG{ zpb6p0)z!sjbA7q_)#op7_Xjj%5kw&8$Z;&dH5-@%hoD797HmsyQPJ_b>(UHnWfnP{ zj%MbW6(A6~^*RK9QF2c6VSk%b1!b9z<2?J-s#&d3CA5trBFC<(c`^he&GYOyUSGBz z>bevvQfn<{HE_GyY_=P6-ps~nnET^le+MqG3%+sN3->L^!B^j&J&=d6_U$!D^)g5r zwZ50>PV?bAwk`;UC?EbX`cF0x@GibvOWVoHRA3o8Ac^Rg$~?Pgm9|;9H*P%$yzLSYwqs^xhpMw3-q-?c!?vdGDJT zF?cCON*(i5)3mSIF%gHZ?P3RIs{L(m z)s-r+Wdqcjo8TBo46BhTWUT~RRRIuOs|YC*fMQthF4s&DJbF@gCI$K-ol*kOh~PqF zs#8gdfItGet-(k$WR%fxm8@7&K}W6$z~~VW!Ly-5Vn^WEP%=|CEmfgb6%$y*B2q@8 zU;OfCuiw5!1V#dY`u~ylo~%$LuFx%Zs2A8x#?>aOAprw9-WC{V~U8Tl$+ytwBc z^D}BiB4*6uR8}cnUtiVU-M{}35q>8I;M-f4A|en05Cb8*+ErE9?)%lY+YZSiFqmU9 zvnu-F*%R?WAmZ@jZ+OWngfGAI;NI=?pZxrzj~_qY^g~tfbcC$NhOO}$Qv$tb?H1C2 z2^3;|lIF+i%)s)#>-K#N&NCKWG&ZQ4nRndv{dNF?E{(X)TEub-j98kwpYV;7{#LF3UCC_oaVt92X7)~DW!3D-Df$!cT|PN&FE9i$R>Qu z%XbP>Jxl?8pz0Xl0j9y8|19Cr=WmOF0*?QyWmN!xfFtA=UFV-Tb>^98O9~z)9V7rK zx}*jOAPQi>=1#_HM7~-+3mB_mn6xQfBW7+f`Ij=qT|Q%7x9izom%I0e<#qjR3Q#xh(mK#*)GqH0h??LlGNkL&G| zoU(wEq06eKG7K_i`QG3B&lsbbiR1&x(@OtR4bYSbcDvnXyNS_{`S(5nRJCsCoOcMQ zhDczFO#Y}1Rj9Vze!boA)96fyIORl$RgA%N6`U&|_0J!s22zx$O$qTU??1eA>-@#D zb&oo4>YTD|R@K$2H<|Bt(2bq#5iF21F!Iqk55xvQp=y?lk_9cWbIhI{F}}FoUR=t0s6xBxVDWoVPh6qQ+UK*sx>o$FaYB^l2XRMO9-R zeF!du+0h9tk5uyFi{_rV@Cd+8_~l?+bawxh!>66x~ErR3zuV9}K|}jbq0bE%XJh z?BKP+`{Zc;^)ElH>z2tI2p2I=$=Ng)gfF^zdPW%&@t>@Xo#a@WGhU?>kiG zoE|@UG#;PTO%p<3W&$iy-BoSABMy#j&VPXj>&u1RqS#a zDT|0?k({S+1l`!=RR%rT{-A;$>IDFn+ z8Syoi+W-HKn?Z`b0#3)zo&cXc=ap~0`uM*5X#~hU$F1LcQ-CnyWfb0LdVzc|)~?hO zF9S_s3#(IhoO2<;$W7<;hDkUM!;ZG~i^c{pdIJZL9oOU{IY;2DsN@>wX#aNemhs|lbHF@dN7Ad^SLk~$#qCMS3MKl~wdaECH3F>b`au=DFRR~owJwr5cavT?XKU2w)!IJJ^x4G5=?S`@kAq9s-j0i-55y@d5 z0l*VA!H0SlW9)}vx7((ii$nT+S$CfI+ukv_iqKHiL``%QmRl!BUwZGsVm@O;1T@WK z8vET2L{yQYkFjRw>#71Kkt{P4U(?Vx3{*BKBJTqLTyOF6G7j^&Tjr6Mtb0hR|6jnEJr5V6R>91xKxA}CRC#AYcA zh@_mQ@AnrMSC?0pFP^{nXDGfzA0Cy*lvZm4FDn z26p8cLNJ9a#lKGpDUb)^tcpO4rmEgstg3cCYuonGlgHQBtH7kDB8FHTA1pe|3d~&C zktw4Z)U)>J^rUaCw^hq-mCfl=67BT5ZMas>zo$p8R6!U%wd4#5B>K}&)Wab`9! zx@3dLpq3CSgAO5N8zaThGJ+2TVwk~#p&^V05di=)SO7wR(aa+v*k}+CQKxuoQ(NQZ zg(?CWbYKyXRQHTgiO`DGffXYr11lbMXn*{*{@E`o6TjzJ1y7sYhL}FpK-|x4(y<{;n z?-;6-R-M$;gr;GV)aWt>0);nWnPNF2J1|%qGWE{X0fQX3<02o}+$SAN60{|=i zWg;r_*Jco-U(Oo#{Jp>V9|T&+1Fp#a5E}rai543bFf&i^)%PFH+nHx(e%t2w+uA@N zhiK#sKvGUwhjH8wgLmA-SU1i6ll1Yk4ptQFudlDyo6Y9(`ugI<#cq2&i=hg<-|ws+2QX3-G$i6! zH6b$d*zLRZX1iVkZZ?~1MfNcol?)ew*nkj8)OO=w27Qt=0%T4GngBZmQU*C**2|-q zVenqap*#3%1AwXx9mP7#mdEs(p(6v%b8|l2_s+pYdDG(TgryT!K9tu=uW7*;04Tt5 z$#N!?Cf<+>%eZ4+_i z#Df~zsA3FaqbahQ5fok8qH+%qn2Syv0;-B3Sg~6&%94hZ#=g5=U8_hodjGw9Z8iJF zM;~wZJ)0zSj>!|w=BKIe`o91A*T43auY4^y@0fn?1z^^Gw}$y#N}+Eyq>=g|Fmyi5 zhvDD+^ZLjC@#EcoM-wj{K7RE4oA2HFlW*Pn{-=-f>I4xKON$WzwdgvPp@&+LX2XJy zEK83O1vvmHO(H%Fwwy1|&(5p1U9|1d@$sEA-|*FsuQyMAczqeJPVT^;eA!=Y#>@OA zLKdRMVm6;Q4<0-;$)m__yS;dE@$};I^4XL9c(J!G_ag(KcTGEU&5W4~x*#j;R+l-A zwqFA>`RJ+|Lo4XkgP>&u$fZ94C~8;*-KCs#u$;3L>Dr@qp?%nI2b10cG)J+j$veub z`%W*OT#Z7C^k(?@w5UsTGn%x%0SpN3U^iEsUrJ;2P;pKb;Y|#iCX?`z{8#EFBQiAt zC|hcgD8_zQpG7S3;?xh=Pq(G z)4qiODw0MRyj6*mC1M6Nhd>=Ejl>SDB03sPipmZZ_cSa`A9c>nS~dVPD7|&nsG?@7 zB9lr_d;?dq>$=@;9b$zCu1v*MP0i#lXi5lb1c*}fH;OFb)VC0@Y$l=!U`pb~oJ}E( z*({|bNwR5HEe?e$YAMN>1`!#Pq_LNr_q+Wt_9>03I;NaOK^0IDOaRe%dDPD8pv7sa z&^gEq9WbgQc!(Zc?L4@w>Cw|?C$q)T@w^QU5ay6nG3VkQO;BcaNT>z~ju-$PBSQIH z93mN_h^fdX>u$4tad~yMTHm{U>tc0XRkNmPAKbs!@Ao;&lNT=t;AmF=tAF*sfAGPN zfAE9veeG-CI669ZXfY7~4$!K%QUNvl=%>H*E_h#s=!qRMn_5abrXI;Q`|98Pi+}o` zKluJfAFa|L%qU5J_N%9lo?q^+$ms$Q6$Ga>gp=tm6jdiAu##jE!ZZpw;IbIeIX9ax zZr{0g>-_BWIDq)zy0CY|J!@N+Wn9H)2rQo_~{RI`^$H4pH{OohedY) zEsG&W$9}n7&gT!_c~|l{^!@Xv&mKSebai#1X8W%5h|8ui;;!$3NRhg$=i|OJ)HDv` zeyg-%A7j(75A2*LP_-oL0GMQ~F!v})RV_g}Z6nH7J)o@Y( zED`WPE0}&OFi1Uk1F0evTsi?t@e-b_hp~url1+-FQ)pAA0|$!`1l-S(YczGy+>Rnrjw3@f9tIQIhSe(s7bz(x1r{ghasnN$eKk|4Nbu`Q5mk8CCOz>iCBhebUdH6^9F&Ucd7+RFParu zJR((X?b#C;fr*(j8eqNMj{E-T_VKK0L#WDv6-jEQ8I#J?c{dZyhz@{}7>EG?8418S zG;^T}^Cm79v*oNkJ6T?>FZ*2@a%$^(RyXV2j-EerWQ*m|?b~;L`tx5LpWeQ6_W=TC zH6Z`@XIZ^G-Y!(Z2(aD_U;`0)@9Usz_nc1DK)#Fyd^nJU=^saR1(|J9p>v<-DDH&jx5_ zP98n(S66;7*K+x2_w>{4FTVfe+u!=b6Z&P}b+_++p(uACftnZ)nHd{-Bn$JlIXgT3 z@>jpo4@0-zy|}p8b^A1otLx2ryG`R5V{oVEeem7pI*W}dnPuyCFmBifUoWb*H8ah* z*nA_4_bv*joD}@~5ALGnwB2A2VCKbmp9eRZ3$a3=$W;@8vZ;GhF>g1k`DMU5NMf2z zo!Ub_rUx?$Gf*u~7Q{qTQl>Ycq;ktApB^)t5}YElsS_9g01ox!G>TM3A~cx9{D?}t zd}%*Mq==;YvY|g^dQ&{2B2G}UxtxKhXb>Z@flhTX0w58gD!>R<^WZ4w3JJX#q+ou8 zH0m&p$4B$>j)eL3oYYj4s;ZU_wsX!gJI7{_ePSP8rzL&x!3Y2D-~PMBa?vzxU01<# z^d6B)-bkPd1fYm20&0e+U|_=8RI+N$06z)V3QmpEmH2nghu&d$z{X00L+KsF<0G-4L;RyPz~pg=5SW+tj(vK(bFBUnAU z+SR+zhSQVNrfvd;VwP=Yr6(*?X=|!eCQ&j=Gesmvr~uKo^I3iW&iOEWVZB+uxL7@V z`eL(PtI_P}D38PS_2t8N-W8Q^e*Noz@XfEEpPi&MT(39Jo;~~Leg75#ryOsotN?IE zG&3_G8dDmt(`J)n#pkEToAu?MJ{a@1+YQs$E87k5vyI2zFH{wYR7DTH(5bE~gVhqh z4hs`aRmH{nXt8|w;GNU6)1$?roh@RBh@d(W1twYzt4muwk?rmmof;$n9fsSt|LFYQ z*Z%r@e|h`Pd!AiZQI)a@nr1^6P|~CRb0Nq<*C35(tBH^P|&t@frpcCM$-ioimL>p+xgTP*4CacM%ap48RKhP|a*i z=GZw02k^wr$0%Z|asXA*4NB>7(&v_O`5ysp(iSi%K?{nRa3(}mhbXVm6ACSF5*Nlp z?O3=S%yzh1MxZG;ni)Xl>E4;UycF!TjXgWdJ(07l=)EC9w(8_)8KR#ioS%P4@zuYm zs%A@L$|8u!rP=?cdV90peEjQ==JPpD;la)4Z5`?<OFHQ3{0e)k<72Gv`~iB>bG*<4m3-CS*U`~At$@oY8^ArO_0F~;c2bTelWDRV5zN(^SE3^Z*w zE}P}oH#z`-l#&~+F|0Rb3s01*MlrY7tZRP#hA6G?z5 zro}9Uh&_N0u8E7~V*dUY-pk{#+wZO}uReM7=_q~}p6>e{GvxC0I@F|Uz&Io@5eZdQ zg+P+a@S&)}g%FuZi9|BjZ8#azt{;biK-2{thd17HES4>Hv!rPn1|HVc%k!o$R!VAO zB91o;;|(uMhxzztk2jugR?-T)iFIZ+WF2K%b%dNnjarlyEi zxLl?CHTh|(<(vyR&X7Fe-8*+qPmY79g2`f!$QIO*BQE-*M&yx^2{3yBGYII!Nftyj zRS{)J$|ga4#^Ob}y1L%(cC$shXy&uF21Eo@G$sVk1(P9aA}WPyV?e6eWx;@)001BW zNklaBDa-~FRI%hg{zS^xNZ-{0+y{?mW?uMdyT-~YC0({06Tf|aQQ zATVT{JN6}f|Ay!E^M|PtGdTtW24=@iQ@{S8B7pb4ZrbI1Hfv%Cm2*K9hMa@<^Yi&? zb+NkMBVob)G2%ETF^pc3Tm~g($=MMR8>)eMP+=fNF?iW?G=PGKz!JDrz>E<`F;lf{ zrOHstw;#NFespXuWE-3d&77TMH9%EB!_l${Wi=zJ5Rl6pl#LlwE7#Dt8C?jNMc5%R zLc&6}F#{FZJl}MoOJ~O?M@Pk^6{l?susDnqB{0!37mpQ#dgL%#>&@K0K129C9r$-rwW$FZ)jU5 zhiX72H()9Pj!cM(!~{fCwewqNXLs-2zklz}Y<{$uwca_0*b~>1#cZ!qF+YB?`iuYf zdzV)ich1l6-oIbP>U{p-XmR)d{BQrq)w2sz`s*M4a&x-==#wYSY(8t6X1bvt9?UEg6I5X@6%CIu!$j!vYsOTiE!ivpQQd3FTQRn2jX|LmWheE?QLslMmC z-+K1^#fKk$_~QBXzPsM-QlIjE)cYsPhqumSi~!+?;YC{Q_MP>Tm^da2F~oY-%n1p3 zk1p!0g**a(UMJsFudh}=`}Id{)39^x1htLCFIV-=SGYk|A(WJ+99ZN~KDVmNkC(1f z`SrI~Q*V0G%(Nd;d7?c#L`+$;^g`GM)`Gq?E}ci_30k2FA~IQpl*=!sRR^&B^y-JX z9fGUy>q%8@5G)m!GX+JxiOYZIa|-|>f(Tq1@Q8#SUPCK1v-bXjJLjjTZCyEEdB^B! z9CDfHXR~|v9~>Wd&!0W-h8}Se9F%cLz|I*tZze>jrkab7i2|TNE)f9GrV837oZNI% z4D%!#Xjui>%4qi1`Mq0r?jTuhR<(<&@)LUyGz&Nc^&(j`8JcNl=ry1i6kH8Bf~-{) z6pWZzR1glZU0*;#V9pF}wO;M}ecLpP+1xufJy(E$Mvfh!snv)%OUfc@qJ_5$2@Ft? zT^SV+!jxzsQ;E~)RF&y(f4u&V!96k(pj98Jtjin*ql7F{6}@58KV>!xm+=KTED?envvW& z!Nt10b?^NzfBEj6+sWYadT0C1@oW}j0KniKF_mPMisOPIlT#UhoT)Nk&dGo?;(XRL z%{%93C%b*Wy1ab+Ae4a<6}xpn11sm-O;r5MHJ~R( zZb~1sFxwB=8BTBE@4DvFf+>=rgN%Fa3_jnhYMbi(=x9D$)=flmNM?>yXGU#+g!`)(-3V9KI^kqFrp=jMa$BOZ2+g7-e87bufAcj-lfApnDAm75Q& zsoSclcbjbpD2&6V-}b??3z3}*-XS16U?w#WrlKl zDWdqlZ?FOpAwoSnle`;;t!466<6Jbeew)Yr^);j_YTMprURR4tQElC~h$^H7PyjGV zBY}#cf#ocS7`$IBPaZsc=kBeuqvd=yKaL>~Iq!Wo9aHiELfjIF+GtS6&}C86D)_3Z z`mTHaXfU#wSaGILCPxmvH+ z>#u$7-kn>`toh{fB6rWvZk>DQ`ax6$*@0vrPAMazXJqFK-ZnaK$PR#=!w?zmXfc;@ z+}}Qb=Zjzb=4!RwY`Xov?|MRI$YUB1kcb2Y2y>Ra-t_yu3$dOp_Cp_H48d>reSV|( zw1EM6Ms!Y8lIXDA2IlBs$i_tDm~Wk*!VOxA$kCKRyxPhs7;`KviqiLbWo;MaBqe1dW!9XD9GZy;0RR_w-|1D$ zo1T{Vt6{5rDYXdz7f>dEmZn?j3BJToy?*%s0HC5fNl&eNSJLYzRiuw=u~T|R#fWLk8Y1szkY!t!W#dVbv0^`dT(gC`UqrT{9U z830nBfpHi`BY7sGAd&%u$sN25CmIp}2#qWZgn|+=_S>-^hyAWwES4uHOC&5EeidcU zMJ3uh2MChDHC|QwZUlgoOeN%)y=DbQ6J%mA_JPoFe8Zsjw?E#NlH;TIL^NX`Rg!AX z+1U9|u~{JUV!FCEfaCdi@6NsZtq(wC2B1j+&3ObADEp#-f%hH&($FVS16PJ1NUB*3 z6(Ds6OtvMTQ&Iz~>zs4f57$?hm#fRwdUbVm*&ZGLqkr5@R z_Fy*q#+SY{^xfsv>dEsLFD{;6Ute!Fo4mQ21vhJFk)1yDzxdft_8)(8_s*SJ(>Tut zCPoFAOpeAZ&XTDrVDAzk1tu_I_8EYX5U`2WyvD9>^p5SjeZSvrHtWsxi~dT)vWPHI zb8@PpyQ|C84`bJN`@JHi7=c*KlDyG<$g*U$2quV7IY4AlNQ#a@)cXB4=OsHvqKSKS z=sE;~77je=EDDUF%2Snt9V%y6&`wIH(%}sa2z*Gw; z<<~)=KKQn+8Q2kJR8S=I21<_EGMXhHkla>*7+P;%`QjHIKYzYjt+Hf8%SjNj_aT|% zBBC#)3vHyNsHRv(Y=k7LNQQU}$7uE|Q65k&D&E zZoiw)+O}Hs<+fu$2$*W z)2bv*E-OjSW-2)qlXr4~eFeyJfEMPo)7)~yZ68F z_|YfNo<805127{S`=HV#72Wk_GVUGv3XSkLqyt5xgK%29q6Ny2qEMtl;3WcJ3L-!} zU1iBL4li}17gnNDNwrj!UZS3EI_MJ*kV?bdh)B_~h>9vBAfO(Gk;)Ftd=Y&GU}9pz zsUd@KFpe)(p%h-OsR8(c*#QCLwr;B?uGgE1kc6m*CK}?TnOlj!e1c+j-%i|5aG z`#l)uBw#(o8px{|nh_I7v8SCz4HF#gfQ1E9fMTZ%0G6}#<4A|}vg|uVTty#aoXy+1 zZWm2kSG8jnGcYI<0~G}l03cJ7jKrf#sa>*(Lj+*5#LSK%Yl9?gKQlBU-7EiTUtAn^|FxDS%~7 zUEhuQwn6@)zrFj{rmz zJSKnqKerdlwElFvQIlp~og5t{#TkNg>^vYk7s71bq{ZUS-FrjdXURhzRl4eQem~t? zZ@>Gqzy9~v*Xw`%r~mT&?9>w{5zoBo_G3Q`Ib~H6WyI(`m;e+AvJnztCUPm~Y(iN8 zjhzc*O%vPMz4KeQO!Z>5`o%AP_2lW}9(BwKk<2oZ*PLwZ*6U4oeeuS7t_p;pKn2ec zSxU(O>=AIjJPxn$oXfIgLdOgMW!{W1xm@94>C!9eG{~ff?*L8`1qcF$!AID4`)B+8 zMiJFVU!Tn4QI%~laH!ca=QJ7-A|<3)Ok9|PpOiC8;1ivMVFfJ^su^P8JAs)t)%@Q5 z2lGW^2K(*)(UV8J-JXcDNP)Q;pkvB9g_c)G3gw`KnOm8SmU9Xh<_6+%xE=(vmVLB0 znEev5XJ!C(?39QxX#y}pV6vRRavHLbXfjc?eiV-&S!YdaXx(lP09hTRJwf9g12Lh> z0YGa2U<9aO#^jP@L*h_D8k{SjTuah3nHn(?AXHT(qGesR%h^2E)oj_c^SZ6;K+G7u zH`AOF60!FI-K3w_?E{f_HVi!>Bf@^P2*M@fQ8%l1qcjMn#ze%NzyzeKViqw`%$Wee z%y#=-zwfT z5fTs*v13=7{sjmEW|DFqh9OoyM#l`2>!x;&1~W5s-ZfR_Vx_8CR5d46n+D!s0C5=B zSC>zlrk>4DOp&M#fe#MaIRUzq*@qW{V^6ix`c)IUhA=QAjxcE+fFV>s2WL4C9~$M{S6Jh8S71 zmV|IZEFoV+u7|q_tw{|&35yoAHV z_1>LZi}~F9faDO78AJ@tL`I@Xa)cOz;VH<7CQCm&d}rwX_@{sKU;pF(^`HOfkG}iu zuYD!f$OvL+pybFSIBpCrr9=edAb`M#OvH{%WHhje%Ar<>Dh5#W1`Ggb(azuh@>d_e z_x^5k{q*URPe1wi*|VpzyUvRGT0KIDi}~!~y}RDKk{tB?*!O+#u8P3`+gTezAasZT zNIY3=m`(5bkU1%-O>{zEK6JHex!KmQN*(mJdX7dQy8G?ZTJM)-Q&RHrA zSedD|O||WM11zH;I@qOWRbp`7O~c5^MFs#0c@XBa*~#h2e7P)HgQ^fYGcjTp#BpPFcJpl2H}9;VCFza83GB{4JvEV7?dQD{uXNWor#o&mlQktkq_N`R)8 z3sN(KrwLV&5Q)ZdY#KRh&wPlC1dfnM%RJC@YOoP| z;&P`bB}_veM-_I2P1BstPN;DU*Mxa&nmUHS9Eh9`0mv5z9mFy*om4O;B%K-Ld?0WW zF*{eOsO5|(3`T5-kaIROGwJ(Gg(ic@E*Cm_(bxbpM+IQTDH9RpoQN=|e0lLAZe!cF zi{-osZvhrk7lDod2KF?`{p9#~xm?y&-H*f2bvfsL9LHfG;#kF|T?FqLnVp(x zRtD>agh?cZK!_(t$IJO5-MN!<|EuTEfAHsjzPeh22`D{W9N)WlPk}R#CoXZSR0&Kt zBymupY{9!36SOEnu&$bi@4mCT{Po8leDLRg{+BuHcfRrEx@|>;0Ek=xgcWo?B9eBa zsHqJp1#<*idk=`@kX-CjMpZ;iB1&jRrfD=wIWysGwph#;58rw3(c`C|eDbSb|NN(h zuazVS-npu(ymzH1)z0Q-Mu?7yiM$IpX955+7?Ks{F(IG>QzQid1~_!e9YQe^)v442 zBOoT=8=Mh=83gmQ_ISI$1V+l0Vvk6*pO2C__s-R1ju%c;x4TXyvq}gq5-_2v4dX}{ zUE>K#LlS5b$%5mf$+klKr+n$ zMO7{1)C?_Rdjc@Qyx%(Dyj8CX7yx1wMXU%agD(wE0#E`JBQf&?Fu8-F0X%#D#5;HT zo$s>q`)(M=3m>6;{JnKTRUcv+>bd=VvAsC!(d`Pf{9tN0N;0A=_4Z` zI|tM}xPAZb+4;x6{?r6#v+$4q@H_9^zh82NuHPeZVeb z<)L;TUh*Cx(h;EjaL_oX`*imnYFE`anH1H*wDr0G7Q;X?-1k#ESgbz2Tz&MTZ+!3f z{lF(a@jV|n-!cq~gM))wN-otUJ#K-V@{;x*c<+j#$_jF$~piFP@kCC(F8Uav&eyAFs!&+wC180u=d-0gR) z^QgnfHc$y_7$q1|?mQZ2cC|{(u+|JBl2J@8Q5q32yQ&X7JR-$JD804qG)?=q-?rU; zcYS;P{Os)Z<~BSWaKNk*CIU<0r4*>tVhW1teror|vD9I?SmcU&TrFy?jILG`2sRA| z+UdRJ`t`%Z!-K^*7AdM)hOw3cp$f!`fRrgD;qY)X zE?2ddgjhtXup>KO&W1uC5Muo4j#okeK>)>SF+@bVou+M?(-B=o%&Lhb66}#=AA9Sa zcOE@@=k*VLXlm00>Tb8ay?y(wZ;s35{nLAo9zJ^b=+W`X$-#QPS}ccJlFI-vJUr5} ztapz#O#t_;PrX@qcS^BcBkFP(t@-}+>)hzBoxHqcq+n(T1h6w52=deO6 z5v>KP)paeeAI5P#Ik8V`#GBvv+E>2zM;`kh|B=r=e(l5Io}%FZRem9z?K8oN zRNcMSAwr4`NkS&NQwCLPuCGi*{_u~!^0Dvw*!OB55AHuWJ-v5ybhufq*PC@MMaJdQq(GOov>=zu+{Vl?Hy$4R`qkMqx)$xg zYe)B%wMu~M-hCLxB5)Pc;xUJj{n|hImEZcsuUz-*_0i%JKlrhaedfC!JUDGSdGAB5 z$|=xaJGp;*dEvda$)COV?DXEfVkH}Cg+$v0q)p9KyL}(EGfb8MXcyV#YV32?4zxSd2M;|_V z?YqD0<8AVb%QIEmVe(EZp<&AKDSD5(6oV=>5E&ES!-D|<6hfthWTHqwml`b?#KNsr z)RGi&RVhV3SgAD7iSAug$Dyj(My-~y)?u|;XRZUJP7y9jTL_@VYAM5FF$}|4%!DI2 zm_W3uEC;JrhEcWFQlKF=kYNfPsuU}w3}&Wgs!9|wsz#e8D?>5yNT&*U0c$!bKsBv} z?(8AxVFE`17~NIUN5s5y4h)9?Xj2zuR0CLw>ac*j(#=+g=tT5M!oqvHk75b}W~CNN zZeRtZ0cOUb^d2Ll1&U}5_h(O^U0htAoSv@NOEne5-6k<5wnIvQJFHfZ z7*tedMbltK7(}Qjz+gDpFL%HG8^7__{>{Jomwx0&zxvg$K6`$)-QM2b-d65Sj+`l~e_0Rvr zPyTD4`O)tiS8D`IiF?O~X7c#qv6ix4tyYV%O;guys-o(xTQLz`jDwZxy%7SD)>>+b z!$TP;+Qn3@0V--mBaKMlZHkhMK37wndMhgYz*-%UVrF%ywcHs#i78U;a7U<;H1?mR zba$>3GbMRWL7@l*Y383{pJIbJL<)+rO@m~Zxe-NDsk%N`qYAVwYybct07*naR8WG$ zVmw+cRaGhh>oF-estT)`R9>+p`!wlL zcfAAWq6B#RhhO^I*S~UmyW8%z;Q@rGlv)G9WH^=HCvW?%bx@OBKaea|h}7H64WmF% z7)gg8BuEJheG$M%fs_~g(f1v!qE?nL1*LM2*iF8O-u)olJ>0{A(jb!*8^*cF)L|Sd zl1(NukO!uVLC0E#T8gqLNEg+7!^lkNx0F3aM4!5-STPl4h?Rw^N2q95`IdJ|kVPZH z00yC|RaKQ>crYlTC4v#kdHB`4n~DN3dW3{C+)J>Ss+pJ|T*4jZVWL{d?j7mw>^(wM zGw`6ObV5OK*7WvaxTry**5bjZPoCUdEmoV&YBiMdvcC0|j#n>L`Svcef)5cGEPWwR z(qTtLbxxiEdk?8bkKx^KzWK9%|L^~2|M`FMgP;EN+wZ=2b9;NU+g+ZYot>RMee&e# z^Jf<~w-*zt~-!-^A1w znT6Hc_GT-pwT(iCYoDf@o9%K@wG{7D?>>^n^9Ad3U1Wm;(1qLS4 zH0Vt{y44X88l9wjkMQu;HS3tDLM22BDWWozY2T`!M)SY3c-8``RD9`J2D_ z#j?Yfp8fXy^=nb0M%kC$?s|XiJBK(`%!(OQD^%5bndW_MnIC^4O|`X272AE=w^np# zR(tfSR!l&SwWJqAZhDCzEl3j^ii$9xePU~SaRbnLpZo(VJV7xjrIcEPiUNZr5)7>~ zD+C}?C!grGLSV?)@w{2%j*Vc{PzY%OXoh100!w%_W}zvA0^zt?j#x~-i)1G?3BuH% z4LcjG23#PujE10tl!p)RKX~xyZj&tn2h78h)?`YN*n{U6mnuk?#DUd4w%grhEvl8? zx6|H(8cwoD>yGHn5#h7QcBs|t4k1^8fB^#~7}W>~Pb85@GNqOhJr`67M~b1m3_CB- z!Kz6>hlr>JjyAZpdG|L|f~sm&MYSl4wNMqnRDtDU@%r)MM<1P@9IkF|Zl6DUHcfj$ z!JL~$0p{07QZ^vr&RMyy2n8IFHnm|fs-l>+E-L9+oJ?C|%(y0JFJmE~f(kUS1*wU> znUJI@oCIA367C=o!3eh!4);jPg4WRhvoQO zD(0X<4%e&S`K{mj*?;gq{x^U3@1C9a&v!~CVKYjlE z`Fro&Y`3j>3rED%r?Y2I&!0W}^4Gq)Uasz)oSqyX9~~e4&R4(jmD`(kbtA;t`SqLc zyt`Vi%&eMta5)r`9Lj1jw$`4!`;=E6Reiyy+jo2)0Huqu-a9xN)q0UxWkQ2U(1XYb zZwOSRQ?wXVOO%Lkp!b* z4v_{AKvm09Z+CmQ)^^<^6d{_=!vx4;s6j%dmZbz44O)PdGo`0e*2Cn%&H|VHwr_Vk zk684+7{@jZR;<>c2ff|wr~TE{O-hlIBjyYQk2VJk24XRe<6;z%3_$<@O0LYQv(RTY zYeYI*1Vi8=h#rji)(-Dww|5r*Lb^bJG8A!zIt>xQ9?U43^xjB#&IHHn^Yi^~|H3;$5Hm2&Suzft%a%jZXkE|&nf7~CjarK-OsX0%XVHp) zOv5sTB-}f@+!xEVw@^eOoHF&$tXZ=iWA<6DR&wE)zQh0|Tp*^Xwag8y2vh~^-OK!d z_Xx+G=(5!E!qXMA2@L1!22s^EO;4Ym-P~@+`mNlfS2$j608{{jp=yaz&z?X3{eSUgU$9o=BaL^79jTNq`nVpS9u2ih%Q)|da02empsJCP z20zgn1s>6Qcke;;-T(yP-D&K-_ttK2w*Z1sOBG=R>o7__OT7nK7}bVO8lsqm#{0B- zFAh=FT8r781tA1E_oSYWQi>u(H21}xB*$#61TUn467ygv`Bitm!-iac(Med*m=}Da z5Lj#;Y|hS}Py7Al)pheu4R+(26L$OQc71Tn)VP{yVfy_MR1^v`6Qgtipy?3{wbMF?` zdKW|lLHFKCifB$SDukexXuSd&2GnVKp4KG*V9Lz{(&FFQ6zWGj}%EmasZ<;I1q;28%R-4swZE8{>s=c+MMzTqZ`N{6t7zAJ$ z1cpeZ4ltO|$vv5W5oV|Zy|-x!(%Urcr?Q_&it1uH=DwkhNyUh&*iX~V_Vy(gNlUe= zMO6*ZtTd_t6jcXI04a8d)fXaOI69Ls18H(MCFNd6WgtQ%SGEyp;!Ud2XL_s(9FWH! zdGzi#-`?+bx4UZ`0Jr4GVYzhUd+)q`e0)4EDo99ZDMm&Q0CESWfHHfQ&1)G2WV1fl ztk)Npm!%YdZEDeb*PaZ@?RK}{?|s(pi2%L(V6{hAffYMA+Efwu1mSrHb_zrpaF7xt zL@loy9TevC$TZhvcHVK6P-jHlSp*z}#snea=LKb)X2HqIb6Qy>$S?VpJ6m z9ji%DRNPao6SL*&yk?}TkTf-sD8-oBt%MVjM88Uc!5Xx_fkpMZ_cm5mlifg zq`QX+)I!vTT%6>>N4lDbRZ~$ja%|(2ef4(V!&Cj}y>$_|dlTus@Au#N+7S^eT85z% z6MbKvsBg$2uP$Q3uF`xL4kB(Ne4UyppFni0loL& z zpZbCC|K``f`PSQSsT46K&`J8V-R}0=-Qm%}y?YO4cU`4WhoKg&Azf8#9fcu6_T~&a zifPI8>5L@t2=@7_`+oG=hCwfa`5iYkgos5lTzA96v3xkLxl^yujLW3Rvd z;Qsw#QB{N);3t-SL?(vGyzb{>98Ql9-g~k~{zoqwE3@>>h{%{A&8tPu?ggIIuiX5B zy){)$r;AK0o&gjp*?^L^86rY=O%E_rq=6+O<13s3Z>50HaG9+g03aLA`T6YKB?2jH z7gd#_3>arQsEDe%Ls~kprxG?g!&+iGW|oE!fI-5{<<`$H*afEt{&7zMQyfZzQ3SAXsw{cqF1`?o&xnZLMPEqeEGi}~eXB8cwe zxa1)Z509sZkES-ApFO|4zIpoe$-CFnH=mz<<5&L$wtW5Q#M-S8jM#3s+wJc1^5W^! zC#BT&!Qs)-@#)c#Xk8tTm+f{~YFu@t5VR%%S#5^*-hFSeTCP{CvDTcMa&K*lAS*>g zNi%_{1vr?d&C;}=<_K_Yi0B^O_nh_+?Y*m-X3RuTtQbR8C<=y}nHi)xp+#OAKWoKG zvDu8=1V9O6C1?ciP&PNIS<8SB1!$1Cn{b2_l^|_)D84hL6jW6~j9N28Fc?CZSY*!1 z!TRvQ!-v;5Uw!`WTSAVD0YH9V0MF0PUf=c2!BR{5duCr9fyh8pLOh1MIirImr7wqv zhu`zbk1totH{X17nkF+PGp_~1V*IX;zw!7ZA5JceA|en1L?Y@QExExFA_Tj;z{atP zsF*4dg%O#*L4ndjs1y=Pz_diNQ9qci3}hII2m`LB^rUz~B4{j9?jPKH_}Yg~Pfy2T zG}Y`&lJ~CSY4?6-w1YcZJQmB<>B-5(9U;l}pti#Zn8+__f zYGHILbH0kzaGt9!&d(j~?BB_Uxbi-tWEh^)Ig?>cP5NrqbC=<`;=z@9p~X z?B?p??YGNnxg3@pq{e80$tL=W0LD_U`o-`5-sd(4hsQ@pM@NV2)q1sBCox3COc zV8tAeDq^tZ^5Y->*ulZUAAIqPH`{F~MO7Dzp_r|fORYedc(ABC1p-G9MFOR?PDW@^ zh629dPqmhDSS0SDjF4KCna$@;Dh!1s0UxyPR@7?wAnV6TCzViDg|ehkr`KUv9~^ED zjt-6vhH;!V`bcCW?!-F^jkKs1u@ooe{3(LX=0H@>&(GZxL!bR8UX1FRT4A-2q#+{H zgoxR}BPomS4$f~0l?6hVO*JOorhfCv*nf^&{4L}FGc z&EJ?2bfL^aWvT{Mg`h4(S^^h@0~!%`;aUciAjCZff4*cD`zJkKeOFZsQi^J+<6^yD zEQVoRjH~5xF^=OH5T&0vid>`;l$^D=W|`^kN?<@EyqRg$cZPQb+m|1 zU|AF%3zS7E`%;Ed4_B*`gUzQOKmPjHzj1kSc5`{|5vCH#nJr5Q5FSLp{o0!?aPN(J zcC~Ar9A(&xnrvRT>)Z3MeeG%(7K_#T}04-WlHcQa|oLVZnKYuNjB&)1Ugp!$+@;)`$0C{wD_}YVe zpZeq{-+uR<_nthtyg0i!Kfk@bZPR}0eKy8OrVYd+lql7XSK3bz0;#rM*I_g;rYTx$ zw>Q_9XHVby=D68x4v&sE2L~r7r>oU!wOk&omk@(UO_>WdNqMt}TUd&J0Sm%%w``?{ zms&=ZaWMjHZMEC&ix~vF)`w!ImWFVf^-F{`s#Z%?H4za*ZYaniqF_nA6$H?FH&0L) zCKZK3p|Ip$IQx8|sxd@HHTR6PQ?c0+M>KibAd4t!2}JMXYPCLl{`_t)nsibKQOj_2 za5M~~6cU-hP`NNk;4) zHbO*)Vh8ID5a$=yK21sqsDc`t0Eklr#@%jzdwX+oasp>j2`vPp7ZHRwjo#;-Hpx;8 zTufhn{}T}=RctXV)`y$J&1SJ&YON+3Bs3Iaxto2Tkpbj|SX>zdiYRBb{@mghkytI4 z{qXSm>az9k2$4;y(~FQqL_{_}F#XmR37{4-WTr-i2*TB?sYEGiN>wU8ut^X}r({vl zm=%;&(M17xgaxyFs+pw!Dga0@OeDZiXcj<*ds+>MnI`33b%ZE{rb^Pgc?30PQek+w z z_~a)6?swbt5H!^gmGI?Y-ouJ6hM|*7E1T7FvpGCIK7Qkkk8Q8cpFMy6>^uqZ&u(sR zdYgKreH6pJd1&v1+loac=u=BLNGVe8#10W?)BgJEvJB(N(c${w=y0-v{785u}s1s7ma%Ui_t5R#V^=kQ&i)6*r%mg$w z0Yudqb@qCZ?6U+wh$%DiIEMno>~X9V3YEnfio`}#f+~dw&T!2vMORUQ23od zL=oy{^~q0saxpHy_~kE|&LlPqTGfNY%@2L*vy0{G%{RaHyPyA^+ua_*xFdbj*}K!> z?&p`6tM#~CtjHtwUF@rk7 z2qJnjD*<>e-Rmf6pw8&YGEJJEfI(-7zGM&kCqG_^t*&y%?n!=z+`U=;*uwQ<%KNrv ziV_kx&o0j1eRg$wz29z+z~$j#spaXDcmMaF|AoK&<3Ik{ANrwjx$0Nf6J>I?wpVc9 zdfF`QrWSX+hpBV9Sk_^&T8!(1<9m;GSC{AK=jRs}7Z>N}*H@R@*3tGJ6w*!D-E%eT zJpz$CT@QlW)(M8QScX5#+4=KQhsAPzv{^03ak)7>I5=1=#-R>}2M5c=pjK)zSM#KR z4yM3Z22=CurHqm$8e39DL3eL$?_u3D2ctLNwu^TE{=M%!+Yk|0ngAQqcUe%$C?c8D ztD+F2GDkBD1q1|3C{$ol(lQo+T2(Pd%bb`X9F`dkkOA;2+8Lr8#3Z7_w3L2wa{8(7 z{|jIE0-ij1PRKAUjy9{0y#A4oeB{H6MRlPL>bDdXGN4o_$1am`;n=IH%A#YkY9#2n z8;K(GcHf;`9WKA;dq2K!zS~_+z!3ZBi-2*@XBSToa4=yX9^sQWGMpaK*?Y9TyZ26y zeSh}!@{KnRAe`xBfY7Wt6fP=*N^=M(p&{}z6PU$fc>P1KJ$UU=9R?MXdDH^{6^Y0l ztB_Dg!k)7d^TlmWsMcU71=4d>K;~m3j8MgTb0mnf^GkmFg$Cd-odqF8gi7wjtmylw z6?f@fxa*cF+T9V_y$==LqZXx0h|JsYyNCDvrHVv^r-Qhf_HZf^`t=YGh#Ew~5i{!x z9?;w{WYjN#U{yglij`t1*lKFhTfAUY0O9dxNdkQJ9KaVJ%KQFK{+LfxnN3V*_8Ax+ zyZvx<42EcdMk}p1g%FJ z3rtg^Feu%V+NKZ;Lm3w1YFZww*Z1!~*zdMi*Eg4!7dJOIXV0Eq-Q4bXyVfR}n1SIj zUyPnmyQ+ba6fw!^kpvLo+w04#t8+vYRV%fWQisKIwK?3Z)|>V5(eZk{Dy7t7!%$T% zM3;+Iu}r(rVn(k)is*W&?lt{pK}kCMc6Ds5+$Its2Bq2Wd>m=ay}xG`|sX{as0v0eE(Oz z@#Wsyu9{%yz{Sne-~5fU*7m(m?rh-<649NEDY{4R&G*rxJD)sxdU|s2@OT4|p5-cH zp&+%RKw?k^J)&!<^8FErc|3UVc&32Q#Bfj?A`%K^f#L<}TBvvGO3qL3UF5yEKvh8& zch7hbNke%92^Fjkj=J;u<|Y;F0SX~N)~P%KA|h#4_2PMo`6olnZ9>f7|L%15)r;UJC_sP zTAaW2R^YYO!2wEHkIR4cYrpb^-~H{s{%`-(XFvN{ci%TRlgUxRP=wi_)&UW>P!WmV zLrg`~Y`I)5S8HFdH|x!Vd-ra3yXyxJ&abbpF0U`1KfS!Vnx=;E2zOGg-U&1Wq7X5p zU?s~j4IohgfF2$Z(=>UX_Pg8Lt1>Ls*B6&Zr}vJI4i8qN%x!h5Pc^y^V=cp|R#QAk z5i}MnAf~qW;4r8M`UlqP0u-~Mlt9)}t0DoZMFrA&B6E)rxqcLfUv>n(ke?xFif?BLX+asMKm#fCR}^(;r$<4{l!W`ktdk}(d|h&Bfy=RHK5r8T5TsL0{bk(gavT!3@-`gf2d zQ`VA1{1?M&1ZEyXAmKx#rUt~F?`iaIX1ZplmjD1D07*naRMXV!P*pK?uclLvVzAks zXGY}!01hxh1+x{hKpZOYlwad6Uq@0iY6YMswJL|J{HcV|d-MdYMdoS;5g;P;&*E47 z>J-qsm(h#HSF+5{19?R1fY_YPW7nqr)Te#hx8{_>IP^FOq7Kb`8!9m^Fa&oyANb9; z`C4Bc97It7-}u^B|A+tn@BMp!>p%SA&;GD3R&AOR$jN8A4nv}=gNXpmV>D$X!-ql& zbX+Wlh*C;5TW$_F2RG~W>hSvd_U8KH;;Q$lc}MTfBOO7%g|_4bks5+r4TuV4C^crf z3rXzv`~B3mH`h0}H*I>*4v!9xxEvQ&#!_l6HEahn4Nr7Zr3_|8Mpc0nE9Q(Yro~@! zDFtdGW+o^JE|)SO*H2hhb`yrH6#`bJuuvLJ5H=`KU=C^#iYp2vI$%w-iqKF&>BR?# zBMipsHHv@|6-Ejziqwq5<7gO89%x~2QVbdcj0$+|=GBx@THg(2K^% zpJpW}=t{uEvR6pjiVAku*OwR9tHWinQTrq#do`OTc(_Mv5&Pa+o2i*Z?^C0<$=$n0 z2;}+s)8osdM-Lw|AS#6nD%F)mdxXIjWQeF*eaRb^LRuJ2L_CPaJs*outw2+);Q%JmM5EYvbXdLjo12{?*Baj%LF5iGzmv>lnouNh z1}R1k&pH@EiV%Xx^MIbxgiiQ0jJ0!xi#r!bmW|Q5+J*L*C z?%lcHXI4P>K=l4%2dHKXlXXPVpvVf^Jw_=LARe_AjqY8Zz4eaYZ<~AfR?FqhYB}9r z{lfqHkAD4Ef90?L^uP1r4}W;MScH3br%0P7kMM{+WZzr3r(G=pQ-OyQnd;7<)w&tR z#W-v>Ywvy9ZLh9xrfJ&mcel5@?e2Ek?e^1tKecohQ!+#V6S+%hiY~wu$i4M^$+YC{ zw7b1Me}2{-9&DSwTr`h1SqVnbHr7E@yHlj6J3A!_W`mLgP#4QmJ}>|x?#DDOw|X zsdjRDB64c4bqK6cXtepNQp=z-O>%x-JS3GUwk*;_4_>U8J@YA;hfofueDe1^;=)7 z_A%id`N3fy8nHyFSxiU`O?AHY4>roo44Vz7r^LYfRKyeD?5h(9|F+60N>G7Uri<3jj4^iNl*c;)N@e}1IOT%k=N&QFL_{jGuSFItOV3y|NB91K~&1Yk~5$xC{*Sm>eWlWc`i`_rZ8p*NztZ#f^W+2zf^26=H`(i6OP-ar&q-) zzuk@U5>`=i<++)YpqN}T?_swouKKqRZm{`9<{1!h>aNp{U{oAj)@>hE<3fowbeD$|^zcNrcy}99) z8zp~6mmW5&c*R>-iLF&)K{4$iUv_FN>q}y>h2XB;fB!6hEiZiGs!KV#%LvBP0zIO zboOZXl*5>W=1eQ3b38tw=Fb_2G45u*O~Lr2GKd$!D_JXjzA|q9$FTwvf9L4jTEFFD zeIM*SYJQCczC;edwLHfnYu2%Y}pd3wh;z_tt#3fCppq&QqkKl zD;90)>oun}N7zU3MxvvDSG23NG-mqHUq`Bymw93~SJV*v=wst9bwTgBKhENwvUoXK zdK1CeROQScu6oydC;sny zCbcujGtnxc%@7U+_{YNCIB0PVt65t}ji{&pvVj1X};bm>F&lX?@nyFcU@#t@7tO$GI*|GW?p2@LbPVWl_)o6LCA`G@^S3f-;~tUtc?9_)?~rozdbyE4wOXp{IF_sHszF2u4zM8!Uu4v5{$O zu_jFM21Wsu&XGh@0VhhR_;e)>;S$=TVJFDQ6=L(wr*@$dpwv;r(;m7f1)iwq=Ty&YQ$%9N~~3rn|Gl zKtRFV?#NHoCoDq3jI_%yKztbgxYz6zm4u5l8dkN2S2p-F2-G7UkkEHR0QGy?^m2jv z`JK^uwQKI@iKkY9hw_rs;W9VX4PXV>3?&(O=jaV2Wp z_yiz$P)$IEnUH2pa1V}lK#t$3g3l5^df$4pja6tUHA{t;9gXN~ZW-Yq1ZqHwingVd z)iekahcHnI61UK1vhOsk6LVGcB4wsT+Zzv9(j<98W`y8>l`CUTDpgMA!REyN0|nFN z*N#b9BW3da?1lcN>QtzfRNEUUxru6}X5twSq|u706h}%0>ClBzTfh{G#T7zrJE@r9 zpD9gaP`FE^g2N`3Cpihxo`c}n;lE7giL!69ze!0+RW?5sE-k%GFJ#-(libS~;o%53 z(SZB4bfhQbX?60Oqs$aK(7n#*#Q0fKH^udyJ2rCF;-)b4VFIQ;W^k;8`oj4<0^ygEC;bnks zts*-q3AeZyABzco6qQw~GjeFbP$yPIGoHVp*WtV_O3qR3aRzx8Ra;0&!`kTgH+a1x z%MH19R()R>J7`}nYyQk*cP8|MYtbS1{SwHO=+WM2kNZtm^rvMKXvK!)jE+~l{>uG@ z+lvDX=MEV7G{xF=?d2X*sRQYQooJ7akS#L)93DXNUnY|?p5?_2p!vQrqg@pF6Kq7z zLFY$aK_ClP&gGda^I#4f{)w&Z{TPd|#SUsKPB2Qx&QaZ`B8X8P?1-uvlRxtJ@cyQ@ zq5k0`1dZ(brzsUS>A7%4Q-2$Vxb8?fDy4}yAp5ys54LR9pPpki;EM>VN|$Tz?i91( zHw@NNPWZv@ohTq%ESoXNK}O!ey&2H0!`%CxhXm7tGX6~}A97;7(_iTxs5`h@3becF zGH5vtxad;l4bbYboH{^PEH_BiWkCOlkV6Zz@n(Eq#}i6uXtt>%-twBs<@?K`Dh*X7 z8!Ht57%k<|Afq6-zHCGq_|4>yd!h$-`iAOfh!`9W+s!5$KSs-jf zl~|G*sVZ&$ZLHg39`X!fNfB=tNA(KzSx`>m*GU!7a7g9bc{iu zUNj0UN##9a?K@C77%L!vSUdD}C-DqIid2FE&G=1!7=%$p|82Hk8*SXRcF2$}JV?gc zd5Ynv_jSozIjwIf1&UaC8cc-RWwm?^7P#ROT`>5%vbgC0IBNVu1)SB-7&ACxJl)rp$(`3*S>R)$;*L4p51rBJ6E3AUJqioUhFnOSLOCbbOfpd3z~ku6C$ z>QIN@c1E;2O>-$KNO{$|xUIn^g5@&~hvk=mjt(E4dW=_S@Hk{-^Eu)~Ou!(Lw%n_M zw3=wNgOmV;IQFwy56Do(sMuM_ZDhUkE1m2^*Wm^KtMr$v^Pnz%m37LF8v3Se)iqx# z8WuX_OlUUO0VO+0tcd|bgtnNQ6>G6KNSd+!_lhW!$ z^=F4KQ(YHQb=BTmO)X1~Rpl{gvt2u#=Me=Zerj-(YL__d9GSs#0%F5*4ifd}ub-{| zpncEJvxL~=D8derxo{niqD~inbfamx9^2EuyX7s{sS+nZWimoBTlr9>Ars`M%n21Z z*6Zm`VZ;X4nP@sP1soN~?pfxM@NZE>2F?2WneM{uIdm;#m=$$k#D(|0cDKLa8%*gosO<9Crnsz*)5$*BA zRRDOM%pwlU6ouB@-O~2{7U~q~WdUa)=n0SmB|74LocgAK(6+XdRI#(I*!WrHE>*MkgoQR7eu|)snn7=#|%WrRj1}%$ZInu5k4cOGO$dy~7Yc z_o^?ILF3k&5EFCsYJU$@zwO$;)Ovb56A=m(ZiV*~ZoM4`e&_cEpL>%uwk76bBxjje zR{DPRflhsgR$EXx8F)Qpk~ernjMuhnWqTi0>RW@bo!P_n2k)cIbzu8dTVTbz4zg2=_2q* z=saz@^bf{AIz#JZiPMUei$9hn_U~WM^qN}D@{?k0PJF{bq>xtwG zEh;Q}W`ga{UpL&03UiLdP|(CLtkFrdi3HC?`YZ=h)dX7pta0TPO_i8I)ge zclb&?P&^9rIH+XRXYE*J@cmXyrNb@__IXdA%YJrl%>Tv>LhVOLOQ6yZqX04NgA(~L z(flGrhneAw#Mlqe{P^)0Krnp&&o8X0 z=>_00tTvWV%5RD@v{r%JZMW|Ip>;u`4earJ3ln^*t+tMZ^QLvw} zBa=FFQLp*pmwswiC^kA#B+qI{q={?Evk7p}dZQD^xCq+0UK|3^J2)p27Ti8N(;yW$ zLE+G>&Xg?pf&7-Btg#Z>;B$$)s{DdMAgaW~_ zE=*9qv1~%qzoCLW{0>D^hDW&ayvh%4&%2(C#V~!d3>D=0!X4%(oX57=2a7me8;7 z)M^K3{m{h@0yXrl2qjnPh3$_;bBS5CYgt+0*aTwn#tvYV@Q*s^LDCxE5MT~SHLR5w z1(gtU#>V$duc-~2M7bj(CzP7;Sf96nb@J6L!jh(f^s-)v<&_^sQzHu+4DN##iwZ%u z^OJV}(AqW1NJ~3@D+YoN*Qs~Z;5>V)w>Tjnp2OOdMS{;rjAH8lAz-rXBNz&162Zhq zqf;$TJUWJ;*eilE2-ia_@@uE;joTCU=cOuwz?l-Jioq~P(oTWoN$y+NU^0LCmkRIG zhLf92>LhRQJQHys<6P*qw#_i-GZ+&!2hU8y#GwH9()jpC@E;DaTyRIZ0wl8lhMj=% z!w=MQKKr|zo5PmA6DpR2)5RCH^5@w`tlP*TZLtNT&VVQ5f19n?Nh1)9jtppeaOHy`^i z|JfrJpD4La@_Z>{Qbu^Jvx|bl2%mMceD{9i5NRf)Y>Am&$q(NE4+7;Q+uN5u{TOyAZ42}4P6TO>)X-QBMkt;aQE9TVazJmM zBo+VHhCjQ0993@8%K&l(E@~Rur`;gxKo=c&I9dyFEU}h7IwRi!UL^Hg9j{ii*9)e_ z#lJ>+RMXZr5V2k+jbVcmnH)%Mpq8lU7+)cG1>pG1TJ~CHNBe$42q<%@(cz1HJpzD- z7WcmR9K4%;Q1^WTL6AIB1>CaSv^#C)>KRiMvX;*WQ)OaAt=@nTG8u(Z*6J3SHB%H7 zDsXrVqcZb0cY%w!v@}wu7~2H!<3fbGUp+)dg-YK#7vsG$KrB-$7 z=o=IvLQ~WYK6InXYQF*y-2WOIvz^s(z2ZBHJ?rmOeqs<$$o&i%XlNhdm+3ZHj*x;m zb290%k-ck({ky|j4_2ro^a|v!F%|fWTJhyQ8eIH`M)jwB(|mPVlswm{x=VKMV}UibIzRDm76+ z2w5t2sk^wk#wqYwf^{LSov)z5kWeRtO*<2IEHsuo2dYt0)r}=mbG6cOb0&|>d#hsJ z;P$$U{=1(zcdlZ5&>KzxF=Bh2h(z_aTf0{Z6}B0JRiD3;iv3aaeRO)dzs7HMJKI}w z{@0c4nlw=2g2fNC(8S3RYm?=1t+)xq^5gVZWdza2a$*n=Q>vEOy_1cv<<~$%t@zlW z#YQq#TcpK2GK@FDoLEw_lRBH~QNcVMItJGvKo{Ev%@)cM&hv%Z_7}%w5-O_U3_fBz z2Ou4{2+ZL!axAI|miF9q8wif>eGOF5R2&jl8nNMXV|laADU3l(%*!GZb(3OSeh$ zq`T2@OIUJE_7Co>ySaV4Jnd*(vYzZo`;L^c2BC=5>0}_RNYO#pyE<^Qo9?KNGFOoBuPMU!KN;)Kp);! z+1I|uXg(zC7qp6l*;dq=iEqn6dxINLZxVJt%DTJ{+RyggFLHnPCW}{_)i@KvVX`_V zT5}?QT__?GR_-EK@<9OgZ8Mtz>h7dSuy!m+P#KN2n~Hz)be*3>jYRTqKgqxz&pR;) zahPa#H=8AWn@m4r*J^pq_9$&Gk(5z51xZcd11A0(J+CBAF>=Y^C`V(HDyBRxVm=8f z201Zs^`(esTQ*8vFVHyZ)A@(vD^hlh`3Hy zAmAt1So1@A~~A{}1m1i@ITPO${A3>iq2F;<%u0Do}!K zIkBq?Ydf{ z-tZLe`34kG5I139{0FVE=qme|=Z7apr-5nhSFdAF#h=F{8i664=H3ISE9ENdl3m0V zdd&j39YsHF zVqZu~F@b#& zMB2OU6n;A&+l3DqV2I`RHf#9t`iDsoKE}P~A?~pI^y-*|UmChqS9psS58ANQ}v zyl_E*#y}{9U~iuFVbIA>neu2O9m>&tO`%`mCE}pbj|M8xmeq))CSRknltlDfP)ieV zxfT2@D=X8eoTrz~beX~yJjbqC8Q4hoG*|q8X8|(ncw|?l@>MFPS!!zPJl=%v@zgEq z>6K}e^PLhSFmAV~Dfrv=;ddaOj2*wDucnx!@ z)2?s6CHB$eRCl6r&7vi;3-Al=@ z9v)VX9?Yz`FC+_qlo|(x{*N3a-a?)-qlJkL(2D?-ee~bj2cK+M0A36+i$Sd4P`hZH z`$7!A^(=~+chl@ID27NFby|FgDCl8ESTbQ~63s}QSaMa9UdQd~99FuM`U2(n;<>&J z?b(eeBwayVTN`X&GZYK1`#al72Md0*41%K4kFlCzBE3coNMneH-#$atP|nTaBTxx~ z`UP~#D7^YAzRLPOAZ6%9KeJo{%-A*HA@J;Cpb0=X6meOLbn|_96dE~rCjg~Kax*)# zkq{ahw3Y%rki`QORiJZuL^1Sr-?|wD1REp9!ipPc-<7vZcyX;=53LzaRrep7{c-# zyidi*jFt;S*0PbCpaz1V77^l|*pw;;}hMHQgp6E zgz2pB@t_?^)PkCJ^fi;a`{&MeIzqmSzk_keUV4)*3JEPPdIK%A!)oFzk;J@bUA>I- z{rLSC{)T9Vv;nN8yENrdv^b~YH4w~q%n(tL#$T_H1qsmj>-GbX@UK-OBiPD?Emk!{ zD;Vm&7K#`go))+(FLmp_Z_Idhz=HEbn+WW4fC|bX=C8D16qn-+{UH(DWn63A6-F;x zZ?~*p@liKK70*EE1}SeQlk-CE%NJTy2STNYNLN?ab7wawE&Z4XH{W}&slUrVISXsb zOuSe%e8Q+uQ9b1+tX@u`w)MjLxzBLdpXLn8$DGHx@QGDGtT`Cao(TOGDy`9h1_XZ6 z+p<9vCsAzgkZ587hT@#E#_`|IKj)5_7B~BDg0*dxiRdD!4D55?+Dy2xs1d6 z`3TV2F35s?znij{iK6sMDVbV%&)idZe~yySfJ?=PQxjmJnrNgA4x!puXcXSyurViK zY-PF#bYbs4qq!E{!_Ut*k=o13IwV^#k#1le7J6JS{1s~^`1 zq^!yy$I^qUVkj33gEDtQ!7dO^``x?vI%BBi$L3JFmC#w8Pn3ee?%xUmhy7oPvV61YC%l=bXbwa{ zMPQ?+an(TwIK-3Q4u0Vjw;3iIi3)kUOz#x$?K;pSbI)U(a3vd@nt)*_ZgWE@j6MFI z=9reZujQ++Ql3?aAUGC1k>>b=VN9MeQ`A~XXrGyK!wVdXkdX(5_fH-yceCoi3HJ2g z9HW^V!)-yq#?F_smAgkrBAfNL5hd!@&#jx0w7%n?4H7DGMo{GuE4FXtSemwmEY+At z47!UUe#AFC6p|eokyV7pmx+mEDI_^gg?Fro?L~deJWvK~Ekj{kV@^a@#)x#&>L<Li!4eLROORcF;sP3-?Kc1xO`7^ zA^b6=Z8UGsv&knL$E~31Kmo@L0Wn`lDVfjq%s^x*sY3{0{AMIUD(W&+f}{s2vE=T? z`!RJFY8-v9SzVsLVN2>Kx^tZ?*saqxH}7_{@jab2|H+`}ap#c_o#;mM|0~CIx;FI= zbbF_&HO8$lHX#tDrxU$KubAPa2uzvJlF!U6y#T1uEKyi1P$`>auCr?Xix}sYjgw02 zj_RwF=v2be)Uh@R-~h{a8J8&UAM7>X$Ay#O;?o>NgFrATBQX}W3JuYW?EW1}GZk7? zfALo-LZFYNA1_a-1AK<7c|kddpe`jt+eOFOZ>AV*dnAK!PZUwF5TSI2e*<=DYF?7W zH+@6G>Js{kglU%q=~8dyb*@na5@svQ-T84^KgTn^t+N=WR{#-6qU*pX%Mx|+eSTr| ztArFAD&qpbf@ zF}({5pwJ8JjX?$1kXVb-*0=<8gm4!Z8^%B~6=YSUOEQ>jp)YJZIF#iCt^YV`2gkzX zGF+yx8v8;YrV2+{U-HjBRdFG6zvl+$PGM#*Za3-YwUQ>5Y8KVo-u&(Lk2TJ1GVL4t zmwVI2xX&n+xe?`9rOuYv-z9EmZmua^qR#A=fW2W{qQyv@&oS{jEKm7{zcx>XiI~8M zUO}cHQ5D*;>ebX%1<4DraYaDGK)UILQ*&r49-f~1E|+sRXIq&o)(m;74OAp@7dneb ztm}`FIjW3M3W(QRoG!PH&(u_?`t11Ncj1g8Bw4>c-q6KFMsc9Ag^%9mF%0JQY>O-| zr)kH$M6a0&E4*9FS45y~vp7_HqQ<_vS^hO^%*l{O=d@cTiWVHyBxWDf8FRsjlRwra zPK%4pH94zOH)k`MQllpFNey0|r)Gmh`8+)LN_H)`J(u#!*Nf6bYeoAls4;m6a6>3j zI{geWJ*g?m@S(9tvy|5%{zq4kKA-$3EkT~Iv!^s}jiV#|!2ur^HlHM_`0LUAE^ca& z2a4YD_z!eeRIsjtwiO$9N})|dL&2##DZCPgEXZFqEP{4}q3f=_CZGVV3-iZlWl0+r z`@0~Alu#x!bok;eF-WD&Jis;190dDa$O@*_QoZ8fS``L~zmJSY}USX9# zt3==;76}>!`g|wxKJFv;MxN%TX=bWj=C9SeeuvZy59}jL-V!rdVzb3^2SfcBce!;a zktzWkyE_L=B-lfCoyk@9NF5`H3W{!WXJr35054}gVLyn0AnSm4-QaA>r?G1LEOGLR z76jg9dvERxj}{+hv6*Eqigk3Lz+gt}Ch0Tf8w67QI=^SMX-bJvP%u{mom1wB+gXlf z)9As)k*MOP_EEC2JpLNQ!T;{v&oI7W{K+p8p+YCPxVlJ|-zX^w)%jc++d1`HLk<#} ziH_=w)<%ksGD;hWKneC)5dwozsyQG(B!bM!2q_4=L`OYdg+q9fIbdTR{X7TB_yU5b z<9}*MaN$c2V$O{HD3EI5eSVx4u^%r!h$n2hr6n%pLrqjvSypDOlu3UL0<1iI_`O0m zyHuS;VV?F;j6GH7cwqpZc7+E~A(sR&5v?^Ue(zTgY(0OT`C*|(o%xOS?*g3)MWvxm zhrssgA?!Ek$~T8VILs8ZNPIkqOXq=PIGuLcOk=W8JU>0*N8?x#ln#x!oNUK!+0Tec zt&=h`rak_L4e;R!8u0CLu@)eMu+c0-DqZYlMwqkHSYwSBIWl)w zkV*y_c6PjfwrqZ`qn5lS4CE%LEeK?@ zR9y#=luu@JulkvS8;8h}3ZIAPB1l$xUI2yK&D(w67>x?uQ1m=}2(W!Ge(`}nqd{u-W=$lt=h@4;N`7sDBe|E& zG<~RP3ckC1+?DA4r23#?hYb4R*#?cXuis`reMEs-nS=!!pJ2@E&rHq_fl0JSQuD;9?hPDCzI(vwY^LmKYyDjGl=5+CptQiPD1Rq5g>jtz#FA^wqu9&1uoYn4WGW_~D_9{G|QD8%8dhdcp=&|$sLl-`;NT1ugqPG6dPN2~B zLzR}+FT-{w8j0bj^!38hNP<{C#W?z?_=3L(mYT%WSpbH8wtzr)YmDB=5(V^Dfah`H z`=a%9c@{4>aY#E;XLJXnPP50w&jZ2I#4wXA!L)g$OQF@{tS4PKj70KZNARBqZ|@?X zVTBZa#kka+)V>nnN}VVSQf4J>Z2axv;US02n<{!c$Gb%$|D|*;F6rh4HRXKO+H8_w z2*QcF+J=!&ScJ;U%Ifwn&At7PR^Qp`SI?e3Qz6c}f7s7R2T&i5SE9bYCF-SZ}yJ^{-OUl8$hlC^UQKL6O0pn zQ8cL2__Wd9^}-sbn~re(hsGB1@9(Z1u(H_Sdw+ zib)0QkCHFQ(Ts?J-^pX#-Q9<(O51oDkJ0;lnLaen_Wu5fja}baLrKZ43X&MsH5~QU z*y#cTI{O%T-&*17CWNfuQF47dmXH!^gBRjIYm$aFla_dmAFgU`Nwn>MI@TxpkRbUnyQ%ewrm zph7IELLO{HOoFXK9%Mw0VFa)wU&F6VbOIfqCvweMie6nSeyXWVF>+2IAkR5~4(hDfi zI&{AGFrQC&%lnA*r%vCDJLCMn#nXHF`T0sh&E5~_dr7R?Hj2M?jgkN|yFTTryC7#YEk*%U8S~4+c2PyITS=nG?e}+leT7BBPZGrUbThROr3SUE(te zVy%1zcc{4#V1kQ_i>^p1q$!iWlkfA%}Oy6br-Snph#|>=J538nU zNku(9Jxa$(v$Jxae>(OT8D>&a(pQVKd>AqwX=E|-DXKPK8&({81jlOVfj^=>SJd5^YF9MX<(7uv2+t*&d zU-QYT?Jex=({Aa`gCx;PM%kX(r~oHogLvNvo2$my>T6)%*U6GK23mZeiKXdQKH!*|7@)^JYvmsV5*{~ zrUv$w+fM)H`tu%eGRla!`4{02{;wZfn;vT_`jR_svABT4$xm|8zvzst4ss>v8eNZ; zn$0T_3Gzs%VSUel`h>8qc7OlA&^|R~PLf#FDh@jf4q(;)+bl#Vn`F*TVBC$(ZQyv?q$PuA>7KL##YX`V#`?0;9ogHv{+5(D= z{5qQcy!_8%Rh`uFDY!J;?EA;Emi`iD#+Ka$CxA~+1B|is^z_IKoW;mP7>+PJP&yu4 zS|-ahvwrn(Y$YnSlv>HxP7Nfn&DOa2*69S(Q3e{6)&;7T=6@2_5&I_z>)v+!&mFqE zz1{bYU;M+7O`CoN`DrGtm=6kxVMbX54^{O8}l4y2d?Z+isp;<5i6 zmk0j=)GSkSIJ<*_&F}ym7&;|#BCm!N?>Qb71%Itc&v!tVPG$0IhLRH`s_L+qd@u|U zuTlp8F)kqwR>_4V$|2*O+XJ9lHI7|_=gt)xBIqjiJ2KJOEgflEp()`Wt5hb7faSo3Z zT7*V0BX&T}CpNNhl`1V((l8ZbsbEGhs-!;UreydZs4=ier6dD9!VQV31{0o=rjPgT zfT7G!M@kP4_;+)*`TTjIF*fyabe~^cwK``TNAPN6II! zJAHRlOa;uy3~ad)z+1k!x>8V7P*PAF9#mhY=Xa#6=tmj@8q-cmi9E!8opH+{h4OqHRsDp<76LyK+F5|KHoP|DW}ot#wA&F?iu2 zBuglQ#)tc7>IV}+iAI@h20XY}i}mG6H(ylQWa-rJPi*5=7<61`>+1!73-fE%wox>u z<^cV~fr}H|anh};pr}Y;B8MCc&-8r-a#$z^!X(BKOr+sGRL9BmviVCthC{&wfW{B` zcQTCBsdz0rHa$J<0l>S+AssuDx>NF7A!dMi9c5y6x$HzN2~w`mSmP7kWP%!-n-@*Z zc4Ze@QuSD-Syco;aRZ>)SeMxJydT*~h~nc79#0qXMeawJggnE$EN)IW>^$e^*_!N| zpXT|Z>>3Y#RxV#%WV=6%EI1Clc|1JjIMZx7O;lPw*=cWY!GDU5zC1stYCfZR*p_a+ z%39X_Vc$;ew!nGSoaKFY*?iP|)OdMoy?k=%MrEgXOY`uL2JlMP7ms|d{@RJ4$fo(+ z#RBbevMS#JGD7U%-;Q-qvz+n+Eps!*1o{9RF5^)9JG8@PNdZ(&6{8 zYVW(BZVx@Wc!$e(m-WpLg_L#~S*f$tE;s{c5<;o&TQ!2bwsT;RozGc18N2?%ZJAX5 z$&uUg!{U)w`s~A`f$#P9gKj#2uGTyvT<`R!`+2nR?KYt8ojNgw8*Jz6D_XxkVBtAV zf7b(m6eIZadjv~jV`JyPG#>aq%|Ep~hU_h$MAZ}h{l3^J{CJ{tKQ8ic_H^AV{k`RO zw_)CH?$-|R?1w;+>xV=Zjn}fLEA=fGIIY*=N1n@`b`2Xzjty%Fp`+OvhJU7qgX4Tr zG#=Nv26s|18V~{1a`a{(bdA) zJG0lF;Zv1IdpoaSFpuqj-ws=!9^G2E02#gr6A#*O)Q11Go4?epzb6IX?~gou^7UN? zbgRMLoX`#Nw&v@G5`nVx*bI}`O|sP(@vzF*LZ&-wePe{KRF$^0LgH8Lg5bk(`lu%o11k70B3i* z_q}nrH9Xk&IFP34;*DJ@ubsZ@tz4Ib*WU8uLDCytk*kIgJ=fXKIslUL^5xHZYNr?J zXC@5zW!dgFR@n=+?kCkEy!!8P4-LG4X2BH8sbeF?4h)>_muH&vNXECjp*w-* z)m^e&E!2Gdn+NFjV58!MusjPx!xc&G zeCEKVQK92ARHtd@ZME0_?C#+|qu%X)jXGJ+2XHA^Bu%Y6b`iW9Ws{XY7iF;9fD5uk z=Q9Ph8ntv@5z7j1*^yrDJ0!a|ke)HPMb=BIaPzVv>srnM*8jB1FU!xsbA94QoLX0oFAS~8vt}F+OM>%Fu40YeK^x_ z2JEm}or;%d=Kby)F(RVF@4Hj7TW&V*T6~rb?r#j(k=|BPILWc53x_m9^@yo;X>`Nqlw0@bbS0J)s)yM&HI%KE;;6>99JbmYF3>APhv z!o|t?j+gZPRKP3!qiJ-P|;@ z9z8$DRRWR{@yl_tRPYc$8d`d4Ir6#^wDTBGXKT1#1xT|TPj6`(U+CBQyaxor+LeWi zsaqmd5BB%@uNIs}M4s*e>4*>7y|~qEJv{=P%8j&1>kdZZ*pj}I2K__?Fz4vY{iTQH zr~8ovRUjVmh;R3GjrVbcx2Q1clUJtp7=3D18o&WC%$zk9O3 zuIes(Z0{Mg9<^iA)DB}evSPb9-cK&yU(`+Odu}9Z>bnDPdM=Z^Eho>PZYL%N&(HU@ zaYh6(3|K{MGLIp~I!OAB~i#+w=;mNEw`69P#>|Q7GG|d-NdY)Ggr**kn22Kq6P+>cWcb$EJwkWNqz?HwE(j92=iQ~gy12wEB0Nw5L|ENY<2Ku<#A z?C}o3jRrQvJ(At$B%@|TxDPZQ_e!4aQ>)JxfetP{zKO;0hx{Jjb0@p6e=M^oV5Hbx zlVuw0K)7&cRnpFTkKOBjjmDtaeB_}X=uAMImzwIt+w+j6Dnx`UjZ zLpvFHS{)HNjg4-3dZ1w>#bN);1XuaGSf}}P26SKpYz9g){a-%cbB#9Nr1Sbd-7ViG z8r)3g=DJHasif7Z!fWl@wE=z?c0Pvm#?B88en16{#kS-ksGP8P?3S9k!js?MAJg4k z9_aosY`4s&0f~}_>`fau|9L(w@_4-l9IN2{Sji30ZjcUEr(^p?vj^br_CU<yTyg@%gAhRU5CG>KuYdVCkkpjUz752YCzA_r3tW%>vkw#&e||Q@5yl z5b)w}zA1UjFz7**1(v`fZz`noT;M;a%^m#L_86%9Q`mc4X;D-Bq^`BK=C=-Akp&$f$B%Hy;DLqt4Dwp)0QqAnbPJKGLZBF^6lMD_FJU6WcRC z&doS^wwo2qN1MsCcbcDk8kTd^**MRZnmr{um%n>n?%&k=-qo|PwHn*6{P21T254sZ zFTif$>4MV0TcSkWs=3AeY_qY|tDctzRh2o3t?|BELlYbIaH$ypUOD=bXh31Y_R06( z@$oTd#hPy+;6+XoXJQ zF1l~wNoeTRV_!DwCqA#o8!~4XSE2g7hDPBhbkPf-wq4$-wL3!-+bP>l>B~~JNsppg zQpR|WMw$0NoNV7c-Q~H(c``{AyXBR}r3=dC+o?bRyS;A6wtms|U+|XQ%&+#Rla=;B z&^1o$G0yn-_+ugG{1()#w|QX*JFwu_bK^|@$+7-y?*^#-}|7hJ4HcB zc*kJ2#rsZ@Os}90Z_|F5f9w71f+!qdVgSl%;dv69w#U)*q08lu%#kksdVtjcBgXgF z{i%FDBVcH3^pp5rX!>5P$1B~s41IcBx$>nU@E&k3QExg8lNWgmRob7a`a|PI)dL9L zN=z|G$iFhXUxzJsEv}s}TY&yPsBHvAz=y+`f)5yj3l`ihPuo`_$L2={OUb|zUEW!oS5&kqZhdt2)Jwpj ztm4@@j1Pb_A%!yhyu59REDUG%01v@hA;9~E|3@jXhX}m2!eOBRFCU-g(iy;m9D#F% zz(LBg(o*@4k-&)n;Na~3{reX$W)_t0J$B+mNAbF?y&VDNTJKuUbXZCMr z<)r-l_4f~R`sw;!{`e7iR2Cn@u^Ekxjmf*bfxZEnvGw^1fv;b`ZLON>no?47B|kuK zdR6uBK8`K^{{Fy`arr_OB_kV~8khRg#c}e|^4`JR3|=dPR+@w_JZKD@nKCuqnsBg5 zS?S9e;OT*3>#xsEPWH*qe}7R++*04T`ukgX`S}*WcH-5CA6vk4S9_W)=B+$+_!Z43 zwNM8F9vB2KowBKTi8An<$D+8jHN_QQTqY>{go?OsjnbWeeFpFj%g2kNR<<~PsK32? z{ydh041JFs6tWg%)w*)Xecyh?#%U}NEFQ@CvE;+Srjo)tL%6Us`*qAKVn)uFF3y!rf z{brxQ;hl^_rBl1f9(=2dHG}FeZf0tg!+W)c}{v-^icuZKn?TK4F?xUM?BPE00K`} KKbLh*2~7Y=(yxF3 literal 0 HcmV?d00001 diff --git a/media/tri-logo.png b/media/tri-logo.png new file mode 100644 index 0000000000000000000000000000000000000000..eaacf5be73d2b783bccae1c10115fcf252fa56cd GIT binary patch literal 9260 zcmXYXcQl*t`@cj;j1W6^#I6;!M=OX@YL%+0y_FhOrL`hf>{YdA6|GvOwQ8rLMXM-k z&)Tb2)cX0nf8Xbi=RD`!_jz6Oxv$rKoh!!3KpRTUK}|+R2EDC=xl2X{NWS{ULMX4^ zf;?)AWMusNw=wFb0TY|kp?607xQKg;L~gJ!@6}=>@=Pp;1UZt z13FfqQ%PekfgTr!7a=>R#FeI`WAe1Sv3R^|e?1t+VElB52lX?4NhQrraPzPNZ=0^k zwUZ%RMxEGovpqp?AZ8=IqfQVR+lz&Z?(5FWcx3XdQdAd6;mR+~oe$qeO4+G-gq^-5 zGSU0MHrSXPuD3eM=a{_g@D)PFmSYu7cCHai*N?!OS_1pr1G@~HVIS9DO#+?q(Te!U z%=vtJGv&|apnN$7V*-efB_I0GMzvmH6}E`)dlZ&5|3GB-@IU~|zJPcp{-eC5WirBV z{Lx2eu`m|{4D%7dr*uV%;2hWo8?PzL=9jMnCw98m4EoniQnTX2;nOaW>GZQAVJlaA zM*%+0%;WI{rNgL>KR51iNy~8WQoTHF_7qSDW~!^e!pea8!^@9mjKR=SX1v_`Jm(EvHYbYBn+RB)J@a!eZpK-T3Tw6-l2*tuA#!qw0Qeo`riP_lVavj1Fq4*-qqEu4jh^39UHH3 zAA$ca_Fny`DJ#G&r*%AbSUZoe=BJ)-=FmIax*xyuDa~M^{Fb=kwRlZci@8_Ro~G(U8;!*dO@|3tcIA` z+}vb)*>MM1oJ@mHNw%_sMA&Z5>r{n5*-8IH3wdj3BKn3qd8_cOYH4YyL@cZcgW+RJ z{zP%CcKtW+IYLr{r(-Q|oT-(G>t-uS-VPR-WN!2^bW*e;UCDizB;HSxU$V+>q)A zYz4+Mo424TTp!lE8h>ESG{nfd0o;+o#)?2`oUYLF+%2?>Irj}K0dWaa(H|_n6}K} z*PrynjTnKWLJQyv@kz!2X+|Ine4=e;rShJZ_lXYvI1E z@t5qlXX?V$4guU{EQ|$`-!sNd6py}Rp_p9NA#mJ!4gzY#=^FJLLFmqw=H3y`G^7q?ul%xkQqx`i*m5XRkW0qsf&9g{HmDelN6;R75{ALk3VV)_vCGof;x#w?XSlX`u@<|PZD}=F)K+CPdw`RAfW~fWBL^Up7chj8p%Ih9qjNq_jX*e^3A&K zhZp_|G%QM*B?~nT&`b=wW4j{E-OvAI_wMCWzqWb*Vohk4yxeBTIOXf_26THS?1?9$ ziiFdmttN+6QGF7reNJ0{6PiN$c1tziEy%C#;ylI~G^vjcnBzoQq6kNO_9cl~mc?Fz zOw!g=?*J!2h(juQ;oa|mvJ(|}%o%*qhDm8^`>%y=^p;)R33OL2qTH_DxEsJGXBw^` zEetjys%6Y)7T~&1W?W^CtvUxyvUjPxJ44$CuLODoH7#&;CKvXoy?OIyn$~W&>$E!x z8h7IRq0N>w0FOL*6wjaaAaAgtLjB|Y&?j`}62Y0l#XlwsXWu5(?1Tpgwlquggw4|9 zH_B-*n8Y_TaG@vV^QiH0Q%$D70n%LiCN*!HID0n23b6xnxT0#=`33i(pS8!9NoiAP z+4J}wHk*xW@YG=tIA^!BnnH8anKfDUjmw*W&m1Gw2YkUygDbE@2M@V5RGsBK{#oH{ zb?$VNe=-c)?OkDKXK$s@3~DI!2SpC#RdE}N+&KNved@=H9iZ&t4wD;V3wn3r0z0zl z`o!iV;rE54jw}e2sA>U5bKI04Bg=i{>hkT9YTFlG$!lEeH;3|2fke#=MMSSqxqg;r z6>edL`r34R+5BAi+12rh3BoJRM7uYQoB3LT4oxR3vR42fC>(ku4gg8YB*D#UvS4Uc z@@dD0JdJl^YAEM7o=-m*$A;{?E)7TNwr>jEadY3RomQ4z+l^Yt01CgJ2TyLGNprp9wGL8Dv`YB7 z(3x!Vh}gdTbAU&?0PBq3>Lhc;%$J+DW9#{L#OEGnrQyz_!;D<9TWG=Rw((GANF)

|dnvy?{A;{P4O!+45&YE)_+2h#9uyCxYi<6VwB%3BVq!)+~Zyffe z%hV)U*g7S-FKw18v~jZg#}s7e#HSrUIB4kG zD6p<*Utw^uZOKwsHMsu#?@|Rw(?FUzIjBb^**Ky)=n-8Nn3 z+bhZn#LaMHf`=!y>Ds{>T0P#<{>mp8F}_eXnD1qb`-nR<2hXuhtB2l29?0jY)J(%? z9Vky{z?T#n6pI7@?C28o0B^J8=!M%%q&eI}r(<32f;18O`<)05=L`AA6ZM%h3IDG0 z)f2hbaQxzcq~*D&_i$mYR@jl2?Zjs5xD`(FqG@S=C{>KY0{0L3L&Evd~+MtJu5 zd}KoX#{jzfbLJHkN;2=$>%l<4Ghoc-mbx?_?n>z1!h@SYZI>+`j8bnVCv^FzX zEEvq3Y?>ig((x&=-0q_$l;I8KJrFob5P{DzB&gESsi+fzv`_~xqrh=#7pQOj{Qqi90$rLoVVJg!1_yLTEx!RPe4`<~$q!zQ<-?%(#DG z<3@87{?z#K%tA--8!Ch0VdZ^Ro0-AVz$jbqcWw_*c#1FSIKK8Pg-ecVg{xJWZ;Kzc z?%GQR<-TuHx^f8snMw-6a(tWTPgoOz3E8*@mnJ=liw=wa|7AM zWzw4)rv}$}yd7LR=S+t`*utn|Wjm7#n9Rjrkrgcv?{DGW+(0SNZvs78Ey*7Cr}zf{ zDWHs?aJ%Wg8sAiRW3*Pce;o&`P86^pJoC23O%}&B^(#qY@ z%Gc6`3L8IyGnP;yFF7HTEmWs{L4?+b-NPE&RS9SsR_D5mOj&w*`r0wtf}K{wPAmBR z3^^6knMA8FNfZv~;fzNeefd%rob1B(CMu0!0?j5Zy}W$+>eUg)jTcXipFeN9U^WxO zT}5eJ68>b^Rd%n>O{FKE-Io`$^fop&_W$Q%ZH;}sZLj|8p9HD0EfG=C+nKU%LxC`c zbNvG|V7R$?FjH&m|E<4L@nK7)WOzIK!6`0;)l3Ylj>SW(k*Vt$ttFu>b z{QBs=nb~^TUXKzj?&o{M#b2(n5=>8QuWIzlykrRj^276u(aI}|gwo&dKyVaY^7MXi z>Pz*2T)+RO^-Iug1@E^p%!7&eu^GKP(NmL6l`IaA&wKbDZEu--r3Dv@nicbMvb-1D zQoqaWB>ojMtU6IDVK+=yg4NR(VE7b+_)7j*VqHgeg}5fAt0UbylD~>Tki~PWJmbM& z&=~p0lb`h4*W)!8mf5IkD?ixrtoKs#t1Cn|8I*_-%cPF-PZen=*&-l9|hTo-~1B#DkMnO6fot(BVh(5pPJGwy6or8Cnq?lH@9 zeeqLc@<1l(>mhY~_k~~~a1&Lln;7O9+rAcSDE#lii1c(WZ&|wt-%}v5>EkV7sB!M;9S_ZLKPLv5@k?pD1(WwT zf+haYFonN9wVO1nx?kvK32;c&7=I>xGD#i*9ui+4fBZdZ*yd%j{q_;cC8-VzpYkDc zFY1GXFOIe*ub3!>CKG4Pn_F-KIWu)skR^4mkCDTIyVK`hXU`kuwe#x3pOH@6fZd`_ zDyPkB!=F{1-uKYuWRH;--8C}uuIlrB@ETE`J1>KK-1g;+9y)SDG0v!8TY*KD-+fZ| z$>)lhYXjUY0KLYDaiXsgk{BHI$A$K}S<$YKBV z>GaNa$UMK2{~rZ`7MCANfogxweA`?6ceq^Q6I)*Ttfc!)=0E?F)wyc;su7QAGeD~@ z0vb*v&1>c;883_f?pwBER~L&Vk|3R2P99#@3+}pDeju>7hmFT4umavz-Y5bQ+@y>q z4CerA#^nxQ>DE3BNJ#!0>R7cHY_O=E6rP0mSbwpc7(ckL7h%tOSA~8Ej}54Mx;DhD z*t(>srV_9_7w@+*%FYHA`a9QKgFrY$L|S&il4lza)ZR}7#Bae-e;Ro5xz$2GZ(foy zEA|gk>2#bJ2;2vHy|dw8URfbN0!8$^QQ9%`xcO>p_ZLKM$8^Hb*~R6!Wbr5K4&>0Y z2F(13U{~pE;Lb0Km=j+&z|jMKm)B=(Pc^0WoXcH^NP3fc`P->t3qnb`+ICi?IP{%+ zXfw|0uHrdNdliTTM5eZdoWEG?>cp^eNx@@@+wgTXJY^=g`8Ly1spOo@8!P(P$C<>#+-6t#pCb;s|!6&_3>RhXK`C0R}G!MShlI31*Jm5{N`e^VQ2{1~A-beSn5DX|(}$N^|7%-V^BQ1$X5ktW9e^+24( zFDWsx4LG|m4>Lei(&X9B%rw2F@RkJgta3x$TAvnLa!&Q$qkxC}h@#Huzk%#nd@nzz zf~Tw`;*Mj7^rYi&$(z25T;f$-sW17<>ah-?w=UEg$nMg9!kT1Drz5<6e{fP*rNAUP zSFMlT18XPoY#sS63J!|S;qWxJH~x(Fvn#|O2xn2@^RKirH+nO(q&2h_v~6x(u^1BpU^Bn4?)GEJh%7-z+f#mF4BVjd;{ir!mY(_4}ey zp=6f^9RO59%Z#h6&rITwTMvUd#HklWff~klfAjdBQ<#(G_;*lx=aQ_J_z;oGmalqj zl8!i>Hc!p1M##7Ba`6=DCBDVFF60Yti7n^8^f|wMX`~5wJKEo%tO0x?44QLWzWIJh zrV^_tZqsHt#Ot@AwW}P&jC+C@?7lq|K#nhazvx?w`^@qX;p1r9j-1H#P9%1gp)V6C&WAW6Ggt&sTG@m+D*^Y>B zbHYLUpIY)S+=bDaUJ2Ou{y7yMNy%6NDa%Hq(R`LiEjidiN-LTdI#-9ZKRv14kmL#- zvOVQtNSSA)X@j=7#agBGI49cg*G6W(!@keBvO(?^@OtP)(22U|(9|49yHg)4Yl;Yv zSVXqqLtEgKTLV)o#NIKR5Kd|H_uk*XmQ-sM+;b|SXiO7yG5E!~lozn4qD^q!RQ2WS zn)_)~QM3EtOY*63s=)OO`!_qjOQ~e8AyliAbOwsJPn!IQs!*1`BONNdNuVcs>-UZz zg8nASws_y_oGQAYg`h9w5W2FW+o6$iGJj6BO$P6M&$LPL z@hYwsUL|YB5@z%Xxl*Lao zlFnkqncZxj^{yD-HOc7xoOiZE*h$m57>;=E`3}3Ok*jV^VuPIvWV{gnnA3X2LGU*N zdLk(4jXqK%cm&D8bRO5l2@QM*#-%jf*hQXx3Hd^uwpEfxTmgMr8%GTXb2!J4LISl8 z{J^iL($woIf3$P9uXM)Log{ie#7KKLW|`~T#RCjRpg?J#CBlC>)0GKUcGN#ig&%Go zT8?@yZ4SMrvvENBG zrr`~?lS6aAv#kSO91}yX8ZDzY2uIN0lIHE)XM1ee^2h_KNb8a#S&d1`Jm^0!!VYgZhgGn~?0s7?52o&KQuWiN zh0h!l{S|%Bbko|s|MKn~!uO}-0rO1003V!zk5CCyO6aSXFV8@5Hn@j&q`+KvAAR3~fUN|@_I|!< zgBx@xN-jcwbAF90i;N7oLK2VX7O`=XD6yaa_*!T+W}rWQ@%qHEKJnl5V+BFMFN!?f zC@8%H_~X*@vL9B_^r}B6^F)tyBk-sm#=0OAW-Z_+s-$$nV8{1=8<(trOmg-`T5T-> zJ2R~cfJIWj!W^6$0~v+T)WW0OGT|ylSxUan;uuFmGKLefspy0s0qL&{{m!=&?Nk2npNjuzXo~q`>qm-Zw?6skn7iL`=JWy_4u^MYe)&&&pu($NHxgI7% z)uK?P+p85RkzhKmMksvcr%~tRL=}?rud%^Q@bR=?+bl~r>X60(?78&kj}V&n5iO>K zi&imU7onB|BjZv4&UcE~@zGsb%IN^+xz86Dg90(6w!chIpQeuAchi{*fJ2~{+cT{# zKD1GGa0jq*sbRs4ndC1ymXw2ogX_r_*480;HOcoi$%tGD0YO=rnd3I*_)Zk9!)8aE za6!8cU9L+qmlcG2YO;Adn#lcDX#SfWeybA+@Uy%H$^KA0u4UezFy zx0r3NO)%);iVd`g1cY=oNm@1Uo<4v_)kf8Z8{NrM_M02)dm#bQkq8L8tSCH9;n&Wl zqEQ+ZR?SCWrq#?9Tt)vo2$PzZ*D6WGdBeVIVtTl5yg1PAP$d2XCYE6lreBD}{a4bo z-R57$!+1;YWIf3dC$VC>w;nn2uKI3{*P3-Gj)`$++;6uA{qDkfMcHL4v%yxbIX+0F z=-h>+rX%)9dy8Y#G$+>```-Iar-r@o;HAB2I?{OOfiR6E@6`C)baN zoT>(StLlN4^zAyOx>5a3Y{|FNgub9LbW7$iDm6!EXC87*F)^`8Y)@AgS1~&mFJON6 z`RUPC3xp=*f50tR9U+5U5?SnNBo_^kAu9PL?)|%W?>5w1nHg2zUfy_eC~acC+lQiM zk^?RTrGJzs;!qKN$$Xm6!un0h3_emG>gsqq0_MFNty-RaW)SQ~F?<4;cg zU*AwSu~n_^1Mrl@hk2Wl0dylM3TV4g#$t%8TeW*6GUO^^u%%3zuk0wEsTY6xv;NGr zTp71P?R1(dHCgYrZ(`Re+>N?)-`ReUi!VlzISAFM2yDY|D?enA&~h{$9lZs6AjbAL zCO#_&mfB@tzN=u~^ox}`qyuLz(&#y_2D1wd6QgE5$#0$a%{s1b)$j^SD?DNYg*zf2CTa+TXDC%X$P62pSkM!!RqrFc~Jigdr z8^~x;IjYQYKwxnF8)qcW8XN#^i0+=}Fi$oD21?V=p6W+v|M;|Zs$0mzV7vsxXgY)d ziHYcNo07Y456JVodR%37!zpOk+Z>v_%R!GA7_{Wk*#pkh(33$1*Y!Re?1WCr)?JmS z%$6k;aT7}v|HIt1Xri2FegA((BRLTkuYWd1-P%+F4g~%Fw)_`96GoGv`lHU4f;Lmd zs7A6QP_SkPgGr%>Ra#fi#to@1+1$I9&L2QWKeym`{Q(6NZKhiYPTNr#{Y;`yxeRoa zix*)96#shkQGy$37x>kP@uFx?Of@{(+gCZS3QKhxg#d)!cx&ra^cHlKjTbQk6gO41 z0IG5Rm>?31Vq!{KSaEQa!Y+Kfi)HpW%@&O;bm4tGEc;ln<_88-OOvej?$(vO2ANFe8M)90-HF8Z)7cQB>rI(_V{K!OIx{~DjH_X zHr*q9^4X3wGY`S}C#G=WG753D6+=l%Q}fj=j2S7Tu&cySb`xb;UdP zA)B*Oluxw5EcK@WpV@HZ`bEibhv$sv)5IJ+0AMV8q6Yvkdl^OmKM~=$#;HvwkEVqs zJ9ri~;0NrxiTT5bNlC|Cp%WP4M5WxyX)881HZKX^-hsOSC6Jio>EVHdrNh$yabHgB z=jxZfPR45e+PZ!i9TnyDLT}MuQl3As0I+RF?q!0|u){C`6)`OqmX@r@-j5aAJz-6l)P@jz0!Cd9 zp2yt?NYTMTFi1-5;MW&RdY_Hn$V}hs0fQ@glaE;~|K=)hnvLA0-%ofy6mu#$_qw-@ zMELPi>wYZPl(=3uYiOP=Mx%!YhOSojZa5^l_YxNqeT=8a*@WzbX<@y)O&6Ay+n4lx zS)(GAwoj0QNup+5r9Ouzi;LbX)f%`^@VV!hN3Q(*f~haOSr{3wrgLvjH_dcT=r1Ln zJv;VI^=1(gTDOQ1Ydqmi%z5`NDx6lFCGriO*PrV%$93fPPb@}AH^MHmXGL5`zj^ta z$<1D0kLP!B?#nZ7ET71ZrCgqJ( z225&a{b5k($KB*>US7W3MM|%pPrN)bUqWmQJZ9_4vr8MBKP+B< zaplxmGq@hmu>til>$<~)F}&M zd}dbE=VmB7Zc<;PT}UNH$wRv{FYuiA9oofL!@RCczPzE+ztGgsn5y9xd|eNr$L|8je!E73{v|t^`g;H_vwm7aa0mW>VpqTlrFHKzEkKE53;1YC;+7K>^d)a9bP8crqVZ`U;$j8nw0+E#yiR<*4ttX-D&pBSKG#r8G`~MN1T}Z3EZAMpm_Tvx*|ayR zSjvx*Pae^3jB7~OF!?4c4z%PlIe%!{3j7*JW+ThbfP~DLPwQMgM_0{79C8$AqhF$v z+G^d)PS7U{W0|UJO8xpuxIxh$zh`k-sXZoI3h&?L*Kqcp$`Cg%!ypTW+RR63MW^eT zwIn>$+wLMG_NnBTI}-wFZeEE#i)8Nu1(ENgWo*MX(84O|(|tE#HrEBy4;&V9pMpfuimsBt9RtTQx>IOn~yw^($4i4+X4t#x<%>QVY-`nhWKXO&F{2 z@<~ID7xU`DMu#HHhJwU(N>?cQt%Yx-WAbbqZ*RUSMDW+1 zN(yr}`=UbAgeA65R)*5lUH52Go(p+l>kbRO7}M77KiKQLXc1;a%AN(0R>sj=pV!H_ zmkDp?06L;`r=Jog%bpTR+y5p@8ZxTXq$Te%QLz#X88Y3!M;nBsV12|QhrRE8bBFj7 zJjCU`#ey33wkbuaTolDA1v!git;jJbW9G}>BW#B_<3IKW*B-5eLP)rWX`}1^=uYkK z)CHLbM}1P)nQy8su&kXoSBMO6<}$Yb%+ymWCN0?C@@>NWm)1;mtYA}dg?=nDU|!yB6=FZ8idl|(>h5}o8{FsI`i{9edmo}$sIkZ+joNa(v-X> zt`nzvvbf?SP)ETW8`dcx?L!DAIiq?%st7A)$t>M-$fbD9@~}=1bea28y#jhs2w^@* zwox%4Y!cnoS9ziJjMYcAcF8O3;AOB^=-1r38?FWEqZ?)!O2Z> zXoNGK6k9?6=uBzJ>Ur`(~REQ;rvC^NB_7Rx!V9e+|s}D zl|0l(Oosn7#f0wlQ{v9PdvXpc{Xb|>Ir75~3`5Do*k8D&STCwa)!TWkMOl{YIL$T} zdyMSzb8%j!g!=B^H&6G}@ljBs3jyS z)mpz#*vkIgiI*VHXI%QQahju|LBX@YKyWNEDVR}0-^jzD# zX(As}EBHg|-t13_)dOMjaL<4N@^cD7^KVy$AKrata&;L=90-3vB=vhc)a6miVyg9` zeuS{2#ct`H%iujfVrdluc^}(!&sh&;*UdtYVl*-WZvHAUg9-Fk2BIbm>ELOJY zJNNGLn|3Qk;E~MJ1rDGONNQ)d58QO=!UtCE-Gh3zolSZa+215molXj@P1+V-v%Xh( zUh7tDD;IL|H{k@$(!egK&BJ9ZSHXD`Y@kNHB}({Syqh`Rp-mFKzTM%qUg~3xhA#Vzo5AJe z^%#Yo6P9BYq7a>AFq3RkbaKvVdEJ%BYH?u--+;{F^GWUp`(vs^aAn z%743Pf%i^6jx|?>L0SXGU0P-{H3dV8_&P8{3*PUjoV_k?1xR%+4i!67L zIC-FFj9DARt`>u2wk~Y#hgQ5h6gNnVOG-W*uA#}Ki*-@_+}yJ*jm^#Gvo)n`!P<3p z`f_~&-Df-u;@#ST122Afmmhpf0nr3ybzK+Ql^K2C(f#|(obH$-1IOAqgl^T@bEC9B z&E9iP%YMbug9rjUAQ|X3M9mlf`+3Q5ELKo-h|=eduKGAE?Yhnv#Xs& zFH~)=u%_v58#Mb|6F)I0Oy!X_zw-lE9NM?C$ca zz3RH>Is3aYWkq^QYjF_D%~37nhsJ>gzx|FVZ?nBHNL0bolz8U`7-e^6uTLP2Btq?m zX{}3}wn^2eJ#QTK$-tiaL8V@0i%ZAGcX#X{A)>amJ0H?LUB63iLrW?eJu5q0WS)C* z$yFJamQ7eV!_sBbBS>MIoUtQ_sJ<*DByK<&H&V6}8Ih6kxx0H!C9}l-4et3=ekuFj z?|fdN5I0`%Z4alH6H~wRBuR?T)-ZD0&%}?PJt?`2DyYFTf?%%`Koj&?JAz~l> zMAiK!%0zm~WG<0msA&!B0>VDfkkmt*A9_q$Vbii)?e^gbaVIw&W+%d$3u5H6Gu|jF z-53uy*Uz%V`(#Kugy8RAr5K*?U3K`f1k11&rp+BQ=b^;D+=#LFt1>b_8vDZ}s=O;>eus&niqpgsjiuoa7+N zmuZeaYIc7lNE4m=i#kF{s>^-VCZ$-9MK<-jyP3-%6Aahdm1Oy-nBhaNLZ7aQ;^c%m zQOyyZ^$2Y^#kxti!Upf86BP&3LsmKbc_Jgm(?VD$uK%Y6T9Pb7Qbn#fsxX#C z%ccc}I0LaCq84iDw#tWJ9!kh7(6%NpatRge2|BwYinHfeoRh5=ODdf^gP-?1XqX*) zlDr&NjAzpK@$O#6IbPCU{WSJi2N#<8j$Ajc#x1V^hm!pB(6`^eDU*f@rfBAD9zx;l zF?nj#P5K6!@rx4^(TRygY6YS%UQ|}{-G58UT2G>AY%?+Y!g*4usd@mhT_Nm*gwW|w zvi2oJKl+7!EkWDPCYNLoCDF0i(2 z*d6>nCwigui4aKt45xW<+%L6W?-G~AHK-gj~GxYrLYUgrE^}NIa5fjk92C4t#@ZeNXZpHQkx6Mncg_qX~vx0%M>ao7uB@+N8 zwQSWdzTciiLXD-owVm=60|&d^;z@uMP7wJUy3z})i{Y)^c`I^XhvEL^EG^^%!vc8# zmxLq?0#k4iNE&MJO1;KXq23Cw@BG0bN4S>21fdWJIewZUiHs_2UtwhP-K<4vWR$12jQNOrP5q{?VHw^d)M=H z#_03_MZv&kVfSI=ppMk_FI@namL%*c;W2rj4d{qm;a4BG*A3oZnp>Qd-f{1>sa?7R zQI6WtFMNMmLO~;vP53UrLksuJaBoT_N9U`#2XQz4{ruP9J1D`6Z;tZ~ zo}tbl)+xq5I@U8Vwh^CiF7A2zY^_VF4^_!f9-3jdh}~*Oj1HPiFLkOf7QqubjeARG z>9tmzP(DR(@w+bfe6>A`inKD;UQ?_Xb>(zXVvO=;8PMxnKg?$bjUwYX`#ii z2A7q%!~#G-ICz!im{&q0@d?MSuK=A6KmRfCG9m*bmNI6oLH%>RQ?cEj0th8;3YyFk z+1jsn#BrV_1s*7mBq4?pNlAQkKQoDr`hzuPxOv8OvP?`q)?I!eAZQeB`SvkOr%t?^ zaTWoV-`imD#6)Un+{chJ`$(>P0E~?qjK&%#+Ow4_EYkH50Jj{WP=zz0OxD#Ol19D> z0~k7CcK+6SdL3&+vmidB9L)9gYkW~MV;7sbI^uN7E-q`!T?Ahi-{w^z!dVA`{~aj+ zYj|yx*0VLXlSNurf4&sf*vyZ(p6$-xzeX>bN}g}rWsi}`SHo^ek9eDuG*l(XYU6Or z+%E!`(42`aBrFmJWkr^0a%PS&May~9tB~0X>mnha{PtWtKhM3*<2V0Su9>{!Mhm}d z_`|RVA(N@X)dKn8fSNPpIg>o^;$E|!u0R)-x}fG$$H)IN2$4NmAV&xByR!v$g*Y(- z5D%#Ex3yz^FS%os^g(YVspHyUnYQ(t>`{yAAb2}KQ>9tdrr|98#*q-spDkZX0M@Pk zI2i3i6fqF1jK0<9nfvW^3Z+85s}yvqo5vm;9EE9K4#j)u{gqs^A$EeYq1H;aJ$dHFr8+BPDBLV`}KooCpzs#1mbze`p zS#?0+`+JRK^#1%fKk3=Mn&W8C%?dcG@GD*{j!#a;#y&rB{{t3AM&os26;I`Fg&mP! zRK&?%f7)7u5J~>)Gz%uB({bWZY#^RVo1|DzV|TyKfuw8zul3_d6vD%j0?MTHo$l5g zLNl002CK9OL)xTifI;$SEq2j*j7vSQ>+u2HQiL3Tr4$D-6Z}6%d9wU*J+DL+RbLt1 zKJs61Fnml0EE zbg-`q5oEU<@5HAeWVEHh0_Mo4vmnz90o|IHtugRhV;5axO`I-?J+RjX7}$9vM-*JD zDGzb6;P(Sq6Q{Pzg*}+>Fj2o$Gjz*HprtOIVx(BE0{(MIW&H+*`z;d-jt8!^og~z) z$AU0ZrXeiILm1b3WI)=K_z#r%zbN|O&jH{M!9`u^#D}*md|nDN%@J^z%Orvb#3v)j z>!()i<@Vo-`sKC#h4anC+Ru8V%caP>yCeEyY;8vlB-8oYK4^)mT4DAxtwh z){8}2l{07;+nJ;NXyuaQXJ9WxS@P;0v=i;pa=s;MViNsj@z+Z{xV03Ku5!>wJc z^puQ^>;UWnkcXJ?Cvs^mZHz>(^n{b*`@gb5KoqK|$r zu&YiOGU9JMXSv+b->zK!m6NLX0;bdg8XtHKFlSe9zgo9z5T%YWVlBS+nxo%eKB zew>=hMC0Kk=K?$q{)VNFeNoahf>xkBIMnB4aLo}28!Ia=&OuhBCa3z1N)6OBXW~i8 zoj4l+{wO%d{3dB;W@dDB6jz-Twy4(JYHELNJs5o(OxyD+Dk}2wdT(OOr6@r^XzM}% zDgg;WYX`!JT)bOZ(U`I%F3c$YYbEpB=okdm?TM@8bO%lko=%vAz{oPb%Tn9{q=FNI zOsfh{Y4L6Y78Kygicdh8HsIu90~wHaq>9hhdZa-IqqKOS@LyhFpFzri&&xA%y$5Hd zi@yVLri@46Sc0kGt$#^?s~C%)Abb7mCOS zq7TA>gvH0*y1*C56ksICJjk>xpGmBf>g9JM?F=o1z%6Ul@v#WgKyp6Nb)LyEC;IOm zyXn?7k~3KFvX6wiFt>@p0F}@WK{-#5e-5<$^17V5tK3O`gN$g~DSa=U6?xJ^h! zW2(&k&?PuSy+k)LE)H$5yYD7(VWlG_6%Dqcwo78l%Y*;aPCRUQr;JPdXa5eM!g(*K z#(Gu=-08VA%qIzYU;d4@yc+Pm+{aBC@;TpR{r)CKjh)Cx>Z(#C6bT_#rrRaNYAt)T zqo1o@NQy6w?=Qy1729P5CjU3DbCpu`>g! zvXi>p?XGe5tt(lqAkFwG!YLXX#e*%?c4!vTe(5-{`uVwd&h zf(t-Se3j!z>8>q~jc*e=payRuVd=d?LoCR@>+1y*iLJ9_xTjz8IycMl-7DI>DS&wB z?-fLOIj>;S`%)o9^$XZnHFlMJerIPwWQ0m4zH+LV6t20AjiQ_!QS;>WbP5Zdh70-_ z@I%4MrcfXIG6-n|D>RE9ao8{-`T6;U1O+L`*SIz9#scYWM4UEcEi4Y|?2SJ!zP;Ju zatvi+oYTSbTMErEpSj7Ysi~=|;{QBxZ>1yiVd$F#J~m7DTQo_3r=_K(ruNr&Ai@)8 zM~M%r54|-L8Yz-67b-k1nY&*-9?0>BbiA}9AbUA(EDL5uIIypNUwFZI4jzptkwW2} zuQRaV0s%~kL*`6Kl0sBfF#zBz+|B|Rm69^l^D>R>D3PXdK#}z)1wgAVNUyM?cOB{7 z{sf?0ql`i*)nZd*VgXVlL%Tc&!cnpsSO9VNcerB`ugqP5g(I-jto$~z zJPE}MGIgdzSxJOYX9Nxbtz})vTRZpC)h7T3W%&cgI(ve^PM1u^v@VMT7{CEOPz;Iw zVsktIBrh@Xyr$+`giwR+;zPP{*1tnUvbd>JROb3KCT*+Lt!i(wxAuH*?nB|llT1vV zq_D|i&y4}@7CP~I#B%30&eU4CB%N0E)}nF>yREf#3%Vvr>V1I%i@0MB*h{rfx3GiA zcx7m%$iN!!%#Gtci245g^k_`kO)ORNa_KBL&8NNAZY1N(s2pKOXi?on5)?nM3V}Vf z_!pf8f`fdsgw0(1L&>?%aDw14K@yl9En!A~s`!0*`PVVuL(c~c^tsun=0``@_T6$6 z65N(MsiOOiW*1Aq!Ujw9S+uf*P{N?SeR<2-&|}(Re|k@E?{{E^x>wz1=y7%I8uMl% zL;5gRF-ZYe#N+61v$y11vTD1fx&4(M7w2QI{jT9^OAYXqOMRV(5+~@w*Fl1DeObC( zd$BreAXWy=+bGL^y&1CI{d0K6uV|3!BxT-7|GKi_0qE}F7(&dBOZ^Xq_4L49DDr8{ z)_r>2_u4Pc$MYRvy>SLU-iJd3scuG!N=mV|LE+lPatfiCCUy20%)-U?Yx*lR$j+&@ zu-%_uq{?CyHuGN=y()8SHC(&GCdbErCb^CstcGx~7w|nFrSrXvoV96~jx&0mFmA{b z&@gpHd1lPNXuTyShK--0W@`EZ%ETg*8WW?0tMZi0qB;Pgsxf6)JBEbhj)|Bml>2%o zg^}alYo5Z!b~h@Qksddu{%-a8m@*x;~ zO2^iCNMQRYH!J+spJZfzuTEE#k&w#iWe3#dz$1K=Qf|w#20p=I|3D!vQSQ7=X~B!M zv^2(;H~iGaJu90#JChdGaYd!7`Az!Ijl0K@NVn?xIEWE{;@<;Vx^X&CShZ9Q$v|Ag z)ro=6LEm~$cp3@5wCe(jQ&6zGR!mehv!K9qt}bezB`PY4AEXecKl2h-tIW_vSC#WgrQT>sI#SRFI+8mz+v1>tROvgwyjt?bLVgvyNYqkZ4$=;&x`Q@2^* zLQN~XwwYDUe;AiEts7K|9JkP3jgGfD=PY+wk|Kh0Ic=Dz}{BNus@^%342R6Ok z8*S$9U;`3hRyTq;N-K&1(XituiS<;8x2UU+kjqZI`=KfJLe4DOUbw`oX^>gLi5rTP z@5CyR?9}C|?IA@N1c>C0tsZ+Mj8N3hO5uKxG4KlTHE?T$zQCgX+@!SEwY}HqZM&{r zg=mI9F)G(AZMn9wv2j_HvPyrl%34BsW7?a9?MKZ18y-DiB9qyN(f-eN&K0;aI}ZuQ z|NiFvpP+8j$^g!hj(#+V{5GaX{t%R`04e})B zjT*b6p5B*^B{7$s?^D~(FZ3oR1U5JG)APuIACl1D+qxAWM*;|Gv^Xb&AJs+@XiN*N zudlnfxJY8=4A_DbpPOXtnQ8-mWz_qa2M^5Z%naRv4?J-w1I#fG0N|9cL3E`Tweb7Mal+z*vnp;SMJVHxgzE+V0~Q)U0#DK1KVa6H8N#T+rb5Ph{( zs8?K!{wZ-Gx)>EXn}2dL4E`Ur$$cHprConS{ygepbZ)N3{V>j^mX(cdsiZ;O0Y%%i z@NdDBUaPn!fp5TcIGKF&&V7YKwD&G54g?QjK0fa(3^OudigHNk@$Q$0B{TKTud^(v zm?YACI|xaeymK_EQ7INyR;ZinhU?Rwo1KjfP(O@}C~hmk?a0^aH%kwlxVBvE zB`1d#6+M7`okgDvg>c6WJisx|Dx?8Qry7iVN_1@X{w_YEM0w+(K72>~-5Oi^hG1-Z z7fAHDudnY&{EZPDlU=kEK%wte(4gad?t~3RZjE7Cz@686Bcr>z{L9PnZ$PEQMbO9u zP5yMMW1N!RQ}gs(PnUWf$B9Y^y=;cS?%lbrGLQb5R?3Jho3^T*Rm2_HCcF+b4#izv zeIFCEetkYAWMR22d5(~`Ew%Z3!u&U21f_K2RM#vQovkXD#ex5cc%Cgq>89;|+Jft1 z${nn<(0|Q4b12V~olT?iyyj+JHnvX?Rn2$}E%)XsCpBkhv|s8Dsr^HVx_->^6-F{a z)Ya6=YOohA-%FSYXN*$}6eaP#I!+A^cKomL9I$+$rmM^2AbJc2%|X+{?l5`}vDC}U zIfEOIY4A318o{#kYJU5eg_)U4n?DUw0d8c&Xe8&#ji*AX#yXe(Nd)lD#gE4^5H^Td zVF7mn!Ee9v|E-PxUk)^$YGv%ZH8ziBV*wA$TpCh(R*v-!D&g;*l8K9pyEJ$s3hw}v zJPq?Ds`+I2(u@A%%wL|TDCJIVKPKw=HHic8@QBeVr@!s&>^#zQGY5w#Lv_I+ssA}t bd3uv$=C^F=GVBEoo&s{xO7Iex;phJWsQWP> literal 0 HcmV?d00001 diff --git a/media/wandb_example_val_images.png b/media/wandb_example_val_images.png new file mode 100644 index 0000000000000000000000000000000000000000..53ba70737e374d3a7531ed0c394ebfed7deeb60f GIT binary patch literal 396801 zcmeFZbx>R3-!B-nxVuYncPLt*I7N!PQ=qs*ky0q`?xjF+CpZKR4lV9diaW(E_wal7 z-uLeA%>KQzvze)!Ku*qip09l5n?$O=m&ZgSLj!?8n2HLrnjjFeJO~6gi~Ar$EnrqHnp zs{7$=%?~_|(32`3(J0RIC{t?98@I9v3>vd`K4qqJlREQ- z_?#;Vw(~VKWbbd`S}mhQig_rvQA{`=_l zQ)ttLzWK|efahmRi%*F_1kMFlVrJ&B$mGP!V{J3+!!2E?7A2Z#XafJc&1jsYpG|mO z3uz}rkk5B+EY|P;^O$W;z`1Zv$$xp&q}Z>toMW-4^%Bz-m1_X6E@Ju5tHH%*;JZp4 z;LTiJU6UDAy>$Me(85ec(>O-Q##S^Sq?*9*9`O@&q0rhz0WW^7>PXfl7-U-2+bca% zk1y>Nmy?sz+uKX2O%}!_J@j7YKUc&28CQC0=I5rvKYb2M3?xSBp^3!gWXqUEjpCR0 z{=c0sfA)vyBd)a9Pf8N^m)CkR{%^O&I*>DN3;yrrL|M$$(24#())siWht7=%oXqc`?XWp*8kg?6z&TuiT>9%p(slJKW>Zq|No}{Z&_Yx(S~~S zzV!#+krY4ALz95*Z4nU>(FS{Ilsl&X#2x_zO@gIClN|BG)Y_h)l@7(PCQ( zgnn@`Ap+~2o)FtzI&@~|;HYX#JCX=|^7ML$GhXsO;`LtZP?hXFSo$(}CAoi^b_X>) zZ9HADUaa31{qZGeS+wt4^XWpd!{pj?%3(F6EMSmRXyx;vB+K>R>B&#)b)$Tf5~pjN zCiR!0$!enKDbwkkhS%{~5Am3OCt;l8ae>!i#NLj43fhHd;ABSzCzX7jLf{;*hsy?t z_IJ&4fegahyFK7UCf`0YjP=2Q5RR$ZT z@a$%7{j%^_G=H@VM?Rvayxu@EhV)^p#Wg?hF^Eg-;nKmmL*xva?Ovklyl4>wA|)lo zBp2*Bo@lS>e1=9N8{Hn4)|BhkNc_DLDlcW&r%O~A%egw-45#{|c6T+usB0A9IG@)U zFL8bAPwlfeDJcYN?@w7-SpwS&*iHG^f<1^c9;ekR<}3BVepf}qlE+JFpP#pN^L7KC z2Xvnah{GnuZXS&nSnDk{ZkMW5hI7$2&SbDXo$(|4H)w0FMfYbWR{e9`pMz`U0y`Ir zZJypNE5F7PJ^JNXX+2$Y%~`jo=RFHXSoS`;SjD#VGHzE``hEs3SrSQ1NHC7*ou@LJ z{-v|_ z`t3Rp1@hHlyP7G<&j2lV`Gbky0{RGMK6M`Yb{YGJiK~zU`-LU-sG>= znr|_r8`t@bliheJoy?5ZwC!vY=ZWrh3#Jlbd=r*#lF^QxJqY@|4y+5Qq&Z!%9($qb z`c{^Z!%mPvq1@H;Q=GSk-7$4g$MufkZm$1(Lhx(jl;TosQH)^lbsbZl3S+Xds5jZw z_AdPz@1U?D>Sv5BeI@h0{$W76V7eCi3E@ln;&pKFxdHMLL{WiM7sr{u{z*i#q zemjc|lVXM1qeQ@#Q+~W`UT-z5Lktozg_wWM76u{!G*@E^`!o7=Quv_*h}NsUfTQu| z)$@la!ez}{;1aJ6XB~chmk3^T-vM%;pgVRRyV6A5Hor65#P1vgqL&ZYl5<8%D?ej1 zva{P~tLgGOAhq>AS*uuAERlG4j7ACzJE8YRsAS5g(o$Da{z2~C zS_Krg&U*@P*jMbD^;%lJotATajee#)zn?%QoX60G@Ra#H>|nUSf&2n5Jox+$D+(pz7|8ez@t%|dtp`k+_p2I&(3bzB7jL)Q6O>mg^ z*-ss~^{A*Q&-|fdeD&C)MStIxDqzn-0WFPxPDr zDJs|Zh4JEDz}mxFFAgG;8DH(1c0JzspZIU=Nd&ZeoO=E)hLH*dN}o;l_Wnpm#uhoQ zbbsTqf6|-saD#nXs1y<3J3mq9wAw~5>ggHI)3a}z=WYUA%$lDqNz*2YjdI9tgHoAB zp&UZXAA9?y9rPrZYXWm&p9x9t(?!C2>}(=MPDl}243G3UPV ziU{p9q2t*v$-lqiXjiws_?r)!snl;6hpPg5sMlH;v47sKgwks~$vARJ=e0-NQ_Rtr zfhJ8iAfa+v-Qy44WBf%ecT_;C+5BaO&2iaNClP&c1cZbfMvbKd&kqmi?}u}jzP|-B z=b*LuW(~Hn;JO9ZZ$S#wnE)7sn%%hR)2|O|xBq}}vh8Moo#Q(KduFG3$e^6ol0p&e zy2T_0y~B@}I9dx7xHx>E_UkwOyxQgoyE%u=J)aLI$ET`2?ygb2`Fxh3yLwnWnzjmr zLBTK6qfB~<+h4`Wyu7?5^*}nO&%oC0!J)=KB6gqM z*!kW~?%;6hfX4=|u1jS@AQIkAcA8a*AI4071+x#0`tSW7TzM+WMhfI|6Skc#*Jk73 z&{lGtXsE9T$rk>8PZ?LP->`FkbtoV7u!^*sduZdOi#AhbxEqXM;B3m3m}{wqX{ufB z-(2n7$>;IsFB+4=$%Oi9n^%uu(3YU~zC1*~ArR@;$=OA6qnA9zGf?IDY$n7`a~d8a zQ?cUbstmndukp3dKt+2&F5T@Nlhb^RXT2W>IEhyT^E zOBML`%_16_Y5SZL73%Ipw)eKcyj@js%G}aEpUwMx*U{`6Op))NY@mkSvCf^g!)RqC zkjsSaWTyXgRr7k#q;WvpK4!P_>uOS;z7^kpz=j!sKh?SX{xdbDNh{mw=jkxJKBYU(<5VIn2>%mgCE~|89I0W&CtoA z4i-oq#QkSvl&k%4?I9gza;@F^l$OoM%PRr&6J<`wMcbh>+K#%n5YQLoo19;nSsa)k zgBVq^FuptNzR&shQ#FfX;pe!%ZQk>9t+!nK@m{upRp^Vo8z>G*v1_7(iC>&h)q9op_hDLl2N z8C9J~e2#6YVe7j2Pp5zJ)m->)5elDM2b9yWe2+arRR&Ey|G=~WH1XOWK&S*8njRFw z0^m0Q1a)hEIlmrze{jH7)ABTD7((B1@$cU<#jpF>9nv#b+f569a(EBNxAjwv6A$ z{BAeRSSTOJsI9(FXk5ktGPz=^1@*iZao1?W{N4I_a#ek!p%?hQfqczO#ECB~% z4uhkg?D}mpvD!ydt@urMHV`E07Ek~GxGy4H#3~&JFo5&lGWa9j!mm! zPBZ|G0so#_5&%Rp>wcZbJ+I(yFB`awuu*9JyiVt;9MWmIAh*Z!rkxj4=m3i|IP_kJ zITuHn`1rc~vl*ufxa}#S3Tk|x`zBSQ^FC^Ho&3JZKVY7+IiBinpoBUI<-6MH+NMiO zOUnYJ?6b+5Gf+_prCXA1FSukk9nzP_={HOA0}8+rx8D&U8xof`nzW$E+2TlAHN$_vTKfWHTUWi(|>DLca8ks zi#^Re#&>6UaQ}6}qdSm`yxyl1ijq%%U*$*QGa-DODms_&7h1ix%ur&@ovb!$#gh`I zs0Ip_q*|dIW?iP4Hr1cchLWidKtDH9I(&%{U^%(OVV|D-uA-EcPTFn)h31?OU%9Da z`Z=8^6^~~N_Tfdeg&z`OZDaKEYy7w@|+A8CSio(FH9ZiDj2a)pBCjux5nJ$iMbs#1P%varD6 zRQM2@uoFcOZVe0!Jg4jvTFQ%=2+EB;@s#Q|pQs99RBCB3695dQ2kbBl?*iQ~kr3Y# z0jY^U?-hhMBDnw;36#38V6W|RZ2^0&SL&U96R%FOZ-^oH~7(U zj5B@tV{f0K}Rf?-!|kB*Hi*x;>m1D2<$vy)sUD(gGUf*!2=o?VCX?A`TO2+ zr6sXlK>MxvX7f4>w9$`$-)hJr^l8D&GVnP7TdXlvAZl<6L}FQxU={;*nzf%^XNnho zWfx6OIpl&7xIt8<%J@qIUBptx8DQOsA^##d1cRjt=-2lUF+d+)a)#_IuOwOtX##-I&BPZa1ANUDUg|O-vc4K#=dnM- zLx4sI>beo$8(@lg8uIAI(IGrRWV!8 zPScLSyV&%kQlQj_{K|Bt#-(ht1-P@1{%3EeZO1w`cMRLT50@aO>(}xW8fD8e1qq^! z@ajSWoZn44+fLr)zOfFMAQy7N-~?OkPw`j|j^_wC>`z&9mO*$Ry%@0m91(Z8#!rhs zG`|HN-cv2_R(XHJB7a_sA>~usn?Kzv^q132-xQ87E819H zU)9E7x<1`qo5+WBuQK;o2Q_I77RJ4B%`NET^u(KHpz*vvSYOXAL=HpXDbeWr2DU%G z0+>-6a!AasFR(%P+vzO-i2t_klMCG$x>&#hm(#-!)@x2nf3L^obJsOC^3&7z#UdZi ze!bX%*#lwJx+;hV|H8jagZTXJV=_x}Jtt5B6n#41Y!gd%QkdCb16NDbyyluN8D##J zHdwntm)gTDJ0R;McIHYpvrf<4Jh9!ae@zqZ}3 z4`5FIS4VZJ2(60^yDd7M7YB#We*o3|RjuFEK~)X?qT}&x<=ik+p3C}I>}LDLdb?!k z;Pw7-5* zHzHWu*fcqN_X8p(u-BgzmcKHo=3#vQFo<J-tR6u1VvST`OB#`ZM>O51K~sG;D0s`AONLj(|RJ0@n3C@;Nvk%=6zIsOh4* z0_2d-H&57AhG4(5XaASf7f#@*_TC1?9z3vZdZJn_9iq4suh(a+jt zd8_T1Kw1Ec51?mZOCa?Se~Al3c)rxzzwdLAH)?0Ty!Y}-^T&;eJ=vA;))g(8+DwG? z$8_31$7Vy0!1E?G9hZOb)x^a;mo8s8_E&7lH$QKFd#`yZzs6gfqRXrsldPM-=6#Vd z`#(%p0y+c%8c>1j6_Xj=cgL6c-E{6T-Ipo7_6jh`W=vb%W`SLa6Mn1(h{QMP0!V5r zy*~+1Q@_5%?Z@?#2mriXX71*h)>&)=f@9bD+;Y0Ho9h7)Ul<5Lf=q}fwVN$l%Mt;8 zu+wQZfHnl3AR%DcEqeirjD&=A94EX2nZ%`qA%@lD*2v#Dy@V~l?*#*~v9RNP%+%D> z8?eJeVP?}g3FAk;-3EPq5UaQqJ7FdKZUdprN*bct_M=RDmO%Nd-7@_`8z33TRqKJE z4GDo4f~C<>yA*|G(lRzBW94%Kg*jG0t&E~h6UMxFyfjIc|-V5c(t zNHsuWifvv)4e#?_3p{iUh(isN7Fzcj1mdU3WCIALN^lRC`<7g6LR))U0|4?@WZEAC z*_fG!9*&zoynn-^rv>0IWAByg{87$3NW8@J223K0&-+BRdF^@aSF_L)oE7-&6c=arHt-Xh!0s-W z-q~{mwp`r3&5TeXAD`t5NlDv*xv#zfiOjl#*bN$QC;U&Q4f1{O?b40-X+%X2pJ0JF zpFGcR9dE zQ32;af!XZD1!#l-HV6xQXT94{#wOK#N@4>9B%m&uYj(#JpuXnF3_Y1MmHnGR0)59d2ry*FJlwUP5~F=eyH?J6wRQBTu=w z7Qhd*cF+sofZcXI?^QwAYmeyucApxDH;R*VpR(!PMslPR4G#~WpPD9!dS-!}rd(8Y zjgJk$)wh$@@e-Fb{}B{LQ=RhbB;ycXu&a^M=xp6;vE!V?!x5(0Nr&%=h$*NN9F!^S z?m!kRrzWu`>l)4-@*+d2ZSD05Bb0KauDk0R-I$`t^845U@vj?k%T9NrUp@=1`aJp5KZ|;=J+j)H z%?Qi=&sl(BEL{%KhqFE`@LbpP-16KK{c^Lr8k4NOx)g8^04^tq9}LF~s+k&sew16x z0fcM!c|wF+1|e_A&bXVK+vDQ(a*gjO(F1~y{jUaq4~+)Fp00$};9VYF2k(hd0r78y z1U>HQ`QN0cZLa?_v1yz~e4vZQSDtG%Cn}2ZArQCa&KRIg0%Y0$B&fFKk7pw3Zwyf0 zZk16hYfIdV8^OPucDXkZ3CR%PUOQjPnOBH}9V@uxm3wjRjw8(1%!kOPu z%Q7^|G>nRe-O8l_iXK=G6y=m05n|YcT&lGgZZVzTjc41 z659;$I+;|T6&;@Lvz@C9I^U4RQsw&bUwy+QC+0LDFe(Sq7LZ6lFDHGp|2q%3b)*0n zA%2Cuc;EISYwu#V_yAyY&Y%kL$s7{M!nd;p1MXi$NPu2RK0S^CT^jkjftOcvwQ-`7 z*RJzQ3k{c=gSgkqEdVx_zj3a-h;%{+&j6HiUdf=2iS@Lfm#7bD2PCW-xj3{i=@VLq zzov1$^PJ88a?&6f6aS~Qx}L^f8=39g}6>f%hVq|zsH4`!>-H?G@HGLu9FGF6BO z2tHpz)K*g8Dy%x#%$CnOwII@Je*vO)Col9Cumdjw4KtFHx0t>*ZIdw4lOfew42;Mg z*!HSU+J@l_QhT!p3$1trnB=t*9#^S4=M#DWaUZ6ZK-OT@vM_OtQ;J%gIj=4cYm9#2D8gg zGA=2vrhGd3$FsIU-fzU!guW5ANq1I)hYS4P4f z3up4wfwfU&4Sk-cb5|w#L3e&LLZCJzD!S z#c4(TGjzek{}>Ep5eElv0Ca4nY&sCwOOM-jef>y(V_zVw&^HPghGNCr-;x)1$V2 z9*6f&8FdKG9gF!sSE=a_2=l9IzJR2SY~nwzJ&$!MHc5F7I-}02V~`1lq^I936Y83h z$I4aloWP$cBO8(A4F1DY6aQBUOLGr=aBK$51JD~U;e)VrWdA&Gz@gxSR)PUey3lfd zY7DDT?S^Ci4si@PJ#p?Q3>+ zb|9)I0ZcmhEX>KqR?*m~<&c}2>In!p@Clj{m))K7#zE6jglvEfO|!f5bg^{3@%3BB z;}63!fI$QBXfWTUo{bw1YrfpL!hJ9f)_RFYe1mcq4!nVtc)K^b*xy+|uSfn>{6RkG zZ$H4b_?_220crnYbO5k&LgHTxNA9GF$0ibBvcQ1MFUfOl%Em(tckXO`w86^8be+(7 zzYWUqkcI)I{KWz@KkbqPOrX{Nn3$MXr|t9NL!N+aCbZ7Y4aj2vLX)^0vcwj@$bk5q znuzazWL4Fk)vE$5cdnt)(aFhtQRlTgViPf^$IwHkmSO4%_bX2!U_!v}+&Vp;;wpCT zg>POR%vStJ(+YDkZfh|_MWKD;d9T9i%vUw|v7w=s zZRjBoJCs=Au-h%{6iEcITT~k$f5;$1d;ll|=y&#ui-T0t4}b!Ef1{$`?6jIxtjxyY z`8$kQ?CQ4A=_n)2u@3gEYw8>3zq0SueqGL{CbHj8CQv?TK?=Cwe%^b_#&5Jquw3?N z9bZ&!p!PxUfMN@m<25o2=v>5+vaI3?u545Rdtd%dh>TLM0R-j%@WjRIVCROJuwODu zSOJHzTlW+n8f;W2mH8c~{>~(;`JH4k856j>xs{7QTqbiE9&r_a0!)Ldm#*nK-x42+ z188?2!wchL26*kYY678lC2>C9dpcB-jh+GyGd}xwZ%@+Ffd7?VG7~lX^M6|C#_XcE zGoQpV)eh&`kz|#)9jkG?gF2E4{R9*+z$VCEV?OA4IPLW5Mgkm)L`^~GxuY-srxM30 z$xmv4O17Ot?WeH3K?lfNd%)#8`k(axXw>g22XONp``cxj14T35s)+|~UCje`IAV~E zJ1Tsc(4;1I?@}Bd=Y70lw;`YlKw2&eEb7m{z5w$mD)BQ1LZzm#OeSi;r+5a=28a|w zSRE&`>849*5-XK#T#%#74{E~`6H%dk4<`*bZC8g+@oy+Ri^$)d270~@{jVO*@OI9;IO;#Gsl?I%XK4Xblsc-vRS@ z9;>6SsOWG0d`28q;L$nY1#_^n-Ww_hh#zEoQND=>)SW1U)H%SStTYavSoOPFo5ie~ zTSDh-D*}$4JFc#)orX@FcE&QZW8WoNMKkk2!Z`=_{O0{?@y z!iV{Ow+Yy|#tYL0K=w+UD5ommQkQFwuEO|V@Xm{4nkFG$bljtzKDz`qArt!x_*#EV zOoLVhdctuMJ>CLy1X)ShY@uh)Mr~Efs>1{8k_amDfPr**y0*}wQ3&YtwGPWNUP8c# z3`V=!>!UgF=mYF&Bd-0#Znoa~$=-rroCBE9sK#kk$vgXgJ}aqRT%M{zr^ck!ewL@xUt6`%tEdl4{BH@W zW9Uc!UwJ`3 zjes_*AUqbf=Q5KhWE`}50z-eb2=L|NnpGw|6Yp_tRWhOHi^H094nqm&=f}#iv8ODd z)5XGN)Tf7cy_=MJxU_Exx~6)sb0;nQWhiK~2gD|qJq{l4{$Y!qb?2^=Ne@A$fuRC} zqwf_YFJp@T=P}o?nsPs6y8j+WrPcnw%mx2{Y5=t$SAEdo?g>sd79Qs}8R#n#4lhx6 zZ>0flyOifK8BQ-{bN%rOZE5|H|QK=i`bA146-V>FB{QSVnwF;;|em+ z3p$p?12r-`H{e#g%o~r@4DlYSDUQ@*?QTw`p&n$3$*~5Z4#s0KpfuONU|G_ z{A@y3a|1zVN%UmpW7k0v*sg~AEi7+u*y4%JARKI^g%IqC z$=CDF=rl|@%rsY>0_6QPITG#m@38i|Swa7uQ(-$t>IUeOFnGQ#fQA#aP>XCPv(1(_ zq;zjgz={QjgV5Da<+wR%9BQ69z;3`Q8{$6xq20$`9^P!UZASMRTGWLC5@v6n8$bTp zy8U4}M8BKYW>lFi`nA`z8(Tf$8c$!Q4WpIEH^E*qryeu&9y8Kzb)9!+ghq8^!K6_3 z4C^#~diHr0<_V0iNb@mvHqwHmvu0(KsI?Swdf8EaPU&p^qabt}QudhI4We&6DdUsL zVid&O)rv88+_gSQ%G`HMM_AYp)#d{t&X-q}t05_&u=@>dtYEAj4nV zd~$tb`8-$7p9~49_8>2{na(0%lSE-&XC)-AY4ptCFtz7f9_JVy(Ve{N_@ls0a&{=O z+{=1Q>qNrSi^P6os|2?>L&W=Rf(Y8!Ue&t(F=ZGeh}&3WFn%^#-VINV$DCdl{mM-6vuN zja<<69Lzb`CxqK{YvDi_002lx*KK~EOMkuiN(xThe#|7N=Dfp)4lbC72vwf!+cx!_ zy`?=WZSZHaqyEScbgs>-)2RVMhG6S=??%%&9M(GSps{y3|6*cFQ_N{w2&6&qW>U=H zlgeIV0wSC*sh+X?WotHH?w+uk%hcZ4N4KawxvALyfPC>NFB7a4)-=Q~`+;-IcsQdN z0ztSP#}X81$-kYg>!xGW?($Dm0Z-57VemswaUd$l%nl-!ph}KtYySACyK3Yh-9CPm9m>vVmL={%3 z9y0+ilouMqGe^c^O_yjE!vn1X&wZ@bs#Fe0HJXJkBy7aEJH%vLR1xO1#|zsok?36C zkmT@KewzA-3?<>4%dq05i2G<6BS1^r)p0I&^jjjATX975<7gOS4DoJV#tf8?_NO>o zD)KdNy%arb(cBaY_6Dzoum@_97ORC7?yd%jBMyStFn!w$8Y(729<3NQsWd4}Ap$#VgDtg#_J%Di}uS4H^|H9}!UPQi6%&E0VyYJ?JLBz6S!6*my>C z2X>Tj7+OO^Q_Ye->!tR#`71)AbUj;AD*nit=*BWXWYH&S(8|_>4r6^S8HW|@B6aB* z(FM4|%57rQ%YR$;oe)Gh(9#s}Co_ud531RG7I1|SRr#BENp!=EL<1~`{{$R*8c5O> zT|~bY`-)+rJaepPyLh3d%zy3V6O*6^_8J(B@1iSC&tKozv3yT~G@6yUuon-NgErtH#-ZwTNEK94< zGCT(>JgO}PlF-ID63bw`Fm_bVZND1s56Xl*P$_ce>R8((JlZ{WPV|^5gLk39a*-)2 zc7-@ZBQi4xcm}il<*?c`}NfDzS3^jJD-(_G8`P=$_7ozt-t(1?GuQ!1xzd%ur?g@95}iN{km zZx_0$*pH`a|FKYO0bhreGLj@LLQ_WpDz2u;01l0iPy9v3Q2tXYiT-aSrh3$%#V<5g z*5bgw&+_GTAAjiqpKe*ClU%oQ9Kil`pi(GpZ#BLB1QQz9&}QX2JGXHsUC#Pcm!|KX zM=eaaXtgP&RB_bErTs1p@hvN+R+`G$G|uu=28V6dNRp|PFOyDbo15(`gU%}a=9s$@ z)$QH1z;CY09}E<>sX17mED42#5iAKm7<^LpmmOd!3$-)z`yR#N=^RG5aFC-={5gd0 zaeM-?yU8xmQBl;1QAj&)bNL|T6MBU{&+nZZvE|qF_2Knpgr1^tl^Gg;zIa6DZ}Jj) z_o)v&hM-#UsIZ=I?sdz~gXz?l zDg^u$8iNOhZ$rb78h=|8@-WH{8Dy)BAHg8r<5|#*D{{dWIXMtiFHxBvrH9l~O3VZ; zn1@l=+gRi1f;b12*64a%b#h{am4l@Y$_;ItgBmQ-p{IY?2Hn0ZuK2Ua*_~3k{u^BL|-J0Rgyq&u1IIG$mX9R z9eiq*6k*_-RHSR1^g!M@-fl+%OAPl+Drl18IEm4lNSgLX4t0WRss8Au_Z&Xf8+v9!&{KSrL)_<^=PZboCl&*53(~ zaIsNwhvTdiQv{dWnI)Y`fzK(RkkF>!C^}iKl8G4jGqZ2kYoSG!GBFSvNvGJ`Aqpvl zw_F%d`-sTM7E$`FQuB)^gOUU8m(UO*vv1jb@drhXMqQs#L4~sH6>>iX zgQ^W3zFW8z;^stao~l*7D+`TOpfA+P-pePS`+`0c5%bZ76qUhJQzooJsL~_>qGiX@ zlH@8SLym-i+5NFknXtt+g#{H(I=hy4mOmp=(GCX*5sfe$E?nBk@0X&&Kx$fqkM!HY zlpP9OTs8q@JiHD)QhHh09+3I4I0Fb5AFb^*0(X*oTm+&nT9gCjuJminc;@5*bDHn8 z1@!v8_#09L32m~ZF2kvsv_D&t#OMlCerjbQpivmT_P~I;Aff!k?rP^?^(Buz^i&x}yq%W7lRjR;~U)K%vuqS!D;nv_Gw(O~Rl2>&hT zfK_H@W`#Eu!e?D18-c*uWZ+BGi?V6Q+=CzCUXVg?SkR&)4JEDR?2Y|p4!5sJqXYVg zVA&EJFYxU!7$ZOpjoH9S=s;OSmZM=~Y0(^E{>XxlJKnwNYp!h(mZ*OB zjSUyOZ#037fgzKsx0ks}TADynO1>z3uQ`aTH>m-SYj+kBPGroMK1jXH?aG28N(cJb~dQrqlpU^2K z{R;gH6DUKy_V6nvb4|k|KU1y#=(nQG4G-iZIk&|N@XnX|kij@>%fgjk+!}!+e_^MB zne5p;Gy+trh;tfYvFjL#8`}eI0ZFO4MRe9oSk?k_b}SJh@vhS_tQ@TN3s(Bz`Uj(I$uP7FCCKO6Z9@d~cW_R%}EhG!Doh5Ao& zz81{t81SzytUqL`a-60Qu^x|QThWCK7&!Hq%gkNOWKh7Ohew-^Ehz0x4&U$TTjebWf_!c&qLB;?fKFT>-o+9ToTyJAe_OR z`9?)WXC)FhBNi!%5+q&r7=ei~dG1cv(?pvp zfQZPB62EtHMr))MR7w~dr9NapFHP&fz8m9OkQ{}YhiEkbMW-P^V@OsMs${`%f%2;} zkv(;m4!st@H&U_#rE9tdeT$BY65cX!fVL=Fo2+E~{PPD7nn56zr4#;qxkfq0%O!dm$bS@d)+2TE9(Tc1lxYSPLASXk)bV4 z!B8Ca<;_f?%~bHACDlQV=Sln3g9*09i(R9tfeGtp%lWl{Z6HnxxZBd8Mm4*m2>+S4o=4m$jDme?XWC+ntGl9 zD*|t1gl3d7ZurhO^lFe4Dnkz@7yOR|gZ&~+Tr1mQNxthfXNaPy>cR9+(%0XmHTnhU z$P$UFL@SN1w%Wi9bq1I;;>L6Z1q`7Y+(rl#d0$qXAxoZrk@45r`YlIDq|ofN-l|e5 zM$usl6p8xpsI%rV_>AjmrS|isaN^c~>wi|_#PfTX`_<6-*7d87^oSr+{9yFIW#*9kdYkbREB~q z5h{T)79pO|Ab2eF%Vre0c}tZ2$6WJJO*tt>`jwD$1th{($Ju4_q_~tc6Oz7M%TG`elMP{{s6s0)PRp}-I+tv!N zX~iaGX<{{$P!U{E5Rh2FOd|7B2tVpHnQ46!c{G)Z#qC-NTt^F`E?gEHoMCuFtayw> ziX>bg?2C({GN$OXIh0w{&`J|-2{a3wKjV#u`3TiO7YJHB!L|BQ!Lwv?WQ-P9K3nD#afyiN$KC zU#XLhLu5V?zPKXViYF;TCR>33s*uaiO~LI}sHs8+=Yl}%sSpYOA%nI-yjx1u-9fp9L|vypjy`3UYW)*07rT@sFTlWxD|CL%fm zsZdO7omd(Vy3I(qYtJOUmJGtq%Sg?itG&QgF&q>8)y~?5cmwrH%g8e2mwd zqX>ew4IA5m^&l!WF>{G|>RS&4eK|qH(n6^;aG_>1d{QOBXoTGfq;0=@LN`EQLC?OINYOt2)}X)8t$4UoVad%*E}XICRmM{7&*o%Qt4h@P zW$Kf?Ow0Jeq*)KUH1Zc&SRSkJPt;&6j62-2P3|5ZogM(^-zn*gc_5Q2}*ht>f1q2G4{ussH|N>$hcKgP_+2-+}CWmRS(TuO0@F$WU)zo$;&48$0a0n=&( zEwpuRiDQTqy_y{zL$g7u-eQi0V2@goHmtjeyNvVQcPadg{1P-&#Jh__{I8T$pE@9% z?A#%fj`vnH$J@@Pi3aGBCHu}65ITsL?oYHzQTSM^FP)>N#1Qe)7NNGoE0S)K>801n zWD1zscm-O!=n(gnV9sU^5(G;HdrX=#&qcLN3?ks`2{Ln}khPft+4=*NDWympMfXl@k#=EaQyp&x+-Mr6MlN7lNf&8jWHlbgYR& zIw)*=sDPnpZ%1`!&O|v~kK4nPFt*RxnQcBH^tQZ2enyfEVI7u@8 z<|x%P1;vQ*vS_hs>KfL)KO@Kq1vC|h`9mW}QQ_zb8|Uy?UmHmq+A#atGvgVUB! zELCJP6J$dxd?F)hs6y(*{zM*G3@7I>VaO^dvUEg*CY`rzPSH5=c7qf0l2q)r%h+95 zVu*UT82rDmDbTm@Qs8oSB&nF-eMv&r06q&bv(OTQl3bualq}7R>f$KdFWW+t$C-$# zW=mpDAgySgf@o!qf%Z=20uNuc7iECY0yep}Jh0?uWNTqsHS3^zD)Er>(C4q1n4+LT zplaB}Zb%(MM$_VJpr zY0#nJkM}e|Q(}i+&M#AsL@aDU=pb)|gGu3{bKRPa) z_H?#Yf|c@#jfWu?menfq_L$MZLc@aWj3o&tIbmT-r@vIU+RwY{QOpvp#~RCeXMcPG zd3}Ln#=Wi)t*yuSu8h1Pm(TOBAqDQcGKeurSqRZ=Dlkh?J5)cXwBsMw#5sPmHKT1J z9@b5PZ&5L=$G6PUB&MbJpjs-{EbXglad#IqPmy`1_$JV=+!IC4;$FG|hAf_GuQ@~H zT0@baxx88w!oQHRO{ynUb+s^R;rLi$ST80#*s;bMxkf;YcV(KbN3T9aNb(=T5k?b6 zmL{PovRc6>{0{(|KxDszFWsnFT1}??8Q*utr3kALFbiM-gaE)=0}!lKo67|Nm#Y#Es}*FHo-8IRPdr7yYt~}Ri&;w9*~p9GfLQ}eS9vKo zP1ed5YtLu^01RsbFdiG`87#_Z2m7sgnaY*{ta=8(Lj%B9d-<(d%M1XrWB{4{+R^1| z?M|X*&HP}wsWJxu*d2|_nf7$GZ?qK0J3O_0gA5)6*$iQnG(CbM1WbR**;=#+3v7jj zx&zEhbjdTX+i=LZsR|zwZ4OF>>FIy|3gm!5Id}*@(Ny-8c!2^I|Gxr^lrkU>G;;|j zylJXE%sY%6GJ@~NS453+4wGILX3?vF9F}z+9vJXE-U(|6juqw}76RSA3vZ9YEbSiN zl9t)ehZh&qJtXDB${tvOhl5!Vt34?!Oy?JCKe({xFU`Kmc{N^_`AQ{~wU>fdYg@Wf zX>u+1-?umCJ0dOKUbX8VW~87TEPzy~0EI=Z$q(~m;Z;>&ht4pERltV=GG|*H62n|A z%_K6fyyQe00PAkO1=_hM3$3X;+NAB)*XvTxJ>cXJZ7IOYy6Y~^FHCpDO?Ttu?%lg@ zyz$0suYUV|?|t%Q=JPE^_}=HA|DE6c-7kOr>mPmkX$D%L&)Gvb0X9cRKHH%Pu zX(*aVZ5zYfx5;iH1fo?Nhh3ryuxLUUXGg^)^J12o{ge+a7Ah#Psk}0ME@<;`a+QC1 ztX~kT8YiMk8ExrCm?x+v@#Ps6)k7SO9{?rmE-h57=5X1Bs>Mb8>&m6&=9lNOl*P%j z;N;?p=QhX zlyhzxHggJLbYmhQ=x8=-BdeTqU}oZipW>aKq<6G1ZdkUYCkn8PfI%6a6mZihM^FGv zv~#HXZOFOAfCMnyNFg*f$w;sRZA^QPkeDpBBqNjtJ>f2~?5tl22T&f2)7eQp*)qsd zV{zvop$!XERmeM%p>Ko-vra^NOKe0P-2n4@R{G|aPmZ7_2%rK@`0d-b(pj&?`;EtM ze&gjQAHUQp3Kp?`GC%13jd*v)8-GJ^qwSNEePrUTCZ=}z^_d_4P$M1PuL82}k zRKP>~!cYI5U;UrI_W57?gHQe3dl1|9#(U1+`ijzP?FVihKY29h2Ai$oTTUGlAnc0t z<^=`;Y;)rl5kN3>@FY&aT6lY_J9^_DNG{QllX~i?+u0CB#Gon~QwvI_QOE#saZyPy zF#&XF4MQtzPFqNWL_H#tcH*i^fQqmR2#`_D49vo0fLww|E*f-Uf(ZHuNg!2a1xEr> z(@E;nT4b%*u~?yx3At-4?Vv`Wtr7v9dy1skc*nxbE4h> zm{2D!minQQ*2P9R0RwEM#3N{}noXGk$jm&M5S)q4!A|N-U`JA{J6v9*^*So_wvZ=? zn?~tJjl^R@knV!}6C~x0BC*+;v2yMSCU&BHCaKYW%}53}5ZaN4BgmO6K}O&vJQ|HX znA!EBX~}^LgF7W1kHoeB*vPTcQvjLU6(RYsw(dT&6O>svk#Q#?y+*{Xs4KLidx!~Y z&X-~^QcX7_E>%Ly*6UUXP!+X=HLy8@Dr|wJVXFAw8mcro)MJ7jS9g zx0LUSZu{@p*70u#3;*5pZhAMpoBl>=wdDzuDJ&bG5uAeFgz35Tz~iuN<8$SFR~(>9 zjn_VlF1kyHI_TGUgdOhoXXt6!T;!0EJrrQ8v|NdES6+}gAiybSnh=R#p}Z450fvkaa=rpj&HJGRL<^2E7IsoWX7j{jDlplDR@mz(Rrtpq zL#ms58{Fo>RN*EE<(6Il;fdux;V|z(b>Z4ehZ8viK$9Z!a$#}8+~Zsa9lU;DbKQ_D zFzc}3bx7N_oqwRB18{H=bl(qP7QnAp;FW5w0B!TKJeY#3VB7=sOxeOg{yKA*G39#J z-uYWX09YN8uxe}qm4QR`U#d zckh1r$|9&RY(I5>fk{5v6KuYPgS6@AS`srK12Izqv*i?wyLNY3rygWa5_lBF> zw{G#wEh$HB-+kxGGc)Ew$BO+$+4WarWQz z;(HjTmn80adW%d9fSGb8ciU^UFOG^idp>Xzrw~x|vqC6DDjO}(bX)*0L!Q=W&KW2Q z@n)WLCT>c1LkK%nA|6N0`2ciZROc&b9iFozH-LK%$nKeGVr;o*E^dY*MeV*wvK8@o zCdy4?Gbzk$Bw`yC@ATAm(a@WUA%f5`5)4?o!wH0rK&~JFoS5KB#Jko=eE>V1-iBO? zuOTWjMsH1>B70J>pgUzdv8XIT$;BXOnapI%%JEhbA}EX*z7q7xY`JY4=CM6an*RK`XW#RgU;E0Ze(nwcXzv_}7>rN9@Z%RRpE8l^z5n)q`t5sP_=>c5 z{=q-|J0Jh(_XA3zNL`PUJI_CN@0H(sg!xDR-S0y;Zgl(XPyHls`ZIhJcor6!T}@#E zw#VQ9gQusz@|7=r=_4=y=$-d};MT2Y&fogl`MrBL?%cB2Ds82`&{HDb0v}L~(0uxe zxoaos@h6{yIGLHN2+Tz`j}JydJ0Ts+I30mUm7S@AuT60a%%`XRaWSRM)hVC%^uP1?DVFz7a)U*xI&Wq#sv;WA0Q)I z#ULb?t}B+E4l808aoEj1B_T*UaS&J=-zwH{v80M9hA2H;Krn*EvzVgliiFr)aRf?d zipV?XBUO)zQFx7%0B8dU_>3e%Pc-frXGjgOV}tS*rrMdP52T(VVJnstw*iGfJoGk- zHij(Lq%lXj?6Ho%@g@Ny6hsaeb0&lHwu|1o!lQOc+`-zKpl=}VLrmJJAbL_qB-L~a zWX75M$0@!lE(1K-iZl)zC3S_sM#l!U1<)H4lMi&ed)y{uVtQX&*o5pto)!H@~=-upMOpaV+r-Gk~KZ z1L$J_FsuL|RuKUT0!0#YSH-y#xJ(~G7+a#c7#+2!SY5typ;)KL*jqXlc9 zg|Vg|wu>XjEP8bm_hcMHz#ROpNrd^eWQk!HWIv*krcxX*>uNC_T$+yw3ni^mo|;Bl z1p(w)UuwCED)1leeWi*a!}51J^8iV$eg%FYc~b|}DQTj@*I5sESaoE^=_xAj3(lb- zOCa~gi>r`2Y7$EIbN6Xr7S-g7|xx_8Q5N9ZesDtu?k zFkf1V>{Eq^?Z1Rqx8GOe+0C`(eP`;K$yGynmad(^hfD}L&#PkJbcToW&6+&O08DZ2 z_Khtirk>9NM|%;ae3-o+@!oT7{=ydQBi9?T*?Fz{ZXMj4N@Z7@dpM4j-|pgdnd|gG z!Kw2Z2(@e7U%$qx?q&Tfx0k(Xin$IX(&}B{!#jAmPUf1gOiG>UnhqXJ+?CqO^|{Vz zNnN@6&@NTnu7{=v*ZH-X^L`ONWEKt<)fArWZ^hjUyO}bxfK7`b7XH*Cm}QkAQK3}% z0SKn{Xj@XA!Iv6j87uWApD`3W1Xgm**vk3N-Me4>!WVw<$tOaEiIfU&0S^4dTW`Jj z)?4nrOS^ylJHNC2!H<0Joky0cKKSgj<2XL`)Ki}G`Ptcv0Gu2jk7m*|IXf|% znVE|;KI`;{YB)AGf%(6fO}E4%Tp%Z{W^kFi8Ws$Pu-8JT%GG%DJcNZ+xBPl746g<9 ztEX&1td=y+17ErnDidLDYsui1F&9*H=~9?KO9vK%6mnJpwy3xhx)$4vL67O)6St z)Wz#C=Zqq0ABYG!7xi~$D%OyOOIIgLO$H2cwbIcFrOReqEQBz+Q6Psm#5yWMaJRn= z9*BKUUCV9*2`iIYG@L;j$R$x^Y$1)NWX&2FX}cyeYtldodK(xaBgq;#a}opfxCAjA z!qEWfqr$*MmPG&u((xAq9cVd5C?L(31;cn=(eCUXvZ)ZpvTm@BiN0P9SBWE}>`A z?!7mVUZ+h52TM;wM0AoC3T#L*67SSor~uK_R1sxh2&~mKu(319KyAVxtR}6wF?=`l zD;Fi0s5&vpC{BX}F^3D|b>J5FP*HL?uMkIbFa!=Fux!-;BXy0$9oDKl{QfM!0I9dQYGQB=o^dQ@5Dgt-Waw5 za$6Y;F}X%Y!JW4)8f`2wB-K|EFFg@Jkp}`)k6PN2(*+1A5H{%Egr(jxKq67(FQIEa9$_jx zx}69JI4e$ca_mEY7jluL!SH^e`!MU{=zSJ(QSaib=jjo`BkoE#`3~JQ-sNh&o8C?D zrgzgr)86GU19{KYDxP9Fgu+EyfQEqCbr}eh;bHcBop<}!?aV6-YsShdZ0CBs<|;gK za4F<)5W}Gw!ct`jVG7jXd#1~RZP8L}63IG529|zJ73Dm6P*#kyX;^z_#JYHx)w_${ zd_AIKtFVAv6B+Fg%c+cc0AL^3;cZ}*<-{I=ta|s?D7c(nyjf~Iu}0A5pcB_uv2QIO z)G${vkFzR%eMQ#~?GOj7z^wiHdHZT>gzX^PWcDk}tSj|gS@V1RuL5UlP;A+1Upune zs@L}WVZc_HI};XM@SzykJ1K=3kErKx0U9vh5^C9|E8bywhB-o2XPAjawQC{foC~Wf z%#c>?PiK{H+EO`Yo>9|qi?~a>1hf^Dv*0oW{OO zR8!9uf5r*nnqCggj4cWa^iy==xoK=1uQ>gM5V#=N1)s_=GifIHjshGgjJk0grx~AP z7d928wZL2ODWqiyyqMjHo1&T$h?twAv{jmRcP4VrX2wKZbm+@6n5E+L9C;W4fr7h_ zmYK=Sce-n2MPZ7(%tSeZiPT0SE?^vm@0btI|8Ek>#W}d+WA{@ADYNL>Wi&+7=pN0J z+Pbw%!wJZs5Qbvyz9T)dxP>RE4C_nr739`R5!^$M zOxAv5G(`tEv3HJSgY{i2sjzndwL(hJ!BW>5wc$48_~LVZ`k&DqL)Wn;Qg};boP2}s z@}K?27ati0P^)U(cfbA%fBfVlPd@jNr(9epJ^SdRZ+y@DUi{sE@kV;`{A;7r=F=a& z``9NxD7PLp9>EES1S3w+Bh}5vfBa*=@e7~*!b_k3r2l*5SvF7f7hi*%Djp%6n~cMo z=gxtJoqYgr_{|GFf~7m}d$0J`Xr<^SMJ0di(Wmac_S&PjI)&O6ei8xX2mM812Z9&~AN*C=9xOjd&*g3Y}3Bh^P=lg$73}*2Bfc)HaN> z!8fXr#X%#XhaC$P1Z9W`0S*ONcz`Gb(2kTMvVze<+?nFwi7k>SBCCUGCkY7>jg%N} z3OJZzf;46cdXwO}+mWj}gGTd))lA?-q6TqKqiljE=X8^C1~dv2oEg?GA{ao-KK8vJ zl9Lk!QZN!^

`n>7_U+Dz>5_@+BiixlC%1kd%pA)`78sUMQPk-TDRjqu#>l9^*Ds z-|HHx9*-b97$6QM9aY$p!WwGFq}H^aR7k+=24lvc5(%v6)w$KEvPD`!x2=o=0Js!o zHx+}HrGS(X8EF`XDBRxQvr|^H1}sRTN;gzbqrpH>$2y`_KO;hi)3*4OFXf$1Ih#8Z&@9c>r*^Y5?%c0W@#`tNACP@oBq+ z`B}b1Hrx!r99vMzUkzAd1p>gVi&VWvoYkxV>@}*&PguRrD14vQKv+V{iQ|yAQ+|P| z;uAIF{zA#Q-cCO@F_qp10K2vC3l^?T;nWlnt0Imx$#w1bXoU$iMCq%zc{vEwLtN^3;C#6BDfz3>h=QZDKZIKhlGT zxk(-?)Xf#+l~q*a#wLIwIA$JMQQc~kFfZMbRDe0OWr~ z3kwf%+2LdQW*6esK|jj^-i3YEnrJtV(^n3Fwv2_PRT0H52Nn+kd6yUZ8%xLywXQ3OnZ=)yGcytL!{V2EK-F`o<( z7G3ZIxGPWA+uLgHO|Fc7V2y{s7FX|uZ(A@tB!7MN@auE6nLOXn9^RY%m-8C1Wx{%@ zFD>@=U5>B8^$xq9u`hB({pzoit{7pWWmVm-YrC3xIjA#S{bkvY?kXJlK+gKOcEH8q zbS&urn|_$N-hqiKNP;RD0@XqbmE{(AqIPZL>e50rs;e3w2zy5}fQ1UxqC-fF=Yln8 z5{X9O(Z?QrV;G)j+fa!sEp5S_m;w8{KlWpP^oM__JN@n7{_KD76Q3#_5TFrx>)u-{ zS>3*MJMGf_)6@I+@87z0>(Qs5Ui|WwQ9pBh{317_S#kI4fB`rMj^}LU5wBT@V-v8# zM-|dk>~rhJ&A0B~yLIy>5DeLK7Ul`ysKCBr4XX~8=cI)jwV3F^DXX>B^W1bkl-XLQ zY2jYg|6MSn+8Hw(9_Pbj9Q=wLKwV2WmTGI891yQ6#45}Kw7Kk+!7gPB#|p(AZ}H>L z*>cVq#gTB)<}cdn89>fNfMWfVFpm#2@wJ}Q_z4ZN~8PexiHQqOVZ2^0|G*zDK0@HE6nbP zMMd7+av`AQX`~PPIeAAV7MM5_XafdY0-4bc`Ur3a5L<-1$x6%;997qH3KHT=rTaYICWh0f22N}C-q!)XhWOxT9mGw*y@)`xdYXn8UwiqBubjW{srSF{d;Y%Q zh-EiG1jJG0FSq~zAOJ~3K~%Ce@DIH3iO>DgFJX`&U3PSI)LReC5Wio6rb| zo@c_*h92w86{eu53YI%}9vPqlutNzVmybU6zBj(`(xV@^A+$ARsB#-g1-v#LL=+S) zMHX`aeM7Uu_ZNl1!gHx~iR7OrM%bXyuC!0e(#3IHhuAb5Ay(V3=OSrm2xsKjK-o=9ySV{$cP z9*G(^$T(`_L>*uDScyZGgv_u3T|`aE){H?tlWd_N^hyzZLmgl?Ff%!nU@PK2K_VyF z^y%WnIt3K{5%`i=RmI3%Fd%|pKDu5QZ9rz!i>_4%l{KZ~E?#PvFc`xvvi1>dt+0~A z%%KVrMN*D&$AEU?12J}|wvJ4_v-gd_fc9KqeuL#cip)F!xeu(My+JmTlds)W#X47b zIHw(_HG!Z7kaN=8-=TZPyIiez)4S>2^lo}+3Lbz^^!39Y>Rg=TkOSt|@OvN=!1Uxv z`v?F1Uc1JJ>Qv6}o%jwn=lMaDb-~eUu%o=5rYY7NW?8GH4;d)bfeH=?p(w;J6ooLK z&joK<^x!c|fL-Mt)JCgOCSXCc_6Xdu*G{zd}f zZ(k(OfacrpG4^2Ib-lV`zg!)a89snOYev`udz-5*%rPkU85Zl!1s=qA4m~0tlCBeR zzt$D=%Cf%}oLUAr9XzCx2g`J0+ zP_Mn7lw2W1VK(409kuqqA5O|rLk)X*b+BZk!>eA+5mgg+rRJpwS3|ziG#?gRy4TE5 zS`7l0w6N7`_;ulD6+CM~?m{Ri)r1h)jBpi!g`5KskSPRrFA)Zd2Vw|VbhXOlhET!_ zvW_DFgurvmN_fuMLkNVR**OFU+#R4mAp^SG5jPirHw!#GWm?H%&7=OB7HnI|rr%5;(F=E{7AzYYwgO&Q46~QB3>g{y|RcY^-7{ zl_a!-D%owv2o`b}nX4LuC6ac%HNs~tI`z@XKs%uA9Z^PrnRcoa*JGa`oiJ{*B&2P+ zAQKmI#BJ;0d~DjLv6NbzBuSu4@>MdBAllf&sB55Nx&=B#^W3v{{`If^Z_obde{Dp* zc4KoB6^9Pzr>EQ}sQjn@`QLl?W4E6Bx8M6;{TKgC@11`B*T4L+pMIW<)bYX(fB5_G zGuW_-r~U(UaoWY>3jliN>-T`NSmP!PcM%cD=C+-lzVzA8{P0iywD^hR_W8wEHa9+~ zZA*I3KaKKVF2_GrWj28UBSG6*zU z5AL>vMw1|pgv9B#@|pNe7;(E*MbrkS$xnz(X(w%l#R1;3*&yDLL%DTPSnSb@aa8FI zEMyP?#0G#HCzsxoc3^=jSd`RUL?CcSugVOuWQa#BDn>4BeFGX@60~;~vaJ#ct096E ziC6+ul#HzDY%~Z#4HSes--1ZJ5dg-JooU15++9F7P%?w!mNJ??GO0mv0VQJzkiq*~ zCg&hfg5!A9bBc*lPQGFTWEY8{jp3YKE}+C`fJurDGP+b2hgw{-j*y+Wy2GH(Dk_k~ zKyo+P2^2~!qb5o?A&kPww=E&F_3Gjj1yD^blR2P~%th|AYu~S1cA_nGl|-pcgWh7j z=-EZrLKoy~Qgev&ps69ta6~#v_GU{L@Dmay)ud~Z1U*)RbQk0>oDhaYEe&hPR%i>$ zhSt!6dhTyTzEm06ju>Z#b+^fX)wlm|n7$jg#a;wJrz7Tgh=s4iIRiMd1V94=u=x(Y zHUm)TKIQMoz|7CuT+VyBS^CE-epaK^#;5EK%ilv8p#AO&2M-rTKWp04RUD|9@UlN& zctcY+EMShuXI#HCPNhyO`=QtzX##KrYD^;7Zu$L2#K&fC6CkM z*qfq|?AVv%V&PEDQ6Vl(&SDjREzeZ4iJ4VBQkBh3G1R0EM*9v>B|294bhD&a01iS% z`k}bNydT^bpC@;3)o}`KiKXenI4jGeOnO;1sQ740C1uUznnGBP%W`dV)sHHFF-sXs z6*zLDmCd!~DKsVk51<80!7CsIW}KqLwx726(`GDBaMG+`H8ni>RPNs(&&`E; zH-O9;IZ)oytgfa>M1KO#5Hb!%xxckeo$;#kAs^n8r{P}*$5b-pSFS#o{yIOMSM%hD zqAL4QR2dEg&JS;ndA_q^*#%Em{)!$RlD|S}F_+u%!N9L~YpmOP&;=_ov@i6BON^Tx@GfBMA* zVOcT*c&p!lidP$CQla0r&O+hiLX z4FES{Ha3lfKpCEkGS}1xa`%OMRq~+{EAla?ycgaNhuEUBP~lZpO_SCpTO;j-?4g1dNCT*I|1ko2)u0 z;w_vJ)O~G20*6ZSZA+KK>4sYsUb~+`;^R-={MBFn^`r_~gB1W_fRZ78^&8(%9d;MD zpZf5LVol!s$N%^ze*VAvtzZ7N&;0Pe^SrVP(1Oly?Y{BGYj3=^)mKh`@7u3_pS^IW z~0_jWV1PW<#h1jD0V&0&svE}pkui9=*46O ziJDRrFd$9?5yvev_k)P^K2YmL3z&%qrVOlH*+`iH7qF{$a2P{LT7`86Cs+r~-UWD6 z9Yl65bkG$50tujUl&wWVk!|%4Kx4u1X4Kp`lR;FhDv^rnFLwLcK#&6%dAi6+$pIurU~cje1{8 z8Wm2Icw`vRoN9`R*TP%$Yo_E9HK{3JBy@&hHE?XjRaYVk>|$D{Ax6GnD0G8(fj%m> zinX(otr2&uFiA)&Au-;GTqbRdIBv4{1ERAYIgWcfZ-umHi;C7%(?$PC$6I!DBJ_~9 z_aTDF)VXaW?xJkILpP0gzGL>g>D}~hdN=)zQ^;WwiO(ovPr*Z2KpCHTMmfMk@DQAW zBRGO#%IN_<7xYP^DtK6eDu!}(*%{<2f037Rgym)Tl~2yd84FM~eWtEX*jAoJ+)L#} z3n`c4)6jxbFbY;iglP!-0R~|9Qk;x{>prFD3j$T`jA|66VtXBE#+Uzxsgv{7fE*qe zDGtW#v(IA&JRjPp`aINzS3Y4nd3~O_KlP>kL8v~nDZ>? z1}b!hfR!}F&B@8hc7{3X)?a_)bpS*Y&O^YX4a-W>cDO(1EWzRa=#T#J&;R_(tEM?S zy-&=~JoACqUw<7HYO~ytK6vMmyN}+@*%Od~qZvaPX4UW`njV$E^wLX(0(A4njRnP9 z47dVD8-dISfw(Y$3e{_|As;?=`;6#?2gKJOG=6QXFi&VPf+;zJ05*v7Fe zg9Xwm`s<~)L^AJMO%*t*>fxc-3fZJGt zAr?{?0Cy)Mq98IwODryvW=gPAkHL;)eGQlQDfFhH6n1JX1^fhd##7n*fI5D@^F z_-J6J5Q6GEKL#RUV2ue#dPvAutkqAX zHKWm$h1#|gp+_En^zrk1uYpHE1k$g zkOb>vIqTO!mE05-wPOar8lyup5e6c5CROWkg9osSL?a%iyGv^T)QP}|0#Xu?bc#sA zP+>JD?;{2$Pi;Fw8G^3Mrbh!h=25$?JKP|+1a;sGmP7eAn-`ks5WkZh@%lAXk>-Jd$>x7oER!HDvh94ph8=*h+$>6 za$b{>n6w&^PNHzqV}^|A(;%u1nW{4+x&x$Uk@QIILY2q|;w>}K2S@;dw;5_mF0vDM zq!V+6kfQ;aQ#K@Hb2nCjjfOFHTP2O|4%X&k;OJvyZiIF?UlG9^gdUcJ&RXV#n4F6U zmb8~frb;Nm#Edl&kTf}37cn^=Wk~QH^+(3=)R62HEV5RQky{4o=^8j82xJ>wTM;p* zF0~MgS!Nyu%m9#9g^+a# zOoSkrX}s+&186J*=!Oj7Xj?d088h#xFhyii)XJDc$d$?`PD+!3nSKSJdb2&ncPrGP z683IV(Q;r83RbgzreDX>P{2&NqLDBMrz>6JInH8{++uUg%&f8E$V@Nd#Fq+7G`hmf z3KhX;S7eMzfWp$m%+)G=D>_YOm^8)y%K*4KU!FDUre#;FChbdINx9NvnqSFf2t!d%nswdnNCyDhg=fKtU`lo#EwyJph0g0iEhWvP@{)G7gvGu-?m>uF{^oM%5Q( zCihLlC=*>z<-~g|t9=)MSwAf?fY1d1T$IAfVorN%S)s@ko|m^%XK2{Z+$5AX5CG~M z0Nd9IK>M@f=}ABh5xjFBwoH31ud%l0RzG;C$&7tU-K;kfQ6d$Fb}(j z_Hb$Hu<|@R56C=DOoMl3>1FZ;!ig#XH8r)vVzBrT ze_y^{^CoHTayYp0)cYrd+Wz(Z=YSq?Fz)&`RGTSWJ^A+QH^1$F>*9+WU_LzmHWg0! z-?j(!#RqE+*L4ZkRr_GJYpwnNC@s_ZHdP&7s$3omwXK@gC4coJ3*Zn6J(%$WTjpwM z9a_IsKgT|p^OVoEWW#q{3NtB&W(*=%2Q{=&d$*xN{N84vEphayIzuzGVO811d#ejR z8zFq(hd%VuOD_eYyN^BAUtR*ZadNUWnya-U!1q7<>}TG5^D}?^$3OW)KLp@7gtI~( z4I$@zR0ux6>u^t z8Lh^@7Go|p^!a3crbe=slq(x9Q*-5}l`DHLZRNvdQ{z@;^Dxf-r*t@*%kP%Y#%ZoR zMIJ6cUV=i-rd~4htgFRLlLS>j2*JF#>;<+#oEr`~!`zuE5C!*8^ybIiY87qVO>`}0WK{RlcXZ+nF~uRe-GM5_ zb472u5q9WCxHt0-q)O%x5g2T9=>*!kih)M46^{&T#oGZ+x`ylogA&ZQ0)nliX?j|N zll1{{6u5e;<3)!f#ib}&cdmWg#x0Lff@#~*V9bUsV-y6kq`DEgR7JOW&-w7B4}9p6 z&;9ZreCi)P32lH3&7kPrrTQ^E=CmT&!a;Ehji372ANl2<|381_S3ma;|I1H{ize;h z|KX>8;9vaOOD)?^J-K@Mt#3BQ&pq0eZ7@sHVT0)IfmLW@AOD$u@QeTCtN-+${PTbG z-~30=?#7*uzV*hx0`FiA>5W?_&%o9E@|71~@96kAKKZd1KJHPG*i|T=$+$^6&S$x-t(!$$1B?Ks&*TS(O13 z!9X$+8udtk*jB9}8OcG0oQ?!Ljjg08Z30FN4T-CI^v1Cz3K5KfoJS&6iRdFkU9(9f zhYFw|gCmM0Q)P(bUX-;eNF=sfz|_#08^K{Ss{a^q2uY3RXZAq6WCMKiM)}#}Ss$DDhl#;mXxME)`QN&i`hSJEiQ4eSuNeO*}_Huv-_sJpBi4I9d z^jQEPsWk#s5@u1|5)+KI>pDp|Cql2pVi)Mv>VUivNRfF~?vD1sesPkSC;~7jqL`dJEd&aw5t#{MA>D}~hdU%?I z%nJo6PtX-mFq^|q-qVOGhD-2JXiy9HYX9-WPfY^K*Ai;3Wzfv@rBZ4EeJYk&#nl3q z@PdU2;{g_6Ay^1D@AfnH1($)8JbTX0VwMmJ_LW0ndrf1hrNrtweXa-POocb)P;E9B zlZFX~I2dV70(yv{uJG5cu&y3Tbh_@756d3Zc7;?Gt|^LS61~`eCnzmIG)FqXExRWLv7zWu<)v?^;t3U_SVR`@-dn|d17&RJ|ukQ`BUnD zkQO)h|DB$esaP^B!6a}^W=EGjB836Hjcy%a|2A;@Y#I< zu*$7x9F;=wD$bRe2MV6Ejs~D`vZhA80H)Io&2tU`I$8V6gOkA@7U~~)2W+Nsa z%)b?gJOB)oFv1l#?hzY6;Fg(TN}izXaRdbI7UaoPHH#`aAR}QM5Y*RdjWY%V1L#i4 zkANGDBv6+Taa4ENIy528lvp9&3sp zeRcTwi{E_fYdHFyv&X(M+5T}~-g)#10NTIw$``)| z51a1Jd!Kq?bK}Fu?S~(G{1ZS6lFxnaGa{FY_22#UQ@5WzhKWQaQpMVv0g?dd`hC#m z7A~=Qqn8nA!JwE#AQD>a&@yDSt&2*7)`w^gXlLw=H!zs@iY<8(HP(Rz3K18l3u(8~ zX7eMY&H&fJ0Byf*c-35#L}(nmQTN2edf~KFIupGVPYiY%dy>|aNuqY(dx?Fpo?<{8 z;Vd!^h)}>(9IWK3Vo6nj6V(m7C6De3RRIhaIvBxP+BrI9vSID$1=Q-wY$Zml(&4i2 zPt?)M%dD}ZH6te40FA?vfkZGgot_E$$TxvzW>o*bpS~MhEoB05+3s)myM{2ohvn(r z3INDVUMXSV%3G4g1279(<$#&G(j>ynUZHV+moHnSDYl?z%ygteJmER+-o!L1?}chr zrs{R^BoS2#dH^sA0B{kvQUbslmNSz`R#ux;FcrW;LifY$8>%Vh?f- zXyOoI8O4+eS*eb}2jtz}2zlHe2g$&!tTq`cFMkV5tFYQ8LRkiuNPL$^oEp05AeTyP3mPR`PmW23QPc zrvwyXR#^PM*?YTKOS0=c?AvSAI#s9cxwrfF-%N9c%^`;)4TrRcq-ax;P3F&(X~BYE z7>40Q0SqM1LGqFZ0}1lrw;&IKf;)Cp)mgRH&cm*%v(LG=hcpus@vt{8y6f!Pd+oK?-u1J;`qtVunQJ?$*t;?L z$bq8qeLju{`Ci~De_Ak4bt49@(=_ikZ_ejkIl1p%ej_Q4$Bg7CX#+Waqh5~&EKDM421$k$7 zP{PR?)4$WDoaf`r@!2$;4d>;bYvXsQ8_)fDW>C&e(=u)<5$;iVQ*yh^Il7&hIp?PD zYp#2(o9aETr8^V~9R9 z7-+nre=@%4B?D3BQ#M_Uo{@~gHdn|;up?*F4dd-?eI(UGw=^((de_~Va1`|PuS{Krpy^rKHcJfAbL$bgtPw14g!&%0Z% z`taq;$aF^b@4^0l?=H;lMj@D4j7Z#{9mCp4P{KC47cwNsGXQHcLfFQe;#kZ_@Cewt zNu&kD#NnDQuSuYf(vbBxm9z{dvr*c#ta`qmW6U%USu1fHP4m&4b&6l+1J;xF z&kZqxnGzHQfSJua&;+u@;XxA-5&MB}1ppyH`<|H*LUd0LEiMWQVZB}>-EVpW5j9AqTa1Hr$FvT#6`hf+sbU#n}ra#5DXMEj&9o#>ffD70N29n zm3D_hE#Qt`L^~4cjOMZI=Zz~+);tF~XNT49E!iGeYFR1u=mB#^K?b)u*@}zX;+LIB zn@G%RREfdoF1^~)aIta)xq}wms{;b1!g^!xKuW@7Zmf;&5jUVyh6v_Mz*H+Dt>sc3 zWPd@+hRRa05cE!!qxs$$rT(pN-MR5gAH4p^;VW;x{>`u7{^=*L zs?bv32l{L1{@35S`8rk)EXr>ki9Y)2PdxSXSO4m#e@0Qkl@zYR(pYoZQGD{VfAfp~ z;&=Y}um8rs|0|#U3s3$m=<=n@b6u1rmRj}SeCC-y`OT+HrCDBm{9_*n7~C<+)(gR@ zs|dR(UAlf*`@1OLYu)KgZnt_(KyxKH3C~(tGp(3`T3eH<3}|{sDYddYTuiLeJ%zi0 zN_906kgG`T20|xrz!d`OKp<@aaR;h`l_AtA2|>t3puN>cJE8>w}M z1<3h*edc3MIeL<$jAuo%<| zQS+)NtxcNB`c_Kt2>?Su(gF@AL)Y0wkq*9O6{`qXLj!fvQA0{j70jr*Z6+N8^SXwr zLrVojQIQ9+Q*r5hMLO#gA}iC9U0hDRQ7N5K!px~x?D70mnEZ&03o1^#J_<9dwmJun zYg9)lYVDmmu|=y^X$f%>^R85B1z_pb3ulIPN^=3smV&!h8kC6%CPb!fDOE6-V5w4y z-!)n#_fgj46WbGV<<|)pR1aL(bWd&0n43x^w@_8h5!Ll^Yn7nkY6Un^$+GgcY&P!& z{~xD!f4IT>>3+JO?x!CZy%NM{ zw7d45I9(GSGzH7gO^OW9+5x$?Y;{gL$7AE%^7j%lVthNr@(n0}?WOs~2t9iB6{esE*HgTvzlpAMK5;^-4N?(&(78uv8YR6{ny$8AfpZr;;_ zGrukeXWOM(^r0xdcuVX96S6qF0lFd93Rh0yUk@5Aw4+_n{N|Kjg|@#|mz+Cv}zH~_c) z;fEf2`8zL3A*xCgOqG~leDTFcKlZUn`AHc99z8ht_I%zn&7XettKX>W2d`bL7mGV@ zzkPaox@wx<%*+tu$3O9j`B+Q0EkMA9ix;}pO7`~=qph_lXZh_vhm&}$GPxg4aMgr8 zO@4Vc;Xav5X`hYeRBU>upN47jHw>e<;7-czkYj4JJ!cru3`(1DH)J^1R6U(7vUxRm zU!H~Kr;evPp$%?^1H2VuOb8KCNQ5dg2V!&|U@ss=ykZI-Baac;)1HY17XZ?hg=u@l z#MCN^qVES6!bIgt`lws>&2M;zh>@B5-qei(g%CV?Q55FhwQV7@-YmL<$l**xOvxQG{seGMJ6{S)!-0TF z+1Uk!!%L_F=)|O}Xbw@;&Rva!HI@)ydM3G2XE`*fy)tO>%aHd6A#qa9=iF`Tg|N(kKT%^$It?L_3!-3XBJoX9R3pQa6hF;LQD!fM7 z`SOY{-h$5v#31$+^omr=28=EW!67Xl?@QNsiRQSh=dCd-RHUP>^ovyWst2fUqnW?s zrT@dHpN#L7_tX7!KiyCN@6);H$quBoDVYH@)0_ULbT;jXb>_~2sur;=`#E&1v)6 zYp;Lv`R8xGar4fdJFBiUvk=1JrAzPK-=AXJPX|-qXS1^HIyVagCNdbwW6Y8K)ZBEO z?^l>h!x@J`WL1i>7ZYy9natdi6r-M#*GI@`R{1D|tZ=RgWyHET7ML`Q8BU4}5!<=K zrV-D<{~W~|;%AM)+CvCDI^q$96e>Q(VSC{aLW+7ec@(DjSr#LuuS1V(i7BCGW8n5+W<(r92!Sy8KgJ{>4j-@rg~97ECgxa7VJt&_Q+4+Q z)eXRwM=7{q=27e98A(Oq(E$)M05=O5D6TQa6tw=`ov17!0938*P=Sb00pzU-U_Ju~ z>}>}KguD_L4i0vQluS@^fd~;3_sT0s&(6eiL1A--5j(gPDIDSzR_r8FrVCCXEYvBa zD6KExrMajwQwI<$03-BBH$aOHCo34okV=)WJTQOl#b-*1!o8akiI7(%i`Z(}LjnMU zxs~nP>j$r2sZGB1%CWaIwGvbS&0@Z8n%-yzt=@X+%h&tcYOglSw*Zu2Xi0Eb2lV6) zr%(U#FS$SH?~}KYH$El0|jP>N4OK#CIFkEK`R6|C@^;?B9%nJ@&I9wGDpLV zp$;h3aJMdS6`W>d+M0sb1Q990aB2yycSO!Y2EuTIRA{44WNZSU0#j?GfP*^55m-T9 zx-!s$pgohCtiUT_RdW|tifIofrz2RRv2JJFk&JB*p#eqRe-fAgvna5s)I0t z*@XeX6ovSVC9<{zM&EHK6}c5FP;_bmKn((M5cOL1M0JT%whmS})&zFkh4dypnB3-S zqB<8;AaR`wz~W$0n`;{YBb>sZ5MTkc1_gEGg&I^3AS;3>W^Qxg%OU~dB+E+4^ngrC zD%=DhVP%JE$+TiC3`fwWUaWsaH;o?$S1WzRPcCB0!}13ho@s?gjGw@1q|_!?#N>IF zg0iQ=T0{Ut-1OwN*Cl60Y{aIZ>B-}7<^VXw_Rb=I1K<=kJBcCy=(FhEA$uC9Z@Wpu zWUr!QUKnT>a0@)7IZ09fGw7D@o5qfH-2 zk%RCsb!7}~o@f!n@uuS7HI~BdXO56brQsuX`lvoc$sD8lW}O`(tXtl6%$nHramTso z{NpJlU%cd2nDg?}J4Y60eegz1ee|s9G#2a3P-CTJ$*oALnQm#|hWC?P_+W~SA(EW* z@im#6Mle~K|58v+pK3Lb;?HJT6M+Dl9Qv{ql~20Gjb~*XgC7Ne z5=0e;*fO-aGhhsoKB7?>Br!A*5HM`7o_1GEiMCxbG3hycuOF8?xx(9sVP>2-4baAb z_f9+Osvo4}*?OCy+}r~BN%R5D>DaU@&yKuj9~jtm{oG?`Ggkm)cznZq<{z{QIfpMLu3kG=o> zJZcgW{l~o!Nli1e#dzGTF4l7jfr%BE0T0aNsXzZt*RBeYM?dg^H*eiKI=VZr=7*OK zKmYq*{N;b|(>w3JsojTWa`5v%_todWak4xirkPZiE?puDRaw@H#olbT7>$7KUQFJ6 z2M7D#{qA=!9UewEN8vH9*XwyzQ3z9ulU2jWP|N#1-JWx(D`W<@F_6{{{uQx>WKm{G zWMX3mGKQ>C9;s)Od~6R~$fg0t0u$)gpJ_1%wqgdP#&OQ%gFdy@yE73JB_~7(fSl4BP0^31nQ$x2#&~1 zeLwhIM)yKy2(aGVdgdZ-ZfXcLINDD+0GKJsK?J1&iA~0oHbx8~tW_yc!EEN{0N~yS zBE*P*A|Y8mY}A+{(-VbB+vqa((K34rv@HMc8h4c1EB8V4_+ z3Q__=yj5bFo36MEUKS`$0P8v_=cn!^(7_!%BcirjR=#L4qk0YPxS9SXM$A_7savg3?%60piTv>CD1zuSOMuE%ZDEN;OD>irB5%Tmo+iDQpZ@7WxeET z(G#5HM5K4a^7U7*J@G!3%lmj!S4}C!jVCYv`ak)Dw~nbQZ~gU;|H5SO4;#eEF@nzp1D%)cfy!;*fE5 zabdQ9?b78d^Zn}=$w^f}Yek8kxL7ff_7Di5hYwx9`NvMaavB}7dNF)&QHZ%aT$SzwJdbFLK@6|Jx;_A4)q z+`X_a!H`u0aH*;XpcOeBP)F60Rm`g3N)7C);-%I=3lpkTkM>xOJ7X%19b&TvV27h5 zHlQr2b7BG%3&BdI5f_IO&%ISjAqu%u%m9FeRbk`|_n=KFY{1IBD41gx7$lI^1#(Ol z8V5OiIfH=8HQaz@DIMAaZCL@4QhB8iXcRc1Q;2&(IH;&K-E(oYrB_SVQq8@amxQI6 zaAmS2ovV_d@4%pW3+2wh%T8)IkqK3R_7DawFSs=7s(U7<>b=w;kQ=NcDTV!5AuWp_ zR)BIR0C@>*2#sQa>JCteTjwRD6H+j@x~OHT?SmqxUiH?@mHMhWvUaAp1(dE-A{xZx zxbnFX!&eN5$JU6*!50W1^F}VqkBqBz-vjY}x}WZ+`{^Ch2-#!{^<7W294$gtGQly! zyL{YQVWeVPKevzH83M>^Z>61;%9Oct>|tvqF^S7zyL9XkA%dp9kN$~1B4TkH#oL8x zh7i2439G_jz#W)x2kQwKK#n*zms=xlgIQ-Fk27XDll{)%*RDbvtv3E~BRaL&gKr~w z`W?;@lQ(_FrSab`oyGEU@4b;nunVi5`y+-k^D}SgTmb8w$Y{GoGDs_)D|ttmFsi(L zQEci?Zm=O6`geegQ~u!48i5cz;jQt9HTu6xX=|=+=TGD*OlT2+ZLdR&Fvrd&eIYC0 zKmn{XIuB*o))b5>kHKVF-8AODjb{NUm@%7`Ww{2*j0+~fyslTxDtX~q-vj8a?|~0K z_So~!KmY2TyN@1T?132Lg^P!$r>FC}e(bTw{`AXVi7`I%$Rn@5^6DQw|NLM2(1)t5 zBU7&zz^6X+c)tzeOxjNOSIfNl@`zU#FI;%`+2?NDxDkjgM#M-&i3GF;<{5-!XRtzK zkki>goB*jD@QT}K^HIYHB<(y6Qke6c*M9G}J zWm)KwYDj~=!ko(vE~>}W@0+h(=V0oLN@!w*+g&E3IBN0$VTwV9}rgEoV_TC!7tSNoD_wmm@{M2v0{k5mQ`H9bb_-#LO z#kEJO<(o%W4lexSC;!%O{MJ7L`cHrIi7!0!hoAe^fAP2evtOt$h|4}>2|=q;!{M=d z=*r*yuYXxrGb=h_2Xzi99a^e(b2A9_V7RG>XkSPVGcOtGqI~e-%U^!+E&Iz?D(oL= z5cf(5xLx_hWuq4^6@=ilgv?bhqEaP*0+w?UgLPyAap|DWten2qtIZsM7`cf=5>o}B zuo6)77I5(rriQAfwfl@@R}#`zgvo%O5J^_n7A%Tx&dQ(` z-n3SsTJp)v#i=!^9o~0Vpxr}t8*SlMg5k+$QdL-?M~VyZLZL7tVMnVjQo)p{S^|u6 z&BsCJL2)eX2C$L?aBfSlO;y&eGiEUL)B*DqnhPqYq($qcv`Z6(t1^I#RJ-Y1bwzdo z^{M-TYsXYnC>qxmYoLTf&FktG+AHq2E9o2UNe+Nxv5F?IsFmcG=6-jR*I>8I%5E9CX6ht zvNw!R;<6v^*F6J(765Q}5djny0i;J(hz8(d_ECBWkxr>h1P~+u@WQe4>bmoOpA)!J zAX)-2(7|Hj$YgN{2Ete3sxW|&#FV0&I{?&oW~p$xmN~8IQpEa9PiYDOv%3Po?lJ(b zA^^-bt0J)i6GO*#m7GKkhmw6rn}X&{vJx{$HyoVMor(0#IiYD>v)Sfn&O1wVp1~}< zc?}x_x1U+e4Mp<4OsB$B@tmM1abw%zM55y*3R2I&5IQ|Ikpk_HjIvSNv_cQr!g@H2 zld@^J2jj$mk(rg4bVDSV#NI+ya-zIZ#5B+uoiL47($>n&@TGY0(kA^g17>|6_9d9; zU}@iu#P3@t3e2YI^v;u_m(D5x;53(ZcN7@g(14MIwPC_#0Ku@rtRj%;(m<6NWc`!j zzdV37+mK1fj(7d|cH?AkK#-l+(RkkRgmUC~!4~xMjyOmh17iW>o=&5>8^+2G26vvS z)6WpLg8Cv1tCK#!LNsi#s4&hMnjpLkdKiE0S}9+RAp^fC4glP?wrBCIEE4&d+s@S7 zBp{xHHGO};B@?xYr4`1;w=A%Y8tsVPZ8)5t|AVCQQXTs>8g4T|vKw8dz}8gGMm#UM z{m`5WZ_te0wN-BWsexR>m;q8}JF=OvVQ6Pp{$%HIDC5+{^TsX?-HH^#bP2~1IY~Px z{17((cP(w6u^I9bGq_>8+9qHnFQ2M#CT)5?OyEn%!Z}S_ZcZ3k91COoi7ZNbjuyr3 zCMw`GgsWGtzWVmtk6yZz&#$VgR;yJ~m}qblI|d%Te*J}See2ohpMT)ze=g~Bc7MX6vg4;;p?xzcJbiA%-;O&o44Qp{_ozpwYRr-u)n`In-yahXmrD*46n%kZ#fGZgRbGX19h`gh!UW#TN!H}GtJ56PYo!I?sxw}6P*IBFWKf|XZ2>ME1tE$= zSCzH|I|!^7%{tIs!XD8IDzN#5#nmI#$DTO&_Lsi;k8tU*aw zF^ej==vyYJyAy%cP%jp`{Az`dQMFWk+w8sOr=4CVloh$PLE$99TLvE+=EAKgRAPgg z-K28WLduou+{jr$3>OI88mR=W&LPSui2*o_tFkiJ)=HsH+~6QutBJrBC3z2nqap^> z7=|(`tSsR!U{jd1b6{oeM8?jY)X-xGm<{OI*`bgKQ_z~5Sy!z#tv33MCRV z?NG0vdnzVoO3U=D0BSU)NXKv}DY>&yQ={lr%}@XgHE{=ZAR!ZVb3cTiz!ptIB4*1y zsZYIyN)YX|Ua>AvuDRK7Z7EPn(F-L4z0&F&KINw?QgSE6e)Hhx`%j17K~ z__VR65~1q2v(mdOWqIo4&^=Jwbzah3wCsE-AR#GDnOylmjY{j4A$FpADAJ)^S+_^f zTH%BeouX8|A1(fVx}WZ+`{~D@;+cQ34L!zbS$1ZXoC7y!mi;@&=lhYJ1B87)93+Mu z=m;3ms0nO{XSy>Ak9okXsl{RUxZ%eD9)(fQm;oyoh)dCPI$N0B*#cnz-3F-rOj}6} zPbD!revW~$1_gHDk~msy7r@!=W7g1)hw{1U?8%|hG?YoJZHRsc!izg%;uh@ngW@XZ zO`c8P2c#;*^Ew-MTAF_ELVG)lq_9)q1d{P7h8VUyBHz`?M?e7?j1n`PYx<%xVJ`Q$J#12r>xT0HtO@#= z2A0kfGTj#``#DMORj*#V_O(Cz+IxQPXX_DdA>i7z2abH?KeV;H)fPeDOs$>&<3i1|XUp9~~`^j{`G+ z>km8t;O3ie#@>dDn)!jNSD*g!mqQ4P#o{9$`N$RKkO4!MnGusU+_?}+1fdWDKos(s zp2Iyl@|&g*T{~!6Zl!5Jk@4O7%+xdvhiA;Psa-ykgG_SBuqte;G<7Xzjq;c&+i~lW zL87^C7*(2-r?Hg@)(j)@$~_jG&@0Dy|1fj6K7}evtgA6v{O0BmqlZ956eG+n2~3*% z$kiI+WHBMeA~Gm=?=*M;0zirfpEe>i_ZU484;3dK=?E=R2x))ASy4=_IFKS|4cJov z1)>n#qsNGdahCy{4j|VK3t__+9e5e*eBuN3G%}4--DD^{uG4mKUCQe=WRx>-A^8@U_qU zy}$Cef8j6x+JFCR<-GjUm;UT$9)E0c0srz3pVLmzl3aM+u#aZZeEUUt`D?xWQHM*_ z&wtRp=>PbcuDMJQEt`s0Z~W|k`oDbsziZ^+`lSn>{hPn^*dtFMChYG303ZNKL_t&t zdN9FIv8oz6W(Ex6(9){z;!QkYbuG&XQfDys1gPYD#saRPbC^?g3N08X?a4)|TIgOS z5mGg#3y7*ZccpdChb~46g}At}Ibd3XRE-5{sJUqY=4$0ekXV8`D_GO__9al88&U5@ zRI&k#mefH4G-M)h@CmF05sO&|Y1ge3tlU%(h#Cl{yqCfTfxSfMjffCH1dLK9-DAWir(xCML;HC`j$wFz? zY1wvNMWxDJ=ssj6w8EY2Muu)@e-f%M)~aBr9$%JAap01dT!AWV z5U5GhRV)p))QB!>?##6zR5;M41h+!0J||id<{b*5o~2;DYglM=#4@X}-vAd}6&)!p zN`J>o|A$XM4pghkFu5W0x-mK%HK~1-qyf%$~Z*R`w>RsSPGq%@^^RZ2>@JE&lXH9jt9%MTbrYSv5o=o6Y8DwkmcNo?HP=Jp%PH1Ti(PN0`jLf?)#WS&x5`s_w z3P?scn!v0na#oJBOjkB#m<4Az1;$$fvP{qLtT48YZ8>?1`Pm4_Y=#hew-;V}{i6>* z6vtwRhZo)Lja%Qlca!V53F@WNks&wCC5cMHJHn>Sy3 z^;HpZvuIW@!(;Crm~XxQ#^o!QXGD8@i$z%;tyYiTxbebwz60R(H{Q5@{kobF@#*rU zZQI}e?caX?Bk%vf2i{+or-nOe zO058{dTk+Y=4dR~r;2MTdUR+6n-9FI2RI%3(NgRg@5K8_dN3G+sqk!D3!Z1AF}| zU-;Lb{7-(x+<2j+{_rE0zGC{#uiU-#fr}75eDspupx2*1xzf;MpZv%(zx^j){NgwM zqrdwzHy(PZ?7qwJufF()PksF><-w74k!*>YsJqbV+N$!OzWkoQcJ;zFI_3B9oyV`d z^xFCpfBR$pzdd7K{o|MC|M^ubnzu_Vnpf}Kdh6w1|8HJ;>@$!5)ldG1iz`>I9oEVh zM2#5=5$+sZb>5Wfa5T24XY%$jOih^BT9g8ED?rDt7X>FKd#balUb#l9Ppu_~L&-~p zur%T*L23q+EptFy0Dw57vkoLms8rQOphVUIfTF1t#!@v-RCaY^v7$f%*HXIHfOjI^>YQuAvJzQ! zv;tgR2nw*OF(76Q8AGHw@VaxrbWdQeO45m|Ig6Z{mtID6Gq)9i(9Wqcs*c$eTGnN7 zZ+y95Qr`gJyJ!zcdO%zSvMPP;I#&g}AOLde%HnF|Vx?mR91s+wa79<6ylc%2ve0%- zvhE;4D(JYI0ScwEzAcE2&QE+Ma_ZKJUPgV4cCV6C!$tQ~!OE?G%^N?i;EoRU8ajue zRCu`(MT@TUd7&_wjvh#UniRTTCZ~xs($aWc= zTRwFp>(sduU~4qb{flAfV+_$l^z2{~J2o`^jDDtH+uc8#Gw68_L*+s?cFz0d5!v53 zQgPfOENPx;_7yQ!G_cHw)O+7UgvXXS^<6XUo$&AT{Fn2Tjptb~Thc06($ z$9zIqhR;J|0pBh>#eknkH=dQDtgw&56NrvU&z`y8!@1QPL-8mQk5&L#6(pAGL&RQ zHB8-XZv`q;}E6cHheCycnF!v{MfB(ZJEzuo-@$KJv_FsSQpZ?lE{Ad5gfBBDp_y7JQ zW2kD0&PYvEZC1Ne@lz}}YZyV)84v}dlkP;I02U@tz2pkAQW3y#GiHZUDXtDzflvy@ zBCKsEZBr<-D^pj(1q3m4Fd-1sM4*KN4o6c0Ev(dKp{C*hOkv<-0*NY2&BYq1s-gy$ zPHu84aJ0^C#m)>h7H0)Sja>m(7~BauV^w$8W(HPB2V+yPyloytdIu!kipfOQ%&iNI z$QV#kB4#Bev5w_brAOIm6NkNJbq4B489sl$D7Sl% z70W4u$P5leMZ6;J(iV221wbuI^b6pQ^`$~Pc7Tlp(kW&`WH&is=}Oe-t~%W4)Knq! zuHi=K&dW-USqoGpS3P^_(yK%1*xFg=g}FdFCK!rRN>wve1DurnG6X^ZYDd%6q*jtZ zs8^pW;MfNrE3cKrwX5WqummlX)GC3_^<++b*|BPxIRmDpC@SxML^q8ep9f;Kj=&Vy z$T5CpmL3>mY|X}PhtsJ_1Auv(hzYwSk$kVcku^iWz_l4zS{vW|Y3r`>VUQ82hR6Gm z;{ZaR#1eo+Ps!tLHw2lGLUX0) zAo)iwAiW_3-G~b7jXr5VyW#nl2tGMOExlb>)}s)n>@dCYr=NMnEYen9X6r2pxt=*0 zVbjDpFHo5FVFWO2?H4Elh$)ttWTqIxV5H%mJ`#`2rU;CIsDOc_mgYdd9b{i_rsY7v zOXU-BYO+l}c=DcQL2=SH}Tj_Y#Zg$}uw!%zG=AphQn-XJY z;>{)74(~R@R-W1LrR<$RDch%$dLw0T?8UH6CN?@JPFyw#2kE-q@pow&UX=5jhbJcB zI5d+N-dJXf4imSplr1o5{I&arIy#h1<#$#C!>_P?Dh?IH_;!y0`a#67pWu#=IR4&h zKSXTPc&1tjf*E4eWxAz~jE%-k7ZArr!w7gKF^CZe!LzF;Bn%F2hz=UUCr&U;2pc_j z2}&`y(s?Q39tGk(&zzsTZM|VBK1EE+?``>zjmKfT?)Tveouln}x=(kAxOHN4a~+p( zXC~QJPBv$EXDQAYaNGhcY*#(2$)@6zAJ4RUHfL8_jJcdJmK+zcxu%(zvDY+sAR!`z z5Ge#uqGP=KSB7CkB_{Bq-;SS^QjV}7gFi4{=s6F|$FNzH;rWS0Rcs?=Ny6mUM%kOo zL`Sl$Fl9f-$Xwydl`BU_M|rgJ1rXg&mrDljy(kJ* z;(3&=kh0V6q6<_{MJiy;CEx_K27(k&u*A0P1*S@6} zb5%G&3tyP%9>hgmsc}>WxWkD>+>G6Yt#uCUOwvhP7%@Af6zRM{&wwj41kwX6P;IVO z^=&gSM5%+%+1vyUvT7xbgWYToo;XcJ;sBJS>KYT6mCg`bq7>@T*Q?SC?Jj~`VJsk3 z7dJ1A-~@7py7C%K1XeP0XP+Cus;YCTBUG74eIKfTiJCKM7fZmULlx&I+-odx8|`J{ zV`v2vP6&pJ@R)(sxmO6A7nL4GOd1+lGW#=7h{~#5|@Is2-Pf1@fhPdRIG`Aw4ui2 zq?J*P9dgY`ikX^DVAc>kXe6g(eVW#+V}XebHL$20(GV?W)GBP4Wj0aF#)Z-ZbHt2H zw8H?J3MR{pWp*@4U3N$85&Mb5wPgon2ATT!4u6P%N5t*qF^*)YT~^e@joSJ1^9nd7 zftUzo+dQLlCcs&q(GSQM+o3OQEHI^M;tg|PL!L^fJz~c=X9!t4CQSz1baODsZby8Z zSLN|+{`Ls?z@pg6nf}tW^lgEO7Pe_L?&b_7(-05+3UNeQvkUp%kIVb$AVwK%;p3_4 zHh>Ignm! z9H&_9eIEf4S;xpgSytV89e~T1FH^zKKKGmhSFc`8OdbFUL0~Qdk@a?Td^D>{F62W` zJaPT{gR9l*#g|`x@PTVw@bU5S;$Z*L4}P#JtF~?T_Vy^C@0AN7E~5K4zxmAvuRnPG zJ=dRo?zuPD>m8e4zI?ekJ&iFUgxC+hbm_mTgZaUu|v4CXc*< z!iBycFu*CORveM;;agrnz#w6Rfyd}E1|mz&dgEL-)m}AmH4V`xxIM-chs*lOv~cTz z7>K7hR?(e^12E~A*kKVM3NgYx1|*mKgw46TCnrkx7y=@qh%k}6nOko*csPy}zZ7FD z#jy7=I#_BNAtb-rES~nk-+vL%AIg`nHn;^EXpJo zRhcP5dImtH!vtQ5ql+yUj+*5ZSdo0MpftJX?CWL0%`?|p_B8;H>0 zWSrU4U7fWub7j`;t8aY^3qEMYI=vTZkYn#x?>FT2$+4ftdN_Rg#e=reU;P(fC&e=_ z{1s3GGUodduMkmPN3Vx$7_KJ+afT{rdm?g-=zV{cHTCfAR;fy?oY7 z4L2|VV&K^qZalc%v7<((13CZ(Re`JPl5hyXwQ4aq7@DkKO1-ufQH)}2PTm0!5$}lm zPGXy2gPSr-4YX#2C7iSqC_qY55h7#-pa;2E0GY2%ya&`BT0v9{s-#NVu6ttU0jlsN zNmPdT3Q_sAQi56yJ{JNjp&b;Y+_IVxXFa+agK-NL6*gUTMqIDiD?k9KADUN8YdB1q z&76h%1A%*&NVQQjtRx!cQ}t;OEKNajCg{-&#sl^23b&;L)K!r|K4`J2dxE0uIj7|^sKJn=(w*~37x@?r9Brh z=pgn3L^tnMTcd_>XjpO`*ckm%1U(Y-AzTf|z{;3OO(4?#;D>b1_)&1R#`J{&0K^gi zqX3}M1mI|$>i|Hz9hc^4-(s#iQqgo4cg9#gL}~?kuX^ zmUg<662eI1+BNc!MrQk|{Ap*ey{3ybyu-BGUlx}%xz~Y<2Dh~y%D7517?ZX{zj+4I zL>~OGmlBM~T3WL(Q+Zhk6U>2v0fcE|c?f2JgA06Q{%O27nYLuJ)f7Ef9vo#-#WEja z`8l`MRJ>9=cK!M{zVVHxKleGGAhXA=UAuedP6UWT?0YPi2U4v=aNzkDp1*VV?q;(| zz*A2?`N}J==&(ruF(Cxg4RJ*kcdHeJAQd+vH?Ci&5dQe(m!En1BMIr=z5Ad1)3%^hzL`O$Q_wV1oa^(tA8j>%F zQc77a$|qPb?Z#cA0FP1uC!r8!54&u5pMFXcs8phav#EKOOAcKwLot2x3fZ$p1$I_W zT)EMAC$2oI%Fm7+lHfR^l(~~+DTNTsy<+y1h{$X}^1u~a3I zqJ*GkIeO8|#tVvjAWA7AYuJ zM#DtvclUsRkSb;?M6ZZOx->KUxJv-A83rQG@H^$4aLEA(SMJG&p_0WgXjMrFVHlLA zu*U?Lc~;Z^kQXsgz>NvikUXd$gE3oog@pxoi6wF%xPs~$igU1_kA&KB4kxMC>Ps?G zL=d79*rko6(htscBwf0j)&pxWac&0y>IYDkdf+f?&h7>-stZo62yB7pm~bB z+kHg$^FRIBU-|lPo$8zJ{u7`6?AL$wpLVOz#DjRqq{r*{{!)}{egDoH71xJn-~PxG za`WWrdi9V0(Leof?)Pl*<-6~__)EWZw&YVkzV`L6U2jj^ju~sXbaAQu@v{H+m;c3= zf94ne_UbhL&;R4E{e%DQmq6D{8BlVxw?6six88WnZmD}z94%`gIv+xmG`gGbj$5LWaxPiOM9?oHC*d=og*imr z;}I$RKpCo25?JBJ&Vb6g115k6S0d^ZsKph+Iv6XoQV7JXJAi3}6}(1m$_zOAO2GmH zyYzs-x|U@HW@w!?C(RjZAW;WVuPOoi3NpYqstwqnhDOL(P^~$V64mR0 z*N6u!>gc&&YNOH<%V3D2RRp_$R#9s)H(qUsmNe9HaFDn}vK0}?m!P#n#n|LXs5hK} zm+CA~S2ODfE{M^t)lhBERTmBiw-hUFZGr#7E^(c~l;i4=i)MSej!46VeoU_OQG7EuJ-TxXKFilljA*$#;L< zfga|7zCRDHxQ+fx!9$|7#cpOiXe-A)k*+eCB_J?T0&D`9@~<8+(z^mM`yos`tlgo6 z;!&rFAe&ybBLImIMn$cxL=ytGEslQJ?pYY$#a#B?`7qcbUH0RitN%>MV+W-xKrYNM zUr~3P6Ea;K#b2i6b$HRp1vC?vxDDH-lTx{g_7>E%0(U|_%cZ!pM0XbdWk^=Jr2ibl zpDXVVGwpQ$Vwt93TPOMa>Lgt1q7Q4CnLcS($r}ak=LPCf!WlDKF(>Ss{Z@)<&9gB~ zoFf!J4HGVQ>9UNI($*X+H~%zugNT~NqF?vfPHyGdXP>?O{tr%dSW2}vGoS^S`4qUd zT;8~G{q666|87cGLKsw;E3+X`fI5f*1sjGyG`RPD|BY{aqY@cZ2i5xz&YDF%4Eoit zel?3WJ@@gCA08e$AY26|Az|iZ{^0a%QB{v!y?SGncT@9(5~BnAhyRIk<0~o2>Q#03ZNKL_t)ZrWy817syj6=Av|X z31^p3R8>r3>F_imjH&qS6Rb8{t|rdiyuDmMsc3rc>O7D+WN-Wn=wQqQV50+3a8E?! zo~cscsxq@2KjcfyIw~OLTw)c7^08Hb9nGSk}QSY9k=k zMR&D6vZb3t$PB7*J}^<~mY|-%DjQ>E%jW?{t1#53ORf976GYWS_)O_QwIUGU4P3l3 zj*x1Kgs3=8~wfC+#FpnJ(PETM$a=(*KNE*K<%;vWoJ$UVU2yvER zLeNUPMcsCg2#_nOqD3G5l%Q@^>nn$dr-%lmr>8d#>s9AU0tFjDatME*B-T}3Q#)L` zWA;kx+w8|pyjts-^4j@Saa=Pior$P#?-c%jEjI%C%s4j}Y|k<){erLVF# z@@>w{ILjOJ*YW-+0LbEXBZF+rXII=+<~qJ@HSpGH`*9iNO-k;MZ{0Qa!i&C@H_oL6 z6n3yXiqT2}CMmQF&tYM{`@`;3rtM-VlO|3{Feejv8I|0zf}@bBQX@&qCjbH?n@l#0 zEkSR~=Ncz{HZzpQ0RYCck&zNHY7zwiq`s}5jc0CPwzJuC24}ilIL&Db0gR$!Qdg*rU?Yd z5e63@w)6idv}5Vb&rk>o%mM|eM<&0`;bt@BQPOs1gLDDHs3r@uU&Dlq%%*4pLGst!=&U+xInfh!Y1>4}pQb9?9AcRu-%kId-LphLG_Ut2C;c;SV&zyJN$Uw{2? zJpcTdix5bjSj1Gp>}C$!yL)fhwpXrP2}FlSM>Y&~UBC6#TaQ2Sgbf1)x_#&NX3(k< z9<$&L1ehlgaT|Vc`_AK!KYn_4_JjA{zvq5Tl>5J|_`&Mjas*;>8wTO+b#e{>3H|VHge}V_Uha=3Z6o?(REi7jo9pI%ZrLEizk!lzW2q}4{Xa(XihB*t;yAzQOmTyztQ$k`QCQd00W)(3J zCC}IXjLjkB)QkvfL&aRlA_R!YFbr8*YqNJgf8h{3h51c+L{`02yD-+lM!*-r?YqW#HFJo5m$Kt;c6{a3#AwYNY1#m75$YSwOb zrJQu9-O}Nn)b#GQN4~(oK_vgBiD!T zbY$Os?e$N6`i1X)pTGCDcfS9ZOe@q;0TGxolwEr00lEXHnJH$OMTHP42tAQ1Wg4#$~tuqMBsTLX76QG7b&4x^23wPC;-B;2uET}dl zXU5{F*bN@Nb||!82(v~g8c^p-#0FciJRn}!VPZ|Lbwg1FMEBvx;!C5NYOqDpBb5O$ zk^&GyZ%$3DoQRlKG}L|u9JWloDzIc7AZJD*Y^^6iK-UP~^Iegp_AVG4YXv-th?A)L zVds$gej^LfM$v*2v@sl5b4Qe5*Px8HuiG<)u((A+%Z>+n+Tc*AtHCZR3b$4%D#way zK0NB<1F>Eh(!$hP+d*{D_()glQF&Azl}F`AUbb2MCV`|`ifI2I=3f&=ajQbNXivuI zVRlNHAy0);RhZSXaunoFvbmHlZo$;^t=^CYA2J_m6#Uw1GnJ|Fd=@R4z@w0X005)( z(vD10@zp)Jhh%eaM;p^%Ctau9L<*x2Rd&~$!f$5+Ce^S#eXA69x_y}zRq5E2_J_H3 z&i2=|C;YVa>ZChXs5osadr@IllA8bRh&}xo+4}x0fvvsdfO|WB@W6K~>`eXkr#<1Y zaoLaaa#6^v5Zjs!?#W=KRQRD7i~IJ2XL+pIV`;~G?pueKl3P9{H{9{_MaRwu=zRSC z*pw1h@B%!V!IV%`^CGfrKBZA{n^^6Fq_br%w(nsXCBirZRdc&x!e7cRWedXuzO;)) z2;s(!8?S!*+w-q2z+BzCd$$JMY$Tdhycvc8cw(_2;&pKfL)kE%A3UYRL^G0TyZo#fv`PhBn2POm0Uj#fV$6E^ zr4NUF40&5-@*Njb&lAEm&*omBC>5{4(=^hs8;yvfCv$J-^)pla(jKHWp?*YR#-H6C zA&fN35Ny!V@^nq{>{!4P0)m;jd)9^zKz2Gp$g3l{gUFMEC=Hg7gsUyc8^)J@!~`Vf zDl1q4BmRX+$Sb*rEpG||VFK5}qN?&w8PXyO%#?+|%zYw!kMD_6LLkb*T$L=$4FC~S zpp=ri<-kdzFsNeUh0Weclf>AEyNIpX?ufHPVLd?LnxL#M&cxAW4L>l48mUL9nk~eI z<1))L)vO}cn2HLH&q1z!Y#?&7SjkYagX+VEz(Z0r22rr#j9^xsHIW1xx4MaSEgO#s z9f1f!&?UG62^s=*X3ms^Q1?rV+@-&F4;LtC`j;YWk-a=!?Fd<>rB}kzalzJnOTdf4B z5z7V!R#;;YD58=(@A`vaiD5Y;0zHn>7?HDW&pMB`CcZwwu9MV$nQ%1)D@DknA>(Dc&W z7IQU?vL=34fX3EN5neMfYz?c?R;=gXRZT9WVhVNFLr^Vz=zUMT=4M5ty#UlpJc6s# z>mSld<43{OI#@dZu>e4Z1R$#tH5&jp=mBWq?6854nPe5sp&iA_UBz{t!R z>mXpFx`ZNIAC0*Y9g|#9t_@6tm-$U1;2QuS4%P( zA!SvpOmo<5={z*PSxdmg9lSQW<rE2%Uq|=TCSG{ow^vf}7rV~@ zS;nhO-s5H6tfcLYEqfKj@u!H2x06hfM`pYqLULJGUk%X}xE5-_1TyF`^4-zm0S_Iy39yS;r= zVPuD+veS(V9LJRQQO;W*31e> znIJZ^m5@@{8P4>0msL}WvE}Ziv@3O=%3t?9@bGepuhZ_{<)L<&%?nd7eGTQWg};kM zkv%`p<6kWQ-duBkcIQF-1xmxYOCGFatMPUCSnX zWY{&Eigwe4@`R!rmB``2!OLHN*`9wsOh`&yFYesAQvuAJ*p_!#s-ktFz zg_eq`vF~oB0!;b+x@4O@pMgn0nhOg8Q1(nGl z3MB#v&3UWRIZT{M$yNIUl0*{41Q2oVnW9&S4y{cL)N8eANYw!xHY)`x5(fBxnpw8>_1ZwbOfuOJju|vY$l|H5(`zNRL5Kv#gssUb}hr z%0K(VUyT2yQ%epg+N1W(S36pY*W#yytJUFC>GXRC=u}W2zWCVtufNlE{4+oM^Z(cH zefwVRC+fptjnkwj!!gbV$L;rD8{|JfrRV701HHaDe&by?|KsMRq22t%`t47>{_5S2 zJ$>WtuYvU)r0cw{+q?1hC*^?uV>UC!w`* zg}!#cttNMv8`mT-IG9X;K7s*=iZTS9xI`%6wUUV^B^Po-0!74Q^dxY%2tdFN2e0ea ztUFYwXW4B(gbW&ki&yBKstOu=Q>}=TxEgw)fnv>dWm;KlKo4g^rCM`6r~~fAjyiIz zTn3K|Fyi6eI@V?ni0>%|^fye5{MfVu)LeR}MuKD0J3-bhdRFe>#6*@D+&AYA5-8~c zPzQ_L(f+D5_W@-+hHxK`T~-vO7N|m75=4(DKmv|QSDilwgqq%0JM32NQ5)2ZaA1OH zoujRJt$Kv|2R*JF(tXnkOazNeV$Ld%0B0cnkWLyOez5;hc~l;iN98YHd}1eM#>)6% zn_~_s6r7NW-ZJflU0Tfq(@Y5m)1IA>5Q>`HeYamPCH3rX&+oUk6sL)L;~utv)V6-| zOKDIeJ7ya7NFFHi8+zI&C6x$Q2_2*flrAze79iIaz?cIolfw;eBjqg*efEx?~$-B{+qq(dviB7k!^0*WJ+oG zI0_^0?!#VY00PqiSKjko29s_PjTxCr6QU6&T%)Y)yJQ@ikd!hwaaPyDBp#0<3Uco1 z%sJwsK7g9p-LF1&Rf|B#k3aWZZn0wS0Rm1!2t;Qo1>mJmzmz<^`QX8gy7uJB-IEV7 zA_P@68<3KSeDAHduHCpXY&K`BRdU~`4jcXcn{Vnc#J)f8x_Yt5$cT9wY{+`v#2Ko< zTW`Kefw*EKdi$MsX1_IU%gjQQfKpj0O#?5%Alvm}IYBmIi+eGEbInw2pCPJpg1DHt zwELmt*TU3FiHOak@TrsYl$E&-=hvV#sc3}>6`EDmQ-Zshc|KYLF@WTj zlLQ7}mWQ8=gp|NJ_Ru{i3S?%V7*zmgu750c2a3TdqE@EC zefgC?dRsV3d&bR!*Z$y}EGy!n!NAu)0+E)Fft7kqR*_f6?xuoX8)qJz2k-!>E2LK@ zz(`R;&f%P64J|U7rZ$*Xt`Jhkz~d>(T^gvNI|ig9fmgMynF(!x)eNXW>Zn3awXm|X zz=)%0MO3juECOI%f=v*G%|r>Yl?QN=-kD)=U=3QU0C0thlZnFJn8buBqL=&=WNo}s zQtH?Y;K4K@27s8(tcglcu8AaCFkWfDaKL#D4A5k%gcZ!FJ|#r&mxvS<>`Q9SLA@IZ zTKLk5poc8rK0!gTa)OAP8>lk_DE8ff(m)`pPX&G5B|udh$CKROPzK8eY7j#_)>d8C zJvM-f5}PVD29O58nKuLlO!}qv2h3-#$I#09TgF|lhtNZUQVfn-^eS3cir%nzTJ_gk zS&O5o&pT;|B55DvH8kGTt;xBeQg`nmS`${Mt+TvOa^CWLi~~5_l*y%6jY~tt0B{Vo z4?gt&(&b0N)w=p1V4_nsaeKj4NdOj`tyI=x%7K`lZ8EQF)XB=Mk<0_K?adfvvQnw> zwAu1d@`*oG0H)-IyELVAk+qcDE``i86Dlh-4ci2TDTdiX7AM;D08kCnE1eJkPz7Mj zMmO@d@-BtiktqR?g9IRDQV%CgN=fBgS`t`K?tZ=H!9<_|!Q6T8?^3gtv7s zie|NALtgAy+!v1`Wo7osVZZ+)gL?O6aVBkzGFf>PRP?YgK5oyuU4&$_h0J>z zvkmSJW1QUF!_1p=V3y_DR;-Eym*bsZ+2>HSHzz?%1We?qpnRy_M>JN#n;f=Kvlq6u zM`-?-0w|;qMoBF9G{Z(CValhS@_#-GsEw)0J-LS*8o9;DwkMOK*_4;-Jc4j>!~xhl zIn3j7A6MoKh3t83bm{ibxOMl`xVy_<{dCDsg{6lZDt6newLLQz4Q+!`_8Ps|*ROoeJfrR9Fa?)Y~@>T<};xN}~|WTp^n+U3AH^OxrrMdsArvTc4C*$_}Ng99`Pk zWoOu7+r*r)A&hy(Mq&O@KrR3wc$k)ALdt8501qFuRz5^!K1=KgSEWe_YpxKA3c2zu z>Qn{^&eKuiDKr_x#2%so*O=v*N)09}!tO#rUkb%-8cn+s(aoDTzkBD-C$C-0%&%vj zeDYhbe(SxBE|<&IdVR87=1z89cXV)YbFoNBfAY<5e)RL77m;<}r;W-&C{S{@l$gkq zzy8{{pL+7in~y)DqoOsWdN(ed$vv$O0M3W1n6W=JW7FqoaM&SfF% zzGvX(ty^=qm&@hQ$HlTaUypGXUSM0LKQDR}#VlaH+uDVb(zK;?az?LoB7dRKL9=OI z=3BhIxYW6Ro{?ed7!}G{wA;xvQSj348Yt`d{=q(8Hf=g3WaX)pQV3w?%-M4H`OGrw zUS&$x6cmUMviSNKLj zsH%JzlDol?5?3NpWq2-3t{~>*W@b$E<8by;a>C$7CJ|UR&L#u;1Ba9L+`9R>LEt3h z27xmeurtWAiHE%^@j=9f7zVhxp<-VHLPqRs$btJ{v|)lcVHpf-IRx~Ku!Nde4X+vr zX1b!f2Ez#uhV-x&>~02fCI&GNP-X7my+Qy2iy)yE;^P;ed;aAwzw()1{Jb>o-Qqv` z>_@)-&wuyT*S`0WYmc3NpW0_DJ+#P6y#IcE+Pv`MbvXUzuYT(@UwFQ*uXp!Wz1D|E zcL!?Ck4>wleaqor{_X$gQ!l-6_JzNN+o#=|?|!dR?mX(fuN+=`^6pFGm3`u=+jqYm zD*|f46*Sy+H^?IsKQMdm&N&W`@7=2pQ9b*qPn$DfAisKe6AxA=*9V*)6Vw@Q!Y+MV zw-6XX0ISGUPyvmJvlGMF06K7VM5ujmREFMjm{f0IA?cw&WEN9}30xH*>4+pktnUDF z5@)MaRU0OUdL)y&IaehRj5bi16GT~C&`{f;0#$BAd(_%jj6ogTtU(p=nynUxf&>bR zaDqXabJYcO11D%NEYJ!T2y2GH1^qc=0UAteU=WLH5RjV_uh|?vkct|ZSM0}1>opqE z1S}m|L1KNMeWRd5)Dh=kFe#Kx)Z?*mZ&<)Rl2g6Lx?wsuCl!DgJ`kdMC4LYUf~egU z$eDEqLJOE{e*{^R!m;7r!P@AtaqpmB7eEq7tV12q)gTw{7A6D9MzvLrLJ@vnaG;jV zdy`gm33ITa7xjf;?QJ7i_x-Vot1eM@@YYcY-G{Nu?bt8GH)ee+L#M~^TDsmq>_<&~ zWa>(_@X-5G5bMJjm8ol*W=;IV;%Yt0f%vFADv!#e^3akWjWY(6Jl}t3ov8wp*@K@( z6sCNbp8$=AJi{05p{!Y;2D^{;dx#7Gj9|nJY~@@3J?tjq$8+~eCR8XOq=c=k`S@BP z0R*>@Ww{bEB`1x8ExnPyjcWQ~?o8Uv{x{bT`DtgOWuNW~X6yc^5nE0a699Rk-02XN$|i001BWNkl1ASB;MR6nexj5`av5XKBuSn(M}%^9?sqtD7x!d@l9G6xl+fH`b} z)k3+hcDpx&CRTJ~K38y6og5$k!5{t6i(mLcwsr!f(zl zloB(?_4?(nzYHLmC#D22F$W+7Ghg@XlpLOpAA9VCC`@BNIXQ{LAPEV{+{oG8s;bIL zPcu+8XuX6r_aIK6_A2L>b|)Q$ z9WRJ@bH_3yrIZHqlsp8=M|Q{tCpnCaI!z&p z`GVp>s^so&OjTfpCqhVodE$WS8W_xmDyyy8kWVEU%mU!<`SOIRGhrHtnKK8XfCQfO zz?f*(2CFJI^BL#La9yZ4M=5%8(_tK)jTsLCWIQY9Kpd~2Q{-jRH0MWL)o4|TSqX3zlLaevnut}2YnYli_kf52d}Ls*2Xav# zgeo|xb6uTvgGeP5gDdkgTFpF|s=&dhTG~J&)NF!;qgP}JqQFA9HwY+Nw^X!@jtGp7 zePPU8%TrGs|L_0s*FO7;|DktF!RF~Fu617j_OE~AzyACG@%wK)U^-+E^-0jXwEFJt zldF%*@#b6KyA82V|I9~!|5yH)+h%RIYP`j`R=2mK9xr93ieLWa|K;!fz5l9y;*g&D z`Ojy!)QH>rdHOrc@ zhSz{5?;DVi8eB!-dhCZks7@aU=}bMK+K5+x!vQs~SwXJKvJnXeC;A?I0adTp<|HbJN2-Ig_gou9>aheV z^O^V+U>$WK&3QyCdO*B!N+XJh3d)e2g3_5q_$W#*r0$JiLDUJ8+QyVskA*wdTK(AC z*veVd8w#?nVYyrDf%1LFfw_{`@D;ZLWicTK*cvmno~3nEh!EQJvS2dPt3RZZ#*YHk zTJ`}L#jrT*Pf-F;#{fY3`R)kYm!}~C@IvRP+%jqnW!}n2fgu1PzYQDjiSoOe{A&O( zh8s-hBhPwRB};y~KL$p|Pj%#NW<6qu3hw@`yZkaZfo6B6S?aYr1uaudGC0h*$nK74zx;ESXpjaogEc;J$ zb7Pvq%<#%C%}YHm@|khQ#b6c*0LGk*VLR|e!lZ~bigT5EVZ3#6{&kc9oAZwjMSto9 z06hb^_wLqRHf;O$;V;ue@`UT+2J zx7b>-R3{6?L*({IOf$4lba-lXp9U2|@Z<=g41$|cjG0K4+n#zdug9(NsehOcf(h=y z7!tTDPC|bM-Y++nEdlt&FkK1ksvOQ+T1M|Wd#`KQGT<>AR zAtC*LOh)!C4GiVe8NOfn3`!gGn6yatmgcBwA)0wpf`^T zP0S&0Gq#c~SIk2Q$!vyH0>E6Iug(d`D%}C7>$;C|v)N#|T(<4``S}3cx^?UIZ+{y= za;HFv0|4gAZCKXLMs>AXz4_*wS58ijj*ms8ZkFzrQhIQD`tJMhXXL(O0-(b{fs6<# z5e40BR0mJ~{3l*Wg+rRAaT`LIZ}3L&C5=qT5t%|EST;{e>HIYLHthPXL?LG%?tMUE zvosru4`H%4x5e9gxMYXurWwJNpH&fHkI zK4(8Lj)ayW0Ngu4t1f^VmW)9ea1}CwfxP!d0dfeD50zBHN;ber*c1R)8}r~=wNxoZ zI0y!3(4e$oU!aeWh_3dwqIe*P3=nE3018`CBNQvgUDnJus)&T!_3d|hsYxgjp8;2z z<2K&i^rv>+?dUq*e$%7klP`ScYwcJ2s>48p<62H*1)(^^>gLJ)JKbaY*6G*3_OGu$ z_2SLzA8p$DsD&CpKX~WftKa*~0cl_J*WkSlSu!Rns-;%C43qM1U7 zzz{#W%7aD$5ta(^ffx!fTpdRy5K&hLB2jIMD2o~qUbAJHD;HiEk^vqoD6ED;Fu{RV zCxW>ElfV@qz?x7qgvrIBGynwmMocLfU{*nfF?z8cm;tKXLF|giCQufx6j4l+^CBU* z17s3iEAj|{ndeh->S`c5QO1$YTEQ6v)GxI;V=!5SCl+G38k%;{2TSmoaCBY5L4Y7C zGaRrAK7dRhYJqu$SUV0tV9`S;(Lf$yGGHThWf4j%Fht3~4l+LgojW-oP-m}&qN#zv z3Kb#}mbK!lpciJxxk?5a09!)VV35_I&?|wNwW`~oofAyZsWy$c;S^}pq$Pi#70aNc zwR$9i1;ZUsFcA1yVr1{T#C*- z)W{wjQuch$?rw!`wHc$D-D)0CAAr;1lyJBt3U3{p?R4k;+wqLrEOYC(A zsJgt`J|cF>E?aw-9XJ>_Xa5A`7^Q-)RZtW|00nqR6v9kcN?}VB`_LCJfTXa?)+vE4 zE`FMcHdG)@C;*E+CeCcIL_=to?KN|9A>wPeF*8L*%>@m$z=-ym$BRIq>Acfte*>QHdvav#JsRf!PLKEEXq6 zM}g?oKlu|`)SG_&;!pg{NGgwtIQnE1OSnfVC z$kM=<) z0=&mEAqIk(45XC}31+B6Hz-imRZ_6<+8`7c4%A$^F1=Op)>?QES2Ob#hoH5pa9y$7 zdG;xKaC&-l^}2C%=ac8I-ud0$r6ERKRaVo<(@por{eE?55Ce3M zkNOtS!?urp2<@m^D%G{zzvs=>=HwG6&(xrQ{H1>wk3Z4Jum1fn{LHWZ>o-q&|M+$J zuC&LW{i(CB{4;H#_ntecZ+9wEue;UNczOl*$gbjZFCG8&zxgqh%vd{Dt**cL^gCbr zch{a;1AxZ5b{MOp?pqv2LFI~?+h{_hAk=xbl#Tvh_TKK-mgKq*`_)>#cJ=PF&$%CS z=ZiBOaYPPfOOz#269s}LfiP{$u@WfogAKg|2@C^z$sZ6P2=bJNyyZ1dNub0JaRdlP z6v2XQMG-+jAw*N5L{j{i;gFom`MUR>bN1=owO6lId8qE*wa-06F$Ty0!&|sGw|94S zeXOefs9*oqZ-I%`LD;!6p)mq?#t?=psD+}3wW*M$K*l2QR^HyfTR|| z*`Z*EMF7SQCpZ{8i!hdMP;U!SL>UB1EWr|#TnMJ@U;!!AuopW~2og(o1)RBGcAN&R zB_)*$ScFFEcHjqU3mJ`l9fK znzXF&40emj&rcNqpGkbn(`{%HY8Y-j5=@7Nq=5t&28YDZVSA2^n~-dwS1uhqu?nC> zJvbaVrddhx-0jw@%UyeQdi2`kT zy=l=Jz$`zco5qg<)oMlpAo~DJ-|CC*V_|H`o-x03)2#hug|<^DDig6KEE!~AV2X7} zdJwv*ollC?R2^}zrt@H?P0inR4!Nd1^RjIzcG9A%o!KjvmW_vsmMyE$$WmS5ZIulD zHUo%l0I(l2W@gqt9nNhe0BBYKKoWpSBWaNXEAbZVS0YqBs@pv2QZ1iZm*s>V@_40P zb*(>v!{L$2@G2B zEKD!*W#f2(4jf}E$GFd7HUIdz-yh@1%Z;l-vJU5#b_2nWZ+Ua22kzBzjnhAy5U!B1C_DzXj{eTau3aEUm%wo$hjz|DVF(#BzFg?ui;W8_COACI_{-9@8;$aT zOQG6Wyalb=6RN0o`55(BaEjVb@EQYa!BZ9>W&y}*&8$2>q6@H6)0D13ElXXcGzFRk zM9cX@FTC)^JMaF~)AvfAkG=BByYIYn0mRknQO-|=AOJIGU=O_f^2@Ki_S$#edh4g3 zeYQI}(fxkEpCTC6u5-*Z=6vg9Q{W74nx~$6YV*mT|MFM9a_`=~Z+z`*ckbTVn@PF3 z0o*hNeOR~AJag0h@-KV}bA!t?YuonX{5-$t1<9IJz{4R=o)I6b>`BLeb2Tox8kFT$ zQT{HknKoldxhi2f9o5D%B^G#VL9&*ysNE!a*3SwRh?x&>(}#&sPdPij2~88Mph!74 z%%d4lA|4jK*rkBHaJ80Di6Owumba;S=Nw3};fYR_vyX;J_lgk0Lg#dVn2@u14s>W6 z5t&&bYZOth319*+1810DQDD z#?o;L#R)MG73x+Lu~7jKQ+Ahz7i`mW9?e!F{{7zuJ`joI3Pu7N1gwJ#Kp<7HI49Lc zh)7!1-rJFeQ+G#E$g-8f(4VvnN@`@nZeUJplF`T5Vl*aCYi9+-)rfcQO&hN)tr%o6 z!vQD6!N(PK4)chpfR4~6!Gu$`IAUBWfx!eeHKs={4MC7%pDsE{t+)}x=x1NO{k6}1 z_UHcLf9P-#|McJfrQiAd|M}MaM{=j>|7zF$T&HKZNWOQ=9^m2Azxc~P@%cac;$MFL zD}Vbp{=Lofu*==W#c90r&2;%v#G8cEWGe_HrU!ia{Ie%$el7ui=ACWIVX81w$H-@w2*?;~|2q~(#5+aD@ zPWRk5?tdA$4ZQ_XMGNKS{Cq`~$lbjd{9Af6pmB>0NvGj299Rms- znJ!fVxdH&jgob5=vf=`Wi6ZdnWNE^}}umbG{2HRcpJs<+mmMUzt%TRWC3^4QaVgFvR4sd#Sj_ts^8=-F`i#8bfD;{xJU}bg)~UHvb?+{*>cd<;Qba?CK(4Fwc+ zwgmvXIe!I3-7s%&nnKIZd?OZCb*669F@3LYc|_*S^QqxYgpHm@9C~ ztL+7m43&LCH6q~{5%UUx!ZF(`0CKElRu8mQPON!G&1}xUprSQ^wbTnt5>#blslD6) z#^PXDY{E^!ux!*tPRlcxLXm$DD8ULjgyNGJJR8l9ilJ1*l+CH(oHHB&!Ln0E2$bDM z&qNb!)-d^e7a}G%pB_1tRD8jn0?`7n7V30Buxw4>ndFrL1fqu7%-uaBm+eC7qClRr z**G~ihETi?56mneFlV!(86TL1o5B%WY?VC|9YpJ;Y25tB;tnQT@-xtu`%X3lPm}=a zpw^=i5gFi4VlkZ`3Whnnhx86IYejmbjWJ{pmJ4M;vy<_j_5cXf z`Us&dsI2_SZB21>8X3vZwqvv=sW8TdFtUuQF!U^)<2IQJwjLiq(Ibiq%NQlz=|1+a ze(w)|_8fcnpU_O)OC^vCXhVb}dkK;zg1-O~1rt5<&dBZF=J_>aHw ztN-Y4ee&;p=3oC0|4QK4-s^5X)c!?4rMuXq?bh)>{{DY0j!64kp4GbF{+D0u;?*}& zeEYTUG3lG1|E%D7O}E?l2n0(NP1FIy{C)M9Nk?#jLq@aPNa{kS0HYIkpIjh83XNg}Ck8=b5&&W~fCKLN&L z3@C6$okI6Wfeg~Vr+No=2_KoG0;-+ZI_mv|MxDsi<)LbXuGClP_GB&DCV4^>YN3)_ zeV7EM#A%bTmUtzDg2@m!@nLWK9~M*VM}uk&(Sa!hp>f8nt~CYUDu4Q-tw#V)1He=F8UXuhL_Y9o z#-G9g&zcr_WvyH?0eH-(ul&sw7*H?KuhoL1bC-H=BFMZ?Ln~nDSc&hj;Tb4L!{jGO z0SL2HRz9j|;jtDZqF(IQ5ZF@10=9StLJm`W@*`lYoPKECatEjuJ=w81HipFm(T|#N zL+_{NPF=WmpS=#CT(b})B;!)?`ho7~~rMZfV;&(iyzYkVBT?^q*etj&@b7Pt$OAqtG zRz+HRMpyHab7FA(7%U4HEU7vEX~*K^>zx%g7{9>L$;^FRk{q}a-?{-hE*SBun zI=?tq;Faf}|B`$uBNt*$23C#esLbqc6JC&WU>?mc&(A$)X5Oa(!0aN2z1fO6XGkL` zG>&z93INyvkIv6udg`e%!340;iZ=Xyzh5^EfSjGVSv)#X!BR9sMd2{z4@Xg1qwJ|M zuLWnsyj?qZ))OFCW4hGt)y`bOZS@pFHRv@REX;EW^SM?{q-mgY=K03wGZlXVg93_Y zpV{PpPDBWVDFop{$XaeA9s+R)h2-Tqm-p{UdX2s8gC!C-X?ew2wAH;(Ps>goY)`$TfYXf%g#6C<88tvk0**9q7#I- zip~sYAmtq>GE+i|$|MbVbOXx>MK4WM2Yh8tE!lux24RMRm?J5PB~YTlar(?Aefw57 zQo4lPLDW{`@ciAce*XTi|Km@Rj-oKay;tr&{K8w8?`}7-yZiFV>u zfAKHeBQ@kB11WZ@2`U@X9o(JPy}r!rH!!Tf{q`{E)9w1<8%ZL+A=}8Oe*rt~`={-W zcKDXchY5o@?$O^ z!y6@V1oqCOnu=4y4DA8N=onWPuRJwG9G$6oGR5UtT(q~SKnJJHZP zi>_U^WU>W|uz!>&001BWNklHjG|En!I+v>*Klbk?gU|Wj@6h|@%r~8NQ!}p5pX0W9ZR(QzXhOc9g=dVN(uk}+*5vp zX#s`+jFsb94MlNCQ4L#QK14I9M907r<^uf~kqO7{YzubwIIg&Ge{d|+g}IRc zo_Y4UcT!rwotHoIk?nR%01;gP1VmuHUaP7DuYB~Q$ax2>fJT~ZB{>1+#>}IcW+4iO;`yH^2xc6uu!Lyl zPZiI;u^KNNBZ;*U!fd@_e5veTBU3)(h6_x#6kC_?)mWe!qg>66dSn-1G#{@Vt_@SJ zfHn$&LKtV-QIWta0R{_JWoAd0VF+&Hg82CSRUpg&c40$Ju?Wq=jFg#Kd0HF#3c+jy;N$3KW@Djc(IP(y zNF$z|m;*C0+o-Zyg^5nOeWZx?#R!S_uv+6EvV(}o9u1q zKr$vmVyu+h8oXmx8o56hhQzodSb>|{tE zB0;x{uFoM6z^y!@{vlFGhTR|ift>ej#wt(|L6q-+_AU0J7wm N5v5I@~z2nZpd0 z$S~-j1Q!)ZG-^Omz+&VO=~plY?+FTSpvlow3u461AOvNARLvzB!$^HtCn5uxC6^H{ z!k2(d>^lOJKn7AZY*kOV&>55%gEL5@yBoos*#RP_&S26d7?BDLDo{i~9Sw}2YbQ4_ zbyseUii5691?>*p(0MF38=<|zh&`e=aq_`b+|`J)R6$s#H8 zUbXMK3n&xBAOvjtM$IE02x*Ibk1fOyS>gp;6?@kcpgr$fwF|a0voq=M!3I(=?_0k3 zA>A{66kM%UiNTivASMDp75$2L49p~~G@*B_1c226G>L$tm~>ON!jvgg7pp#nXJ95M z&GJ&mpS%Ig{HFN_u#maRDK>r3U9wCpt-{z^9`7^dr~I9?y5@&`IeStJ2v|-m+gt>} zN^3m>NJZ>UOGN;%iU44R!c!!fO60p4U&08eNCOV2|%!DK2!&^x0lw@|Dd@ya7szbocJ}bRjtXu1O74ll?tWBd(_5;AE zc`2lfNHJgu89DdsQ0qZ}tO)>enH5EIsF-aElvV3DSU<007w@BKvCbD>4zDB zT^{-sngD=S8NmJ=0Maf4==%(msOY7g8GsK5o0rj%CIIM%@<9}s>4YEnWHxDJVtlk!IXU;Y=R;riw@54-4jvkR&4*pp;om#<3dHxxIT-~^iyzb`pN@2PbGSuAQ z>rKfS0U042L02=~rd+}WE?HJ3(~4-xIRz!mGf_lcUYU>3>Z+&a+tc2Tb`|^+nrwvCr`pbC8gKthLKf9?i97C$94) zrpIoA=bdX{a!=P>mi{b)mva zmJGS7CCsOIHL0y?>caLSZf@VX{iVP7iw}M3Q{}{uJpcSxzVg)_uwJh(w%gmAO#p5) zZ%0$$LwE0(*_XcdwO@MWl~4V`FMRe-KFc{X6Wq;xB`bFSjeqbDuH5^+|JJv@b$)&^ z47*xqdkwkN}K8bHAn|@x>Rw5jc>_QceFjwR5^XS)F zTA0aJHI=UvqL|RMeC*G-4ByiDsSEQRAuseI6kuy28O^+{klhfbPG@&wE*vFuZ}0P^y-is{5snPv}#5e6z=p&`)np6@x68|F}hg^;yK zzaz{LdG@7ufhbIw4^aq+xX9b*f`~B(ghp1Q88rmriP-x^}%P$vo=BmHRW>=hDL@O37Zi%BB}-+SQ!R~i95(es81@6Q`jZ>T1Y&a zCI}QJCdv-lDNCnlphD5j%P2w=;1SdsT`|Z5z_rH+d)y+M*{Py{+ zkKg4+?tSFWYj5nWzx<_7eDrtq|N6b({nCH(&wk|}|K{KS=l|XRM0mDqAHdKL&vv&S zX}AAx{@efZ!Q1-q;k#e_leh1`{paVG41slV90O&70U^wqymO0l)I0co<`~QLBKs%T}K!g9F16@iIpL0 zq-2Uhwj$1;T|}4E7z}G*nMKti5ZXAZ0&&-(8FU}9V}e-( zCsiVGhPpSVkp48h|bfGR{124NwGLWpSR-0-D4gM{H^7~5era1v+6 zSZG#2gsMk^4&Xr&J1Ib-?&9XoP{j&zp$ZUq5cjpv&WFe{8XTmfjVvp21y~i_?T~`% zdiwt0tZ2m4yt5K=5mAK*JBLI-O^AEJUj59}dU-$^ffcZGBepw(UkC^+#Afc$NjuEs z!t~UT*(|znn-ou}Wo4rFp(=~1(4f}BhQT5{JDd0l-Fu1?De)y!<8e<&ga~^GKy2UZ zU6JUr6KO0pB5+Bb02$*gm!V^cstLS4w2vNASS45(*Y}Lr=%EPD=b6eSH*6xo1~58*hMF8?*x;|C=za7nJB8Pa3uNuKvFY4HKX zeC|@t0(LB3Zwq2lLPlMK4i~(m4yU+~hEO%5c21-U*uu;XTQ%&f)#c^oB6ztDN7~@i}P(c;W6H1{&bwAOCoFvH|cDXJ?-)s!TZ-fM&nnGll>AOJDkxPkiFu zX7kd|{0u7eEzgMF0<`_*U;M>hRYU*~!f3|Cx#+%!5Qz4bgWlP#TiLt`ArM*i;7(1$ zO_OJXES`F~8j)*Y@?!tRTwaZ)%mC8@0_JMOm;JfIn--i4k0DdJs-me{h+~lJ+NkBZ z*y0B0)x?-UnNpWK6Im`Epk9v7?uR+MP0@Tb(N<@ zxv+`Kmk1VqQ*tbh!nprbVnd-i}(5Uzm0OrseS zfoO@(NX+K8=)MPH0Ms;#DFC>ck7Hn7l(tH|MJ_Io$Mh>RqXhzMn(~Ou6VG&P_{V^& zWndbO&tQN8(FsaSYECQ;XQ;7@0Tx*lV1p$V!2l(&Fa+rYNkvQm1==2c>!8*(fOaI2 z3FW6SkU;Nc)MRJVz zwNJl#_ug93{`;?f;(wMCPLGsc0KX%g`iFPB?)BgP=fC?;f9toNm1lnT7heT^hTPNz z=FkT1P5^}f#PHwy!~cGJ{`BV78=Zd-1Z?kWwKza#USn{u(*S7WXqc~Hk)>yJ){_G6$rx-W8eL%SP!a(Q`?mES5(!WM zS(Q5}fY;z)cvLbO2yjEA+OWGCgvr#I0}X4Z5e%E2Sjlb00_Z5njs)*aE*Y)MmbPnE zW&zULX{)nb%R+umT&-HC|?(=&>~^PUE4O#pUvL2W$n~s~o$6Wu5UZOr zkwNX-j7{&-;UUX&gkH-B6Wu_q>-ImSd&Z9f)he+Ln-XBo2n+ox1DF)GniAGTqyvYoDgP~mP7y;Q^pc8aDQmnQhVvexC0hC zSYZHZ24F>3%ML53S?;R5795&{%0gjYg-+HB)BDGvSRjfuXfh-G=sxaeXq0#}fEl9BBX_^4w;=%!(A^@Qwxho#K|TA$VC^= z0if#wfVe&yz7J|Dgr;)Cnt*@+gju|2COa)yLs?xP@S5uH(e*W#e>8{cmH&0F)?=BE z&O6#V;1M^mlNM}Z0TW981tU06%mPBr6pkD_rdk#<+H8X`hdabgSc%)@yAd!6djZHk zp%r;n(aIsaP40&|&-GUL2rvU%$M{aIH-BS)7rQ=gyK8Iv>p0-GpFc=CS{qG!mUZJY zG)0yD+MQ`$iIovKzC%_yABUEX4*dWPt)a=Kn@5u~T<^qO{`K86+Iuiyp3C=&v~{Rx znQW-}gEw_%Sv=p+qsd51Yr=x%g&cBN`m$hZ;c$6g8`uwQs$C8jbm=-Cag0;gF)~GS zPE-&KW+vs(|^R)?|{nP@c@O+nj-*sKdeCzCNuiABMy6SVz+1zs;wFI`~Q1v<-hcCQl zqEO*Ps19L{qWCxkFI4T%^Pr3~R#gLP^|<Ii5WtsVc;er$OC}>8*XfFIWX{EteP( z>1ad~`KX+bGbVH?OwX7+<5u$>rCj7CPD?J*?S;?fqoGiim|&ifOR$IlxLMAb16iKH zY|l9aIFLPa!&X4CK-n!2=j>s*6#_-`-Lr=ff(Or@Gf_dH<}W;DV;sk(Y21vt$;jEg zX_~-|jtaoDi%7wwCU5D|a-HI@7v5L7&lixZI53Xpg`ee~L&zZnW-@nkr$7x81$v){ z*#|9&5cpA#zN2TrIsh#|aE8OI$DY`fyt6eq)OSvb6r~eVb~wnvN_3fg1p-`1^B^t| zL(6mp2F!^rKpTN-C#_}$5gL)vb!7}BP*hJ16W~UA#KFgc$G`YTpNsM!DM1p5s5yD#EB_k)Pm5#}TofXtsWDZPg=4)g=-X+!B$iTO$%wjUXKNhQ`69q@qR& zD}gcG+#v!e`N(Y|oDeBtBs3U=+Y8kQxqz(92WdMiIb)Fp#&Pt@n+?S+1bB zh(;>08CgxEgW#n`N^n305v1l4d8gVkgyj-^0<(zABrV(kwnPf^2-2+)lZgxw@qt0b zJjodiV7dUy;0?qRMEpv1tuO|qWU%$6H=u{ATS+H~5$zSMfkNfBAd@zrF=->XqquA> z!*`%}EN)^PslNgU$`V^oAb!Xy3ROEJ87=JqGJOdMt}JpQ=zAAIZ0Qkv)ZuBtxe8p* zgh${6k_LBHH@eH+u45QHVfZ24G=2=g{wL{4dXk=`f7kSWnn#n6kmurpmk)bpeV?1; zv2IY*Dkb==6I4oDs#^+tA1$Z6R9)*IRZY$LF$tdA1d&vlqBH%WlagToo+Van;f5-At zcE}H#M|m`u!R&bBF+DPStUcGdW?pYB^=3Ps|5vOiv^Ze9lnSG1T;X?u#U=1$dk-gfgz^8VW)KR$2xnRF<)91@#Ft zUo(Ud2pJ&|at?*_iyT6*oRM=g;bL$%H_thjSce(NZcCKLfC(%rzJ4;(tdQaEW==&w zK7`4;(0w!uA()MBM#Pu_uOjkQaHt|GKOuJrBu!X6{|hh|06?0i1SQ}SYmDo zH^e0p;$o-|d@`^NFWvP!P;-q!q$X};NG?!9vXQk(?cR$rhMp1Kg+c`;J7rR3B#KHA zMj#Ofe6WG}!N4$cb5&gfJKwEZfpH5-PP?Qh#17gc?wtYgC_8CbSk0ljc1mQUsFJUe zuZ?!ro3J?|Q>*S=!r_SmZP%*ELxV``Kl}1WKKH->No&l4j_|QhJ^SZh>{Z2Da%Lnz zNx%4wcmL!YZ~x)9?tkv<{`NWXR(SWD|LC82e+D$FEz>2Z^W?j67r*$qzY;LKAp*k` zM1UZ6Bg8?xXC4rnHhSutuKO-)tF~oviElfgy6*kMz26P@zfA1H8BBLxcxHP(2-x(@ z0Pq&twB{oWlH5)E4P!7E+*mHn!9zilk`1Itjt(Bp!3IYF@8Ig3KtSRM!1jQGc8)|& z03nX>CKDs&~d5+{`%WarFc#%SH6#vKIY7tVtI7Q0IONKzK1 zg8K$~Y)`Sd;n(hfD*E0hFEn&}m(Z$4crQE}J;4Sf}tqZPLHp@A0lqQ-_#-d9#*P!XJE?Y6Xi`v}UtBz3CV~|$r*ch9 zx=wzmwB~4(UYCaP^trGMGys%Hh<;E{3z%tK6LGtI%dg`wi~*RGstTtmzspNACe^AH z0E8yvc)|eiApqzvGk}Xr!>mO$8xR0a&j>&(0YGTW-~pJmx9DJp@^z%kSM0Bq0z z;Cmx5NzqNw538%7%(Nm;R?>b~Y;zd3qNO#3mBdjB)#!)X&U`r9b_ZjA;M4RrT!PMY(-k9i4z|31&jve1~4kuUtAG5UTVt=3p1E{2?j?P-v{4?E&0zegcs_x^` z&XOM!@8x<67Z%KK>+K9_AL#|M;U5U*QNb6sS2K$XPf7v zp*(c7+_?%^dF>guG^!59cnwjSm!a@{*k0_Afq>d!aX#z)(zRT?&m7SHDfU%^zn~=^!3+XAAyyu`u>WUGtdy{>_o)O z<6L6{{LR1lH@^P0uXDjgC~(v4)BYP@`}zy7{zA=A3v=xYe&j&2S~a5;2Rf#p=FD98 zV%J|`Zs+M{^X7NId;8AqrfCR32Eqolgk!)7@X^pIOpO(PDdDh+v zL`$)y4S|AtZkQG+{SbnCMn*x_rl_4C{AAo-4y2scOm2xyR1EO7sY@Hl2`~(!(R;uh zX~~95m>`;@psFnD)DaI*Qclbf=8&~v*DBBj(>?17IFU_G38Vwr3ayD;!BupvfCvr5 z{ca_q47jd^62=q92qpyt0_VHSca~BFQtxRGzUYO-Vx~bom+RI zX2g{4J#+fn=kVN1L)-Q}e}uv2TeJa))<KE2+b7Fjc(+433VJAP&8-ZnSjED1x_b zJ6>L%w(_nD7%SB?rar-A92hIacc7Ahh={mDT5SZ$&){wx%%4)rY*|3UZ*yv+v_GU< z#uHtwC+SIglAfgZP1$n}pxL`Q1Hq@Y^y90tWz~IzXU#uRElb`PZ8=`R|A3IzHBe(& z^XK~L%%3WZmJBQcrs&@s|I-p@WhY)-g z*jk#DC;i_;b#=oQK;uRm{yUhi-dP{20ik-ymk((FwUyw_d#`7@sR7H0N8nwZAy<0& zRrkMtPwV!~c-9gB?g-T?0TO2NT?mula{(ofJV1{MJYZPYimlsr_?eG>E@s&R&#a7?Gdf=V2phsJNuUns8>TUzf^gzc`X$Iz>*lg~FpE_Pe{?^Xv6_sXb>aUSJ_GQ3FJPfoGq6_B(I9QMf~D zh8g+FKp@KI`*B=|S6z%3mzO?T2th~VKt2NEALw1~;OvDG?%r&^4+#H9|@(d)AdY z;926{J+hI|4!klvYS9k15+2#$tQ4bbAnON@5M^s&%zU9x=$b^(T>u-A@z&-!*Pc2+ z8Qh2r;0`e1 z3|}es9fC>j(uu-USd}A_DgYOA@<5`h<|Glj-cO0h)Immc;yS2ANknl}GD8RN0fj~( z2NGzl3dW9T*Y~%Xdk{bjxzKbHp-vFqS!y6aiY{tU5g{5dBzR(4oqHSe+yQCLlO@ZjX?E2ub~B1u9M<6h&2b(=t- zYUp)EDRwwZ`^~rSy_?s*b(`Nm20mpA|v(5Ex9~0>KgSyZkh%JSUiIngW*E5 z1HViJ(Jf>vv5wtHdeV?@yd`3#jl==eHrk6sV^#uW4g6`2ftc@`Rb&8?^|N-x6?xib zU{W0dCgG}l;ZD1->bFiua=G$3V9>?Z1$Lc#@0ONh_Y|ZA9O{3e=*2iDV2O>mZ_Gq(%K;5bKUWUGfmYX& z$}c_%co4Wozt)obhn68vvl~2!J>+%Uy*sj0`0JyXyd8xJg(vr4y%W>#OAuUID<(vxJ!mm|0q~+MBb#aR4y_GpQ{Xp10+2xbx0wf)(>W8zFZo zv$UwBxqW<-PYbw2d$EuFbbbs~d90^>zsdC_tKj`AFE}ApfM9UGib( z>rZyI3kUw^GagY;rRJg*Xydqwg7T9y5Q_65Ox}D)Pv48%SN3HC5cW#%^FnB$2xUhz z>Is~c*@MF;L}w&5m8D=vkW|d85g5W=yfDw&Km(BVt1S7;r^DK zQt`x}31x1^6L6M72%}j=94L5ZMgbMExsS;!VgMrIo<=w3DunEaN&pg3a?g@&TuB~i z09iafxliOQqDf0DgI|G=k|*a-Etkq{w}3!Qo})S<)7b)rprc8}35fZT?qi*d0~;G| z7#FCYYCI!f0VC|nv^FL}M;_gT6$%3zvy)b?VxrvGN=V}B%1~Op*yBJP%bf^<; z)lVTSG6(NSqcC*bKpO)Ij{+i$?84R7DliD{?9Bjj6>>L>#I*xLWF+EX?EqDQYXuKr zKn<}b^u3*Y@e7ZC|Chh^#V`FZk*T(Cy?*h_|KJaQ?mv8OaQWshy~{OB!CfuB8LZ>3 z?k>^2`3eC9{SSWr7yj;l{ofP8`%_{)U2E_4v(0tKQ)uJ8tA#wLC10*6CYePt4vU=YR@SSz-qEdg#O zLI%J|e1uhiA_~*aG`O|YJar>b57}a98OUfQIYE=i&RNA8btPfdR$KwN-LPK>dIJNX z$Sx`dR~0uvNkT*=Ua7AI8-NFxc&$>y<0OYKJGGU;K%rrQJ{v${tn^gzfNU#(>IEng zpuU1D3x=U>nyo6-ub4WIRa3uPqw7(LTcj15k%pReU}=?~uDeaN#^Z{m7W8UoEPaiu zNN3RYRIUc?SSrHK`sBdi0&JnIOr$FUdObt^ZH{jUKO&+Y#Kypx(~iJ~6|V2AJY`4M zJ?w`Q*4FLR0#@hRy>j#WS&-(9{2jUA|trzJPWqAQCPb@;z#wC#m+VUe?*5r z9w`*4L=a){OBIa?qiVjDFOB_y*kgKlAY&6`pNwidHakQ|V4v85SVxr->cJ5g5knl7MO z+;TULI*uz@-8DWRtJFZjz;Hs=o05{E-U2;52bdHdl0(UL=(gN!xdyCe4!!j3oj{af zr0y+b=fZC4GQxq{KsyYPpu&>3#kYVdNC-7VBr#U5l~tqU^CN=CQ@D_?pexrEHCu?Y z5OhTv3@&=Y1gj%ZI|IUih`IAf0*7>szx;Cd<-h-BBIz9heCbEu{M~Q=Hd>W>+YHaJ zF;~OGjXef7gS~tG@OKA&c;mE@v3cW-&wl=|{A;~-(3j$~SB-DZXnWe70ZON@x}O+Y zJovZq{Xa)<{)F>=F;$$<=DkMNU-*%~<5(*?0Gs}ev(pGtf@+M2N!>ge%*A%Xa6ECY zMFdbNn@gmvh?1%qpaL1m#o*kHL~C(rC`toqM7S32>V~8?pn@rM1Fs-%qy$(bU^5Uf ztQjf{@CeT+QB(!20!72tmB@ghcDUKb&`T$fzyc7Ml|`Llkx5|?*v4V1HPfJ|U@BTU z&|pJgiyeFm>y>N(Tx%1B7)ZbySAaL9Y}XfXA29llAAW*8e#KW3b zW+VcLiK*0A0--!d#X&M!K&%~}XAp#VaFC0tVC~ilx!Q?f2PDNxQIM~e5j776=Ns7J@ru}qHiHk zz5%vk5JYzyWUKM|I^L_h@wun{zg+s0;A+(|0N@<~8E2f-wQ?x8H0DnL`-p^jBR4K9 zWaT$vQ)s_QZ*tEu$&c4%fWk~fnm-d3Zp%!t%7>J1o6Bu4UQ6Xrahbz1F}d<~rt0K- z7Udh{0qtduvbQg`DgqQ*L5ImniqV+gN(1|MP5TBc%Zc)9)<3EWwWF!~6N4-r6_WR7 zR@y|lasb$A0#MEG@^bCdo3yb1%)4fds$xHmw-0)BSDG}lXy3N6;E|Ot@y3ElM+Kd2 zGL!>AW|ie%m*M7;M>frq{eiSfz@+(=iAbw902nO+7={F3)dT=>3(Op@iK{jD^rqk2 zjSAy5LIBP>UJA^!MI$iJrD|e7<^2i3f-ZYn&y<0stxoG0*dz0&@(_>AaXG zXIdU2ei*o_${ua+~(uDa|#1ELvRYBdvv;QM@a zO5rHe-Bsj!L%7|Zxv6t8DTLyXvb=(7ghK#var)cme}1o*5t$d-Kq?i5rpp@5z#;{J z5*WscI|`v2=LIQY_DOq%@O;cxGlT4-reT zRD2$_fq_n{2zsF-c1>x=Vqq7hJFOi4m$3w^N!{N?Zc-uK>pZx^Fu zB;r+FpS3N37U%)@l>Jf!xX1kAI3k2yN=*oV;d{ULkN)5fh+v+i66Pv*hvvtTo1I>) zriU;Q0YDVY-IEjX1dy4@ECuR?mOmFlW{X-@n4!bleu&v_rp(G_ zWa+3JTr#D-x?(a1g)l#%x{d)Mzx@f*1vWW?yJu`D0A|QMsSIyr=G63VAteMwaOO#8CV&CKqfbeRcB-v z#7}_@+?C<9J~t?-86ce?!pu<_)dFQr5FK2^T^cg;s8>R3G;rjFnZU{6fRX?XiWS!$ zw-u-o4DglejnqVX;z~8hX@m?criu+?4JbyDEg*)i&@hNVTceR{>n>k&Gv%+lKWS(U zt=|6rHxU2n^#?sVx!zoyzHxg0Gb`;Y>oxXVuc^7$P{)qQfI0rXzw_^Y{kOiU{U0bU zgzBdLo>yOgg`D{OO+5U4=s7MgbR?`_mCyVXe(!%~hF^b&F8!x}=HLAFfBfZ!pT&48 z-S)J)516xvIP8LPV(;F_+pVGoxpXxlHq7Q%=9dD2GQiIwn$8_9lpR`&cz?o1Xkf85 z5jS%ch?{`{?oFi=79#~k_R7q-z5xs1t{@d;3Ke<7^)<93?{(Y3;Vn}fRNP&Ah|~b! zanN-q1~!M-0Cr(G2+UhUCw&INgxCQ>57eew3(TQr74sH-OQOzOhC<;UK@Kkp*5SwmTc>im`C^7za3k`rSQ;`MEE%;RU-7jt|oQtdauObIH~1IwIdgWI@SV* z^;#$N42e-efNBrvpcmlB(6xH1$s;|jbwvtxcNoK5p_b67bq{Nt#o?rr_oKesbtkT^ z3IW_0%sOaLyOBma?s}~$>)6{_*KGzRSnX6(-%H~VcUOU$IpRyQ)*)`>yC%&1f~)l+ zy+|+8i}c)d!1_6W0}eS>MZm#=EpY@N^d5Q%cDXt!D=z^Ns@r9!K0Og7huqpd*IV(dcJW=O}@8%g*ixKiOQx@t-BP zeeA-#CbHu2qMW($R?xCC!O9ED)rfI~+H?O#!)QtOT&6>%ZE-ElhXt)0BsZv_o)85f&#nirYpl5sS3iz&3nqsvqKyL#dHS09SOO*Gh82&SsX$2T549#6hn z=l}rUc;}sU+aiR`X0rtZI04Q>Xl9%Ug^tzV_-lVPP(VTm;fr7R!pYL#5SVG9qycE_ z8Y!9OFkSfTKmOxpKHBKX-~7y5xxXhTYXI&(#9`^?dc6j~m5gRIdA(&)58+TdKX-5q zoB}P-0;luWbunt?xMVPKv7yaU{mb}<*=RPyTZ{2SfsvJEmMI+8yA+j*VVZ_GC37zY zB__4_$;mEMBKg&YyZMADIkHE8_A}xtI{=pFEQgR1DrRI_Q!d$zDxS3A0hrHDh0|QM zl!yWXay&sZ*U^YL5T_hwF%!Pr0VGe83VWU#6ojjB9K-A(NX!%{zpSCE${{ZoM{GCC zysGKaInMESC}bx@AIIEsCi3}JZ7AL#g%BvvXpZ8g_)b-ALA+x?*M}u=tNzaZvt0=;QxkZJUH;!6x^TR*XzW=pra`t+A`O;}G;g|pKcTQhlH}rIP_r3o8 zwC={!2i4`LxjPSpD-6#7Xgvr;=*fTa-~IypHPTLL^%Fn!*Us;s1C7!fAh@(Tb|4pp z!~FhRL?4pBFEDWT^Z(hu54|!S4E>M%)gK}V0D5gr^1iz3llMqsenn9~_>AJBuHi!k ziQotohzfCSqeXx=N~};&gn#G!ipHW&R_nX`}g0zy#IZV=~Cf@ z$ZKwBu)Lr?WK0<|!_CDd9)Mdt<)hpGdN?En+q0xH->F=Mx3 zMPkk@%tp}ROa~F}YaV;_8k4)ggT`91VkMx4y89Ub7w(v4=uHM=hyw!Qt+BYbkTqm* zzUs6#1fr+WAy8+iR=u?vb>P(F3{C8)6}^Z9sC%rqgj~c3g^5OinpeO;@(dzE=!ce| z9YvwXkS9aGiLnwq1)eZJ6T1;af zb{5~IG(XobWD^|jNk<#|zXgAJ4xn=g?mX}75gz1s)wKW+&ntg{-qP%*Q8JSfX5P*0 zZ0NJU-kg7SaxA$yzQ^(k=FS9T-LAdl@+?0g?JYVDz&s2kb0^JxevYY^D$;EB12k&R zP^4QHelG6ze3Ra;WnZA*vGZ2PG1 z%m?1Jg>AjubIW=-81Z?==Hd&3`$5U2Kjz+az`kM2S&3Afh2_b6n8Kc?bXzL!W0^{H z28Td~%|9&=63x<1IHciFfnhB>OMqhmjKU!}vOrNKszQf_hr>X`Va~IByT zafb|(i58;?fH2W~0Ni74x>iJl`N6BN<_2_a1AvHhw_Cu5rfn@{C$i*7?v{azJatRP zoE=i1QZZ5sk!qp-F9Wv#f?ObsWxPT^EQ;JtcRii7)26aU6Ya>YPFdS@Au&+o%9M%`boQX9$5AVV0Q> z0FZMMb8^q|PXbY324H4^a%77Tn5E*ZL6$4cqFNLvBZIm45CY}E1 zHjb!VJ5B~Dd_~v_RF%Y9HZ_ap3SE(ennrY6^%DlnS_8~CRHFe42T>tYz|D3VNdX6$ zvBv~BWX%95fQRgOhG;Nz8(AP=07gWWkR)JaV^e{E8i+YN1H{ZqE?^)B*dsv5Yl0J; zU7-_xuTVH?QNeRGMbyR=r8&A5^WZc2=_^Z#}`SQcZzy9qfzwwO^e(T%se0lTk zZ#=Xoy%;M9q|WV+|E-^33^K~wZ+{Z(ZUaP}cLWRscTy%0qk9Dm*9zhSyz#~-+x2I= zS}yCWx4-Z<5QQ|o{7Hw@a>Li(@whe+IqsdWT@{kVm38F7gv~jhniW$dv;;8N+(bWg zBIVjxqK$@Vl-$rGM($*~h3sI^p%Mag1qLZ8sfdyo;9#hd5<$U^r~p(=7^)Uo)Lh^& zRqmPDprjyk6$7+3xU-oGk-Q4C;{xWMIBAqtd8hOA^}j>VQ^LRODGsyqwEgWLR-Sf zN*YrY0HDpf@fY5tS-ta8rpqb%Q!b zUO_d=D1->Fc?UZYZ^Z?Knov{gP)18~1w8#OT{He9D6FfS3P4r*9yQTRQ2+oS07*na zRK|SK2*4y99yb86tXi_}wd?|BzpCt>M$_m1A;$`rz^OMa{ zDM-3+*pa1@?f0dW%HNliCqQXNFSci2%YD_0-({A-&z^(XAlW%_l6M$@+3$7RCjgrp zUka2e0C@J;F}r7OW5VoCxTFuS48YUg0DLg1#U}t&2mmfS2C%LfK(`72K5@;tyRwG;3A(Ig0u_4j0f{Czxjhgw+W<7J!%{9J!wpk)gb)&ieHYS#G%Oc{ zG&$=PkVlTP7g8$pSqe9qy$xqbYk$oM$CliO%33;@4$L?oIqlEgELV~!4>>v)Zl`qT z=0~L?6eZpMsnlZ+2fvnvU5-z{vJ@<_o_(gHyIxUs+Rw?nz$#jmr$kD~BkC!IkOF*~ zDk)@CsOUvHoZ)+{Dv$Z0fsV4J;)1^~4bPqOlXDMp&_f`5$fjZy9_CVVu*5LU!UaSK z1PZqc{uriIgu`2W+!kimf>@Ox2nx;eqoTsC{o!zI7n)U=PvkV0Ohtq~+(NHV>|8#} zAzj*>%ORqR^Yef9>%abeFMlHc`pPRWfB3im4<9{BDfRs}y)-rZ z^z?MM+qJ7YnR`kcf+qye(fOv1tY+ivQnKmNdl07*g|}ch^iNz0u>$_%86!&t8s+l{ z9*tTmvZ2Uxlye&Tj2tavkz@AFX35l{?DUr}N+E=ld=hS-F+sO6YhF!bno^jL#e7wn z20FXlAq0eccnHDG0#h;%vltZs#{_9r6n0~da!BJihCo0_Zby&i3pa{FF!StBN))E( zCD~Cigv`t`8xcZw9t_O64Vb4{Aab)n6hdHG*{DdE;%j8`YM36BayEoOK+5v=4zAeT ziHMPBU82cp5&+DcLKw}Ys&YugoG0oiToL~nASIYcGs0?6gvEx}rjmofk&?>*8C?X! zXdu&CeP9|;n<+_tXtfr`XcVf}MAO!(@0l3S*iWr))Rj%Z;uu93+5%U`ZNqLdHo7&w za353M)mgR?!Eh)-=y_lay$c_HHc8xCj&@Km7s`-k9Tt3If=n*y86;j{)Nx} z(Qo?Z?DUnFv{E6sH-t|B+(m;#C8El4?^XX`W!A#Qs0U8|%m3~_`rz;XqnqFT=7R@s zGpoVQfA|Nszx_`XVjnz&8N{L0+3TMi`akT>8ycdSfngS9Aaq+5sj>Fn<=z%1pn9;X zjt1)0JJlrPAdwY2c8U3PsVfC)shC}jM0QMSERAvRmC)9iiALc{X>aB@;O zl)&1Itf~;<8*;D=Fhmzn598|?zgkmL zWD&N7IDweAI<$fye8b)j+LN9&x|Q?Cr0!A!csz-NFRU4>=)@pdXZkF|KBOEwo?iVs=){6TO&ngz`^BVr>sAYTp z^^SG?ZKUQH9oheOu*$rR2jtcLvgDsI5eh`*%lVnSQ^=eHNZD;-K0M6W5Q zKNpw|^5fXtcNibX7{K#Ut%Cs$#f}o~pMXN_5j`&uqT4Af70iVc%!m|lQ1vv+JOLpE zP)KPChB*Hn+T;+Tn!wxz1wNXw1>lQ<6gC}lQ0A@49sqL#Mh2W z3AnxQ3a%LdvX6Cd#y_d@0K(^@N(`1_atW8&Yu9NyX7E z0EFNnsW}nZ>0+N)rebC?8_UaubnKV9suap{hdR zJDKsdNjxiuWt@9w?o5>2147ma8^za3D7>paPsNQ-sq6(@A+7C#E>Q9@ZYBDm+ z-OKju15gE1sa!{5oS3zZ{IOzS6>GLk)jMy0>VN$QPkwYQjj#s z26Lqva2J>oJG@p`iKewvG!p{gP#>VE8jfb8LV-1lt2}|8IU4W)kkV*BX z$O2GQtsP8m`Q^LO7D@&o*)%F3n7c7KL3gw$=*PLex|MCFB8Nq7)n9@Qy`MGp7Jag&B^w(?Z!4mw@HKD(x$)tou}x1;YZs6Mk9$$6m@QL9`R<)*KKVUKR*o0hS2sPHc)+Xn>-f4lGN zD0RLUnaGKel-0*|Z*uzJd;ZKMom{ME<^Gf~GluebVJ1Ums!p7$*qbYp*C^~; z<>e~3u0W;YuFWWzPIgR(K+gtC+`wrmQCM~wfysd2K$!1}{zhrOacao#+ZMtx^CJPs~ z%|pgTyq!t-wRsLI@G(mXM_jFGcQMZovd?6h=iyliC1`TIjDH^LQKBgyrE>j|e6D;+UdxR5KFdX(oxDELJCcm8v&*%K|4H6CV|_AcjiDB+J3va)yC22Vw+ z(qh8^>@|e2yZQ`ys3;kebAPi<#60a$ADvNr{kZCltQkc)0aL|Z93)ip31Ca_F z9%*SU{%d0qaWBjn77244LMl0x(;yuZwJ;xoqPoS6j-La8QGtAgVj3*x!M+zn4_Fi>B-BEnU0LMza#-S z+2;{Rz!q2+cwZ^^o(hC<=@%FNiI@v79XuDV92Fx~jsg{5vx#`VC-hx!wsdf|*aJVoC@!Z4_51pOw+fJz%14A;3}!(}QiUdpVm!8f_wL@+2^yQp%2d zfx@U7Lhw0YBIe;sZdtY;Q(eK_rK+;0q#8Sb;w64ErNA=@%V##6Cx=rALAWw=cU!Gi z<{y7l%MghjP)2R21eLOPRo1(Lk4k4X^^Tgy(aA^|Xj}%NQGNYyeDPC#`+JS=6eC#;z%KtBo_*c%6zFtQ*Ugm^ z36p6s>9tBYe5JdLcE2EK713fc6et6R~D+kD`hnuJOF5e&-V0F#gjkW@@Rq@o~!8{id0p)EL}7FHrr7(1BQ1rY>u0hv3f zhWM4iRe(VV<^(8Njn1IhszVH5I3m!1d(tx}1<3RSv}FvY7Z8Ovmanid#Y#-zy#vIq z!y2q?;sWxhk%^KCIk|gH5HgHTgbvy(H4G57rb=|Be&*2uA@UekkQ<71UUUk!#=Uf` zO4RKO~*hQ@I9@y|wC< zVAMV^Z)jSB)-W`UtC2!TZ>W1p!&;i{fO8gcTQ#y%RZ!}v5{%I+>tYk1ngm#A3@T^D zTXH6PU$BDl29g6VI=_lxAk}zpr0e#(bkTUh)q0U$q!;N$dTz=q?T|%(a13)CajPaU zHywjn1sHK~M2T}P@X=9ecQonn>+_+RyN?ZrPGRY=smo6D8O}-v$7b;3&brd9|Gm7` zFY8$vo0c!POq5ZSutvBCzq_Cwy)+~VUh(!rwoxRert zDU7~{rHb$Qwf{$eDWSw(7A$7&?0%T$Rvi+ZkWkp?F4X3B@Wi|`6u%yJGbM!NDdjkW z0TfaQVfICxGB1E{o-)P!zoWP1E^zh)cQyr(oznn_-m@stu0LUDLb3*U38dim-_b<5k# zrJMz+c^>w(>|d@P3^3E><;B;&_O)04{GZPyR3g9jYrpnmfAKGFE4h05>?%Va*=uY@ z7A{UsPUZ$=g4jR)m0$VNm%j88QMI&chPz8WDa_DP#*zfMymz@YH34TKG;O=>`=#*J zYIS{m4FD9(#)>4XEO8b!pRc0TY~hRv*1-EaeQ71z*#a~(uu34Z)P`S%#t!H8(u=Xc zC6}MdOK}NorNi;{8PB2+vI4x#XbXi<%9ayR28lAB#d{aIkdh-!E_gu5+rGp%ECkev z$QG@uG>6r7pAh$a4hJ9vcwz)cN+Ae`s3Q~41=56SPpa^iiCRRYEH{4NG z0Z1v0qaq=PIH5qa;&B{PN?r(gWa5~aPe|5`xGgVyb}=$@O36c_`I3{(MF>dnlsHf} z9TQJ3|DIAxW}a2F#{4~inXM70R|^a)#Er&lSG7tJ1SbY{34-Pt z;6X*;G>R+u3gCfmga!Q>!3SIkq0Y2i z0|6ROwBB|@ts*YH`&!I_t=kEcz(+6{9JXQ_1Zw02iRc6%GPuKtzx?Wd{Ga^zlMni5f3$u4t&yR%j37jBYU%-;zWqw~VC`T;7BQCf zfBrwv&;O?%zVVsYQ4>ahUvh#8HQI~7jL1gC8PmJa8NIE#aZx~`h&UxcNX;vj%hfl2 z|NRG_dF}f8J8Z8C4>hgfF>+l~RB*Hwa$`|saD|u#G&@!TgnR32uDu2f!s37jlAZP~ z*Mb`EYz#(p5|Yu)NkP2z>FxVgrRAYE**XjkA(#TFJ+4sSkSLf;UApi1@Cj!C725_b z>EgR4}>IN|8ouM*~B4+)C z)KA5=w-eQyK|jI#6u3I28RMRB1+uMW3XWT({D{8)yXWuvGB;^^EIGP=7F$Lm() zicOSGgs8zI({nZ#-l~k(Xx&NZzRF`!5^}%>IuUhv)Yu9Q=4&@|RL)y!(pt9)XMpKj zgM5#AC%wY!@6tu%PXg7V9RUc#p2(E4_LBtw!%f1>fm%eSGPO3pq@Uh-q=cDeGlldG z0kcw4z9CAX6O`{RG`$P~u!u=bRm7MuQ&)z}P6C!ar4&~+?)U5_k+1!;T;3da2|%hs zS;eZ}7vcqjW?E3B{r=1nDh05@R6tigbtbii0N_)X6@dF^ z3?M{crf329{SS5kMo$2~@pOloyZ3$fY5->|0`R%2UK*2iA#$(tQY>p}P10 zuz!HVvHd^3Deb3XSWuqwy)+7xVF9xiL?+#Wt8S6A=2LTlArcP%zaxcmtMCQG(vmy- zviujONprO3FWQ_I6mLJDLI~5EB28M`q3C$NKrJv*I5_=r0EHcN^bqw!N-0xcC*vHR zYzJm`L_%y=7r|I9ZRvE5JD!=g%lD6fCA0#SbJx&f-JW8 z7~RjP{TLn$PC`nsgwfJM*Sd{Mh6Q(myxwV2nn82NFl56Ak7V1ye$t+Jz-mi zfY--0&FA`F-+cmr4#A5BS6Z+h6f>uAPd zvl0T}ZlU4@ib{n+aye%!Spfv><`KayB(b#H(I_09ZVpt3HcyAy$}tVav7y*Qg}e8X ze0oC53RgY{Jw)DVmc_6rr4)#fmWS6Ah(aKuR<{wT#J7=F>RW71xN{i541)3&fLOz#40k5ChC7qtL}g1ZGC6#0 z-R=?Z0CpNOmkKqrM~!X1Sdc|ykd3vd6Aw;x_e%ZbAs+rirJt5~HgNNkKk?@O`HNox z)!kb!KmN7%1!~S}qx!m`s}>(@{c`tPUwQnyFTe8FKZ%;)YOtUA*+1tSz~Rco%6iHQ zY@VXNFffC9M%@9=SmTFiF4!vTo~qH4cVDWpd*%D1VRSuFY|eh_Z*TwZe?|J# zjyCV?6s=g#Q6Zwd0>QOn0g-vVC3J4J^#pnb8wQY!@$$jtx~}W<2YtU)yJR-#O0qi| zwj^5zP@Aec8b~4|69xuYQ@epStOSZVS|xNPow^#VF$c@WtO6891|}F#kuu1DT4aPX ztcDsh$g6zA5!r&HLSP1KTsnfo0(byAhMFrl0$|!Y!0fI8P)6m1nxmQkFbFV+?0^#& zRTbtMrhs#%_HG*K2J1VLoye#vRQ2o^PERpjutZZPVJJgemG`axgrOEhZ>~&Pn4lHB zRg94~LL1$jne;-c9$iU51~ToG(9qV6rQQwzv~?P}2@SlaO>eb&J*cQw%*jz3z^p8T zy1-8xxl*k}I<*Ac0MuL4*%LB>i1UtktJ*>z_3=&WB6BoNR0~wR-U6}n+BkwoiYKb# z>&LZgPqlc2i7Ba`$*KFb8*de#P$IUfQFnOku|EIPtQP+wy+|+8i}a^7WpuzNzkvxt zy3NWt!n0D^12QF~GH1R6$y$JhrP4do0f3dC%ELkCkHlZ55*AUU1O%jzpYRV`m3;qo zIX-I{6`t0MRrXcfMzoioD5Mnjd5V5ay~u2@yoO1D`xKKQggN$~O~BcL<}L=AxLQYR zuL3N~YmS2bbjLakI2hcIPH8EBrb^v$aGE+;wk#e0I=iq;grl^_s;406&GS((D5}~6$wSWDGe>fHXm2bZJ>6_i|e6`9slY7NgU>?oG zIF=`J$*WpOVc8}pz;Ar(TR-%vPsJHz^aA`^Y+j~R6jk!wP=IB02sPpmGE0Z$grh4! zLD52y!HXBIDJA!mRjUB}KkU8VuO-QLCiKNxxprjc+2@=()z#hAbA4^@9n7`tL9#sz zmKX`-Ct#S75R93%o7sxY>oI~{Df>{=H9;DUENi6 z&OW&__R6(_hscPX`&9K60$oc}uITR5xpPOxj}@^aGrs)Rw+gi@g!)eR^5tjF=BwP5 z6RpIhmF?wD0hTj|urk^zz1ZCmLP5|nu;f*rOLeKjUh8Ys_J$)Phq6c%2+5XpEeWA0 z#IOF6%-PJdud-j8+eEVqb={(Cs3t-P9hW$aw0iajcc(y$8?PcJ;3_kQ07605tYa35 zxzMjXyV)8Z(G5A5SO-L$iB5XzIw@YO$fYlVi48cNPWa#xN3p1Y%Dv-o3o$TbUl=D*fT0&xADbCm8QO|Me@92qY%_ zga78g|EK@M|MJC;KmSjE@E_g1U^qaEU;VdCJBbb!;3V^q;;%*|epqk|Vt@E<`3L{? zfBPqY{HK5IH-G2v|N6fV?IeC>DirDJZ~v|7%QyXx_Ap@2r5ykOAOJ~3K~x&)^p=m( zCzozAhNdVP7ziCXJPkxFIDk5g;D-S|Ge~Fo{BHcm|L}kOTYvCxCe4vGvbedyTswj| zgPhD1=mmhQfgDB*iE?DUR$thNB`H4= zo{M}l&3ow=Kv@oCaPN#3@dWJkmnEz97ldkUo~(WQ(gUapKI_8YwYMv1Czs9f#rts2 zs9Y_2H=xn^-AUsXmD1KK3L{2W>Iwj8VL6p}f}nQXN1zg6)+l?Mok`pURAH}j`ruq@t+ zDutJTcO{j^lmcaA|5A8i3^hZQ7FK%H*{Y?wWeKRHuoAhlJQJ{h;9jtJ# z{*SK`fFIon0NKQLe04AYfAUHJyq*of^=_@=)o}svXZI%n_sIa9{M`MQR~-Q10N{tu z1i8tG|FD$K;0DvCW*3T0F40`~0{t30r)1x<|m4JyQ%3<5Mw!d2=mv86I z7@_`5isg$qoy5>`(~tq!V*rpJw|X5PY-$|I<|Oe{pr@@%4cPLH!qHi4qyZnm77)St z+9zjPYFnYU!N?oPkDPPMin zZyU2AaILnfi$kE0sf^wC0b2!YtH#ZgQD_+re9Y^hG+=8x;!o1W&mm{au$+q@V%~7I zwsSrJ0hs`=_$MJaG7zZ#ta8pxWi8kEm}P2L*UELK6q-c{_{)K7oskP{aEfwM4b`=< zQKG0~A5D;JE7g=YWwyY1TmM09D%zIQvNbqtd$Of>NlCdPI7R$RFSBtcpMLVmpM3e{ zZ+`Jbsqx?Wn}4%(@Gb-zhFsf#3c7_2Bou((`^iuK)t~$%Uz$iZ*-9G*VBASNxdZ-< zzwtL(A*~7k&tlZgg}WF56yYRn*6du|_o{81RohJc-5>sNYtm+}t#R1N_!Hr+Tnh>H+g5lJ*y5@a51_y|E6kL0*Ri`7Y4dQ_qx2H`4?rP0m1VmDK1FV9 zg{3OXiK~3R=kv|Cz+S}((6Ow-?Ku;XEqa!_sy!+A+Tzv`ha%S%0ug6qUzW@qLda%; zhyodGjdd6T0v1&+(Nc3pfahGEcN@-?7YnG%HOkXIot9s16G&V zWl`p?EaSu+5X=@LUX~Mukll&7BlbX^orzQxRrzZj4*u{-2~N(lGTbeS-+&H~B`T5~ z6+2+CnMt4yCo)XJOAmsRnnF}`AQ?=FC?O51QOH$h%%hA)sH-RlggqfaU}+DZ2+5rx z3lS)ZkirHhVFN_r$uK&Ln7b?lu)~ZPYC<36A?%fAg)Bi#LlcqA+@BV3K1qa%L#86}m4wSz01K=L2| zy}$b({=pvrN1?&oK#OVA>mLbJ&B;_b8w|I{PAa780N@MB0UC(C_;UW8zxQw3 z5{d5}BS0$T5QsBohUj`*F#;65K%EIDCJZ~k<2(x_L9hD$WERQa&`9FZlYrEGEc&yaSYwlE+@|=lKc@>5rH@@M3%fK%+`>1&J)~0(X^Jyf>a<%n);teo`I5M&=BG zjf{s05h;JqvAdfxf2{NYv zk{rE|KTN~OZ&+A7>G+*bS4IL+CV<`a#*#BJTAc_JB);>R>!8TZU4x>M>* z2lQVVZWtiCmg&gyt)eG7m^>Fc%t%bv^AwE*YIC1iu1&I}jv~^m0FyJt?*tBz$v@8? zh#%9(^f7%*|D2|+KUd>wVYBOAv(*e`qnwEnL75?`gxjwOGN9-2QI1 zPdJxz*`7^D)_+2MZa-&T6_Il5R}H9FQn=i*hH8Zn&ijqcw*?W)<@vw4k8Lx&7f*Ns zG-SXWrzI01AS|BE^2u_;<|qUpH$hf{eI8p2TR9m3m~svUM$DAa zRIJ;e<;&5}$iYJnIjr_aaXd87R)c1qxmpEN!ljir7S4G~@2b9~OO4wQ{%^7i?wY^ZO^^2bOXLhOhyN8Y&bvl1zBV53%KM6R`1scvDV8 zxSCyCHovrSEBOhwQsm(o7f@Qeyx}sa*ETq5kS^Tmo=mGdkOKtYL`T8^pU7z&mJH*x+2@9V0Y1MpU1~q90#Wv>HJv=as`nMDE7S zW=_O8XJV`^${B&O+t!`G2yD4~Tbb8DKm{9HBMfGs3TEY;GpxS(EGHLpW-@o8z(hrn z%G}MCo$NfjElORtLSR(h4rWsYg%E<7(TX2YVSW}TL<&t3D=cOmb6v?Za)r7=U?N9$ zcPaF%>>Oyx9zrnp!bhX(qNoLl%h}xuO2s1CJrFUG+7d#bK<>Hgx@AS&;GUV7o;-ql zh$$v}U=wh}!HEnDRKX@Xs4UUgdl*~*KziIlRim1n1Xpk|IPeBU3Sk(=Bh&%o{*9^# zIs}5mP9kLt+RLdNUVH>H>G7y|_9$V+EqvGARU%$Xs^rfOM`rBV7r3 zKQ5+0^%@$Pzf~W|gW^V@^5X6V?*Gw0`ltWOzxQ{Xn0zswgcf+m65#@xTmpmHlDW7G zn;QY{3^E6BjW`KzOpcsjzUOFAl2h!u(2iFlY8+u72h*&Zhj_ZWi0tF(N%`&3NzLSpNfh34N znqZ!L2pDQ$Hd9%EBIK^hFnL7U!3aGV4w+``m>xv4f`Fr%5$#=O!s6DkG8hbj!N4$q z9A~}hnT(uiQDFrnMG_SjBWD!_Gma!C7(I1NrYTaqX9giB%myYL6dib09mn`a(~ZT2 zRls2EjgtC~#i2}a1v8v&2WUCLOu)c$Z%QDCt3zO<;%14{jnTc!N%TJ96H{VDSd{d3 zLd4XuWH)E1NCG0;bH$_1aqM-HH?Bq!qZ|@>0^BC@oz70uL9)+E{4isGE%&BTL9kBr z9^%jv{PCFPfc^~`V4dmbiX+Rn@J}JmmQ1hUpk4`p%^ua$GvPOGP&LSjx=I_htRj|FI5*|*VFG}D7f?w$!!{^k1}ar2uYnG8``aY3j;T;uGHPJE^38N| z0I@rtu{FM7sV)QPBLPUKLXbIkFYW+fs#;EaD(|C!x~o}Vg>T45MFnZK3eYObo9Dg~ zz3zC-t(;axDg5=pTieS0eLoZqb4I1@6gpcap5#{bi8E?EzG9OhGO9{ftFaKcigH=u zZ4C~z*oY~kvg)>ZIzemFR^)4YRXbVIIFxpVR$$3o%tGNjG0GD~8R%{F$&SxCAC9XX zZw3NTWVN1^fP+H-aQBjcH9}&ViUH59DYUQu`>mo*hK@q}`{h9a{PDaF=e%S9zi}4< z{L!~FfO$3mdm#WnJ1hWx>(d^0Usl`G3`7zbF~MgqN`PCUu6!Qjv00SbOQi{ z4gkXVWN-3eCf@)R#V;YCAvI6Iij^|s8AUY!~#euHi6oe9yJy6*2 zwi;)uTzD22&uIJYu%7e`waghDpq6#Xvz9W!0Tgm=9)Kcm4-W`oEiSAYOiwMG!@9(r z)xkCy^7+3rD7HnG+RteN9-X`PUdGnt2cY)2*g9N{azz`fwcE8%h7uJOGGA+J-hWRU zbN*PRU(R?_$h1OBmBF-SGgW{qS7amuVI@UX)G05H#-a1(AbHv4(7JPJk~T}*#yec* zugzFbonf!COE0knGLR8+CWO2K#9;-03$|5R?OAaHlwz= z+cdR2rgLput9RSA?E)1p!K`Mn23KwEpD%5aH;k~B%G_9hoHK{>nq)cWoXuRME59Zx z%R0bJs!LgJ+%u5|uwRirlzae5S7sedgjggw(pLh1?uNjAM=Uer{;rk^TL0wHp5iqFma8f77 zOfF!8=`2y~(R~-?yGfskKO_CW{)I2DFm=?6!x+xkDM8goNl7wP7^j)K-c=#+NTg20 zuF`$y^o+}X;xIsryJW`>(V+lNR6J71O-ZmAG11Aj*LXtOm8gZrFjF{DA}1BNrU9gG zdqH~ngI}Fqy^VOJ^f|j3PMSR49F_ON1eut{JfL@1vWF-yrDvKo_fbsE`I&L<*%HHq zbsCr#f`Sdqh8}Kgolydl=#I)AK%5oCojVu~>}KvDP($P!0IrzEEa+7xsHk2GADA3Y zfC!0+!U1RSBHBq@)EyHkGDl}l24b7kqmx6?$Hfo{%Cr;Wh}lJaA_53H`wlSZKscHW z1{PY9kZTm4XDAmw8pu@K;}J$!h|*%zp-YZPN4Tp#Bflq5G6n{-M7B35`=ln2uafQr z4*(QyJQ_hJpuczR;2^e#nZP6Pc5;X%!qrUNLouhBZ{R0DS;RrW(cp6ZFg<)S%4_v2 zhY$ps)s<-EX;ut~Cp{2Hb-gjXfdPKS@~GnCuLXnpmFg~Hn(W!NJP;hBqE{9J@TKd^ zw{{)J1P17vo*#9(eH*z4cz&%c37sIB4or_kNp#kZ?lR+)3!93@T#q#2?T#Zn{veu+k75a%K!-ZMS1DenF4Bs;%TWIQ1*y?QXOU&rv z+k9Epla#k*t@Z)1@o&vf_m<}ix0I{Wn~V&Y=Yq+5Y95if)rEX9M(4IQM0LZ}TJ6_Zh}dk<(QvpLhZ8Ge zRe-IWvlneP51?YBfPzruhTv7Zo#DCYu zfNY2BiAq%a78^vSecXav4I9drB(kt+KQ5~#=9e$Ocy0E)zWZrdk8T)Sz9DUGA*wCD z)7Vl?x+}kfi?!0irCAy<)Oc0p{O2!UKHT3AeP1-Emc=^B0L;BeDTR$m8%OK}biiBS zwswEpqy|2QOABxB2<^D>=9;VHcD$bStEH`%X#1N{)jaCWY~@GtD)(+x7^~a}T71Kt za|pCmaQ7M+s@<);;$?-~RbC7gR#XPy?(XFVQ`joyoj~^7oF7rw4hlhSDR5OFDzfXI zGnYVz+lWhbv99k08f`Wp!?I`947hu7iVPtLcL-R_ioc{*NQ(mzv7m4Enh`Sq!n;pb%jKDCrsHCC* zKf3KAi$iA{d!!i<1z_+S<43SKF;VAsBs_vBc>e0q6{iqa)yLA_2@*De)ms<1r$_9VwWc$au0V z!o7fjdyu;g$rcbKDNNv|NGjlIXGls4b9VtIq)0T)&djqK$k|OzAZ|Ld@WEZ(L{)zD zTR(pN=l}EF?T&Gn?S;&}3dEtRglI%a0-2ye2;hTaFqz(_uX+69&wu*$XJ7olX#vD$ zN)VDGsZA!m19D^t5fsTyVCpi1M08dN#LWSNh^ZS}Z>9`!Q6o4Ux|kUk)|ff~vyS-$ zkaIFs_6X_#BT@qhl)o-v;wGr(oxRb?lKYqDPO8Wg>Ry)?L@-U+ zC^{c)9vxY5NKO)uV5nblJdq~$j^mON0o~$^G!PygY&sKxO%0NK$9P4Qp*QSF9R#?X zJYB(pG7G!v07FV~KOO|;vzhp)NvU%jM|E{qe*q-H1Y<`8dyjk7E7eZ?bkKg}Smfi=&xXZg%T-O22RdC-Sn7AxW}0@c#N0PN-xRxktW z^Hh1^yQ=m8s2W?q%3dzYN9o~w!!7H7w+T>Ks6B-lRESH(*}Mo{O~;JN=UR7ARkx#Z zd;)+18kWn&0#F|D*LZe2;Z|u0oL4tvXO>oZpeia|ukP2Upf`^W;M3c3`FX2VC@{yP zqpDMt^CfIwQM(+6B9E0(xmw@e`?-&`=3O|q|J#G1DmVSvs~N!aD+X{C8Nl@w1FLG% zZbNe`yshJ$QE5K6`?GmlXIE`33aH$xLUSv*iZ)YeRmoX+SS5eqdHIG^rE3Xm6~%5P zcx9(R4R%=!Rn(oX#(+B9t6FtF7h6)5{W_m1`cUnw_06XQ)XBEYK%Ff`7wq<$0sIv| z_r0{X$gY*Lhb{p4*M2yna-9G?CI|4d`vvu(@K4{KP?fey18#Z(@Z-+}z+d^S18{v8 z0C1lHg!=%%id0-Uo9l5}yHqCR^IJll+gD}MO2B0(&&ALE{qE5K3_Aj_?}0k&>S$)v zh>8GcDsLdm^JPX={#qGZ<%d?b5A?k|_75oqghK7fbq8L-tPsx6`tR8#UJfs2j>AVOGmrn5+S;Dlq*NRaokHwJ}tSRTG-?)QK%?XTq9)Uv$k~c zE^Jc*Pdm z&G5E88C5Q-wdc}#6PHLa(lH9C<*nvktHoai{~c^_ znf9>KR;`9THPj<-u#$#bE%iKV=DcAl<;_VtPq8!B^Q19bxCEPGpIp*Dh7Dz`W!Sb^ zME3iuKm5Z#JUkq-ySsI}oiDaJKO?(4F`Ft8S5U@@D0}v%hnh3<$~FoV+&y58vdO%9 zsFn2}ITva3PQ=~a41t(J@hQtSw6Szj>G|~8XP=kJrl$m;>o|qbxns8rA#_B^EHWFA zPWpT&00!V&;AVp;E$#(E;yQ0N=L|IY_M$@NRnR>EA%p^uVdIL}(6?N{sZ}Ja2wH_R zs9y3E$@ZcXU!a^&Ah{40Rqnd-kdSlEZcQ6&W3jp-R(j;-UV%ct3KYt!u@r4Zz;r>* zh2pfGQMO9oT5i4!IeX6Txrk2{vX|Mq!Jw|oIcN94OlEnpQjlfmLNE>}xSN|3QFE!z zITtEciNA=AMt<>q?uZ?k12L1@LPRH9I_5&8Vj_3%xJZoA$(CIwi`&T-VJ0q~m`s5d zTSCW$pT(Wnq6lHpQzyG+v7B=tTJ#i%h}ael%uH;HK7B#-fhN--GW&Gm{xnCxMJTZE z;Wo;{B*UnzP_bZ2kcC(@-a~pIQW}ZwO`}sbzGsM{bElb(tPt##+4!gcPuGCycrPk2 z9ONJx*=cei%nlgX{y4pNTARbNkf9J$)kddg5OrI^Ocv+`WESe%#y9e0RXjt^70KZrneZc9Rab z_!2UB9HNS%yXNnVAY(5c1>c!m{l>5Vh$#|1q{Hlx*gH)OGP`xL=>5s2Fw!#Vuz!31 z{Kqix^ZgJ0^w0mdFFyNW4>yni$22h(nUV`2kF!DN4*He_ro?dci|Nk&ArkvEfgOa% zoDQ84oK@iwOVU7`#Q;{H9ROodgIZz*dUsoh13*fN9GE(cNoPWTFuh}WLoioSQBCny zzEQgaKd?cS)d!LUOpG^nAVr2Pa5y@p1$<<^GTgJ5_am>367(&wS63zNHK|A7wWg6V z&3Yq;k?9TKi94~c=5z%R?4TYQlVT72Tx~QZ$2UYrwxH;J?trA8ujPKmm8RHB8s(@n zz`gUq(g0!dd-vf08?hv#2)OhBDO?N_I)WN{#A9@rF`x`nT=%e1zA+P#uMYCLCXYBw z(~f9Rojv`K;-mWP{U~ZiLet?kF3Izh_7Z1`0sNJqGnOeGdlsDrgONl{=K6)$mpq1t z^i14^j`Q@Qmp3Ad&#C8y=rlo%%;c9P7ypr~^)Y=+AJfP5y{Q1)PuvDC;v!W7NUlVc z5{&PHx3YNvZJ5pz7$u+4r!%mUFR$9dK=tEhld!p}`5v~fw_L4U_WSEL<1C@I?jE;* z6tWi>x$)8}-3!&<%?id)>JLv^vhHmPk*7Ebwrx}8c2%|VhP!2WfQMCgJZ$>ddYtp> zNQiJYL)!vf=B)y^H)1X4J#B7h z-YIj1<0urIwL~YRaL%}*|0{ng01yh&h1i8%7nlMCc&2CLD%pNKRupb#o? zj6wkA7L+izQOg$x=irPLJ!~lOMc3NTq$=N+lcC9_RROs67XX!b1*od%1Xzo7pBjYhP!UP)#~RPe0KAv9g{uH!PBi&x!ZRvJJQ3iNYsf6g6qu|wQR zq2HW2~R zc0jvb2my>@*o^MHg0&l2eZ3LF`jV`ETj;X1)!Jw=5KE`3gW>sYWzOz75B;EeDo%wN zSWc(K{PFORiI}@Z*B5kw$aN`D`if^^ZE6wQqCz68t3df!2v(kR8K%(u2P>kdX1lH{ z*p?%gku|ff>zW`}$?Sz724weB*3#)IUw8ljAOJ~3K~(X;T_E!8Aq3CfW??}^3popb z*@A$)7*^$wOcZk00kAbH6S@*c>Vr-UQOr8B=pZ<-nF>2J>fjh;CcQRQhYt!PU*JcW zxIY+FaKi@3&!NLX7Q<0IE6sw@xqHCe8v%>5l0CqqA5J6($7`CzFhO(To{CJB4$6y} zOP}1PguOAbCByyfH=vmz#L$@mBv8lZ|B#$+x70j`Y2 z=+m1b7UsVq^az|1?qUy^-`!omJq+&O0&x4uoTj9Y-@Tedv-Ufif)f$aDCupwj`C&{ zpY&>k8ZT;*`N(l`?L-`EBR?7jlSi<^WY#$LUpd(Pif97Q(9U7A-U%Opf%V?T2e;2i z9+SQxg$t>kxR0(g;RbSY|Ay(gs45WoO(Iq`c3v=uT#q=oUNI$@Gm#M)rRd_U7-yN> z(DTGSsm?&Zu&LR=(Y1H7&eRwkLHqufg+Bd7pjx?bI?9dPi^>$xp0>^rb&+Znb3Gdv zz)d6o&&J|5AKJC0(wl(+>^cCr8P|4f#hwZ;sR(Zs5wTKfDq#ot+_qUWfS-T6phm1K z%{VP*63t@`P`LI*OJ4xskG`A%jB>WcPhTs5Z|)ZWX>kCh!N_mu%G>( z3gC8FEp-(MK$L*0+!VV2U{*(^hLx%dC+NkVQB}{11%@I+R>B(Y0)WHOQCVH6x@P-6 z09eCtC7{M_EKh(%XR2`G`jV4@I)7GX6Q8F|d4#h1$W%nfiapD5XAQmi=p_JdrU4 z4FFCl1L&^+VEQTp`1xA{pvy|ve{szKo?TP3-mBN%I$Ii2T3)2PUOhB;VeLgZUnaj= z0C3e40B#&c3jk7?6|p>`ooy~D0|n^c@58DrGqsz1PvZ4eq&*KEl}3~t>@!q>F3Q5xGlNHL@ru>g`!2wWoZr}a0msTcUzb_ z)PSEWXSoV3g+LTS2~<}^&`Y-Jmt7u5otfP8Zntx<2uMH(p-!_hH_?UQo?{IAAN{C! za8tDs-q8X>71#>E=N;z_CU~>4=XQa5cfFzwR`_HUYF}+f^U39PF+Lw`>%FLYOW@oj zuj^Lc__1bO0A`_Thdog}+fIz_WNQq*avpF91qL8zig%Fr|J;PM!V`ZJ+?V>IkLgvI+% zQQ$!4iW?F!>=`yIID+Y9*a0GZ0s>|?yPEmB$1{+icVK{iA~C@S&=Kh1Bap<9d`EJ0 zgY1vVerP~Hs0jnVX6i2D8kE>LN_=$f;!XP9&pt;C;vLc0k04%Pd+r^i;?X3*g#C&l z+(&_qzwxVZ;drn#L}>qmYx17y2>rxdiY`4!XoZc$_{4f=5>hDc&+zGgg{xj~Q%^_hw zNzj`#KLZZZf35m#pfJh_h2gBCz}WY*&P>j6_H<(GHR_yPuy>1}ePF+I}U zx!e%g@rtAu=r8!;|NluJxmq97$Mi9MOy8Rds?{+%4&@Cw5h$zx6H$XIf;-&dgkX6w zEE`Cxx~k>6!P}}Q)tA>>3<4_})lLAFKx)5+&E>$#d}*i+Hh9OosLcD3n$0N+RZ+Wa zR4QW8P_qUMZBdngc2)DmJHvLZO_W2bw<8js6njx$&f(IeI2->00W45a-q=2D z%)3E3DTIz79EM$pyU=my7|da}L(V}2MBN~CR6l8+G*2hb86BPNyn+O^qq)uV+M3m^ zEQC-!g(@O;(US^)6gap=Z_Fq=&w!AFxA6@txJ&?1U_vPDwp;@pVx5YfGXc49J#q-h zod<9XtU6+t~5bE}Su@C-Eq;@i%PPP%~OrvxRzL-ZW;5 zGj7qbu=%^S=eFLwX=HPHeNs+?Cfo3BrQBLGw*IZH0eN%PDd!=C-7uVh>3GZ;UDpjG z4MRWA>2P>J1|j5}cOvHAFhxoIUet_{!)BuXm$b8^9j%R{rj&1)4s(;PU`xp=8==e{$<6MbIR?C>S6oSjuAJ{Uels67TS+N??T!pat4F z09I&OhRK1>?ianX{*hH)kg>zG`~tlMPGma3d&3~;l}y~pPoPId6eR7AssquzBMP~> zfEY}IMX7^#W*{d-Kzm_!5jF$dWn?3Wf{9c#5~l&O0E}Ki1QoDLT%cK9U~q@f6^tDa zkTXDF6=x?CjgO+eii1Q&MI)R|00Z^LxH76**3^KsKAtC6ELPb3}%&*vv>b=l6q&ufLt2;W;E@5I?;5P}+K#OR0>5?z7$o(6e zcXN8xkDol?%{)c$;Bz+7e(yFNh}`6;(^rJ&JuL@ZsiaXAz0dN}b&hoVOIkGkB9_I| zXaIJH4nSxMrEL>ZjsXCnD)q!M0BG;hP^FiO6jbj4m87#3hg!u8He8!|6HBq&f0lZK zeLVU0<2hSCSG42|tO6w^fN>$Y+|P!pTD3+|JT0hPr^XB~arg4U0i+@wMF6nx8I>_~ zKRbX=_Gi(na{nulAB$8|QA8>PpTg&oDnM3(+!gvmk*|6@O6$>!yK}MS@vQJ}N|?eT zK5&>a09^{T#{j&1wrf3Y?J0#MbpW?x2jFVxP+4YEasbyuhq`+y47(`QT3h&cg=}?9 z0l+-3)-Ob`V*e6{vF;M7U1)3EMxfHEN-EWrQFxfjySQ_I+xQlCSgEMId@T}bTaB<1 z6mpu+{H$>o0KB-CHg-j1>T00Y4600A3vo!2kN?4B%%61@POS52)O_=Od#s z<{oAP(2b1xduflXS0hm8@ERTw0B|~G0H-;$Hj{oo2=M`>`Q${ai$Dk<0#jhdifwJc zl(Jj48Y_J9<_>cPJL<;i0`WNGI~Op-<%KJ3flX~_@#%mwg0mjv6+FwejT;c={b{?q zI8#zLqDb4$w#HPf=v+#u9XWfBpwWd;V1;!HmoMz_Zh8VLJt2uYiGiy38lYhWbqQxx@hT^eAgP3SC(J+#l!FvNLx+xl(zL=EbqxLax+)T zfE4}+1#m#zg|S~lmKAW8D0CghF?{wZ9gq3#L;m{B^7d#sqoYvFj<)%%bL9ziyUvyX z00mCkw&f{s*@Vxkuddet2*qCzXxci!s$|ajPr@{8l8EoiUTNaPL z16nogrk$h>hGLuZdBZ`&28P@I_MS|TylHJ)adSoDnsJ_xq24uD-dLCIVeOu`kf!dBpn-6wr(rvG?vCMnZ7TL`2WNtT( zvMfX(4ub>t$76B&8^>W7hvRg-zkeI57MLyz5ve;9Exv+OW~*=&s)|UT(tfju5EI=a+jVA%KF{$2&JGYo0B-lC~OukSLph zLiNM+lK*>5_~9f=HzNt;082c@I7Zk_KW5=OrNul>gG_$Z^kO=Ir6UNvdK|BN2LuZ| zLp$;r{fwF2JE6QtaS3!YVV($6O5_5}i`q3IMbo#^3yf{1B#3^{fnW=e60tbYb?A<8 zQ;Xg$bRrXn0=!It#GSOWMY#h3987l$yc2_(Q+I?BPL_5~0f2H6ka$q*$U9JG%`?=M zMGmHWrUjBP539g05P|piuH=DBynX)d^LI$9Rn_~w# znMPK(K8t#}1&Ad$87Tvcll4c;1F*nc9VP}7afJ@Ti<1C}3)@PK7*4L<5t4$SASCw= zvXBOoBPkp^70Hx091n(F} zs5tud=0h-NhH-J+r=#07klld(SS$r+Ai@lNB9K9gcs=74_ystPG;OWKF zm_DYD>Hl;3^p?who+*_5KNEA(FT1_e*XO!nM^9oZ{JnL!yHlCj4ph8IJW{2(YG`Iu}A31+@ z9^ofw*98)opW;(bpuH!cR_n{k)C-}(N$+;~-0}9mGCdkT(Lw}ZH3%~bT+3XicNbVP zF)`<{mrrlI`Q%CSl4{({&H(mY(ck{+3N8x2CcTo`Lfv7k_P4A61u{s zu7;FtF{y2V`LYe|V|b^`Z60iXM^Ee%HjRHWG~u%9a9Qq8*|IQ1*q0w zxE7Os+e;52HW|4C`nTljX4)JN$IW|VFtD_bvYCV*Q4kwS$A1>jB= z8RTwou_91qCXmi?ki!A7*CBx(4Da0eLt z=+;pD%C!@p7Veos9Rj$xD=<#Xu&kP#1Wt}*IJ#wm>(~juGXP^s-XKNwy;A+cg}Mf)CN?8>1|Ad+9MrBDgE2-WAi3R;{HlzdV#9EA5_4yQ`HqE@Tm}GS;vPpi zzySZ!K`^#sEO|;zV+z{mE^JSG2rSp?Ue+&AF;m$ z3=HGg{>w%2BY<=Ur z5L@mK2H3B^0?Yxx_qoU{%^k; z0UV3QRtNy@M+5MKTLJJiIu;6BDTNPscXe{(YHhhH3#V^p+!V$i2LJ_RZ?5s%P_D1& zgextgTE&e4vyRj{1hSJP*}n!!`Di z*Wq01p0u*gZ%GRnv;syeNc6$7Vi3=3)E!xtK;f)kxvF`Fd0nDfSWGIA)++UN(nkM~ z0ncEsP#IM%8c)v2`J0AjS*qp=CHW>;YTcVp4mve|*4_sW$+OAxaINIKVp~{&%;(GC z50PlM3n>G^bM_nx3PzURa?(e_Oo&om| z5Kz3jwp=9Y0c6ji2%`B+r^-IxDd!)MlB==kXoJpf>F#Bi%?satX@}+mu}lC8A>>f7 zzoz8P%sB%g=cFpk(lp39Pd2$R5iw`?8Pdu*=S*o-oXDn#8GHXpz!l2vd5C3gWC0qS5=1p`JvVu%6d{_}^l1DKUfZeP3>$j^WNx%$Cr>J%;wq$3<%g&gcY*b8Pj9Zhdc z5~jmIlX$~Uie`s{+Dm~7-hsZ8tRV+Xo%SGck3hqCQfuMrWU7kf3}BiPB=VlpDQH?`~Ca3g}Y-NW4daWDs7^zG<2StLkS1U7T&X#Cp!Zbp-T z4do+O>tp#?K9-N=8_V4-<&0^9SuPK`GlIS>ZqCR=Wm&RBb+a`e!GuubBGsxd&(GTD2d|$_3;#K-;0KU^u>P%CT5GG%VTscTp9jfRX3tw;K?qOA zqlR?~Ju2rFHo`LxhZ&0rD=jEgLi!&tAe=TxvcV$q4m}hqYR<))z?V>_D9G zIH2y~;-MLny0ma@|FnJn%{)#E>{v1nhL8zGdFolG*Ks_@L)Q;WY~V7P1BgQiAO=w& z1`$A^X&@~q0l&s7_sIaCN9}n9mesfzEe(bxPLQh*#S1{{`JNgW%1eVQkh8|( z6$!9a3oI|Ju26L+ET~+Kg`G6Bmam#+V-0+}2*Im)VGcBlqgEp?AU3MlVRd)BTpi_| z;yNzOb+x$>qWX-Bd-=kWRlX`OuApa*tpfwk;X=+8W>+7$cE3U-PfG9g=&Vz#2L5n5 zMe+2dXTbA`0xl)wFK&=EnCLkhGk_-Js^Kv=n)4LGrovkVxNBPlo(_j1g4Xw4*Zt0J zw|jVaaPvSbIEaE_QJ?}LjV){d03ZNKL_t(P%^3y)d3IW&+dX>$<^mBp0)>KG6&ly9 z0Ut;wZMZ>3cBk^{4{+q*nF1Anj2m`$%UPPH+y>1(=UiZ{k_vNWiWSVu7q%G95s?TB zwD))4;=VPd?V-XC)Te1PsJeHi$*Jvl)ZrR(*mD$q3>sCTI3x?E-0$))Z1|+V9{T&t z*o>mSkvO!R%?2n9xM5Ya9TboaWS>mM4={oN1`Jzba$y~_h?`z9XVoU55rDjb*}y?m z)Pn$$!r(WN4$fi@5Ss%uxo@QLgey6;9u2~#BhYFh--2XMyE}_SfXI=DPQ{d3sJR@( zUXd7Rf_B~pQUV1WZV(4Vc7IKzaO$H1sxI754i+s2N2Z;4=WugHPuCR4$rb1)XfQ1o z9>EnPaOK{?lUZPf!CZrp3r{d}IQbixgB1n`K{MoN9$O;?2_F?8m}_V9S~LLS;sk;! zAd$fHyK`YulOs|GQ6Hmlfv~fvf5weGNfHRvx3QLY9sgVE* zB8IC#)QrUqf`ZURBX&0;xB$uVeUP>eP?0htp@V6|I4TMJB^6-nFy-#)|QRo4+CbNoAz)8c%v5<_8I=|b&!d@x- zo>H%nlBD|KY^rSln7hYEwKkc^7L)O8ouMhXXQ7QiZ!OdVm#Qdca$-O^fftz1qq+YkdV>pI0Y0C@d| z07#bs=pg`@D!H+e_^)ttj$_8c$4Q5|8$~_p{gVTD92~&y6|Md+Bho*edLh-EDtpG` z=~?AiE14~&t+-c(;$BiHE)EP>gt3av3zI8j5gjWGubSqzpQ%ansY``zM*y1gZjb^N zjVhf^j|fF#EO-X+=9X8(V&y2VcsT2flG6PmAJzas(*yvUqEyvp0NDVbnKG6)c$*Xe zOh*7X4CUn^06ac9fZgC&B)zb(v!==-E+gCAvn!H zyBU})ubB;r%0#X3*b;l_*)pazk}=mlL|$j$`frhz_w($BWx6bwOa8!IT}NTgw)tDJ zESwgwqm&gBv5L^NepPU*BM^YTVFKhlZV?NXwBi)&Z6`nDTZMBP6fHYf$f*=MN0D;1 zKR-J=s%p>2?}I!4Z^V^nGuoctO0MZ0%OfKX4Nj74UC7zSxXRe>A=d2n~9wWAB?t9)YSl5%mHrgFxDRUzj&v7&CVo!eHjsT)P5fo50j$d2q8a)Jal_^JKo?6TM`y0e` zbFHM*x38!>4@8Fmyr}~Vv^i@Aq9g# zuB=1?kh@aDJc-DtxCLOZ4aSIuw&l@GnBAg7iLZMjV^*_XIr11q4nS{x=CZ1wEA1PG z8m_s>HZj;xE^*~sLK5xKkA!}L6U1R)C3E5l)|6-pKp+Q79ju>32nr_{AV+9Jn39mF z62lGf#$^J~j12@Sbxb>BKwV1EA!`wlVp4z`9TIwV2$azQ2Aa$pK;1h7ffRZJkjq4X zD?zTvliG%zAejiNQQW!B)6@*Gz*+5cF2=SJ@0lFfZ~8v{;FI4Q#^LSTz4DfA`{L8_&6`i&{^F~@`NfxvuM8VwV7Etn)bTUn zCw&|sTQXCa57}e`ekYiQ@um9V0q-+n@f0uT>Vqg-2 zP4vD22sglynmr~GxFCWQ)ar1>{Qk+5S==Wei$|AVu)G`x>#=v-Iv!Q8gvKa6xr(W} zLEP- zv~h|E;@J4@uIav_fF_DRj;@xE=10rsIK^Ajj80B7jVp(R8dY~~5z;!lYVw*+akiDkwY#KhzrV$Ir+fJ`O6izuBg`!>-9+A1eSd3idV#P342WU&&K+4*IOTrRj*g1DO6NDoR4fc zN4qXSH>#!(&JS6Qsp(@MbYm%XU+~O+JKwoZzcpuKvup^ELzsXJ#B-;`u1mmfI22Oq z_3iET?d|*f`=9>wr#ZvjW)7Bn!NlCAH3*%U0Zcj(g>*c=zrT0$@4R`_G#rRjC#GO# zlTO>~>;6Um#TQ?M0MEH;8X}TLh)J4;n+8DBGzCqgCFXG>qGrrIrbG<`;GBgUN1mpM zh#Kac^Ee&~hwBu#p21C%&Hk>Rw{J@s(-mxb(vE5H{s^b6jd3zdVt^cAR}f``r3Mr? zz>!oTTZ_B#-Rn1>FkTQwH|fQZ1aeS5^m6Cal9>AyjHExZl8Lb08Ys3A>MpGl2&BTI z1R=P7QhX+DH%ny7N@A--i?DpI!p;2 z835hh9(Cv%QU@Zt3uq*l3EFkChi)|jEG*1=fEAUHBdIu|5Db%}AsoTt;vnL7B4zjG z#Q_s6^iG9RAwmh>XyeFWa)*ezHEfe%RJ4u}=7JmMM9zRZ=SYv@otwiOLlb>6FOF&o z-bAv8cS_Dqkcpi^je~@iV1gE+S26;0BbbOsU~+4m z2}Lie-@7sZ7PzuNl~_t7Av1%G4gfhpl%N6R#BOA!4Z+MCB0vrdhXWuL2Vi4EGJz%t zkfOke8BkI<2|z+{^lWg3@L(hWgm;cs)EvqMuTm9po{CL!x@BPQ$5qXI054!80>_JD} zH9vau;)6JbfX;jtx2@0Gjj_G!?)^|sqJ zH;pN7-5QFNv_smNY)Rrs`=?!dO~=%Zq>bas$XU7V@5ixcfA}@sG=3APR!9sizi)*U zQ=Xm+?WO1_6?vdlSIYq)9f5_HbT~Q|j!aog6cMhXD^#d6MgJ%jK_V?=$ACp0sr(&u z{wbK&xAO~KrF>C{JXbtLReJN3JYvKc{*kQ{WYzJl<@GO+m-gWJ|_r+%I z=0E{BQrPwVJF5=wG#`3 zR0uos(|pb|u94?!bzZcD87w%vl1~Co=O$d3bp{fAqru-;>h_ndj8h)HvcK%fC+Yjs z|MTL;#qiTV;KbXS>tvMVdttqGFNo0x*Tbj3^G#+RQ1_WS#@(OHSx^{v0>Oj{S|Dq6bi86yZCd;%Wo~NQIlS30S zaR6m-Mw8LxTu>^`2*}Ylufq4Q_|u91y~pM+elq>(FUAmZ2;hK*&=4qu5_rgk>V*&% zt`>z=WClfPK8KJg7b|F1%gXNa@7*)-F;Kt~>4-c-W7)k#pUnzF`OH_d=Fd7|N@(zJ z2UY7V!(Cp$0;)iP^3_yb#}Yz`?IIunvBE?y+L7fWo*_Q}SIdgF$+~HP>m4amy7-wMOC9cuK(ewfv#})`6DmA*-$CmN7tw_m+oe$D zsP&9gaj7myRpGpYsJ1Woak=v3MKmJLjj2oRob`;7h- zInQ!XW<{AZ3E*XJmtM5Mrtc0pr*SL~v3DXFJ8R;@~aSnnNbKwId8A;c}fKp{mn|=p3)(+SiX9k!8L&T3FW^jiw5rN_4oS+6F1H{!G26sSc!T>^WQUY8z4kkY+ zHY6ZSu+D7<5r7Hr-L5T8q8S{NGte>}02nrgBVlA_5TGKi3W7W!ZD0Z)K~7GF_dp~k z2po+%*b+Pv5>cL9oS0E|WxgpP_0%*i(Z8>=V~9cltHIzr(fm!qWCqmwwRsT`mi;YryA$)Y%G$*EYf zMlvRKB5aID7ow6akq#n_ff7hAceNhV`nVv4~`ymR2P8>PdeT( zAKVff$WxRAz|j)ltMz>hDK!L!LC8T9fw#U<(}(o)7O$v}jFCC8*^Aq7+tU{hx5KcT zBs;Eu_-Xw6pZ*tv;-CHTpZ)mZ{$R0p_w8eT+C1=gH2$sVgAVebar^R@JBt|lfi=AO zBYa6e`=9>&JO9}$LsY|CG2Y#@@t1#cPhai+^&h?Y-GA{ny+B> zNE-tQUj3Tx86UY?AIrz`v3xAwSk4GpUSS+QqZ?lB%w>VSpdss;ys(OVA(C9g&0&4G zzmQ3)SU+p~D^_w^#g(;s4tZU=FGR4CiY(7OfUOET? zC)NA~J6nt^|NYR>A6O-RaMg%2+dlkN4QXKk(eeonyJ-FlA}`&`vnfhSs95Bnbor#7m;_@f3Z~2Zw z;Q6TFp3PwvCM#0$InP4LA?HjS@**Aw%9(QJoH=Jg4ta_eHtw(7IkzMKFm1lx%Vb$C zPo7UnCjtt=fMylBIaZXGObf`cS%@HqKol}97m;OHfS*tGax4=#Ed2_z4^Ol>oB+Z3 zvZ~xT|68&>gbSa3drOTFQ6-^;1wulFD3$Fd1ON@N2ij*1t`0t)r&g@djprXPuJ?^&Ru~D>Uw^2sxh5)<2jG% zgQ(xyAXO+^-KpBPwOm+>bM$9*8dWaBGyEu2?pm9DUZ)O7tWmanzHxDiiw3b!1*?nl z66RZXmSWXF;G9lacl=_K1V9$DUILnGZ4-blgs$rb_hU*WkdWf$_y6DzY?}V+FaPS{ z;r+Bk{FSzuiFsqw6qszXY{nF}+bw{1U%kD(yQM&&a8zv?MhL39*=zz)(Yz;S_xZP) zLKw#}Anb=BZsPWO+cXX4*DwJkoRGQTR&_9XVQdj|D48XhC!3^cve{hox8U~W@^w%l zH0BLRNurtdM6MmtLH(u?RtsD`qk4ME2%n5Ez^p?E&VdH*6bikK9gd z6Tn6Un+zLnAH{{iDoUv%KEOzkiH?G(-iQKZ&I&lhNt=?!P#A~@_zRX14uVUZRGC1` z2R0avj*iS)^1(L*2tkbiXT4)~!31yAnPo>{#Rg#b=+=n<8d#1dfC3&#H*O5TNol@! zI*>r+dTJuv(G+9|9!LyH;R0(IFt|cE9$II^;9wJo!Nl81N87k}E=RGcNaT?`dg?%w zv=cEH5%0mk7_1%5R49TS>Le4qP`$uT>Mni<+QSK!A*#+Id-F}n%LgsV7}P1M8=Qzq z*{$SKJJUwisMNdE{E?|83I@rs* zw{QJ%7-Bp)WGnPf{>%SJ6aKsZ`A`4N{pZ)|%fxTC_)?S@U!i>|{ZXH;L_)KBYkKF~ zUo|gw@|WLx|EGVOfAEKm+ym2t-m}E5J-vnghufy3`$Oy#?xXaB-oTVn+Tigkeb9&g zEq>W={YTfYx6})iJwgKLDfu?aK3OM-&T5!g9u3>1dqJx*CEuDt5L`|B;D(4h#jgFp zlg0l#)@TuZD%>Qb;=64XuZ4nATqSP4fIut<6pg3`2PSBw=itCYf# zDKwl~U8{88DwftvVe^26uv5M*DfX_e<~I8|<4Wl=u<&R~v*qucYmzenDzu|b080K- z5a-o^whdUgInzRFYul6kal@-`iz?HscNXMi0G&pmI453Qe!&Y7&#L5o zr9!c)PGnhJTZGb{##3&`nXIQ7z+ZkjVv(Tgg=)_i>Q*i7HOoak<7yS#>V%A?%t~RJ zu}Dy@!(A*l$^e=YZc`Ha6c0xSpjQ)sw4K)T9b*R2KQVyz3jy%7cL4wTZxVpJ{)`J% z7+9~jCvA#-$^icKixI%@zuw?novmCQu^}v+ETOQvwD1{AZpR`Rhtu$#I$qT7%7iR@ zv@)Y;gWrZ?hMeJ+&Ci0Q+_F0=E>HQGbA~xQ&sa&uECO{RYSlq=%UNo?BdkbA71cPS zDwqSa);YN}6&(2kQd5|boe&m|R>mn-uOJRN7c^w$b}hDCtT*zB`gFe5!bt}`)SW`L z{Xqm_MVFSF!wJX$&QPI(R)nRg0Avb&QjX7=meVf>Tp&lM%R7{znRm=$=MKkAyR!w- zvPB2ILbZ@{wiU!Yo#N8+btP6WC07%c%6YB4u4f9ScEP}UE^R)?U@plT!{Y7L{{bLc zh*23iWKe;bf;lF~??NxoyIx3AsZ37F6prLnwnnZgOyf=U|>41?|d{XU}K95hqYA zgb)G;Z~%wE1g6kXXi6H#nZI^&MOb-!VV)mlPsu9wtuF;!Xn>M%$QH<>Joz~=E!%7K zTyfR3AO*)oOKUA*ITj0RCM*OQoFgE0sbQ2A4aw)NUDV9au&wp*6*sx0JwLJ#N> zfKJ{1RM~%FMp#aIx~`v{rL=F)+Q&1bZ0%+^$A&IYo97l@e5}Evy8E@w`TS$u!U_yw zF}t=TFSBK(yxDTdy1$05sG2``7KwRbWKE-6+kD>Bl`OWl(^SYK&j03R#u6|An)4=v zRVFk8TO#Ya!OW(~-8lpj`OzQ#=$MW_{>hIYA0Ep|yyQnT4@B8LFi~#YEt|D%cYpZW z+yO@}i(zBtfbiuPUx>&tB>==sA#lSPn2ze%DTF|jQX11Jvgx|E@A@JjIr}ODgc7A_ zW*d=N=gXZ!Xqc_!YAjxO9(MjMErAFiCK?k&TXm9lzq8Qxk1&Uuj(6zM`VQ?ztub*Y zVm}T;jBvVk-5uMep>`5_f-{?SWI+RXg2T<)49gBmC37DgFa)J5 z(RN}rnb@rXCQk%Wz84h$P@RZqXq*Ty(bv#|jNXCoVZN~Z9VJdZn+$S_9MwK0sR*CmR!3bPym}W8MfwKw%^}B)}D=$?L1vcKrMyVo(K>c*FMJ{Nw-hzkVG5 z*}wdgzu5hW>I=oK=$Gc4%V#FpFAlgOE)aHGz{4OjQ#ch z`j=ld*U`tH??pZvI&UANT(#Oi*kkkbSz_PyyZ0L2e!hPl-+rfm^Zo4;(kC4y!uUwr zZh9x&t7Z_Jb$v@h$ua79(_$jgq*o9`pCUfzI3-+Bn*NRp|Nlw($kqB-K9-N=WBJBX zQXjg(d@KF)d9 zW}oC4m0Jy1p$hUjsIA1+1)s&IO1(=&tSYn5PpH=d;uV?uuRpBLcA)FR#+gdQ+!_l7&(W+lPesp>>*f5 z9cbA&Oa`KC766!o94LsM1+uczo#9xg>`gZIP`TGR=CkUy zxd`K;3cJaRN)gVL<7=d&(6z3XJ$2HPlrP5AaF|y{*2k`ZPMsjq&%wd9 zJP+1e?WsMv9=O`Dp42~72i4)vHOuOZkf?mV8b;NahVx!un2qYIP@!ox^hVVT#QCY~ zPBja(4ln8e03ZNKL_t&z`y4LJRUHC6gk#Pc!loKH2CkTmc>;#R0RV;2b?uLS^rPdL ze*BZ4q+^;?kH=#p&7{-(Ga3Rnji~~->iegM$Ls6sNmC<2KuT$|*{JI6-PL~BcWoCC zJZH+;%n$+vEauUqLBK6^*Z{DxH+P8%ZF1z)=d30;!XOBPc8*b1Ha&m-aCrUd zMigQWfjdE!03Wy3?|8f-*vQTUB^{+7Nm|C9l}22#X~WZGk%n%+f#I33kIeVw#ktTz(UMpME0%PxT zXxva_(5WTHp>dh1SU2Ly=!R+PV&m2V(J_!mcTo3;DRO+&^gWTJbWrU@T$n9FQY0#G zQa0Wi71?`FE+V9^cOnjPOFfGbHNXZOAcnCaZa`Onu|S<$1S3-}WQGRO%|iqrrY=B7 zazNS;jwVg(4kPffBtew1O$@@(HGyqjp!)g03ZMQ5$49!_{<~mrj_*Wo z?#S+c@8#|L&p*BSlJ=Y_IYGY97+jD?!#vw4LK zRp@nvF(>gfE}_o*Su_C{0FLvv1IYjW9zgi(4!}SE=^ns_0v3iEfPeV?4nQ9nK)(q9 zZuKmU6@fUgGwa5M+7LBNvp@x|5Y>1WXh1Ax9IEOT;QV3#zP-??EdtTA^2&_w{C zJ^*M0zddD|kTcBSo>%Z?4m0$VvQia%Pu0Al7$;0BpWU?As^zQGjXKY5E6cp zTu{=M{aAZC|6MG^j7sE%xl^_mYz{LJ_Q7)MSmp3l1Z|~g6-y>RbNgzi0E7|o%GIbh|F<&dYwuYMnY@H*WQTYZkm|J)}O}+G|=87ox(RxI$R4G*!2-;!s|-wsyZ%n4ZBmTpe4F zMLkAb;ZwP4u$U*6ohxFsB6MLHEL6<9yhP-!{cVkc{V z@#yXWkQjgThd(-w>EHdupEn`_;bFWd<}hWmX`WFzZ({qj+fO!y5Nw(xw&i{^nFXL> zMhH476S;-#4j>S@SqN0%eKT)F%xu5kr<6n_#>m8TK;mQo0u^O>pnzHPGeEZNL^PRg zxbY8MM&Gu=3>ce+OaYupA^kp&;;x7dv;lK;au1-aCI-d`V!aYR;$0qINiN{r++Rbz7k99$k%+UB9UZczkwrjDa>Bw10%Geh0pOCz zZXoYKsqqbvl@O6okRpP+GYE(ga00j&yi?nfg4(1YiFW?yrBasMmW)gBZv(OHDCGEk)qjnC^^^vVtH!}CwvJbGf zQx#Q}=$-&}^QH}Ktw15<)&KxcX03A;^dJK)q7#WkgK`v|j2ej!Z-`kD5Wx=f4v3ET z3?YWXsGk@jv{5G=0kd1lBljHl=8+r4;o4|~`85b#*3=kG;zSTYnSgXaBy$G|TwR24 zWEWT_9KAQu1_sE15ThK~prYm$)x9M#S8}lQ7|mMX2@q!nyP=0Dz$_8&YzP&%cm z%o3044dXr3(6ZQ#;Aq}3MQIPoIzm!4x(-nT+pTKL*f8w{YSb7UmcUn$k7{6Y*iL(q zQ9TCo=Jq8+4-Zenc1(VKEeb#hgm#K;d%MkFKZN^q2Qz2tkoVSRItmt7++p(`#;O{ z0#EAgJ2l?u@Sek+<0(;~iM4Mvn>X=xOyduJ^7Q!E`m68Q@7!KDe-GGt2OLy8PEBOi zcw{^p?ndtfE)JL}LF7Hg!EbjMUi_MF8Xvh@AIrz`v3xAwSf*)a@sy-P1+?-Evl;0q zrKTEH+W=OyXeK_L4yjhxCuFDmZ~0hf+*=q!^RWd3D6x$Th@S~7`V&@8)&eNx3bU%Q ztq=mL15e>^^^*0Xgi68v`7-r6WH1w{0HQ!$zYs1OoihopnpVrB`T`^^qWfz*i!*5k zEHVXfK%g1fIg#02QMb9kvA&d0@{ zRkMn2b^+L}-dGXFi^)Uhy<6ePT(wr*-i4sR&a7j;$c)*CfEW)skK_tNGiexr=d9E8;^oWnFg`p! z*kt8SM#S#MJTJA}9SGB8$lh>6A*6IX9*>WYPkrBYZ5sj=6GfJ35&{v;it=X6+%O+) z%3hD;x3hTM!C#TKkRS;jr^%>k5271KCRPH$1n>kHHW4F)6_I=oM8cy;fB$v9{-MFU z5m&9eZ?U!hAPi6xj0Ic*JCP%i5+OOEQ%jvNVqhf&iMaXTM2QcqU1SAMV9*#1&gG2? zKj;|x_OV=TstW3RZ;VK28iyb~g9EH_B(M{rnv&eYcR-^hh;O%nu!*pl5Jt^yI~hS? zq75)H!wBR`+_2FoIpW}eVDDyTl2kzvJec`z%uxk$Fovf_Z2!Nr_ijD1B*~fB=VoE) zkx^My=hmmEXNH_!US~%XfxQTVL@p#iSnNvB8wEWHke>9YSN$LT0lf-ZNgyOZD-c`? zD-E@vcp0*X&Ay&XRb@qnr-hm8!6Q69t4{N2XQ1slj)OXpo*sTN_qh0%pM3@xAkd>? z6c=D3-6|RHiK3M|-mODCnGJxtCyc;wZytQ2F&%c&0}0ru!o@q>%^+2Y{MGDNm=6Z1 zPQU;pWhTH63KADU(=>*DxOXEssU znJQ1721M4Zfa!+g1gN?%ca9Oj(HO2Bxbt`b1U`tGQ%7bl=KD_Kr04;RNd{uLnRbu_ z24JSloK!&$m^dl!It)`v7b0#(EC)=atZG34ks}g`906u`S2pVuw}PXgH}8m##OAhz zNAiQhMWSN1$dZWr1Y;tDi^}!xI`~NYFAlqBTM@Vf8#fS!+p}kQhVc4k`f{`gpRw(q zrhodM{Re43{qz6zk3RhH^NF7Qi_h*1Bkn#fH=vv0_2n;b?!NqL^P8K0@Z$PE`q2;3 z?*x0-t?J>2-}^_Ojp@_R?q1;)T<=Aq%-KG@#z&4c@Y~n)!r|qNm9MlYXEk)HvS(Ptn1EWQ{IXFPD|G!U-yjt*sORDFC?G1f2ht*frdu7Z(iRXuzZQv!b{pjW$z>QWx$|gS|UCP5~Lq zSpcx+t?Q1Lz|FeEy{ahytt> zwip56a45zEfH!X(D~Ag}i~(z~#WIR{%2=sVC6Z&Am-}Wai&~ReMt%9n#dO6`q0S3{ zV8AMxwiGK%#&WfD$uDzM7+8fjx6CsGz(G$&E5KnK+naYYiE%<={_)u1;VdutHiW_?_1{fT5xrApm$R zL3Qdt8FF4pR3V(^aUpGC5&JLj*6N%H&$;rjyrNpUOhGG3^=04g;J3$nKE z0P_k*HKwD++Q{|v6$r}(s|r}no>%tPIzb_1Sk57bm97=<<>Sd3GXlcK|u(BDNJmU?Tekpqn1Y z55x^HiBQ=9b0J9odqaZ5~&G8XnW9CtONBv?ql5L!SCI7YHG6O zQ6UNwa>ih=kyS>z6%k0MDXCiYUKq-IU`VQwqbrL~-p@7(14hZE(-D!QV^191nGB9d zFk*p{$u0ZNh#=;iO}D+wiVg}Q6INC^OceWEwq;J5aEx?dDD=s!syv9e*d{5qd~0+K z-D(fU!E`I;O2*zf9BIo)f?74oFX&iL6N7yV1-@$-2leC1MDq zBPCL(I(6V96fh!o#||_D8}L!k0iDA^oruobb#j1qCU6&KH85aK0Fer@18goC=#0Tm z%7Dx;BVsaVa@SoiY7)W8re1r)6i5Q(&h#0>C(i5_Om{#ehNKG~4xkM%IXc$h*pkey zS(sG-1!H81Kt{T7IFSNGd=C^qMZg&{8A(iuWN>$enI_2K+L7#`0={EhD!S<7h^}`B zMwqZ4U}WNObMJeaI890d-8sD>Il5iKU9j_E?-(zoha7;d$ZPWmBW9>3CWQwE6hd(K zK`j#Yy|_Np>;7UK$35~e3`Bt~K?n*Zyx8rocl`DKZm-GhnkdlK_ILitf2e!^mw)*C z|L7yWzJB&U{pqK7(}v}fFlN5)?UOBZ{P%wNcQ1#mfO!wOjv_AxyoCJy@9jtZ5g4QH z|MHWc{y#S#@bEWjq_5=yriMF7y^^S1iQW>^D^HA@Pd>Fz2HrlMx8ru#Z-0wB??5S8 z6tw_kr>_RN+v5tp71s4fmVf=}Jy+{}dY|5>_vstcY{L25DhX#As5Voi~AvEY6Ze@qQ+IV zsp@eFoB*Q+)mmCFQcwk!GDlwNauua2aNB7gm~-imuYgM#y}!$7Vciry1UIV@7HfyF zE{&7WSw3wV%dC4d4f%XJ0uUB#tHw8MB0T2o3sEb34mIvU&KdaxZ=Fbc8NopwmcSYz z=Kv$j9h7ktB*7SiQK0Mr`R?M_efKyV!uG&%=CaM_4WY@;=T+7G z(BNgEDdWx9y{WC5sLij)nm3qHUUORfh#I`9MUKLGmuj_hL#L{V&Ta0^JU&1Pt3m3h zTjyDCdR2R9kIddR*j5kBz~tT$Npn_7LkPav+|M@a5da0mKK{n9|N3#BZ{FT?AIpZj zyZzl4pMNo>DFD|`pK>S69W$A^`ze%Vc4Ouc!gf3KF}{5HavaCcKl^N+=Mc!uGBS74 zF_}96=FV)6eFWfUW;P!+9giY%d3ovXR0v!P)eFE9IT7FX)brl3o8{hhfI!lg05gn? zj=j6Q57+E2f=`aYZlN&lbRlSM)!RxPYUksNFGEyjd2Z5BB;;m{YN=7}g z0T+TvlZX++_cq39U_r;KelYKy6ktqxNd0zTxC%_gVJa+8L>YiPa&~edO_O7QdV)#c z`vj4g%o#K*=^zYO(@1<2^af||VxQAEBX&Skal<9a5mX!*Gi)ay<%3M*yoCWy$+iQa zd>~SR_tKenq9&3sZG4*1XR)Y2(zL|}mdTGKnlwfx^NwUx83_VWnJ^0=nS6!{v5I8{ zgAWWDc=B05Adr*8J2(ilduQ(CanVzuJ#4qkq6z$_*B)E~D^6fxGa>-W$_8;!j9Wm7 z4@oZ|6Q&KsWZWnn8AqB1^!H{Ft|)3`3P#r9-XM%4G(Zi*kx1NOIFf z7pGC%5FOxAi3C1TC)$B#BRDHubjUVQZzEGQ>y1XFrxp(pQ=%Ds3yVg8LScg>^$UR$ z9h}v$1wfcI5#$9?0^LG4gYg<*h^0yHUz+)SXIaR*irb|BhDg|BzL z>UeXrml%dV8nz-i8Y#ez7uUlzx;J0s(KASyNv`ob|M+*)e*WyUzxur>HtatC^1J`X zC;#`&ZJPS=H^2XPSe}_|2JTf=Eh(-dUJK?C6eTgR8|LdD{?d;=zWRFq@&ERh|LSYJ zy4DL#-CnPD!~HeXROa1JA=fs3ceobNEN`Anx_{$8{VDpFc=Bscah=>%j0K0x!){ru7yWa1h5JZ zh!%ZE2C5_nVWs@kl$U2v#wj!*0l4Zz?N!;96uG6M)>KmAa}}YbP6#XeX%%T&9z2Cd zR>(U=bg5___HsMSmQaC^;6R4H#2}geRTxzot*&q@R9+%xH=IJrMcouzsmwBD--Kw zQii|nPs1^#{eKal8yUTCSUnGOAJJ;{3(AZjPf|0yb&wCtGW~7gk)hkUeK1s zCvGiJ{TwsU$^kVkuHg-HX!iv9e7WL$i&Ds3r6jFPuCRE1EkHn_R^|1s@&J=s5Vmu! zR%I=ftny_(IX^B}dMi|H^KYTO4ARM;VU5EJe$TP*4-LL+Dk6*}VpZeXsPg-~f2qDNq99u-|fQ4XK zf)!Rj#A?gJy(-I<8uj;;6}SSR;cU?|qw9VV;H)Ku2FxnY+Xuns>PK$iiAp#kU|Kcc zD;TK4AS}?AnZ{d-BDk4@*Q9p)9`7Ml9`F&{0SktbphT1f3`6J`!=3_Xw zJOBZhNP#2ZYmmg;jB(fT+-;}XY}O)%C|&pb`STEPoKi-<{Ee&Z{-=NPCof-qu=pN& z4k1Jl2Rvt+=fVhG?mR>x=V2Ir*8h;V^2&WgyNZ)-G33dT0kHA)J+krzVD0<7%xy{dawg&PAob?wi54M2&$&r z(Fc)3ki%xccr%e4xrgg$B5<(GY8%8O!CiZHb|oI(vR=mFZo0XY>$lKLbH*gzA5?=V zxR0)Y96Im3cT#71ZGK_I(XM8`FT21g(Xp@sfc0P#H3bvfmSncBCr+>qKnI`Upcxtr?4)iT zAZ83W#NkBdz^E!T%!^pN_ol=GHFNEi3FbtO{@w`Av&qCJ#s_F`FvTRs%<2lZtRPSl z?+perR)dLxiSLLUG`JeEsBXMJB1Mv;YA12yJ`n+M^QmVjB4j4rfDZ6Z0R{x*8etBy z-j$?xBp5N2#o%y2JOG`#M^Xg|W@kh`CWSc(BJ&N~waE;fCEg;53wd%7@fi4WhIU35 zf_ue=ke!U}!gyw^;CO#veF6f^$l1Z54S|Ta*P`P{H{%F5pvPeDnnY(vULb`bylP19DuNRBW3`U0l)*CkSXMVndnW7w_WccY)wPH z%~axNn@mM6 zDhLu9kfA+E!fJk4k%+Kz${rA%s!yM;QdX5p#tj7wO;wfm zRGk)i1^%%1?XiWiR{kIdYyb1P#cHv3rbf z-0~F>qjlNTDT|(eZe^yW9W94}UmZ>~eOqd9&HL=klns zc`ia)IXhA3zK95#`(YfX!{pfkY&IJ=3q&Ds2ryt1d!~>xh$y==leq^3H#?fU*_0B1 zi;D{iWZ9YM-A|KmR}#`>2IrZPC6NI#3o9&+rh%-Fq!K5)6}XL0Akz1W@t$oWz{fuJ z1N_El_xfvl_K^%AvkPaAVAl)bd(*99&nn6)``+1kyo4yA(qq!iU|Z({?s$?{Lwe$X z7z?ZE*84!Jz`fmdv3D1R57Li1?YKV-AahZ57IKQtAnhOync>dZxXvQUs3*GjJ&}M} zfzH8uPLTu}m@tlc820c!atE1x+#(YCY%+qQpz$YnUKs$Gc1Tj zi+l7W5Q9NUnGFC71byk`JDx^Oh8J2Atd26Rj#!C?_Hs}T#U+W=8GQs;;kgV@Tq2yhfaI*+ z(?KDOgG0z&d1mV%cjj9G>j)MS%nD|hQWT#-BbWs=^Z*7`zS-YN!f?HXb?#fG?DS?J z{pA-=@9yZ${w@L33m|6Q?t1>wk3JaF?U!GE@{j+MAH8@MSj|!%hT{l_xdEDjYE^!1zR&+rqBQF+|#E;ngL{7m$cFl-X|Itsg*2zE#WIwqTF_;ELOH#&=a z@wq-t^63wTr!Oh=`+gVig%3ZYo5s&224Z>FTpmZ|MY%wxz{+?!`-KH~EQ7eHXc@5b zZe)o-2Ve29BXNy^i#MKc1uAc`0ETT2CiWd;{R_3Aj+oGM~!myxheXx|Y4 zel0wLGTr6gx5)skP}n#FczbC8KKUna0etW8 z1pxoWpY8zYmkX8mu+IRlz6$_Z1Ate5?Ev;;2JlyJw3=>zGyosuqGNh8vNh{Usw+iP zrdW7)5wMDOU4GP9p%lKF0l54EYzl$dk#j+{s&IJY69)jG%0*gp@``;F(edI>SKuvM zc|I-Qr*1Z|!dNFfrGi-xxIX}@J7Kd%TTrR`yJ4knh1$Ob@&KCr5E>3wGnU%)*#OUt zunr_I9jiGHl(w)8t<<(qhZ--xGGt#v6IR6M)Pc&?LLkZ2wx1vDjg8A*40*VOWr_b$NsW&SI5XJMp}hOhVVr*|#^BzS1ke+R=lkCna;)C zvG#|WzO_TB@J*$#on5@&VB`lzz&VMmp4is*;BSQjTZG6P2fEry9Z_>@KWn$vhDRsX zxu~bK_cW}1Zb7cR+L@YJm`@F!d|J`0vD2--F*P+!=SPiNBV<;4MdxL5&u`zp-E>``Rk$yNS!d=h z=bUqPbN8crPHCFw`IwG3w>PuRZXQA~c9h>6PR=ET0PYz%`vM8(fShyJ@oes@6vEr% z@pXQEadB~Zb!EQ*YVngQ{EFqkquF2#Rfn)Cbm+wmfPm)Sm?1penG;k*HVF_Cm`0Pm z?)%Hs0kXfgI5Q~>I#GXlZ)!rbiUGIg-?Ks4-rl7PaR>o^bekbZLoiJ4L0uV1;{dV* z-A)mlz%dT<;tpY{!{DBHirObId{hCP5P?LZlS}V_5m@O~h*=dP2ik1qXp$H^K}vTW zUr)w^juAe=2bh8aso4Og0PjQpd#LZvh`m0Mu3AHASML~ z0D}Q6Py@r+05^rPvyw3=!)8NIU_%0SPy(6hW|jjII$-WP%mh9{Ky>u9WsoZM62TK2 zC-iLUEJC9xT*$l^05k!U`-LL|3KjLOOF+s7a3UjvbIHW&ED;EV&{uppewa%A0u2wU>mNz6MDpS*MGL=QW*gjWN@A!bi{yESYL)XQ6F z1PF2@M2EN;WTP~b8Vi6eVFtPCbKzT;qu4+|j4sltjyGTIONY7;IhRdJ6(QDio z#C|-!mQU_}aNYk~*Sir{Kckz*d#={|^gg{$@6$J?5+7joK+Nm@zePrn3x-m$q4FMI z*hUV|n2YrI8eA_oa7hcR0}FnX8?2`-T+<1dZW_f}VT%IP2znVOr7ZxDA|#%HTo2Ma zeH{wq^iHEyP-~@DRmVDDRbHebi+SGaES6J8`;E**0RG+W z-4DKaI=l|Z&>88N&5=E15~G2(n^ zZOs+0sSz9Vir-ZmTGQ3`Zw265?5R#cow5qs&F5px=SWjUdAzC08!uEe-DnHc`%H_G zRSWoe$E>L;pVQMqvp!q6$`?7D<+y89y&hk;Ex=cg>3m_-hN$TV0iok#&PVsiENecm z9gr9mC{(Gi@_hTv=Ed_D^Q>=gZVuy^bKb-lLNHq-;fq@Qd_2xNtE$d=cYC)HF(_{~ z**t`Bd3~8un&){VV(wkn0dTX->}JI5o@KLf^Nz_WxLGGsd==9)^?m=y4Bxus7ocQj zD&V_qxSpefi3K!`fb2;QG;MX^mtI1$T9)A+;|7)?27p{_8Y6!&PG4QqcTHZi^yWt! zcT7+o*~3KJ9*GpNt6o5hX411rdsjemZ@scB62vWy93}d|P{;*586@d`%h%4-Q`(Oc zq8ONsg|@CUMOOu&aKNInQE?4a0W(sL{ShG6t&$0ZdV_Zim*Jr4DJ(IFnfH#ZIRQpT z2t_1if_4#ryTP2q2~0DrgR!xZ%w{Iw#1N<@a#4~bnxz-PRJb1?013jbK^RGA@RnRb ze3*I5U^)VBAaa8QxRE|d(^u5*h{$nB+V!HY9Uw8@dx8l-8DvNR8vw{reZx*7_i7v9 z2y6+tm_|TCvm=>+j9j-Y!O|SXjRa6Q!2wCE9TJ;lI6)>jT!X+A8qg7+m6XDha*GHMd>YrdRK$M%vjVe zfcsImLdkGnR*zW{AxC65Jfdf)DL(~_<<@)C)zv$ECU*BZ-@gRd}hQ_#) zk3arS(&;B({?#Y+8IRki{f^{w++9KrjB%u=4Ap5I6Wtizq|KjvZC5Wog?{`z&bRu6 zm0y0pyS-!ASG!@L{jbT>zX9Le*o&>uy_?X5BFQyrdbT6kUt*drp2^L`{VejC-o70E zP3CI7Pw&(F^gjI?nmlI|LGc!iS{>Fo#8s0SO!aDGDjF{~|OK}IrGRjitS*4{&`Wwpk6oq4JD)IAD7@p@ZL zRMDa`-qj`*NXm=1W~*;?Hq=n@og4xI9C8kUL(a5>mkP^{JOh9S(234Q%}^@-SdOb= z`iinG@KdfE>64@4NtLWkbRr5>uTbR1_zzhI4P@CYjEBZv&pl1c!m3+vn}(7Q@|nC^ zMX$m-mV7>yxmkz#l(X`=!rHB-;{_E%2*{K}$eBE|2lmYF;=UnMa1Ox{9AtryBzN6b zNsp}kJkJ!4#2!Kp;ftsE@VEBQzK-F(n_h*lzp`}9h4EVK$+U!-ZTVJB^uxlvS{PfW zf3&O3DGcda8A@(g;o|Y$Qn52orqv)>Zt%z#mmqj zM^z?Cnsak=V#SX_lM`0Bt#yQaKoO#c7v<88@F>5kV%3_fDQfxrXrwLsti7ni3I?IM z9(e`wa1Q)cTU7#Di{D{AD?jRXdrarC|7wBu{_l^z&F3>%`$p%AT6}&An(3%FocySV z?;KG+UpAFt7uK)*k!5Oaf6G_&Xs~$nu>xE5#K&ucflUZUqN6*Ax~8k8lLF)zbvCyd zK=r2Ih+GWA7hila&vUrH2T*>@Xua@{#d{*-+4E<#az~li+?aVF_T`!4L==eTdCobT zxk#6D?zq!gJ7#mIKu0}phoQt_oOOOQly6-kRzEsi5NWt4?o^4DEfSDepTgik&pK%o zxp#nh3x$B8Wa!{?FHxrh;CF^=nHkZLorD)p>u5ym0E{V5*o%DtR#qpQEoK{yc~P0QU$a6rC_cgD@#$CQ&Cq zwY4D+d|SXJjMQ%?i2hwePlN&j6BmV_&D_aQ`d3I z2@W=>08p7l`VV)%^#6YP<1vjg-U@D1LRlK5)67cnBSyaqdAGcB_0N5}9IF-i_ zVfBX7m9<-*2uF7Svb;2hT5a)ukBb9f05BJs^Vw??s|((#lci+0PS%D_Z_V?fK@OZA zisf3(_1mSS0RVLXa5Fl9i+JirXzWu5UQQvfMZLVcX6~ztB z>@@b$>$Hcoia;}!T@mD6V}(V z?S^V|eGCAuE`W6byuI@}Bw+%ul?>o|yG+LI;nefet76sS*r-MLe3{S;fVxmkRA%Ii z(qCpXqt;ffSJpKpB z03W^z0LEp4B+j(1GpYeX53GwMc%K$ z5H@le<{}}#&2@Nr&j5~>3V?nw)Z*vWQM$THSAp|W@?6DXD>$|I8~V!9a#+sRMBFQr z-B#1SzULEzsX!iQSjVGR^Hngu>?J~|h1=tr)3#Uzi&j6x++N!4zTx5K>Rqg&N_FM$EG6l-ZC2S#gtH)mm zfx`myR3AWJ9fqsNXkMYK({8QN_9}4OX`7T0Lay^4LMVNp0K*D~mRoCpEy&Vo_f>@3 z@(Sdgu)_0cE0aWvJ;OSjOaURoLkK6m{8dzI*;r;Ez;g~c5YY)iJ0oosKH0i%Lw00G zwj4a*oTU|V2pQy=3RlY^7R;b?-f-UPJcnQ$=fD=o10S(5qPuvJfeSxe*}b?GY|#<^ zub0pN_yhl?{q5iR!hZe77xK27Zv8%a!Lv49V9v4{cey_Xgw^+uR>l_bD!;WrS_pJv zW7TJFAOr#l!p6_slfJzvti-6QmW6Y{th{03ob8x@u>(PAfMp z;*m}27~A&)YAla)oXeZP_1m`H2LpC|N zL`CbOEEqE*6um$QcNy8tL^i5NGuv!7IcFw*{=o|l?_7-Ew#1&8KqAi2=>WUR;_4s; z%NA+S|j2VKSf+uxs#X9Nlr!;bUF2lZqVDcmiM23Rd;Otw*m>_H_ z0uUr7b%2eqcNC717zB1_tUa-U8DJdJND?!mvAU*!sN(K8LJ=uDE(l|U3jiV4Ig%bU z%aCAMrZ08kp&wWParLc`s~`FuE_XaQzxjd{I%{MCcz^xT)Bp6vKm6-YkN@5O z_&@Xh&B&UzZ!d8*VGq7jyXgJNm@ss2wU07wjh*R>o5Kg2-EB7|lKV^0r`(x7aj5E% zXaZBzTfTnFN?+Q3=!bC(qxRRk+lz6t1%C54BIBv(d#={|^gg{$@6*pcl^BSgSJd^4 zQv;OOVnSX62m-)Lb+ILuAIxD5Sd;S!(#<&E`ZW1@MS^mH)k^*XuI1AS8CV?ekdd2U zai4;FUPD?}KEXkJ-&Jdj;mQWpIFH%${e*(HDoojsk@hO>3t6Azdq18o=Um7;3o5 z64-GeQ-!))4#)vvbyHflZ=Q2TSP5}OLTeF>_l)fD0%kdUaY8Je3-A!iznm9O!-8;C zY|C=zp|dPz(P*am=*Q$o4dNiB?ICOp-JYj=-f#Ta!HTTR95{u|p8Ngg&CSLAuY8aH z?N5f|Pvfhvd_Vf@J0l{ZARU;NMOlTkD1f^PX_d%h1=7kyA(ZlAC7qQ`W{1$_5HmJ8 z)3<+H*m9J*bALBHf@vyL#B2GyLIAuvA*MCIs%tg!jPJnc!wT87{H7M*s5(c7nS#)OjNF{w_9Q>* zSnZy#jeb5SU`8CgX1cuYB$V2I!DBqSz#I0zEuVxKVJ%0v&Gw%8ISnYM|`wW|(iA2%+{ z!5}z99q%gjsEJ7WjclM@R(Jqq;`8c>oD0fE-XoggDVb zwPTo=B_v>Q1G5Q|#Dk?BAt(?{oB_-Xb7q)BH|X!x;^6la!F2;Tmmecs1PKHu0*K`R z4xoVxFNR#?Uaf<>$RT0tC=eV0vzAzoP#`)C04bCqN=CQvUKr2~WOg{fy%XeM+EM=+ z*t#zFHi2q_i9owZV1+{oGr`5x$(7));%?ZIsbh9_K#U>SD@JLaq) zB85g!fLo#jk8T_A5oXrsXtPrX91~k~igfTu!F>x#fEZ|qDjy;3hr7FJ-yc{9(1DP?|MBqO{@4HUr=Ly#{11Nrr_-|}cCD8_ zyqJ9V%ns@sScl7Cn)_)R^yTiuqtHC2?>er9ZU!7w@IiXUl-_8^(hJ_qH_s11yc`Ty zA3XIV)cX4{Jh=jHM(}hIFMn1)D*ilBt>6Jb=rRC2;&+rigET}Q0GqO0DFcgAZehfj zpNbW6?j^dd1M9=7h=q4mHy9|7Gi~@pXr6Fb1-46G-vt1vi8|S;m6z@o%FjUy9jUOl zfR!aQtb4=K!%b1<<^W)b0B|@0z_D=0mQeseX`$q_3^i(w3lqv$@0Qu>3){l7S)|+- z_EP|0nz3#^&!qXo!{dbl<^jOnsvlok`1;ncGJVFQ19*AeVWmoyF_x4RSgBRz+hvT6 z8H)Q-q zhylQT$^f=Pt?71=0URyYs;Hsnm16s30CbspN7aw_j1y(AtfJE#<#jHKp~{e#J!JFt zn#*3AGq41lE9d$0Hv_ou1As9SfJq3z+dcxg>9(bbdyW9;S26%c0I>B0;1~qJ^*VFE&+V{;{f2l|HC@~fB*YEfcxYCe&stG)GK7Y^vau3VVOOBN&xOZ zyazCR*#iid4q)ybSa@gOdTED6CcARAT4%A90FwPAAXQQ+Ry5|#v*lc(D7NrT3t%m8 z*QYCW$!e9nS}E~`E40L~TfnJxCi;4;$CvE^mRC#7j*2uj@?cuyCHu)PmEMI3Q) z;DJdQnX`5KPsaBWyA@*`wuMnj83=8a|Gv|4OwHZwzTrUI4ua4$7**Ol8YQOG%m5VD`1Nd?j}&mDK=b+J5LGT=FPOrEpOGczC4@tddg zTax}i_TJ}5mMpvP``&Znw;tvmPinK>S8TXUl^Sug%5(J%6FZ(uU(Wj(n^JokQ@9jDR z3e`Ta56cK02)qT~ zwBGcPoryBwAV2T5jISOzFD?*LJvy#sH)0zwTEL3Lw9V(!=|3k<}An?Ns|h*+EoSU^w*K>#&mrlXrd zA)tYaD5;F1>bfNohna)mQ~VSh=oJ^{3>txLAp=}o0XT@w)ERVO%>yu#{3#p0h)y~|uKylrIk1)WR%!$#vo`D-+BH#nQYHzq=+ ztvDp#Z}%VHH2S1(+w)ylTrY_CDk{1aKJc!&%$p}A^>|ivLwV<{Z2Cj5^P4~WuU~y~ z^FMy$8_&=ect`tzI`%>Y4CjV?(|*#nJLLC@J``fbGiyJw{(<<-Z9eSWIzVx4Wh*To zgg^=4gpbU3x!>)`*`MmLh1`~#7e5UDXwplq*30xVy-Y9DcTE<7d8v;T?68^NOh!g? zAm0LXDyEsJmd|pnxI@G+qpSJh^n1G7o{g5)0CYz9t&5K(JF3;0iO%i;%fFvlkVBx_x2gFV!J_Iex)fi+PsK?pkBS=vbWf z?QX*XG?6?337o(Iiy(kf8Ywk_gh{K_Ozi?k@(2Qus;~U1^Qz1HJb?3%%_YSQztSSj zTZQkXl+sD?Ri6N*^yr))bbQuQD`_K1n#7ET(-Mc65_F93d@_FPiN15Ck8j5fC8kNz zwSf4!=+h{~0%%f9jB0WW3j$`L)CtG_lty)0pD{nH(ybqSask+-_{TdY{*R@sR+xz9b6sGCK6^Q=(+5w1m;{Yc(vEMB>@Tq0ag>z-h~B55U1>L5kSSA zL|malyhnHRvJo0cJI{OFGk04s+|gz;9hn2@VP{3JDYvZJa2Q1Bz!?fAXGT%-3HcAtblO_Ig1(-l*AnaLEJ=mG~;T}E;uR)5Db8hBEcYo z7y)zyI&0ug@GVd&4WneHJ=kCkECanY0lg`Ab zGs!hO2}XdlZ$LYuqPpYu+Dqd?W-aLfFtrPYG93Uo8p5cRhsz!SbwG;0Ll|0!l^YT% z!q-kz_GmBNdLt3`L{xkb0HcGWrKbi_aw1k2K{&e^)SO!o#H}z)(HRG;iXc%4a)%--LmizMlR)9>@T#MnU>Ix3^@MSHt-Y z4;@r--sW!|u{+lr%^k|k$HPNupT>au?X?)8ccn)v|9{qM-AUO1@Jw+rJ8D&h3*Qy* zR5i^|^*&=@Rw`BPPZM>Qrb)4_N%IE+#4FRa0LRFtt3}fB=D(TPU%$Jv=X&RlK^!2BtB~9 zj;gM@Rh3X3zS=fnb}Or*q-K)<@HQ~JYaMQ}9CJJ-0B1V@*xvxNHmaM@_|*KW?x}rV zMOD>wsk&|*N?;a?)fUx?)pi~9)TL^UyV@?y)=o9;&IrKeJp!vC|hrKR_(f7b0WFl*&%C2DOaXSWS7Ys%`l ztUJ8Q!P?DK`TAtNL7A7YwW0u~+bE~g{AtDnAZr4kO#o=Ch))85GGV?89A{f&B>^y` z4S+(qjt_tl4S;X9_WyWz9jY~HtX3lvGsZe0uvKhfnw`a`^~oyd zl~!wda9SDP;cjKw+94chX5TYP;pw!nA(}=ir68oa&{Nl8CCFO0Hv%=pFC|bN?gR!X z;q&+92j7<6z0~X?&TQ=TxV7Wf$WxST!dr%nxuU=MLOvp}KKgrXrG59zF6J7P1UAp~P2cuF?M%(8?2 zp!w6^dhq?@gT~Qpar>8V{=r}P{bz6e-Fv_JPsZ0S8zzz_QMJdS#1h=hP&onBs+o`| zrUfX?7k3UYf;|Y)xO03jP%WMa%; zn1$lu1sxDpSR__iEhL5J`e4g2KRBzt#1S)ZR&pl%wm z2AAI2M5y4I4HWCsw44W1LNU6RGfOr~GN@*Mo2t8U##6*b_gWSCC zgou=?M(nelGDG`;_>ocugLvP{mJG((<=IG0)?7os(3z+bz*GRr%vw1-tkwGi8K`(} zZD^uXEgwlfW3afG8+x;y3wBOp&#l;KfHMKNqAh4-;KrVHxM!lyi7=Y?rAxV2m0Qu) zS-EUTbU*CLIu^<<*YxZmM%M>WaBD>eWClQ<2emG%qREP4I>ixcOJoLiYlKEsDSdPg zhCGn+(G*$D1?<9hFb!rV7+?wkyNDDmFbKI}ptf@>jDwX-no;L@4tI6q%uyiX16%+X zxq-H#q$Xe%Rs$5R@G}7oz7ZWEL^v|cG6W6|gOMqZP=aGaG{QD8NFIteYE6fuK^TSL zJhGayxF|pewT-~lAt>Ms_kxy9VLS;l9b|Ag&=B=-aXFxz0d7hVxXs2~);kEAK?RJf zCr_oj1OO)$b1fJ)W<5KrT|q%iN@Lev2=;J>0kU^h=PVWj2NReNYQ$X38X~Qq49?lK zFx{$e2~g8ko~kn&4P`5mVJ5tXHw9aAaU1}GaeuQBIf9|K>u>-Iq_}MjB+7sq9OU8* zEy%gRK?I1)UeLKYB&lwNN220(rnok1qo;zr&;glz93S^A8w@AJo3*B$z< zYhBJnFAO7N&tSzxckbuso2whSs%X!|*$8;$QTO1Xe&wr=zVRDRf9->RpeWBo9zvkk zfbAq)A7r@(jNzL>i*KABXR^>YnS0~UsqV+}C<;VwnXT1V@9B-Te{faaz7#sgKcQ~( z>F@df&*`OB>t%YGUZ$7nyQVc)TA;=ft2OiQNjQ^MXDv~67MLRtV~Mj{g&D?D3hrv4 z<^%4;A+EylRuV7Fd;cxl8m?bj{XJ2znOH3~UkKNo)25m%glk3aR-LncW@Qd_2Z}8n zxa4u7S`p*yI5q~xxua~>aGh!Z1R_$Ze2Qlyu^Nr%ln7xdJQ7EJIyG~g2QclaS38eV zqIonY;5Coh(i{M^0$c0GV&;Qs>EVA4jdz->;^&(|@iY@whGj9^Y*nB}QKMjEHO`1B?zwJi87b18$-K6Q zk2FgNv1rPwZVRylA*Lznux?&B2O%!gs^*pgDS{%J2#b)g?8j|t#&p}HBM6?@!GMft zMr?pcr{F3IBu8VxW3=u~O7RQle)YxQ`pUfzf9$KgIr#QU{JqVyk3Hu^0-}@{X_8pf zA&=9jqyPaFpa@3P2Nd3fH{TOf3$qQ@f|eGtfEhZ}wf#DD&S!Lmm7P*r(6 zWa*Qd`8v<%@`<~r(+h!k&;4BkGGCptMqNI?iq-R&BNo%$(y_|(xl9(l)p}gkMJ%%- z0r4wuA;Ka)`shQ|_eGkA4&YeaI%Pg9;buS(8WdLY=E_WuGCp4iG~vSaxM_(F^3G z>W9oS3>U)tL(z+_`>?-$ogR{!@Bp}TreZ}{ELk}SZJno}Gv$GyYTH&sabVpVKvW8D zrGUXeRyGC`9bg3v_yMJqEW(XnZO|13XB>fsm92VwSmQXr1WwfYe3?^Ws~pE_1bugF z!>)+KA>6tcId;%qGg@XdFaQx!QvgsiX~AYd+nNq2#0_9f)N9F-Q8u80G9YiHn2C4U zp-Q%KIOGU3wifKL4SdhM1xzqH3M$Hhz({2eWp=2ad2@8%5Ju=mp_z|b&VX@pK<8rS z?pd`ZHlVnGoQOvA2IlZgQXFC2stb`Bz%W<>6y5eE1AafG>1fGFn$PQyWIvG5Z99&8KRvkhx z7*Kt0_r2~Ijqt6LLz|&AZ63{Ua|bAh)M#`lS>=oe=N(~mI|HSG&{9LL1csB)HEDJu z<2@JvnP+&x`4x~vTi0sobp}?)4+HTsZUjS= zivyUxg-&e%Xo3Ln5dd-qW^EA`(bjZt4FEbOEUrvdniPRqdsWvV)%j?;wX(ph&pM3D zs_2yJ7xMLh0RYetFzaH5@$_Zby3on4YhGL})vM2ENm#9Ihn1_;IJrvkQrnu=`!?3R z>lZlV%DL(0;Fx{5YR@$D?L!qt-8-YDCev5m49x1SZgQbY%QJ_AW8SN=#^zUuT$&kget*vqY=fbu~=_@VVCs z06kIwSC0k&`<(&k+W=q`0J!>vQ2_Yjw;aHeE5q!ob#)s6&fD76^EMkJ0DN>a0=U=l z(sfq{1Mu`<0A%HyRmZLlYt?Oa8(MnfY*STQb$U!=Q6*rsy2(LECCo+w`^90iqrroG~L)&|ExXl031@c{5>KA7;pwa(E{l09)Nmz`(NXS0Q~&l z=mGr2_&Wgp69<6b|Gg2wfA#e%0Dto*E^865eaQf%!T`pL0?aW`&FM`v@8S48u_#WPxTQ*SZi~tK(vbP|`AS(ktvYzmO^BEc$f{P$ zXNRd83}_2vne#`aKu{p1Ee(f}$J`pHdNrfmun$)y7Ug*cK9uF-%g;VvGL_?rRG$IfmzIJ@r`0L+j`_a96 z$(m1;krAl(@-YFjI`3+u?eU~@{tfJA|=M6s!OM{S5s($S*v)@)8}shvu%9c z05PrR@M`aY3G-3iA(4W@DO|!gp=aLb)BwqeBaxwTG#Z<@bIGhsECsk4{0HbA`{KLp z5B;4lp#6c{9~pn`CqMfApZ;3fe~UyCaa2oqaHOj6Np}a20IouCRV2JH6`Hqg3VT);bX)xrOKP~>hee{I}%5yZqR>Z;P z3NQMm=WLsn9G0;h=cvY5ofRvy{1-)D>v#7W9>sjhb49Gr!Yo6>3N!iY^mXRX5u8O+ zwuW)*-oRZNwVb{jwid5Bp2t-$rgi>HdzTv4I$ZVr!{7QM5JVIauf6tYa%FXInx;}1 z04b$$)u^Q{i+9_4Ry+q_V)e7Is)#T<9T*Wb-595(b?b3ocjm(5VpYVt$+YUCr3cb1 zMq7pttKL{jabQD~H&opFQW}vB(Nf}a%r+&-c^J*T`VrRcI-+5E`>nU$eDlrs-h1ym z-}z2>Bu*z6d8W~vh=J3NGysU%&CHEbVs6H9Y?=m%%nXR?G5=i#`LmM>UpMB1de@F_ zTM`mCu&CWodvLu_VOFSKvxo}F8ifFZ_Iu75&hV`wWI!v=6k8g!@B2@VRG}roL~yQrx=hGer|Hm{T5p&U(1luG8q}eU3q9syoa}%rEa9huEhlT%0B9} z1I`>kdyl@sD*)Xv$sZQWGIsz z3|n(%cNmMBGobFE=HR0PTbMc@03RWQ0&_rM4LmU+%jg8~tzrXhT@((2feE|^*z_D) z-MSpa>JIEcPXK|t5{vhMfXD!q0#`tY238T!04>&4j`p9wdjGW_`j^c%kRz)ArU0Qp z&$t~;;n;$X#6#)J?tl4lheHa~g_0^n4(=H~!pPB)nX}XiDH%CCMkrwFwlNup!jr<% zbkH*(N)4sdfv7O;GrB^zu4jr)WKd@y8-%5hvCs$b3&_EJcTRibiZjjqw)hTk$jHi+ z4{j|~Nl1rtu(=h&7UHF7Cor%n2#t%AT>xd;?m)yGU3bZH=&z0+e0`(4`!2w-kM zR(oCeN>Lu1Z_cH?x+;AusB$S)f!Ty>Jnc!R!9jEX|))j1fEQy z>iN?U#PjQ==R0ufu8F3BDRBa&R5vtycI%(K=dbKGn^((_D`*4-0vH*M1w|sS(kUdM znQhQ0B_S}KthES}1N_qe3!8f`E)u9fFJcjF-7&MT&3JBv@0|bQOR@exfXOW$DH0-4 z-2-u^Q0wUvtNJB?!ke%rECD%67kz-D1~etMNDf{|7C;f0q6e!QEZT61F_+}O*=?>K z-Mjvo-}>U0hoZRL)1%+r?cbrcOWY#O8$$wEDYhagV%BQaAD{3RKJ#gTN(<0gaK_s6 z=(#T_7WVPtjVBWg$K%CjbG&=|_?$dv&7N>qgtY{GEu13m0RUR2n01vE5r}q8vJ<_~{#uA2t{}kx@6fa4 zTN_}q6_6pr09dOSSj?QA4JxMOPzHHJ25NP@x|Y}P5BnSGis+7@pfngd*|-<>rY935 z!4~pN)x^&fg>}OQ=ym6;JVLFvU{6My7GAXMB&&?@hDTEl07Rd-Q86PfK2Xz*<9?ev zB4cAYSkH2RWe}{8=N3@F2qQ*?b zO|fAd9qJ}vaCTQXh}wggX(^N|c~({;KB#Ad8nzfzxL*4V#lUuLGqNeDW+_cn)OW}ioO5vSgFm^6ls0uP(|A8;;`vFiZ z#?wY@qk#n1<)#4#VXq|KH~;o;{~rMU_E&!dwud#Q0=_kMGX+%_ep55^#AXU7a|1zz zd9M(`=*nyZ;TE(t7r~W-T#Z=_#k6xr0ea1^oSVUXU=n~8;#4CXeZw#YgZ8EwGNO4)X%{ch~?>w{c$xGC0v8|y90@$!Lp+TGk7-H+--WB^*fF!W#j@)y7I<!g@O{_$p(okrj6ak<_kM}oQ@0cQ5c1%U z>7wx`L$%WLPf!5Uu87erqkc^%m8w8(m-uDr+QYEQ+*3ng-)%KFDqaGKqqO*kXIWS z)=VZFrUU?Gv2&PfQ;VzqQ|;8Qv~*FPy`1W5r)tFNiB<7bKkurGR$AS=kH=Hj)!h=O zBlD@aw903xXSKen%B=c9UDa&o9RaxMYqkMkUjnm()%7qg-EmWV>F}!6T2fib(9-Ki z0MA|@06e*G0FDg+44c5L(rPRKI3)nbhXufE4>N#gbytN1%<8l1S_PonB+R<1>JC;{ zKeZ;u@g&f@SnZa$o)WdwHcU&0pKnhSVClWhCM~@;oj4|7@};6N0Wc2C{#nzKxjys& zP=m$2nj0qqFsA8!dP^Ou1{fH@017gIJ?;S*qXl4S0GMY0K5hZT*aGm>0r;B#djNjn zKllW|m-uS{{?>o-PXYYO*Cq$DfB4TFz)$_S0Fb5uP%e)EEIR;`0MI_$066aMnwEWb zQ>=dOAgviQ`T80+Ns(r$k)ygqjUJ<&;^~&_4$X)p7B6`qCGhDB?D?uS-)OJH8>f`2 z%qmUlp$S0*Flkwqlulf1k>k`=!TPAEMJ&4|njq<=i?=Yp_}4lu}ggHvPQ|!Z1Z`&Ut;86n929AyT#0 zN)9BDgM6a6X_;EpSw1D7ovtW?!zs*>HZi*Qph$3}a4=Hq!2xz}0z3x_R^?-=3M&L5 zIU@DL8^4`i`|a(&k$$kelK<&X9DeEF|M=Ml-^j0ijyg^hX>y1Mz?E*+H%v z4yW&l2*hO>Z>z=mLK$Md1zga^vbJ9bDgqcIc-l2Mn7MZsqG8_s5Hld)yG1XU19Jt| z`}D0DO`1Ke(#(JsU@^`I=nP8IN^iB)a6wCHW@KyRl<+C+39D0Z7aonPCzoT^ux5Sm zvW;VUp-M|V*Bt6aUDa{}xQ2{rE@jDf`Jh>l*&4*0KBQg{C9S1-e)kh?L0XH4+S2*; zj*gikqS|RyF=(tVhJLr)rB+J~r+qYPwcTfbE;sX8^h`N+zbF9daoOBDgw8%=et76m@a(Fv@VysD{y+=p4N& zqktLB76k&iA`$AX40W1X-@tlPF;Y;#8XFph3cE^H9l!vLMfQE!a)FWi&_j2+W!7T3 zNH1t@$SiwTcRs)_%+BBhD1%5bpl^p(VGa;TyI zsT;_J_BJ%7YSRGc18D%cz#Y`77|hF7@=ehlkbrB`R-`v?nN^ig)TnWHSYL1fy1~F^ zd!Pg0N>qd3)eOp#j0Pwx1ae>(wJqpCGyQN=8enkf-U=BJqo^wRp|}AD_?A%!rKn|$ zN`&4A98>@Yp$sL2u3fi=qS}B9a0}lMp2G4_aM>LVTi_Y6g=c3ar-PQQ`C3ap=rb2cy9a(a^3fBA$jG&sQpFJhmZsN z^&itkVZ^0GN1^uk7J{C3Z?cRd1z~m?osf z2}G4X++h$A$s(#hFMwqWMUU`mW0aN^$fO%e%hDxKsa8$385J!BrjX>?1X@?Vwjiwy z?CTzLn0G}yEfv4lbK$t_LKEs=(}!y+p%sy|an=Fo_Ku$vNp z_O?Awhy*qyB&%EfHECo}#J1qUN1Nuo_VzfuzLR^I&xGqTj#8p@!iDSlr`6_`>$I}} zpX6hxO0<+{3XsGc*SKzPqUnICEvr6QX3X6*`D&qBbYbPLwT?+#PF-eDir|QVb6As% z!cx@>>G+vcDCpMLCL`eYp9{uRIa z2WS4I8Aq@LZDu?`2y(CX@DxFC4re!>V!*#gQZt)LVV>0sAzH}M60W##0iWmp6a`k9 zDWJz=)3!%5p11f}BbanonzY!}`&}5c)MP1rVM9w$Sj?KNHEW}lmTGx^;Y3T*u+m8_ zHC&1w=Wel8wwUweyUkhGIp#*K-z-aIe9n9cdGlEl7jr{=W%d+vV|`Wnb2%@}X#H<| zT8o<1yYM+ln&J5rpQa$Y!_iWOOA8+dumrrPh|mbU|BL?GPXZvK8dQ=J(&JxB(<%JMr_0P5+pRfQy4#%f zlgm&pFjLGA7OuL?hXn9uW5D5XQ08v4Sqfcq#=4Q>(bK3J;S1m+qPO09 z>y0MnR@4Wl&?E5%v8jNs{AYz1j-K_?xktQO{j8Y;>OqAu1%WnB!pu`8onS+Ez z?M+%@49Wu0?5OxUV=i$)R5?yAJ2Bb-6~Ip+gQkY>ffl`?h?T$kaINPm@f4;qC# zb~{t$Yj+1k2tE39kB$aK*L%N{+kzddn(w7pPi;Hw4co#2Aw7668`iyMm0sA>ppNdE z)zovbVF!k&jiZz3V1kTx!?stLVhbMuQyhs1AO;!KhvIPS&(I#VTo(}0hvaHEM@0jr zL(wggch8{LLcMB+IDpb`n4cNMH55mvW!oxHIAy&h^8+HgYoR?mK?P#%t>dPQ=j6uD zMmO4@L(1R+RZ?{T#neW$lCg(D3j_*?!gL5}UCTYtwW$I3$#r?_n3Fq;H9a8pU(4eA zLOJ7B{mij}Ho#~)2v{LtH3F%bn*-)>>`fb0cfcSHf;n`n=z&58_Xe)SJ%GW%vNyc| z0WQE^oC`L>BV1t47zrqR0Px@a=^yB?1^~kQ-oQ`-I~S9K>Xx)AxXpGwV9O}#N;$b| zF{lQckeh?uigI?kwQ^KHwmd)^xE8-BJJ-Ib36Mnqn9(f{TNfh0$qYN@BEzWIfP0Xj z+UqGXADjRerdxA@6oH#wuosd9I;d`2x;7EV(Eye_^Z~h2JlyHNr;V_vxc56@H6q{u z&OqMflIipAk8hspRet*5@&H`0Lp2~U0&E1~@_bb5%3hxqQo6_`Ot^6Z>6ic9t3Uk1 zfAx31`G>#yyT4xWst7^%Ohw_1Hb=hhUlF814;}3}KOsq7e*2H< zn(-$=wOkwkJ!t@>l~$;JJ1!kCFR_+;_PQ}*l@V28R4WOy0aJZk6*s#~m}N5CDmapa z#Xzbg%nBn}<%8K)sV-To+-9v*n#`>%0Nf0YS(;QO+11Re6#(d`P4oiuR*d8P0js0q z1fbidQ+q7{ z9FKunRdm~*KK-BVZOLItb&XU#u+DO={}LcI?S%OFN&!5&Yyflt0Jnn!cxA@`KHeLE ziyRC;oa5;IIB$f2$VpAN|)?0RHi>Dgge21mMlT<^ZH; z0M+0t*a5U3w)h@MHZKbTVRH!K>|Z{|=HbpwbiMsu2vkJWH#Jvih48=_U_^t7EHspa z(}t69YUp$>fEjimfYC6Y{(}Q^ojT^hFlQ{r1dt1Q|6d$!B&`TQ9{k- z%%`ly2(vj{U<>02Ao7vE$O04JB)2lvfUQwRPpUB#xv^n9Y znK9Kxc)duimx#+{BO)w<0h(n5%d!V|s8&joAZy9$?v{~r-c_%s9!K*h2mjz!b&O;7 zks+20QMYR>4V+L7z}hF9@BE=(5BBD+*=@LO(r7UTXa(a|E3}iW>Nyhg9O_yspJqT- zA1}(gIrDh~$N6V&@^?>hdQcaav%lVQL3`owIYK8P2+jb*mt7MH#ux=hq~zd8GCl20 zc!Q`xh_j?B5`xl{jUz?$_n!?v`rnRU{cm0^pS%CR{mjk({BK?#HXk(oO?2ngLOwvK z#`U)GYNQner!Wd@@IqgH22*X}f_oN~%0dSgE>MSWK|IUplhSI|&Ul@2DGjB_W^-Ka zDu|DMnP`Udz*yhd9soS0Wl3-0OoV`kPf|ik4!AimZ37n`Bc<@D+*!@J-oP=tI}v%J zl#;nM+z`_k;pW7YQmPeR%irDV;kER+8lw@>NNEl&p9GZoy;eR=_pzQ* zA|e8Us)uOMlV8P5Ma?~GOt4738mEtbIqI`!39uST|K?AHdy#a&~u~FYgGRdx_`CLo00~-;G7Z+}jP%ZMSOHmqOgM^BwJai~`GYDUaQ?2{Yl!g26YlsX#Zz#>NAYiEWW_E)`h zay5J+*0u=sqSP>d0>OZe9XGxe!0n2ld+kIID!o&>Dw6YHD(bhOfi;{qqAgUdZ=4k< zY_OX%MZ7cLk~g2KAJ&YW!N47LO%=+>`026!F?D8_xdJ1FuOus#lWBq1M0n*F~)%b z-8yc7fI<<@g^DO{LFx)+BXP9`IH+cD4`rwtc1p#4Q{a$mAyN;Z*Fwg9wMia^+~EL# z!LXeh5g2l9dS-C4gTC{R=&dg?Y$A~JHf+}R`JUhfrLtG6QvKEkmj z`tn!a{^39K);Isp-}`&N`v-i1ru zcR%fWmOq;GQmgecy-Y9D%k*8-q}2*|gc{T*cdZE+0c*wt%+JRit&=+{?rA7-N<@=L zC}MJDYB&kizmt#bY}ysmVj%(5pKI1wE#)O3B2{cbbJ4ys!>YM0I|!3l zQY(oPWp+w9Kcky7yWJw!sBK0}^sW-XNMkybh(ITNCaG;mIYtj!0sQAyEibNO7J!8n z1*2KNw%FKX{<1`vrfJ4$(~avN%tx<^3A9U?v^QT=JO#C4h*^ z@yN{eyS>9OaMS3!Kfi6;MkFCM-F8-7CUl}!qmOP*MBFeXN-23b zfh;Vgw86&QYFPl5o#rTLeT`arZBa8d+?-mmoOSpu53i*x4Fr(u%iWhJR(1QE;hxTa zta)K9@M+seuHRzIgDrro->BF6^x(&7erZv?O^UXszwY5Y=RBnce_m1w;MQ!z{PnN@ za(_7d^k4bQ^~F+(s=ojJh|O5ZQn%_=rsM`Er6HkY*Y;mUsF z&cr@_)v=PNEt;(6g&5Cugek4wH4G%?U>=UTKO8qXH#AS^Rks7!q{N#|(J`e|)oPf~ zAHVtew_bbn`iCEW@a*d9*^?&$s46iNQL_;(M{anuaUdr~;u_$~zpfqT*_RiSKz6=D2I(2GS{kL9`AM}2Z z2i|1?x(9L(ts5NFh(3XSq`Z|~=PJaFg9TeMlokf-S~yy>3lR}7PHqtQt=P5oAF15y z+O~(Z`Or`Y&kh%~pmv8rgcS{WyM+jflCU3IWW%XLrYJMWZ8Nk!<+$e5iwI$$gvaA9OR8? zqvTKrXJYgJo4t37wI#dG^Zq$TjheM;uYEnIPhZ*UCfQ_*ASp9$N}^yfx>$lQQ5*$` zgvhoKM@|p~aGnwb3H%ly4}S1V5CoAOBuFd=GVDlk9Ko2x zx$M2yu2pl58e`^RR@JJ#Pt$rL0kwMKV4t;W)n#64)vEc`KmI`?a1(1t0BVi_z~Exh z0TOiL4OY(in72ATZjqE7%$UO#hqz_BY-<*Z<dHc{48nYYYWhDKmcAm4(ab{~D)fcm5+M@)d6nr1;# zip&ZVkir3CIKa%_gB7|$l$Hc>bKY&`o)T??7T>#iq@&@t6ms&6+KrGilGJ0Mm^^ zNtk%|fdMFY32hqyyzyoRaM3w{JEsib&K&}fwt3$6jSB5y<2Al;LW>^NuyM1 zdwfIy{_oFj=W2ZMwH<&DKNSJ=ngN`54&b%TfXVgj$>R!B=0WxGmLpaMpn3xUWNiR; z0ssR87!7ZVn#mXARci(iUa0|;=c7d-RYt0G_0=?Q9tYPlfa4Vd*bR=!(X7;p7qiAP zUZY|w>_?;weHpu=)w+?mv(%xSgyo}A-$WUJO9n7h05DW}Zjn|QfK~xOD)PM$07y0f z(Z@%*Tv9rgO;7_EN9=(;&jm|a#%{>!g}H!dO~M3U z=ILJvkQ*@*Le3a62p|fvqNWN5by!Cl9No^Dz#&K#D1d3i5E*lpz%XK?e2pJrnZp-(Wsm!B7p>hCnhUMVXB&i6vO1)=#v|w0MnVsnuUijlDOCzltbuOQel@Ak* znlADPdn5eWbU*BOxUj>Y+dI0t_+;0W7u76XSC|gd7{@om#QkJu0)K^n%}pLL7JvX= zcu|cpdJml#qp22!iXa?>!#dJoL))F7tmyDGytK}nRZvFdD8BV$_+9|z0F1`)91uCI zgv9gUOQ-euT-v|Ibas`O`#N8vS|f~GhEkd%BMXI6RpCH{iZBDaFdb}C&+TW+*ABld zc~obFJmIYz!txvifZ1k?ECiqO4u7ll~O-q@0 z&zhYuDO_k8&tcN4l!b9W{R6m0zh0si3s!O8dFtvtmt zknjB_fEnuLd!Gyl`Rsdf?~@t8*~iMzeg&nyEK_xoQgocog(=l>jz zIy1qrkiYT5d956JRm+g8zVCN{)OF1~AKj<#R{&O0IbfN*X#dL0Cwo=#6OTXs#N&@| zyX|Lw=XbiRZq>w*X~viV3MExy03afD{U;#&5J*m~thv47RGB&9#C1ne2?G#`M9rKz z%FZk(2~)F4x;9lX;>C(MZ7x&}M&l_TOjGpL@oD?+ryq4Yip?RwO47Iig5J3u6a(`S zJh~V>nha1E44OKKMYJxi)MDtRWltfI5*l}1;bO~eJbc2jc9;NAa=Fm%b?(%TZ*e?> zv-$-TjtqK`xFuZmIA9Dg^rGaoV-Sa0P2vqbp_~CH&1yBUb0)zZ!-1j`6Bs#qH|WJn zDt)YO5pUpdz|}N;L%VZso)m6fcmMz(07*naR9LMJ&EXUTTXl24n>rObaz5p_E#FQz zRoy`n^Pw3r%zWi0ME79>yn-1RteXx;ja-@5ppD{4v1Z-?N!5Yq$bw`}A`E8LN=VfM zkjR}_oOY}=$l((ujpWYhQ475K;)Ca(c{g(g=O6#A&;G(ko>#Qw zUt@sLk~$0|gE_c;gqvFcpacw{L@=e5`3ZbzXwz$in1CTBFd#YsUI8l>Z)6Z&UB*UW zO?zy90_=c`&1Fv=s8Np&jn3OBa5I-6NM^$1Aa!4nB_@ToJt=&}v;hLpxe(M7uLJ{$ z0jg;&F)>s%^}J>=_l(q0n;mc{uy%(~f(qh*t|CeTv-V1zj)lAKq&t7D$6Z;kn`TXL zn0u4auecGlEeVdB9V zN2C%ECi`;=U=9a09W`M_?3a~=Jau`CO5txaXN@wi;8Y?SLmy$Q(8avtaB%3S$N%76fBEVs|KZc! z{R17Id2M+1%dKqLIRj{Bv=w|Ak*+I+@Xvod84Oq(6b7eh07Lgno46_XB@U;5Sd zplw!-A0O*5*kE;Yb820X7A8d!fEhoT8BOlsc}mu*gHH9N<#GT850%$-UFY&ZNQWZl z$vF=;6bQAffDJY(r=*&p6%l3RQj;04jG)bIMk<9AEM;W?M5F{cPWT@)a*|5+bS!58 zsyYmV)KZ|xtUv0mI)qR$*Rd`i0PvizE;j(0rkQ1EfkH|<-R)x2Fp;~59O&Y=Z7>~F zU;ee&G#m(L-wPlE1JHf_mt$SWI%ed;CLLLKyFR75|3qvW0Qv5}ELGiZw*XeF)l7dv z2!q*fx09+8Ktga}7>2&@KmYm9pPZatUS1v_A2V~)H1B@*yP4^gS6=(%Cx7$9Prv!- zojdd6oVgoIKWE=Vz4FnlUo$gvm#Uh3vTU_e4I$Jbv!2U_Av5n(rK&7D2dbEL7{V+6 ze0TP-ECS}GCmQBokhgjp7AN_AIb+2SIuEh!t&2IyI(r)FHXuj_sv(Djhw3`{?-8 z;rIH>+Ix$w0Eq$iOQS4ESUX(F*9N!<0M`Lg!O*@ZA*GnuMUNm`2Q>9;8=!JxLcfIw zEJ27aREe+#fov7y8R8Bg+uj4*O=zeG{aO^Essbxp2LPP>yf@qj*3=5TN-~HB6DJ>F zs?1{MexOuYk>037OhM#=^$~F97yt(%)C@%OG>$3Kr2_z57v z)(R4A`|~dV%*W41xPm|o+Nf@I^D4EcO?(6ZtljG7@_zqIzx4U1pL`Op(bG>>A_vFq z*)xCUeT~Sczwift=YRUezx-oQw;y;8fLaB91JbG<2)1etRHn+lGB9I+C`@`i5p0Zr zbl2?xHD`*o(4ZO_o-8AM6%-853RR2&aMPY#z1yIzP0yIGqO@IqBy>5Q`Kl-8j=a--Ohqqrn|5{w%<@QST%w-!j`tjzBP6-Km+S#}2 z(c-s-Y7GH^4*-xg0~itjaB&fG0NAB+S21oe`biA{kj9U~{CCV4CBT%tugGMI)T?Y& zQsC_tS=!Ey8IxKEld!9Zp+;p^Q3Lt@Z&`k_xc4pLNMjO12KL%0$7FrApF4R5PzwR* zcaBLwR1UN&c1r{R6%(eshedcbO*;c7FQ=l|8isuZ<~kf4gt=+Da4viF7SFFsH=bYZ zC0D1n2*9q-0BDqw0h88gKE%Cy4q(*;09~Kw`n>Y`fXSDt{Oxu=_w!d@(RulIKeNJ= z=&-cn_90`k(*kg?3IHB^HUN0AWdNBB7=uKL!<3c0Xc++50YEGOpf=Baz8X!|_9JD} zL;2lcm@*+2zq3`nUs;FJ!~21jhpg6`g|F6XwLd53^vY#ei?omzqP$6S2mobTRm_NX zRR&P>Qb_`Utq=gM2!K+#%U?`kfhw1rk~c30T?@YMqVMQ_pHUPvzAz9o(6O=0dk z%R3t>OO=CDE@5Z@D1?eaHFQ}kl7@ftic1)*t;Fqy$)j^iu9 za1xOL$YBmntO(5GX)qWbIiW}H@Nkku(E^PE8BWh4Wq&CIrjSA>7@>rX<&Z6eArR$k!GXZJ2)uKEb1;VSgtWqlw~9}f2UI!G z04F>+9`60w|9$vTzjGgVzVhS8|NVdb<@2hmbY&q2AR9reKPgmeSj@o7NwKtzpSj~a zy(eJj&P0~8nIpTs{A(9DV$O)9CSo^fGeE7iTbldk|`qGy!FE5#yLNIeC9?Vv&)!b=s z?;?Pzp&49{$aUojSm~vDdqfsk&bPc339L}Q5<5~(1WA`iXm(J8?bhj1*iY{~+VBYk zKm$K*4*?-iY8;B*u=ev!r*T0!T;1}54-BT#wjfE`Oz zs)f}|;10P!7tox62B3F{V+(jSs2fCN7|5%kq9+V)?qFjMfWoeT%5fqRfGr5pWi-3t z?&Y?7Bd$-;KH*5f8z|Jn)uHNVge{u^E%P>+5h&sf^@9?c5xpdC%!3XPm}gK#D{!mO zyRidsQ-I_wQUGVzwnr^6Q-|gD^jQYOgJOV2*oFbK7>}QIk4jDsr3;|y`xVQIZ-cM} zws6uU5OWua$I{+5C4m|soYbN;kx!o^;ociY2X~1|J7f8=|BAG@9Vmr)=z!q%P)TRQ!k#bUwrbE zAAjoVul(?i{@iPweK)lH3@Q}RUg-cJG4Gj#aM^vsy9csA;0RikRR>ZUciLNnD(_fU1cT!zw^oDk4i73D%0MP-oA<9X}BI;~atbPI;%i zQ{E|mOiQt8&z>zq4QiO2wln7tsGyC&go;qnX#IXr;}ldp;16OrXea>YC}CeyAjWuz zrG{uOWvb-)293J54uIMEYPlg6U5ce zVdQZOfz@?ER$jumhp5)PLMgMq*u2hu626FhoF^)?j%lIW+B;9(pjzYL7OfV6m!W+N z5VrT&!ZjKgra(m=o&FI5(%@|?_0xKJx{Hd+!3GZ~=@v5rWrPeiWJ7keb-3MDQ9{in zCTNOw3^y7zybVFGiY0OCN!W{ajyn_=F#-#qu@IM$0f zV&2#9rp7BwQmbjnHJTLm3rEi}gdDQx5~~?}{8wh0xwxxR@DPmiq}4(W!2=w~0T!@h zyOP}lt}h~O4u0{yfBn@T|HVglcLNSSbno>SevglbaJ4q$x1h9dvyx|2F)2;vbc8%f zPVyo+aXPhv4rVX@%4*d#O~WV0vwWr$nkVXesU&VhMHPNQiw)^SqlK4;`;#TpcxRZ!c4va z06X37(ypqix~|P_jwSS*eK2AoDj6R}>@|ncU28bt=3MbIu&y9ChoB&59)u6+O zcsvIR*>kbC&%VDl7qFFc9>Xo~eXv&k0K}ZljS97=0GxE6c~d^fL`p={ zb$`xgIG_1pA=i4VM*!p7d7b$i5vIhHdGa;$>02{zbt4oJi@n9V4nWeO+iokOI!2zI z_!qURLI6%$-JQ~Lei|NYC$OJefu6_0rMM$G2hvamssl5I&> zXjBZ=TsaO!ue^!LRz$?ey>8(LhWp~t$z3{CmCJm5c5-_Awnz}(rYcA8;GQT5HvmMf zM-&+GR#C~}VNZiVn#3ks?gV_r1d{`DB8^Unme_HL1EDMO1Cci2$RSWR5G$E%yt@=> zNh_v};Z`LVt}F0G>O1hUdN0(#0Utan61*eG8v|-WAXlZG8!2cR8a&a-}4}^?*!)yU-pIoX-SIl+>fzQRJts1of+1~qezEwg*CaFP{!>@lduHf|%_L4+EXL?me>HX>qd39hb+ zc)U(}+~{S0|GrVO!}g>lC>#)_UT9#{;ulSeRzp(nA<2V{zm%=$1~_Q%_@Dd9k6vz` z|I{Zwb^iL{FsB@Xq$rVE)&HxUv z_i`#fM@5uWe*bg_07e-L9Tuj$F6NBMLTl1HT)WxlAz%`J&0aIppYeviJjp8=?#c~$ z@zPpOHq02n$suFXe__%kO+P(*r5G<1TfDdpSPH~4Znm^ow8j`PY1!tTbX}fTsEYAZ z6EK^LExPWY*-xjtO9vn^0La6>MMcTAJ{X(Vr;I7d;JOU}F0LHF@tOhr$``HxeBe$4 zAeqnWzkWH)ExL2an6fv{9?Y0V8Iu5Q=n25_D-D3|Jy*c2GzysXStUVXaiuxBBmi0W zqfbA-ll^vD?ji+mA%QS-3B6s9CxHT~Q zY5|zkXJuCBi$fH*tAPW6z9IkvF@R0g0NBzvTPQgYEfmX!nBY?1D0C_0uPj{0W0+5FQAiur>fIoZ`zz=-?3jhwE{RDu&|Ihws0GqV|Xz?~L z97@`+5i?oNIU|Hzwto;SH*V>%o9|$=XJHtT1cJ zCV^O33a|3=aOKv1+*P;{%(!UBRR5_ad;BtW?$TIlU)i_n#u;7BJ+zm4UFS!0HRiy^ z(Jh{XJJhoX(y{i9vrV(i($djheMXESBMXPNriufH5k7_hy51bT1=t$Ty_?I&*=*S) zEI%p@oJE4=d=3CnX~>ibG3@t0@AF!j=~TEjfn2Vg7w@K@!0DuXh{WY<=VuNf@4dLg z^?&nma+r+dmq=@TJLa1NSaLStqRB5m|1WR+ZwXe|fz=ShXu6nmywIj3SzxDO?-LS-pk*y_pWfP}jB8;@Qh4 zGgO+($e|Y77H6vhWoCM^?Y5RZHn9pctE)yCU(OB>2&0ZE!`$Y?g|oUUFIoYh;;N`! zMkY00mvYXzl1eI>IMH}9PJME-RlAyNg@U?t*bQ0*mMCM$;hefL>6p?nM zxQ61qJfPH}FszV6My5cs=Y1Gc$L12@*3;`AT#} zBCst;;Fq{u-#R-!K0N?Ow&b*uK|us15rXzY0ytw=5{Nev42^MeV~8$U=$U{El0fDDAl&HxyMcq-mPE&vi-IkqGz-T%7kK<#59<|Y4~^<)=86x#}zM8tW(Fie{^w{*Qm}m!G;Fe)NU#?&t2kc{kmC zIlZnAKJ}T~&paDj`o?K{49kKm01o+IzVpLqE|{MpBOkxuXoP7X{kr)6m z;09)v9?YDek!h=bBr?D|(3-FVqnr)y%Fb#LtgxC|cbDi%B&x9{Z5ja&grJrrMI&Jj zY-})YoJwj%PQ9)h*}4%#0SH`Kn0BTRa)6D%*d>V~19VNYbrm881U@JN$e2hqxwNFk zH{O$yu@OdF2S?>1A|aW;y=hxjP1^VUrfphKB)JeskE+2g8L7LVYuUkT)g55a6^WA& z5D4PY597fLKm5^8{ZqOB<~=#Q*U->kR%ka77vG|b#yeWAcgj2Eo$^lkriF^02O-0K ziV7?NZY6+=2{nhBAslKZCe&3ph}1Tr;-b(Q%U-mw;4HJe)41VCxaJ99 zS-4}*|5{H>;?McUkvD{01PFQYL;O>H6?W^ev z+?A(&PJu4dOe0_lz`S0MsWTU^7mF5kD;1uI)pEAGr&`krOC`rtc}y4x2mys-rXdfC zI)=NC?6xr_~G$MnU=u3o*<-l4;1?H7K)e(+sCd*_X6 zb7%wSvp>2%f9y+G_yO%F-cusEJi(E{JOr2-Uis%uj7PW5iq6X2b*HLYOI`h-mB>zYglGkO0RdiJYT{+I5NA~neVQNoij{>i#=)#lNryoyiN%ow*RH8$!DSY5iCBO*cCXQFHg$!So}t_1V` z{%eY+k*BO(JCurC!7jznC2pd-iz=e`js{EvK&f}Kq}dq`HK^l&uoaLJv8xLcPE)VW zfzl2Fn1NM}->dyfkzAdyfk%ZXlziQ^m4Ve6*qAyyfUZ{+t^fyZSyds>U@+g@Rm&u& znj#~J_39POUB9Y0f{scRa^*&63E$(NLIjB5q{!deC{88kpAoc{AKp;Z~pD= zPoEw9(m(54K7ZjOw|?f|yF5KS|4;w3W5yK#wL1XJRCs_2tO9QVz?@}Eu5K$wBz8tp zuz?v$W~!BTFE%0`-y_(#S0Wiu!q+#KFG;f^c@7XJhrN}yx_wAD(n>K*NIl0@D4#VhH>*sc$8 zYC??mwxZ=#n;a8mDD{M z*O%X-YsR;QY8B(mg%GJ^+#9D!MT1iX0L>))sG1DGi;${_yoPBO0?=@CqB33H1E&45 z004VHp{rAwA03rD`yzS@i`QlIqI+5@w5!>O0w|g2N?S^vJ6#xfRpT?4QN>fVKjWm# z_bsAD%Dl3xQh_shacTenAOJ~3K~$p8DqEGCE-p#&M#)&%S9MZ3m0QQ9>TPL8HtsM0 zQ`)}6HO+@ExhYHQ9y#M1eS*oStZ0-TY#hMR0Ri~@*LMKE^G<`wuj;I>0Bn;3c;90+ zfbFi#Y65_E%;6a3idECu*RBabb>aZDF#ye$Fg_qaA^W3N%l1P&#<83X0M-u#Kn+`c^+08vma&v zXfl9I4qWrODrK45v3Q5=xB_s=5x@nn06eIU%F10h0LEih*a1jr0TkU<&ik)(Sm?IK z9<*xzdc5<>z^Ky7yKy2hToIPyRG=wO;@IEcd`>^FgXwB8A*~4x z?LD(@kg@%e8-!?LTi^7k6DN9W$E>$hdzIPBatX$rV4mwuGnjET&v|cPe;p3_)Hqzj zVb^@brWN-7@oxc67G=UcH_ODrN>#&rhy}e`th{hOr%8KqBTzJi{jr!r;hPm@1h63h zPBSs91wB z_Cbg=fvqK$7<)DsNHG3_&-}AQQ5DEFR_2eSST~~)$J04aY^$jHmjB4d7a5~O%P3pO zPOy<}v)?Hn`ua)rjT+mZ|D)>n$Gyzc`}y1`uL;mO zA76Y(7U3PSSV}ArRASKVP~po0qUhA}YMhv%|)4$Re=v@k=oENgjKktUw6F zm1QsSfEhUe94ORvkxeb5DKj8-U0xgVUK1Na9c$##IBf3Z5Q0o@>uwgNG=+hJi0ox+ z=7A`C4k1v*c}m8YbEXgs2q8TG{QFN%PF{H7PZxSp;sKYcw-7=hc*8K{oa3b7GIs!) zb~+4gyW)wj72pLxYN@7$VeaY>V%$ft?guF6)c3oca>eBkV|$U;>vjL?ucs$|P~53$ z5W}?nI#}Otb5jddhQt`Q?|puKQ-stKLo}$5fO^#z|a_ zqOppK$W||N*QhHIb*?qKDhjoS)#-8T62&4RB@E&RXx<}@LjZGjS5d_UT_$ECIdX_V zO$JvsfN4c;EIVVcW^z(;W0!sf-=Mk0Mk?rN)SjgFu>Aa5r8qV zsHvEOrBfA36^SdOIew-Ag9b|i>0phkX?hJbket9zjMN+*v~hU4o6a{BPx$cI9PHc! zteN5isC97QK;b|nbPDAZT^!n}9Yu9VV%|U_$yU?KB~enM1dRrEgNq?$5Y(?g#E6an zsQF6a3?=C_tyxIusMobf2T$ru7`$=gr(L&%L3j&NKw)A4+DFZ!8xdb|g3^{83~>7$ z=22AvI4PMjY5?ARhm(TYdkAk#7z)s-wbIJnfB(<_-T&^N{0*o;lDmN*()P%biZ?YP zWx!PIC;!6k>1S4dy zh77pR5aFAXtcllLBcs!Feh-PJAi=Vqf7N~Lf+#Jh)>|2>=fxHo6WzSN+EVScIPM(u zcWu9m3SXyPc}7TivO>T9dAPPod7^-v{U-jM_Mgj6Za}8IsD8MPbY_`AAxC*yw2wEx zPPHb!G*X+eKtj`>8>5f`5CtZ%g9$mK8UouyBQrt{l#7sPgf<~()4WN3(sEsupwtkq zQ>~k$HNTu1H%rWJlD_M4ms9gct=5Fl#{L|MEsaR4c*fJhS}O!R>;OL>Cy&>vOBKjtM*v-EI%2p!-MhQczw@rj)C$;k;-6o~SaCC~;d zU}#cEmC+6*F=9a2r@b>TxHK1~RnDIC{C3bmYC+C{sn|E<$to+mmzdb%@9yp;G7f;5 zxp^Jy+14rmjy--F8#o0p7Dk4E80+jgF!^-R36qej_>m90VKnUu0Rbfuq0}`KA;a_N zX{A2&mwl}3Ipz)+pOy`7IcH`LqteYYuqWl?DVsyiK6zt}!IH>f3dbJI=K9ZS%$&2C zl?u!)EdK|h<%QUX$s>$tyfT)NnqW}r-W);+YD3P0>K<%OURMCdZZCFVpZj-m_7K9O zk3L%3Sa?=pTeF-kKmYTdtFg}JQp-}YMIpo{M#QkF%&fdCNNYKc^9sI*Ks5I;ToMRC z(==}8X4$&~-LCJq19NN|T3qO7Kvo>?+FBe?GqVwY*)W=~(I*~#`iIEeUwiE} zyxmK1D%tLsD)m8p>rj=IDsf}zd!T_CDL?u25hQ|z`wUtMv{Pzj=t(Sgjs{vmw&cXR zihAz8>Klk1F|@-LXarrNt>6e&1HFKu@R+PSXc`zCwC(|;1jmLsLRr0!CP`hQ0`7!Un|VfPu*&Tc|skafS7B&_?9Gnm}Dhfd<~g*0Np$ zq@9{oKz4Q~)i+;KG;M1TfmdV?RLpgy`f7UftJ2XXGU}t)h>{4*)oAp%u&xS^ zASVVCEDB>YI22$VW8<-bilQSgX^|BMXX!zWc7Q6@f{Q=dr!f7P5Z!ndiR#2fyoSlca?Zv=b7Csx}cyvVk5kGgMs|JS0DgxHN9fjA;N% zZ%4v#86**i(Gb}-N^)aSN=9O;&SDP$Gn}d`i<+J)3+n~g$cZ_!tNIDq75Iex%G<4L zMY=Lh;yahBrQ>*d)b$tV=NlE0(_O@hJ-Lz)Kr2-wh`2%Y^f;)eO`oXm6N^}dbfnD| zcEHh}|DF$+zUL4B;5WZT7maTV)hddQQMd%mUQP@3)-rz_aP5}7D6NVFrudW;#nW<{ zS4=RgvfH9>DrQEDL%e0-B99vK^<$1Its>Y7W8J2khH1Ax$MH`UC~FQn?r2PsI6mc>^Cp3H(j2)=;$EK{m{1i!^KqqAkEa< zr8y1&qy!*t8Guz8fH451+A(RhsL0lK0YDhS+yli;Z0cT`UjtaR0l=X9fi7LQOnliM z?FV;E&{-sS#eYPBc{Ia*+qtJkm6iZNC_coJ0p!{Nc)dRht04d-J{rX`YrHoqH@hJK z=(z@LJ$g;k#pukvKl&W`Jf3>g{nfV!_r#~ z50Qn3cb)ezWm+~Xo<^!Q!I8N#4_(dP`tmjjwU#6#-}v;Ky}iD0sW)0g0)`vwEVW%z z87ISwkez*F^Aeopyl7+a1*Y1sGhGAAj>EogVR_iO%cp7RG;`RG#U7#`H3Fc>^z&>TA+#!GbePz;7c@EjN+gL0?_A`a_FZ5^7LidqWTR|fl; zQdqp6&Y5K=T(9l4Jlr_<_N@qupUwp{oeZ|7AVeDH+L)seXZX253d^1!`BRA%48cRl zA$SQU+`mP>w#j~8_f})LJWxjPy@`8s#7|e*sU;Z^WTOS_QB4N^J%|faoo+`wO3hg4w?jZ!03P5%r zNiT=&o>KC`YN@NbLI`;RSVUxl6`|9tS^{Qs^vTvLU_5TgYNuA!Ri2XT6`-a&9n3-q zbuANQ##qUz{zT+qLbjtUF*CEnf z_nG_mALw`d2oXuehHK%6VX7^zU#T!TWX*4{{m4#x;D^3G57V(c&7qtN%z*sZ*|7Y+0eq>3q z`@V0SlP4o9ySn@K{V_i|yUU&ZNpem9gd`J&C4(|(tw66tV&R2pmS~%#WWh8cQk1m2T<&r`JHPhMojcRFyQ{M@>f|}$hseyz z>U(GWU@u_}Z(z_J*x4PgkhQak&%fvu&(bOcuLgP65)2H-UDEb zkko4gxu`a90ztNJZKAD!Sw-m{EHN8VN(O0m(9kI)-r^f3nSH@w1QNmfFnsO z?dOPCtuiIhB}{-vU3U!!Nd=B@7!wrEhLpPgEp~~gwd#sVP03B8Uv^jbJ5Q~gp#7+N zOBhrcb^+aPy4U6Sqtc!cCGxd8TvLzp^ze0wPRAc*S-Y)(1O=?S>dqaT*uKOpMQ6lz zi5{u@j-lbU6~1ezm>g;>>FVO4>TCbjzkmE|zxwGfzw*!i%$NS*SAX?K9qboxec|UG z0{H4Hp8&)>ffE4s?~4ygNsx>$6#{$4un{-cn&kVi73g)koYugOfX0R)m^6`#JK zaP|RIxmKX8?C4j-`uy{sc;mHi6D~kCnj=jSBIH}3f=8Dv5M2a-!=qJ>R?s=9cVScl zWp$S8j#d#SHuN4Dq}WBxQIdNU8kB@UtQ{nZ3wR4XGP(5rqz8^0fE2xO1G6nNB&`hw z2%99pWZU9$)6(rY9H;d~|LEdPZSTIT@owt|8o-HYpZl{vpo_*+t=7}>v^*_O%LkPJR1^v+4geDghvSA$R&@K6kB-6~7CZ(T z%I)p@bM*s?fhEKl@B9x}`0s;~t_bBp6L?8%LXDWBjnFmS};8SX`zmnj4y zM9*!c091+Vog0^1;G8{#vY1CMXonocSU1!}iuEMaI^>%N-I&)}kHNtidfgzT2VsnJ z&uI>&IzXJ|t&wf*gAj9|IhQ0b5yAqt^1@UL%LIoD-By8I4oo@5w zPs1>8Fc1xX?2oQF)+7y;+zTvrEbqr#ztF)4a7FfuaF942SDA_vRa22&ey z?{!_XRGt?|D}>@{wWs7cmw3j(tb7a1jcLjrI3lVkMPNWiw(Lc-XxXzlS5*NLJX-EL@C;3RIf=7D6b~est7gftd;zV&*2sFjNcgr$Q&qJ@v`m>sU)w`Qp;wZMVC$TQv?Ny^I zSY^CR2zpfugH)kW`pdg_*V5dLIC3b1r5{`_?cxnhs_T1=431meya(KZZdlN%fFHp` zAZ`R~d#v2i+R(G$_=n@^Rcb*78o#BYF;9V446UKRgIBNLv#F6gS%h*Wm2G#EsFURU;Fyr zSAO|fK%CMSe)gLHzWmCM0x;AB5Z7u=|NWf0Br-<_~i zJp!1hV}%MOucBUhdZ_U^fQ$!bHFHK~eyvyEfnQ1cNyHN~cTp&@kG!C4S`7HYyy4%M2P2TiOtS`jKH+?8EN zM_sy%Lh8)4B?ze|+5Uho8h;#AE1wPkXeR(@1z9LXVhG}0TEc~jbeq>Ky@4aZH|5qfuJvXR%jP0#G#oP$6UTgeqk|+{NfBE*H-k0C?f96{_;&697VV z0K6-w2QaDsp5Tl%ug%IiGkR&+{7Ei}O3LA`GA3`UGRAhB0qjcmh76z`1^}VX02mnn zO+xr8D*y>Q0E&qHa&qxq3j2GVF;b_@7g?FL{d6pe$^1G4(|1Ap{Y<4t4uFawT1^0k z{(VTmhpQA*aApVx;jof$=a|r^j6r0C1tA<RdfUu>TRelWR+~7vb ze|#WH3sYy_hg|`OZtjQsT=Zl?i?GmVO=#({ug8;o=v+USD-e+oaT;J@;-}L2L z1U62PYXAOnQl3PM#%t8U{O{Wy_d^7lGFQ^Kz~d0yrj3pW&5(?rZv>j~ppve(6SC}Fb!#2^a9 zAj-4B)&#b~Orqw)vyV-jc3M6i`Bw-<^fD1C%AgTVErZDRQ$CM6pB%;*!^!9J9kB{ryXF%b7 znJaepGUc(ZLyY^ya{w}Ss_q`^nku&4Fj`8P2M+~u1tuRX=Ug;Ulkbw(G9~cM&dkMP zTvfFjYLQ5>Xt>7ZItP?k!Vu;v55l4MQ%jPv#}0v3$#{D7=b0`{Y_x>JX8eVN#sI zbAeez6e##GD%3F9QO)$KyfCvuk(P0JR3uuHaA~Ggn8*s;aW=v1uA0U;Iul|8nU2rfKE@_#wKQ zDb@UAvgB4gg#m_1DuqeUH3KQ1Jho_Re=d0uoQSCc4#O4aH#r1^(6+6r_Wd@6&@|0x zIXAU79-66sC6!J*)ZGI8iMV(*3ea||MhbXfNf(>$7i3|~Sm>Nl9U4gc#`&NIkYfpa|6b(`B2)Nd?f}WdQLymw`X?HMlbwdN*SgPSs zXlr_+&1JL(yoHmRgT3XgLqJA7iEPXn1QzSHV$N`Ds8?%5wm@oNknGl&3nRh6P(w`^ z3^hp>8;H1gW5Fty0a^*Jm1>D#ceNKxT z8Q}c+FaF_IfA!PsRMtRaNDwZ?I62H3;m%#Y^2?t#BjzmtrZ+%=_0*}qh$e8z+mxz{ zv^l+f%WTKet5)jImnGBYVq@K#EHBXd#LdBuB%sc^%e1+awU|UvPkclM$Bv{z`y&n1 zn0rK#OVa2bA&-tvPjLEK(~`G>1g@w=E>%xpm$rFF*3Sx`LIb=`D%1j+<@kr1(`~2E zcIgiM9(?aQBRlj%f~^4g{K1E&D)1?8(#zA+4FVJeg|c8%{-e0UvKd zt3#^wv31Dp@0 zT8G;#G6pU?b(8)aA~OJ^hk8IL=2JXQqZw>~J9GdA5M$Mb)jEW=Wy&E3@;s`U_Pd%6 zU;x!=YQV-TjLyh4q;Sj5oO{K7$5{H z;wnt8?FV9p*&BYIygbEf?vYm*gAg&pst*dyosR!93~B#<&SkYbh9c(79&!i+fe@zI z&W>#GA?INNTbP1{D3^S1#Bln6ZhT0}&Yg+IynN>2{%@Qf9o2X5WX}c46rN>f$Z&U< zQ$?6bN*L{&D1=HRgkU-pnNB#_Ksl4&Bqu?&%}hhr(+X%a-phPl_#7Q_)|m}vHkcJpC@GbaHCy2!tVo!(`Iw=Z=un)i_zgiNm`4E&~z*0Z;>2h=BU;lmg z0N(%rAOJ~3K~&k>w{OqwhY;55^&E0o%1GRZa?YhGqEJ;8Gc7x2W-QfeiU}=^%sQ|A z7;_#y4yKEPyH~}@3n<+SA@CH{Sb*1B&}yAp{+)mI@P}+C!r0#nSg` zrd_rOHVg{|7EhOrJk_y9oZvVohm33nTX{jU9)BoP23R6Sce~wn*D>RDDQGx~fD{rL>hqcFDSW`R+&JTHq?YbrrO`*st7_Jalr&3gT8M zsf#&Wwh>^L4$sS4l%dMfJW95Xu7*qE4d@KMGN||pGKi@{U{G?>;G;&h+0_6=G9wn7Gkh7O;fL}4ENbd- zBK0H4wQD5)baNXDu$voA{!UO(!-9s*$Q5cquydGRZTjw9nx<)Qfs?2>CG;!xbM)^h zocQIo4GJ+))(Xvzd$G-XK-PFi*si)0mMzS{22<|`NDxVG0K-h!2NF1TfWl84D(sFP zx&|ELy;TfXjc|v!!d(d<;}z5ZG<2nC1jeEU@l*qeM7b!ETnza9&wlr7zxwg7yz+6@ zgl0#2T%O4T@U&LCgulyp9!zR=-`#)k;QRmF{S8jfOn(US@L&B)|NQ^yFSs_%=#vLa)fLnV^0oaFLyA z1(5hPlpQWehKjN6^`10a)k;iBJhFpCBq^O3R_<5e3KD??892F<5bfY6cc1sy{(zOv zI~9?Y^Hy{qoG@*O0bdheIV$K0$+bcduc4>XF)x-jIb#y(jAgv)FJ6}qmjdGQu%~QQ)a508-onvyzx}-a z9G?%(k9aaLPEsgtSw;4;?2PaCFhAlNKMIQqyZt6(m#6!0OlC~Wr##h=0o1Diz)Et% zVu)0-@>OGN|M?bWNCS zzW~$%Ofs%pxAt&^Uu?JEWXUw9vo!;dYyh^0bYchsK+yom`zL?MC{Oto zUx{LZL*w)3(k`ZX%;Ws$d5UKBpQSQy0FX<{$X&*C;uVoy&IDld`UldQ4@>!xABse1 zVwg2GQjZTxLqK3qNs>o$ z|L4ci()%v#r+T4)xjoXt)Xyh-X?=i5>M>jT#U@W=YV)pdBC5rp9)njvF&p2<%Z(o# zP@dUReKG(0SjPn?<7yIW5u^z$K*%8ka0WsiV7p)n8!~aomf<1fz(e36etM!>Kef48Wjvg^@La~L&E#htz2u~1B! z%GZLZA}+y(MWt235@XXytdZen1uYeLT-CzHWy3sOt=yeLaCcQ5U8|-5vBCuVlmIj_ z-VjL*s(qh`Dc1FjkV=DHw{`c`s#($>X4YXy+rGH4FOP4|dE57H-mIF6d1hpuv#RcP zyNau(iOcri`1PN7=bd*RU0kT{KKq%^e(rNW_6Psu>kl5hy}ACq&wTn*FTM2AGXEeZ zh1dSFQ$8BZ$Ea#BbGf+8$gFHNcV^W6700xk5kfiogajS(SldTI7TUHk9~8sdO-|4gyF&oJG>6 zvxt7B?;W@6c-pjZxVXWMsJZZd<#MjNA_{DG3<|T3Oe}(x+?C*VBC-M6M$M>qC4p-9 z4rAl;JP0B?F;N;!$%O@OOpS^{6#|%9*IC=jJFX|j*U)Lo!)xl8-!FlHjAQCoeBCOQceF+=l zt${#Yw8q>!Q_Q#D{$lVE?gYRJ(59PRWGD{ z7VhdN%pEaUVeVc3rYQLIMYXl?H3J4QK=o07ai8Uk+Q{S%B4)_el+weuNFVvxXM|To ztY!l7W~=>1FWv%9Wc>mV#0F!5RgRrreai;tlaIC%d#rxuOJD!$FMZ;xzw|M^c>8Mm zZWAfuQ^pGTPk-rKAF<#30^=|LfF%I`~(2FHv(89b*d}1CpdT)``rKVIfHZE?dIwrIt zsiVI6r#S-gX?a?nmZ#;P((>$cOoS?eq!{#!>)}vR9PYh`@*IKqgfP7Fzhx4@8w>pT z?L4l=4&cUQI<#+S-^u|{$Krz#(=03Jsdw{x@4v7=3^^R%Dy%JM90Ud~8@s`nmelrr zc9&;HcDND(^#2RLbli6dbQ0JsXw2n1sADu*V6 zG8itF2{Z&rTy2AGgImryz%p6LA&`e0;G8q%Kw~n*OgRUHAwY6m(WsMJOwr6Ym-Due zyDew4^gkbxt;L)_Y3z#u&vhn1<;WRfGK>d>KpC9D8B}ChvvGF@iV`gxAlmuRES88j zKMIq_*1X^8B!0Z^{<{-$IM`x2U?AjBGEgFiVGNuMQv*I*Yh{E`%(n7qC;wqDgE_tZ zTdUOo$3Qs0syaR?4p}8kkC@zjmv)0HRUGTOeEmj`tq{s1jq&7R3czTpHCnvql233i zq{_%STlVc{D^<0(U@vFb;W^4vVjv2m?2DMj$U(~$^Q_FG5bC;SqJU7m-b;M|UDqLm zrfCRa(18LWqqt}l`4tmc_Od%Gy0aMthfop;%uhLeb}5?i@tmYD=j@m*wC1QluBy^n z+qQWM%^S&J&LM2i(?#@h2(*S!r`O-*n*)O_3DuJ9;^-=io#vpjDw`#c4|y8ZHJjX9`oMs0HMj8Cjm)xI*xpnW=4CGf%1S`|U7D zjP(e7r}HN-E{L(>KLJ-SY<*ivc&524?UBb!sGXIxkFrbXwR;`iw~Rj09K-C4coV@e zxF0J*w90u)?#>nARLzV4S3#@jrG3FcunL^rdl(GD`j$R;8?8wDvQjc$K?jB!qy+#5 zn5~xh$gpxaiNdr832%FSrlqTnotxUUXBPtqN7NiaT1bL#Od=d?o%61L@PGk1>l|lh z7fo@h!9ZHMni?WATc=7a*HCk~vNYBMO_Eytq4`}XJ3y`u0tl2~YG^^~$_y85%vn?* z0%G_^^$2LptchEKDoK0#Q8PFz?3@@-?g2q;n@^^;g6{;$c@6ZA2-yIu_Vi^CgIys^ z3V>a}#Ah$SKMINfIqw(|Ho&sT9XX3|Rw8y+tAr9jZYOg5qpi3aef~?|{OT*8`r0pj zTnXeA$-U#|7T|zF(Ouc+e(Zm~cyaZ~mwx59fBz_@;o;>M+TZ$>Kl`u!spnt(>@Pn0 zovS7SFbKFK)Bt_uZ~Y5D@vpr7AOB}R^1uJxqmS5c{#RctS4i5#c=Z0M~god+L~st5CE+kQDp)t*sZS`!BuwxNze=cO{-Uc zq$mwEJ9ZEgkU1C?U?PK}Q9B`iD1PLC2t9Mwn994|W^=w7q&|9?>aIH*>4tiYtcDai^40uU?!;39;{0f0@vHKWF=+*aBA+<8oRH$EmV z?=NINqr$6*bU4r3E;TrNt<7W)I`?hiM}%CoKN*<3kVIvGH296%@nvDyJpqWy81fBMS- zrNx~tWwR&e-4LEbk)r^kO_x`%Yv2sQk5}(pvBiTIl=6-VFdCmI1J5 z0OA7x&IW*{8*a`60165qKoZ*Y0Odf~J6J!yDnBesu<(S+VSnHH7}6TA9tXT^ zW=Kn{aM)}(Knoeb0WW(@&9rFw5TcDChhzP*JJT)p;|4DK4%{$)x`AuT8Z3tc6Z(U( zAG~=$&E~znk6GAF4c82?N(j@O5Rm3HwG(sB;^poyy!WgTGLFuZ^T|vU4_SodU&$o z@Zi2*YjZefm?$k_3O}5YRzaF0XkBjmL@2e~?cu2%o_MlP-;F1BG3@s=dUNHX9SigI zHiW=ARDnEa3&ArC!7wJHbBtnB%h?`3Wj=)E`0{t?M zgy3og1_@Q8@AzcsGa{{=ixjIgSl&cHw#0H#ARqN-y& zz)T2^iOLN_2^6Lh=7#C2%0tB9B$ zbI6)yR^`pn!hh1T6_xNlHQ}^*8R`5w=lpkm{*G!2A#AQUsZY%0p0B&>ci(;YkN)Vp zIim!kj&|%hUte$5>!TN6e9_&jiu=Bw69|-=<3O0)+|24q#z=@T!nHw%!3N1v9P#Jh zq5w2alv-#4b2;Z3%+;|5U}ok%3;GJrD%w3FqA`;uVZxD~5kffae(wSQi0Y0hG)-d* z8np~Oobl64vSypGr481+R+#Ur!nFCY*tT4)WC~6!Z&o4L)IzB+i@$v80L^(ALnswO z#Z`5rI;ie8mshcgv1vF2E8(J3fBfM2*oV1%{PbR=;7p3OC<$ld4d_~N1g}9q)Z7h( zN;NvRM68@xJETiO^!5&sB!GMiK*5qK$Vve~U<4kB2N+ZYs9;-?b#wPjD0QsSDl>q4 z?OnV34x#oQ1nw(f5GNKgAK+kuTLtq@SBMH2u!2Du5MkZ{No}Q`KyFONne{|YkDOp| zcm+alJ#?kmpnFv{w8zgluc$$<(NiSAw1a)`g4@%0Tet%P(<9?ZaOWPzAhpzjz`lVH zI~x(ZGSI`^wTxQiN^#993PW0vT&UKj(J7D&Fom!fIY91FT^n;1(#*u{3WiyPI2Wg0 ztw6Ov6%2*|MwRnG*0VM00vZ5P7oy09NY_q6M8+a+!W%>U{1?CVl~+FTclP#m{&D!CyK4iC_4b-+sX4;9x!gNH9FT}OPkAlG(*~k$g+xGZ55`(ZK5^sS)SPTFI>rXPa&~2})(TtfL4)?64 zu5SpphFc=!0z!hZF_Q+x>D?D^Z@%%WrOU40L0*WxId3QdREs;As4N5K|a0Sp>>Z{0u>K*aq3}bHFAt^=jI1)1@bs89L+%KpfnX z=9^1@;4t=Z;jT4Tc*0&5f3c)LPu|u0YH600_jM-u*itn%1xwkP-qiXCD{Ffrr3Kq?9Q$jR%yfJUVY3gdaW$Q9Vw6 zrnwDInAgLzad~1a&!6zvizPN4S8|IpJdAiN(-eUi@?$!=n>{}~up^EdVb;XY=Jy{P zM|`kMX=0mM0TpekpB7i#Gv7b!f;E&GrU+;Kjng@xUm0);u5OwJ_@ zA^@r=7i0tMGa*j;CS=T-sq7g=$H#;`VU%f2KdPvvZ{FvqCUNXjJ=K$gnZxvEduu%v$dZ&S_s$tF;6CL_=>Jbs7f(|oA zDT6XtcJEUfhM`@pDv^Tc@JFovs91whmQLG!luMU=E{IO_3_v4PooI}@CXIb&nd zMclj77Dv5+9fYhPDA+E$?!I*w&Fz;Y641cJkO06hwR_hzqkT^J)HMqw=!$sjOz0k& zzXfUyHB(|{a=0-ZUXpMLoWOQQv;hxh>VVlb>x#5CCQuS_7?jNo)<+j2-Wh80b%#ju z4(SnOCl~;jkl~2k0b=YDR$uty*T444C%^j3pM+)M>+z`D5!gua(?9p%SN`UUU-`wO zS6=zG^NUTCV{PA-l)2lQZvnp8?Eam<_z!>gAAdvH-n{?sHh{~{a1CyM*_y zAN$OmZ+zp|Pq7AHNIZkDB|b7V1}EMzSp5zhL|b7vT1n=BD-qU0mx{H}pkBcQ4)T?| zHtlr}CY7j4k-F|AQc`P}AGweyl7jlRNT(cyAE}9A%TXPXkX*NrBhZzq3Ob0G8%t8J zSa#+ophQj)9b!(IZbu_~W2jnArQXUvvH`({vW52Ph| zG~wE>kEZwY;xB+v!)4Lueol+M#XUsc*V*5~m!%8ko0UuA#iAhd06<%tTPY(V-G7?P zu6G1LDgxl!v9;B`3{1bkwF5xOOjl(9wPXN(xz|&dG=JgP0q}O;R1sn2#^$k)il=#6 zBm?Mf?dD#^V#!%MfOJ%@S^MRrY#D$RAywXwx)f4iafcHInkR&N0>E{dq5!}a$E|47 zmQ4-K0Dwx~$#OT`7%RHvB>9NdJFQ%C~QvIP+2LR@PtB zVmv=_RlWxa(@~yhb;>t5-_-86*<+!(2UAlsS9)SOj4T{0J#PJWknHkFNa8RX=KNxx z?Jmzf!9136S00!1JPS z?&RYWc<48^oYnnV_koY@r}>*E^Z%*r$yWvikdG%3A=5Z;50epocB1*g6ZnvxJx? zZWEU=v+cHL=B3wFX*}(AyR>UoO+99l0x{b#F!N3|rBqc_iTa!wkPgG3gS$&D#Z)T; zIp<**w%zvO!-tnwmsgip@BaOtbpHwFaNS)qa|l?qt6fT~c6GcydHszybkK^coc;X# zQPE+&_uhLiz4YRH@4dHLt?Igd@4fTW)01Ja)6>(Ov)Sm^8A3pY)RVyz1!f-Ivi6BF zuoS7yb5#tpme_7d2FIf|S=v`sRn%cIMqux$Un)}|b0;FpPDIb!H{br=gYd&Y6#^CK z_*sGF(+gT$GnUuae5mIN3mP?lv^>de(K0P6%y-XW3P`M`fJB>2=&>;HvgNrQLLjP| zhPWCA-F97IS~aU$#{8Rw8&e*6zgdh-{xOz5#46ICK|SM=R`zWF0L`K+|}7z1NyC3XEBmaTU0q^k$iJlnL-7#!s6^!cCt_LqP0 zhkxb2w5yA+qxq30l3Qg)>JGg+fB4>mSAYB8`(pU(|Mmaz?ss4B=%SUE>|@#h03ZNK zL_t*c?T3TVOOVU<)VhwIU)Rq)&%gcq-|PA#K7IWo_L~p>qd)g={N7&}Po0n8mAAeJ z;6FTWzW?gC*LIY;mtTJQ4}qcA2H5u7b_lUL z1_umEV736bY8FWVD@8Xtxq>+>KB%B`20M<@j8eE-oH!MZR}t&!Jf>CE+dLE>$B>eYKvJr{!sRTK?Ee z;hrb}f%p7nUboFiE6?jdlusv_0}dV&FS){gF+SZ^m#Eg|f_+JJo)qd=o|5N%BU8&$ zR~J0}MiUt~ds7CGm-QEfqQpYJ5B9pzsVA3wW0(6lG~5`$9f|@0j+rr(b{gUnKM}k9u5vc88qiixmcagfq2C+9X^TgD5C-h!KXm@9LURxg~sd< zqjPl#8NmYr0%tJxVw4*vM|kY-!ABER9mn>*fF>XC);+CW?gWdoGEDT#%oedv+prn>Uu^Jg&&Q3cb{?3h%<%(Q&zqbS_pu{h_s6H88e54WND_>HVkREVjk3rf%KmD=guSOaw*-D3BAFs3aT=M8v$f@&J>fYK{|}#a2|LK#NGj z@*?M4G1o^&zHpAuQ#Qk@s*aA@Jh`yXV=S#zRW&P^N_ItN2EatcJge+t&mWmnpI-ah zf9BDnM^~FoN@=&-xqHqMLc7yrlu$mqEFv)gsO!>`Ter^4Y`fi>4-|N(34jhmi9jsL z5Q+Hhw;voGtzLfl<6-i}CkpNkWF`i{OvngKG}*nEgG~z=+6}o`VNxa6p_Uwx*vqoY zq`7+uHq6tBwA6DI$=C=4&D@No^6YbV%R6`OoWJ_F!^i%0<~9)J1&0cY2t+$XQ8S;y zY|~!4RJuK3ESf%=FGzX9Sj+nJPn`o*2pO=Pc^YR})b~aGaz2&8O2tK`)u+^5T@9+uFp{hvP$IjF7U6{T=s;mxi z2O^y~P8seZ@U23`%m9xpc(FxeuIx!s0a-~oU3J}kq7!NFnJ8f135hCJgslVU9F!Q* zV8rLJ2BhwhATUOg30t)wF^NY5F)Lxk;;;m(g)4{`hd1Spof!hY161mXal*I;c4`$g z3#+y-b2LDKOCXA?q5`g1ZXLJxOat={KB_>|M%DNnf#ak!gt78b-uc~!)&R)W5o)Ov}w1{ zRl{3QD*$9CUYSIq$g)*OggYhnNJxgLIAI2?hpd6uQc|LO1cvP3NA7E)bD{xC$=+)r zJ>6zicWp-4qJ*p#(CpM!@D((8T1gyWfti2`A}@XHv-jWpM}&79X-!Uw5Q2FFVxSPw z9bjr;m=Fxf0EZKC?==9nt#eQdjaA?b3}9w#4co{h@Xl&L7;xEkM*lZ^Zy#$*mfZ*a z_FA=S*QtB%z3;yFx_f$hrh7gz4j$VGp+v}<7zriVauPm-V}}@lEeuLPC}8mq2ok;& zfg*v0V}YX(GZ`y0gD1v`VU);r6c7qV79xaz1331KdpsZR?$__#d(W*?`>a}P^T)2Q zbMNg50%nAJ-qzE7b*lEq+8?J*?O*-YZ!shBpnAd>glP<;CWnZjGmGuO8hczd5T?o@ zU=sB1uFRqa?h=Fuu91<50GPD<3vQyEUvp3<+)L_y+(f;6_iUG1tX2SDvoRiPb?FKkaUCJNi39cGit-@2Q0Mhm^m0pKt$ z^#EWf6WZ9)mkaV$Y9BV=fNC%G(9TIOh2oiE2@n8jgPKNDl6EQSoAQUX@2g2L&OJXbqv z$*o3psMeT51~4!H>}voRH~<)^{AB=sk8UXj)BuLu05H@5+yy``e>2U03nvTZ_K_C> zyJCOYO5_#$4D+|3bhdE6ivF59fI;(;=SW!gU7LnN{mVcOWFeHd)C-ET;92X?mRLOV zZUZc<)pYw*SYHUMC6{NU;I3%;5d@WQmA$XX#Jajie?1&OD9=FBbO-bW{8)ofw;`kj z)wm5}<;k+Sp+z+;tSgxEgrol5Iyu|022_r#U%D2itn=okb=|60Ifq;zr*gxbDM(bj zBWamgr&Z`t2O9+kaRxjPjnbTq;xjk@l#EP-iIzErv*HZF7-29U59nQ;to6hk=rY@$T#%PWZ}GaJlGSi@OWYA`F#dIc65L86gqwQ!vP@XY5bn*OUxv962a zmBF()LU4B*hJF~#tcj7UYIf+G@evz_s;aVi4k1t|-diQY;~3?zAX7dO{Byn~j8!@{ zy9eH;6iql6Cdg*aQy50YjH%+BXOFxo+ZgMRXcoru!Pc!vRjs267ADl?<<)0@rPHiF24QeDzBJ1ARvTFss%HeJ3IMQ>M-a*rK;*!-=$*dLAm0Y4L1*C zNvThjRJBOycoB&&5aG;#8yA>4La^XOq=$nZ4(AWfuYUdKZ(jR{&$e4%`5Vp>TC=`Y zSYcjy1yRj#)$BsJ2E68vSY;@c3=?)%YMb#d4nf^3qP(g(03%8TWS|O*z;6KuiyECC z4u#DZV_nDi4FPEZOy)4V-f<$xiSP^1;#M$-kYW$0yAwrV(8NZn5@Z)mwh9vsM5-Re z2%1!k_yDb$HT4Z^4|$&opOTqM53pRBZ(QF(*O_*RC)_@BZJN;}dPP)7fdX>J zzy`ya;K{W;5Kk^GVFxb07sTuYXulD;5|662;Gm@fcb3Aqf*`R=4+yEr8F6xpWH1AG zFG>a#sJBqth$=Jv<)8Y%cYoji^0S}%z?a|nwLkX9{)^PZ{4GURJM;WKZS|+l>p!EH z3BWEXdIO$zZiHPE&$s8VJiXpsh@}p@?t$@^@uePT4YjWH9e?>x|Gt0spa1Ni|D{&K zU;7Jx1L%I>$A0@?`P~m^ox%#-#CByBE9;7{I6d10KiPXl}3d2tQ|N58x!X) zg4J{bek1jldUZ|lm1g^p`2YY=pl^WLJPB zJ!3w=7}PU2Y7oHO#11ahlQNrF117RT1%f^S<~1uR5qPf_;RYF4iDb8hI$(^h+b|_! zbMBJXqTEGxQ33Uxa+?HTeL%#nXsJ)Sl_oioTGci;W=tpnKPnSzMXG z5IsgBZb4dkIupj`!jX&NovOyucj7OOm=u=B_KAzMAYiw!gRsh8aHxq<6>c?>@eY>c zu>-wkb2bC?Xf;8e>Z0#P0dPHn3gxqa^Jv%ZEdT{r;u19w~&jsPaN6r(7Gm1bFg)p(A0&Ez}EFBI23a~OMG3AQc+y^rzVj>zDRTDyl(WBRogB9kS zIZ(m20#o+vW>k1Og<~}lo#rlQ_dIDZg%Hx=;O^B*rzs;N=ix9EYEmsyt$YkIv4Lil zt2NrPz$iHvkfmIj!Knh}%si|$M`@uWO~}rg#5CbuL^-S`cex|@lBn7= zBmHWUx6f0Yfr`24XU!`i=UmldI=Fk^C$4zYG;7b$oU>=IW2{7w^Mi{AS6}$6H?MtX zyJ--@EsoXvQ!pRT^6dqdTDuDR>NhQ{3RaVHJf?cWtmZI%EO|;|qC#J+!malb%AeVk@&%NLj;GDF|+najkqbPZ>YI}J~rKx+^|;KB(elJ z@uqEGq}V8n;2CraR|P>8@|Jct&`8ZWVF2~uK`bI|l07y5U%fw-_62H~plU`)W&++r z_hy~o0XVt}sAJj!d({(>y*tdJG}q`&K`rlH1aQ@j_}=UUPE6|92=CpaVq07k0f>nhG32Z%#0xb)PM+4S0aX{s-a6uLZS&KXxz~mi&v06#MLUc4RDCjQeud~*?CYW zh&G~%+G$UknbcZoyFQUHDwjPa>L5{|Ai@dpjj9;!8fD>q-)|wQ0Vxr1U;;P_ZO%_` z(41cCke=?ZuA1$OPg?q|90T!rdY+!A=jpd-8uipNe0uf_VYMHg_W5_|S~KP6P8h(k zlA~6ptCLvM_+(##9gQs<<2bj0vb(_6SlhT)S`dQcSc=Qlb-8jShoYO5F*Cf5d$G2D z-3E?#3^?9BOwCOI!-%tliSaYv32EUK3wvmF|$2io4tTqz6fbz&KVMN{faN zmM&+6Ku1GUpd1=!e55i3AbSV}0xRUEDZ^ynYK)g414{(MahQHr5Z;fBTpgi0!q|X#2h?!@Zr#ZIWV5SEpCK{2l3GNPII?mZM0*W7*Pwr-e8&&{N&e_f8eqqYy z?geMbv$rDvpzwg^(I}nG6HtN`IcSDX031{gheItASG<@~&oB(C8i?vukzzxE!w>>Z zUY5%&0BbtioPWMLemwehK?#+ZS1hekk-59OedLq*jo-aYwJ%6nxp$XYA`0^eR9p=c z+s@r`UWjH7KlTgfXD@VJ#~=7al_~%{1%h;U`_ND7jh2(`X2Vs*L^gwW6zaMzB)dF8 z_hrH;g!L562ea_jD3Ue*2)dU6T#wtly0UqRXjw_+gB4->f^W_fnvp{Ypb!RZnx_B4 z&+CVNZi_D&AbVZcMLSNCAT|df3M0Nzz9`$z6#E3Ue1pqGu9ocY#&XT$3sw=yuw@#nQqV z0Op_GTrI~qcLC}0CFSdMxD_dfC}C_37~Af z`DxP(Xdb~%NHqdY=Rq4&-&iL z8)h*Uz+nJ7pn(KU35bvkDzfnafqVzBIjh!82V;U}hJYKU1g#Q_z`-IIlpQ$0Hw1vd zoYWiu!vXgq{+nure)PBf^Jmc&R|mqx%-Bp27|{a zR{+C;;KpqOVb)|2(T>!NPFqp+FZKGMC1QwyL5Ivg7<)vMFZfjs3UnBPcF|6 zxH_cEK^}jtZW>=d4@9jpfK^c?{ z53AOzQRW-~SQk>q=!>_qzr5-%>iAXh+AF7rfXPd4(JU_yF2&Q0mP(2P-TGJBnk7&1 z>?_9Tc9?s;HlsKa0;6N&RCyU&0FcrC0F3@IPRo#zuPQ9(;mZ&e|GudgzVgfCVX35a zb{wvih`X=GdGY{tOu+=!uAOM7ULa$V^DnaLjtjh?Z1kWlj@blpFRgT{XyTZk3Gyo-fT5-uK zlk0QTya~f9nb%@N^BTK_`5dL`VYy%dM~~OD;833P9=YJHvL1msGq-D$b;?uOb)9Q# zW=!oEzM9dEum+F9+Me6}y1j;0{XB}Bx42d2B8=qOJqF?xcJ5?~XNZQ^Hz(uj{N#pAAo zRkPEI$#-Vw*2i!g%=^2fNuKMzb$0*Kn~Vzqfdfgn<$V2aP1!vV6}=?0N$d%^s;df< zzuv^m$~hnOa8Q-1szi!!;OOAblUC>=afYt(o@(pg>(xRRy5{ zMzB1Dpoc@wIUNo%K}c4}VL1mT9~QZHOaRCHagCJ_bAi~x1Ot@|h0;>>Ky%LK zen^K9LX36k$aFu<2qC4^@B2E|wTO>FDl>&(Ie+W7e#?LN^e_0|`X^!&nYsP@{;Nv3 zj&;*CO>As15s_M$85!5t*T3;se-}|8r^9e4T`nlw!*BojmtTI*Y* zx>jyfIcF6eY^dwHsw$euRsc8zCW1)mZ@|JSo8{gyd0Eb5GUHa}UYaNc^E50oN)6^qB#$VIZPBd3+;-nI+bs(EXjy(l`D7n#agEg_C8IH{ycCtw65% zOjto$vnM0ncasUL+gv^-a8-b<@{~>uIrEB0jTN}&t4s4bDc_^QtlaPSyQ|APCcN7c zd2~3TRv$!K>y6v@!EuP5jzK zSd7!Ar;4;^C&u2bR&h_@7!?Df0@&yQJ^$2OfALc<{KZf8=70Z%{6^Qk!rNAw4RHPGZ~g!Pf;$0t6;Z_1Wgj&% z?-dm|LB(k!eB*Xvu8as|=S*=X_?AplxKRM~`X%v)?9 zXgVl~-~g>aaDsN!%HALhLiaFHB6dL4&fHUE1{!cDh-%il_c&{5Pi?Eb*^e0Xe`aFGRQ%%2RaKXJo8+AgbhoL039fk}3NNXItYl zg~>IqpQDjj7S6Ix)`-}WV`anfNaW+pN42kq;Vw06EuXhOvs9505K1h_ao$39%9*os zc7juOf(J}ai1)x$7$xSH@xU^c^K8tQ=AGUA539e&Lvt@4wf+v=9_{701d6+_{JSs_ zkqs6?F2GixV1vQIQWfQpSVYyMTQN0r=QrGoYr~ za&at8ht#%h_1bHn`~2r~&O||~`1oVLusz+Lo}Qkxf3HN@G@Dv#qTrs1sVIV>u!@-7 zy^^YuBi2=+`^|>YM7x{cn#>De9Hmll8ZHzc&xv|gO;e1iU_mg8Z2UYR!!Q(o(juil z+ga=(E|Fz3GN|GTD7?9wU->LP^818&9i}i$@YAdTA0}tRa4Z0iDQ6MGTA!S6OnK$r zI4g7cinm2ml>TQ<(hO~y17v8~_rl*lWiC!>)fEnc9U{9W8`zkRxge`#; zU@?Wky^`$(@r4*WCsP3()W{SHmG%YTOxnn#mXu>hS|{5OdTGx@2GB=<20)iKk@hfG zuK}WFOY$M$+@VSmu>k<9xZ!{6M_>LA|HKan%t?TM_Fwte_dojYSHR#bu-fz)6kv08 z?YfJt$9DURzxX!|IkGpW{L1@3`r=FZFa6B7{DFTgpSJX;{*C|UjeqAK0ye+{JOOY6 z+%$ijw5zCL=!WGZ&4m!iAwTuaFN59H9hG80`EJT!DsXZqz`@C5Z|(#T-SZPyJ+Mo5D86}&Y%u5VP-j4szEo9jq)IDs??{G zc6(4|W=}=}5~#<$d$huRF=dVhX`AHzuHlBG;l*=Lzm;PkKHCNWM$2tFRRPo8zaBDx zTFYbpQNi+Jr8$&W&KW>8a(prX-edr53$v!AQpqS$U+73x22iiqQkWF$ef8u#{?z3F z;7}U?ql}41rlTM|0XWnd6K`uIkrmEYp;=8{^<#!A1K8|o&JgcBk*}F$<;{ONQ`H$5 z`Avlyc58@i#r;{+&?bTT<@~5^U!>nphxyF7YYo7}Gb(AWtxg0WH8wXi(SR1=c`pWJ z0O(r-kYb*Pcg?LUCW)4L96KYG&t0DAQKhpPfUgw#ZN=)+QP#bj2LK-OJjf$W?6_dD ze9i2eIy*m>ppQ!vCC{cO00S>7@}pXO6|kDSGGZg&Y8_#~Fk4l$;frl$i5B)^(TP_k z09v9T0RT3h035t8P4r;{fPw+2!ybTx0a%CtP=*aw$yEc&rw+b`SvX$hf$X)m?V;p%{zih=2z!S|K_jCS4Fjs zRlwHf%#&KZ<_a;Ga$luxhP$q>8* zK+GyR#q5OOXaKT_6;&z;GjMkVY%TvEcV`heo3W?q_h?=nV|>JS0JheBoxro>A^9pr zjv$UboO3ShyKf9^YtTY|4%sJkK9rz`16Q1LHeFtsj&To>IgEh?Jv#-;6E~`;za!@& zoj&q?a$d_z1uSG7&zTCcW>!4K3TJ9+Z`7X}#h7@6y2_Cw^{RkeWq}=79eKsR|qq63Nx9jz(A8klusJ-YkjV~ zYSgAsfU}*mg;?QJv%%q5*sH2|d$J7_%J>J2!2wHcHEJ7dBxEtUd-~8P^5?z-KogtS zzVm;0@ZivQ9+A#h!>m78s7vu`toKFo9^r36Vn3 ziF`L}#*d8_;B^ITjjJvM=D>U$W9!|Rw5u71tr0XQ)Ez>k8?aE{nY0Q(GeH?084?X* z8&x4b1+KtKD(nJ_qOSu%;u$2f8MG%B!;PUw&(Lf4Erb|GFcks~AVO+XMA%IS7G@$- zh`^1N_T;r11QnVO8ak7~v|{Xm!5u1x#$fR!G|Ye*0|V$_=`pr9x_g4l*R_4MjjcBs zCJr-4Y_471$lO$b$WVYGYB!`O4kq6_)dm6v1}T8Pbs<+`W>}-xu`)!>gqdMC?1Ra! z&{Yka0=N(#;6zSJ13WSr@XRL2jBK>-~M0z%!mHXf35o6e=!jF z_+ELxitJ&V@BN{tpZ@rZEH}`aXb%HquUf%Li5k07i-55>K?MiXQ6NyZKdm<8_N4eRzHr zkrKFfa0I1|6OmRfiOAqd{X`V5HIN`1*9{}}wr`s=dHnL_<(F|mtyJa;-!nyc#c~A@ znAi+fJ13YC15iSv07%6%tTPCp3KtJ1L+@y?g~R2_Y^!WSF61CldlG5mF04aKdle@r zBlda&J9Si)b`o3bT5b=5q-o#KuJ0dFqh3Mp`lqTcJY-lH$Ovq$-lWaE$8&$wOHt&Xg6&c_SRbsPLT zuH_wIj;{iQVFeW(Tke!IAM2e5IL+!&BXf=nnJ{qHDu;{;A=89pg~gvU+(8vr)~$|b zd@V1*0~c!8+U6Btnvdu9Xr5Q->Z+ChTd2()QsI#WVa;O;IR`kwcs%gg8!_C|@qjUY zf9+>VQOK* zHA-izQ8X=3>BXd5&&(8p5xaXq)^yP8%WLx?=lt;W;mPUA$@Zj)O;O4Z6o|qo!L|x& z3C}s?nKo6799x-Z3II_2D2ZuQ(V7sk(uKjy^QeDNF?-H4$*UGAMMgMj#rQ)}lxL20 zo!4PBCtyp5K~>${%+`!HBC=uNsyYnAFboz#tm|ge^uP93!iT@RjM1#=UeZjYnvd7~ zDXdls2w08dIdE&6wjDW=rlqHz*Ku>+Unbg zH-5RZ)HywrwoyHCfj~v0OEQ>&*$h7H}2HsFIgxdK!vT%gL4tYaqC1k^xMY#3@9 zxDDc!;{a9GOdQltr2V3KBzYi@w=r%sMefNPS3?UJpxuq3cf1X}g7&cz2)%&8iF~-! z%>C;CtUy!0#Agk?jONlE&ZG+Bq!3T zRKruxfW^zm^5PROd2;)o~gQ2_UC^5eZ)6E@JF6}^3Ps?Oyk~C6n)SczWB!F zQ+*UwUVY_vzUT4d|KQ)Q&d&#mF9^VtBLNJ>#rOZvmp}cfQ&u= z!*WBq0SF9O?W9mg_p2r^iL?R&pen+_jKK+ACRMlqMvW(n#KZ=|4Ye)p4IaC{o_QB@G_x9|4XB@YHx;ZqNMDKUff6==yCyjFP%_0ZGxq2&NNZ@v_-BY(6 zG|}k`t-ZE;`X%;Lh*F8Tf`g+n2j#ntRYJ+Rym_O7AB8QJ07 z`yIW(zD2)*44|wUiQh4c{;cCq?!I++k$yYjAAp8PWEF>+b#pRX%`Ktksiev6YFYNF`-iJ z0MaVHLAUYQfOQQE9ZXkGd*xBa2ot?aR#$1%j9Lb5Jr3pZYE3BfX<)3g%Ba%-QaV z7dHY%D?(RT!(_|tYV1Oo#I4r8a`On>a*bR!J!QDne!k5YyT!ViMqqK7yf;nH_j9j~ zir+;lZoz;7nDz2!?$EIvYZzvz0+0m(fK?b6^#C$BWvjh7FixFa>8Ran%&o|n3&=PI z6I@@KSawHzz^TYG+H0p*EF*erFLu2hOOZ1DMOn-Vlh_tUefc{q zx|z!rZhtx6DXlTD^%n9@#ZxsQ&z%Rbz{Lew$@77if7u<`avn+my?1#E6w={pUaWMxB7#1{ zQfp4u+S>Vy4#SMQ%`lT43r>|w%p5|XN!JXM=V>V$Xq3?J{^x%r=RO2_^s%3h^+gk# zxrTM?de9I8GXMFsK&^a1lEx}7D~qN6;j|z zP#5SWL15JCweyx_Yq$modZIMI$r*&V`rQutMCE<4eeWpn1Yvb>>iWd#bu%f?wgtO*r4Td%b@VV-$2D;3!UCvQLPHN>^vTa!yXp~*BjW}DgVe=A zT~{@ z;AU`-vfiOdxabBE9sImp#P5O&>4e5$&SQadMi2wyWUaLPijLe;R* z6iJ+E2Slblx;nOx39rF+t~+jWBNtzOa`pIZAB9x5VrOP?v%e>ac0$&{?L&p?l*8N)X==uGG#V)cp*29s}`tdY+!A=jrR7hAJR~ zD2E)@`b#CP_UPk214kHBKHBHMbDX-8CK}iHVQyn?A-n@sYHIH2(tQxm>_xanRr0#j zZIkk3*sO%U;3yL+dPkFK?#QkF9{X=jTZVC1!qQw`n|E(ILSR;a+HLW&J2=ZYxM8)G z#T~NJ3?vmXsZvkK7&tqPS&cD=1uU&Eb%u8|W{#M-E_Fo6D&Br0)U~j{Cgf;61h;_C z0`C;3<5DKCaJ*Y-^1#HrXzy7o^X%t^E(U~9C|Vw1G&8m)U)8(OJ(rep2zLdz?ghE- zPJCX0k-!9I-7Y-?TkC(0oRJ;y3?GRQGko*zP9cQ45^mTAThy9DiAZ=jsK&Yu2$siX zlaaG~QCK&3Jsd&^KH)M2rZBTmRkjj*af-27sx?#EhHyS#=1ga$s60W77Zv*ld~^XUsVl*S~@*7jjm>M1?EkGx51b z!T9o(ToIJ!StyGytZ*&>!!XQ~$VA0d9foT1LM?D@V8SXw;`Zd^`g#{X|8w-g@8Z?% zBLD>GB%U?hITl=LjdSJI$MxOSR}`>(T*_CF7N(k~8+0fhoyC}BR`L4X{TLr$_JYKO zbG^ft{@s%dXVh+3TGPZZV|8N{rLM>IuJ7KG)5ncey_$HVtnk_m(!5PVsi$4eRe};+QL#D+l$=1&ycO3JddX~1uLy|=ngH7|BFnW|X1F^P8-kfB zb4_+7*m(QE?ZzFDap?;>g+s~dG2#iguQG@!0pw0@ByxaPEo&zanmD+y;2AJ@BBDwa zBv#ykki?VrDnwLOPnzuzaJqTI>zxK)h_@;ll`=@_+`e)%WY4?p_JE&l^@{S`cJ&|E|sm_+#SPyXN+KmCap zp>C-HUztDvm)@}#b%+RyZa++R(=eGND1%A4j-Cuq+s21m)!K0*e665f&l_Pfg~L)M z7@WzRK#4#u5cy3gLnJBUq{PLf1P~N}69Zz{k!=YbcpzoRo=lwgeYX)xOiC`q4$7Hu3#5Kq??X-x@oLqwzmp!1rkA@m}LUQa;DKuCET56MO8)Sx17yVroSN7LNMOYj8rj*Z*S z=n4Z6Ya(CYzzyhhQ|HUSfD9NUI_E0 zL(yjPu*wzyB+CG_3YZvPMHj3nB8@^(!}!b&K&PLzW<@3{+mne0RP0$cl%inU?@aKahD)6-?pFf!@J3a_cq(}0Po)WuS* z&poOYvuy`i`d9|Dh(-;|Y#;RzfDDF-YF82$ABPfaQVf%%+M1tLniwfpD-P5VOKX;a zSn-NR2G(kwjE(v-iAL*VV48a6Wf@IuyRmqQ={c;JVh34QK9?J>u7~A_)iwTg0F+BC z&avATDgcb45?aWQWk*T?+#)csw8p@b%McxL#@2t2R}__H=F3L6sA#Q3U||ObkiS-9 zfB*kVW01=6MsYW8-Hcm>g;F&=xMzgBUSLPi)#~h;Duv^3%6vNtGhl>!Fr(WI-BQuQ zs)-pkI`XTyrL=X_(FqQl`8&rK?rZv9-^P{J`-Ir!<(37^1hG37te5KCwbfUCM(d7* z&(^Tcs{Gv3d+jfo^N8K#9AK0K!obT-W~g$J#LD5w=DDG}E}yFag3J7dJRwRWWwpiMKXHI>ds9|LlL5p1Sw-NmckG3Ddq ze0K`&ITKcY@2_(CW|iN+nW$BcvaiqF*XFw}6{KL$ftW^*%ZxyQLa0~L=5r9blKQ?! zS)3shL8VfatuPCk;)RY;0w>bVI7=Z^$DVh2^64WcVk*9Y1riDqy-TMUg0p}ZfV@JW zeB~H8_por5W|J1>si_MyPBddlc>+hcxX4Xa6_NYGv04k3m+n-|d9nc$%vZ#rxZ(nb z&9IbDh;%JdRn;s%KX za#J1WYgz#APLp{VD^AuVFkd<_eot4~=4makS_Xz;n1e{#r0ZXX1%Oo5+~_#zgO#w7 zW>(hu`T5y?-=|;yx%k?5@`PvQ71A{0M|3AtqD?5(@)cYC#gwhoP#&VWgj_60?y(4c zo|~8)4`-)cE9+qean4F!>t};^cXA|vpqGLs@m|ouFNlSyvGYTF`rDMCAO@TuFwomj zr0Xv!Hsohpv>f-URbp$kH|@wCIBAcnp@XpkQMDFxGy_{L_K;!90tiPk-K$0M8aOa^ zj;(aH(?gLnY9D~EO&g$Ue6ZMSpDewu-4ofq*Z3g>zyPa70da@G&5b~+s*J5d!2@}6 ziV%kH!47OxYay6{eGp3E%Gg0yuuXCht^h>KO2o*BWIBEq$emc!HjNC1!I^+wsDO8l zxIK+fKP7u={s>4!$zej#3`8G_7jMJQ*Z`2z0NgN45YfKW%KKux2Gm{E!4Plu=tYFL z=kLMABL>VFV3GqXz+~D(T-p~{UXbF2=nia@9B^q3_Q=lPFF5@4CkT%3`N1!I=FdNd zZ3-_fwr8>Z7VQVe{wM#FcGvZP^pBsu{D7~!S6_ZLoImD+zgY6(3zkUbL|6%M)IzRwW(=TGHi3~15Qts7ZDCnt?^@I*vfzeP2+8Szd2%tL z8_+4axTt9q+5ua&0JwsM218sF*!>|ty&096!KSBU~V zB^L#}t4KPqh_m=EVFMckH*j@(0D6{0kf68{XqQeKJe3%< zOc4pE3QNH?7i$dfp8Vcn40lY$2>OJ32~e}& zU1204z-c5^g`AC#>Kjq5$%y;#qX`DW1pOS_JOWIMf9Zno&FEvE0L0ZQ3M-U++}BR{ z6Xw~(s)qGiJet9Y2$ttnG<$DN%iuoW+u$KP1zQBR7QE=50e^?%JNv|=M%HHDIX*%w zZ=-UhBY6h3Fm~-5DcS$U-rI%BvSfFD|5z(mMrQ7h^L0P^UfsSut)7uJSh63+Fc?31 zY=OWJwiyJTVJrj!&tMpXG4>!ZVi0~ee(*flG>qC(TObek!5Entz4>JZWBmQ0@r zb7IOlyE)MUxeEHT?8qom9i3;cCpXLbW5My_qeECmv+vLLL0pg0~>trLKfVX(Y#mL4&LP>jjTY!n1m=-4VcLnVo*Ag09b zolVO+v@;B}(mJX$Q0%&Bb47}njfl8n#I5i!7pt#2w6*bRno6AJ<3Im9-27xK?P{i0 zE`4$G+Af})b4e+<9aN~+`^Arahl|R>fhwJ6| z;=5`AG&U}KS5sjb8*~I`+*-t(yi;Q`q43pxP zWDp&NhUerjh}iXMGy??Pjp+q&Ak414J31<+@NpCnfWuKUYTfWO@y6{ zXNFIy7ote+N|5LbhN?djofRzcKw6x_Ba54wBN6~s6bfm=Y#L(uqzwuLq&;H^s{?RwT@l%k!XmD*3vZYJ#PQZZQre`Agz4zXY zT|dMYB<%XH|F!S`XaDI}TwoSE*(-$6xy(WPSg}B8HouZB*6uyo$S;G&|bX1dMDm~ zmQ+6#dKW4bM{uXehF-w%Bq=)W)h>ZOgN@WR3f*u=0KbMm5_coh9&{T)PNo<;kR^9O z^qN>By?|b-x+aao4q$LEs>&f+OyW`Zju}Q#_G4;$Mx{|AMRGDPFP6Wcp z01+pMOydvfrtzboS}*zzRhlFvla4!pefe$_2tbn^z+sgW7iH7(=ZyM|pEeSJl2ow> zUJgYFRzAhcSFw#`Nj7;Bn`))8=z#qASU0)$c;mQH1V^@!Qx(-q+Dd+60MJ@#XF2e& zsXWv1+cy`H*Jk@wBvdmU>lfWw)Z;Xk=a(%_{cJ8?PK)+!BZexye^IWTjjr^e=(Y~c zv61ac+h$ALcBYKIEb{V>n2`Y-!ZJaJ&;m=|!=iBwC~mk6ph(nxll`!6Ov^b=V9fe_ zo;T~bc4hfmRQ0OtKMdDa)WEQ@pNc2>*kYLrp4)ZHr&=Ih(Euz-x?H{&-$ znKw|Ib7r-^bKXRG!f_xET=Xrx2y4IcS!-carb<%gK`f%2T4FRWLiTJH{|A| z9OXruQ*Koo4;=KytdXCC*ftcYzE^0CjtoX8zKzTEuPv?OuPuH;214F4(CrN=tWII! zXcC3f#k2P3UWc)UA7b<8Df4=0_@}R)E$#Ei$B)zFbLB)1l$3}^#nx836~Y@dg)0Gj zW0+~E(VfSUoxgq(K^sn3V;Nih)XWRN`Ee`78@{Ommg0)Vfr?=~0_NEeP@LLJoo0hJ z7Tu5;g>X1%I;2+GKnt?TH9BwId#~UlZye266;hF(tPrXg9`PpqUl-%rPud8Y07xq~ z&%?z~xL5&CsK)Knl+qz}T~}Pv7rj+YUs#OH!)j?ywBB#aK#oKVKoxMI$g*-St>q0F zX_$+P)@l`h#=m&uM7F#OHWRX)-V!TE)naTrduz3|V@u3qWj*EWwh4GFJt(7QW;bVM zoz=|t<35DIOpl*D?z)bc%3PIjLR7T3P1lG@?#?dgJkQu%ZYC<+t*G7(^9-PAnq|hS zRxal}tJ-Wjt9VAc%=|iVZW>~?c@gdBYDFJ_l1@?DcAn>qZ1a+Wb5ZB5$jq#SyM_?T zMdX@dvUI*=5?~@`j$KSCP2c*v?Z-ctHwg+?T(#O`ZTXRH4B&D4U{!VHjiXjmjp579 zXsZG%7;Da%LvWxea;?g(0stZavw7Q8wf_1GQ%z{_#V#&xjw|jaZux9U+2VK37p_k++>$pjCc&Isp*`Us zAj3{OjT(Wy7tcPhDTrSRi+WT|kA`WoE9q`AW$@s5(LK5{%kaZAUW!aiFeMQ;Ck*e( zl(>s=h)lPx=7{bj5?~l#kD7jexcsux2gE8q({M-*pb@)Nd=KMJNp<)VqbHf+ZfGKA zl|%Gabp}+>PTUJ#k&v1@dT0W6t|Xn4c~U?Kj)8fnJ@gRePQ5iFkvsQ}tznQsy9lIc z*t0iqRy>0$6M<*8XlR^fahMS-7@QdbSM33V7<>;BxWE!YiK9aa^G^Fnd(&(bV9GMX z9STEB3{d}fe)A_Bw}0_3edoXY%`X!KK1uYHn&czESNJ0g!^a>0Q&*3?@8-YyZ+`c; zzJB>z-}nF^!_0J;5QS%^Y0?Yu4XJRvGmVVSF);{2K!7@MCl-rzvO^pV!r4HegQh*< z1>)0TY!ky}Vl?JaY_EC;{kEo;z?T(YgFq%|F+Br`JZ3p)iXbRNJQ2Bp1bg8)84bg= zs*ok5*E}S+2)p2=p;7Hw;0oxT35*y8s;v&YXmIJo$T47i0lsy-M;M-7rPsF?YH8@8 zOl%XmgQCd6y=U98984*RMlbgrbG>lAqs|6oAdv5+b2f6Y@c>N_g_3cm;S+Y!@o_io zlJ*d1fRskwGa9h~8BJ3XSW=0z>V?Fhe3%TK5=a^5JUi_t)hl6;fCXcONFpQLLFOOy z?*D&S-fFepmbc|?d0XCC3YuJ!L!Et(%*SuFbpyYEn?=HKx}D$Zo@&|Rq3{MSv#Gt2 z*sRsgK*>Gyb`M0MM9!VJyy?ch&gIkZ@tbJ~XAd9p(%QBhHdXGyuObLKo#gvp-_L?6 z1FDnPJ=T^B+onkH{_Qbq4% zW~MVJFteMLSt>aP3)Y#X%r;=Klx-|wK{Km|l)KM5H_~7e zgSli#taG*6q?b9Q5GVu$G~5_j*L7Ea?!W$tk3Rg;`ya(NGBNQIz!*Z9=b2YG_gqAK zUZB#-99Mp4v#F}I(lkxeG!#Nv4>{+Q4hKEtoVzv#rgE)UDI5_sT_Y~5j4ssWK_Qd~ zP;QHPLa6WCWo4A{mT=Ah98}RXg+&G+hu}Gv2-dmM&&6VYqZte#%sS6`=7wY2a?_aE z;ah*V{rKm~=SSFB#plg~lit=R!|9E#sWFUR8(Crxb8bSgHHl}fP+(TMYN2AaquCY~ zc_WzAjEFb{F6~rTvLEo~|Nnn69~p9s2^QdYgczAzT_Gc8RwK%;BpAg!`2}b%_|$Pp z%B}+>IK2Qwr=I9yc(xZ8L(|1OC5K*78W{Ve-`VYEx_s2xyNM}Ea^MpCWDVRw4HSk$ zCo|BfHBh~jWZJ+Sn#pHng?GjyYi|I@;Owd`(<|5BB$L6VA0(R{UQ?!Yk%$LoOs&J^ z(WU4=U6zJ}L73Fog+VU6bZa`!a`{aBG06?aUU?5|l@)H|>+g=^CyYKm`U#Gr9)*&i zcg*DEbSKlxQAPQEmIf0OE69cS$@fUnNlo|g$2=T#>P317pbm1@p2UK z>`8l*8Q2pNSp;AZ5(oC`&loqR&U~YOA%z3m-8i;9Om51+q(OK$r3(Q;7}&EqNm4u& zJN))HzHEknS%~()tL}M za5$6%&)r6+fxU4jCBRG4Hv^kb-~Z+B{3if@E?bU24F<3Wpd6hXt}O1Df%oIEcMxQ+dPTTnx`9VvFWf-AlgE4&A)o2( zg<$W9B(oz5T#Y>afsO}Ce<1IDP2@e1y&CQGDFL0_!Xub49wz!nY)|6wKFMRnchWdU zJOZiX0?6)AGvYlwx|8Sy@XGy~uy?sM?@jj%QUXL+eew4<3|-RcU6!5tgz>4l$#6Sa zHr;o^)AWetPShb}wl|lKF*!OYyeAGRwTufCyDTrCEXIiB*E+rcx$w>|nZ_N6h2i%2 zhji2UQBbYdO%Fia0C+rnM`k4guy2k7 zq0JZ8qN$PMrdEF0tG_`N0hetYLyO``?D)e>ImK4DRnjv0<`cQPH~}>i-&(tfww4dV z%?D7)xaXTw+mdVVSgD*eNdVBPuiabYp0Fu31LI~>mx0qne%cVKzNyHLisWk70aaSH zB#T@GZcA&o9Z)w@WoSjQRkHyeyHWH_<*=eYqeVS;p5kyT99s{mE>GdCaw*j`?KlaP zkD#F(wOt;zh{ysqjW3TkeJJI=G%U_}Qy-{TuqbzUkzyS?b{zQ9hx4^j_mImL_xz;W z<>46sZ@R-(Y%W;=a4-NJMgVi@jz<=K79RkhnAT}`-umLGb#GI*K2t8uAp>v)uw+Ff z2>^5g0M{P}@%vJe5EeXfeB-TOIv8_v0mKssKGOj_TvlNEA^1XC7cD0Jm0mEW4JwJt@A*N!z!)K0k+IZ*=}uXZf3i}$8dbpY4<3h9mz_RP%P(&-zwmE0RQ3tdrk#Y{zMClmcl=F(N zLJcikwMK<*Y{^bP^sB>Bsju@qn`Lv)xfp4c*u7QZwPK4E-z?#QHF7NgtLo|)6j^aw ziGM6z${REmYC=8FxgjE=rWIrRo4IHAMw&*NRcp3T%3@MhuQ+dl zQjg>)=Oxy%{vNPQ@+uQ6XRoOe%P6P{{mQwxX&RAjCd4%mvV=^QRE((5ws@r-RHxtn zZ{#aK$3$BTEmY1`_*4Mq6~9&vMU`aP#tgnZxu)7KM(@1-R#7Eg4$Nl4JQvAZ)txag z=Uk?%oUXv!q;o6FI>~SP$oXOw$9M30=V}(;lc9GbOiK>+E7J)V2_Bsw6JV4wh+R5L z7iKz$jw-;l$SdoVwJ|&;dCo@am&C-~b4-mn0DAP~smV3yHhN?d;Xx-eeX0JOv{88` z!&A_tI+4C&85Ea*0ZGv_Wf%z>wGMn>Bk0ckG1E(EFI^zpyL6rJ!2;_^Cnt^)$wwE4 z6O4&=@W+lQG{O%~EezJpA~Ow_Q3l2Zke~qX2?W{036@+gAHDOZg(PVUKuKLyWQI1% zns!9A7vZN@1MG4t-`&k1^I*|@Kfe59^NC~g2m^R$ZiK`D4CZ$_{_&JvasM&PM}*{v z!ZRR>TS;l0UZnjixqdAEKH*YD-DbiI^ z6M-g!Qp4UWT*w(v2pmMoaV;IG_7EYBEVuC9U5UOTkFwYkqn>eD7+vy&6xADwN#YZc zCqkpUs6x8ij^b^)xxKx6G|a*R7PCjfd)LPxCvuioQ~HqO-X+`4L=w!@A)qu~A||Lg z^`tKp%=~?IM!e;*N1Op;B?e4e9!A0508wLh1)GuUNFuxO%4C+fXTM?XNwOw`sT(;v z;!EI}`E)zRM^SWm4!uyAu)gVC|NpYQ)oQ&hZ_C^Aw!E<%m=?lNz0&XR?LU8;{6OH? zeLk_ibUf?4ppS>J3b!bq znAD%x+gECqx8VDfJ-vDPoOEVo=;f+Cc*M3QaE?B)Sum><@$B^yQksEG!NM{vIjkb9 zv(^f;C3LG`2owzDUf98!^KKz5Arw!dMWj;=o(g+Ps>Q3T5h)mGRXM4uSD?TR7x(vh zlYB7ed{A{OVKxm@NyWGDsYR1j#3|LyeH$Fd1+{E%Xf?Os3Wlh14GLi{vZk7`(W{MA zF?FKa`863|!DDXE1W9r4>GL0uYk4!cR~nl zD~0#vszqA)5fcRolAW20*}UhR-KTUQB5t_ryD}jq(_fhcu0voEB08$)q{+b5X^%dpdDo9+TN1LY6tcR5P zzW0ipRs*c<<4}3l3bXP(NBL02TwbrZ)Pb+{fh8Af%jH+llUrp$U<*WB{pmtzrJ2nd z=JFofI9PmPi#{Jodc?;vMAq2=fva^QJ5_VLiP$q;sF9+j;dKXcZItd)!y zL%1b6K=0s$Htu-5fS16+WI(-_LT8bHN?R?l1PV?0?1u1SRZ?Q zrQ_Z-0VdL!yiW|lt%87Fx>w1B(6G#^4ib1nGB81HuikgE7eu9Ka>psc8<&RI$!<(9 zoY_2eJQIYc#~sGcyzOvHB7~9YdP4Se5e2RuMOZvp0|s=*63hik5Rc5byoUdbLq8iw z9bX7FPoG{Gb&hP-Lh$6t&w|y}D9Ye4bZ(*!;sm)c`%`iqn0o>ojaib;)!6(>h=%UH ziJwT*{f#dJc<-HeRpxL0?I&a(IKKlmioJq`1#oi^!O?e-I1Vz{ zr@!`J;cNUGU;9<}mgw+Te(%@Tb@lbH{Te<4!%ax|*3k&35t$q!DiDWP@uVs}g73hW ziU9y%t{zz(FarCXAquIRql0O~oE#pz*J*qLIuM&7!X3o!BXK6QfRi-P8y;q}IFWYj zpc&eryLON!h(wlK(w^y#Kq++*$#EgLc2kkrF+%%+9w)gO$Cr<;g!S5nS*`EnFlnGT z0!fBH!1NRzO!jKdEW+YbFQlfCSv5@}gXy)(o?tZg&a*j_UX6aZj0)Vk_e)eM!-z~3 znlHN!M3Avd4Y|X52Sg`CW^|K|jNTkBi6QUEAte=bK+p6F{J{JD|C92gpjt1RD*z1~ zfQAM@=LtaP2LLHFs4haWS|U0Eszjw@1<;wI-p9$0GOIZR029gDNZ!N>RZY+GxhRr~I%&JPS|ng$vt=tbQVsxjUFpWLg~g*P0Kl$WPGQBMYUyFd zsY=T>USQjldZ{@!xHWVtsW8u^Le)>|czF35%NvDTX~dT2kH;3js+v{vI1goctQ+0j z9JfAo{?EPGO6AhXp(&R>qYB)L2&-I{;^P))$3`2Nah&a~U~s$fE(6+%*Q#IGadPT1 z$ZI=&UXq}i?*L4pTN`OG0bq*2;;scDV9A8&Rx(>3fTNw;aqh?g6qA&|wZml}zWH}~ z+A`|0EON%M(FT5ji!uQ@R3x-|X_b;6fFbt+74Pl3-&9T!%meJ=#CCnths`s2TdjhP zH+d`71K*fVad}^yvapl7N2Bz6y}eJ|!s&0!Yjj?~i5YobJO1WbJJVMlJGL3@R;0GM z!=8+Hi{T!?YTP%Gb;k>Z}ZYTZq} zfqa#AABa~uUtt;H^ctR3cyrdx)ggeu|5s}w7QW`n>=S5bR~+J`kU--_GH2lE;!sT&Sb2v;b;u6oaxM1D5U+wLvo zB?JInj4QjD&D?zkR$ulElyrWjMgcLQvJ4`MF|KT`Jl{x@ZBZu?Fa0bbpQTz+V3o>T zHC*N%C={RxprEd>`kk3E^8$U!{Un4EkT}mX5$$ewH@7!WzWZ0d^{sEUZ4{A5fBtta zuP)2AFEom3%%+)zrU{iuu0~f_LoAE8T6yc1Wm9I)ef!od;hf9Ys`Yz&@uaWckGIJ# z*C5BOdTU+DD=S>9tqo=%w(a55|91X~zfcxi-XJa9iwey3mYXZy3iTyyxK*iBMq0?1 zZJ1ZssJFrfhn2EGw9^>Xg)FG?m*lThRXTEcA3{(!^dte3D0;*5X%{3q%cXe~^iGpP;XRX< z;NNHmP0>N5t|Sq@^BBPb79r5=O3FI`S27VILnr$Z$U2@zn$@Ck1fWwi5DO9D-ms8> z)O}P{^c_GDu*=Yc{PpCjNf<(G>XY1HB&J6Em0Ax>a2FcH$#5xG?q=Xw(O`18*~IE9 zvQr4`Vu(r6z)g6sMve=iS4I&|5buVc5IF#MhREbXgrPGvhC3RTOXC28a01=IqkE%D zmy{TA>Y1Em|95`#C!q=e!zE(|sN>n_vBmSAX>{{r<20=Rf`Lnl&tQM|0B7&D?nG zt~%OxG>sa~ofOP4($1s7fqsxX_1=)6y$Lbk3^fvkfsGsZOo@W`#nZbaYU(t{|FSqB#S55_Mb{1a5%G?pi@QIfmD) z@4%9I5FC(tqreCgw`_L|0*hG#1-d&ZglGqlgo#?g9%vPNW&y;pSJ{g*Tu4Zipv0t# z3(%dj36My{d4NL9NE}RxF*2t{DFWH}Al|x``=miI>1A?zf{T>i`f9x`Z_C^Aw*1J; zOtkKU!;-6R>&(6Km!)he(wj-g(QfIq!hJ4tS|Oi8hGWC41=A^Vs{J{C;k3;+znYH; z6OZ8K?C_)P=wWWM=?vC5vkkecGZ^Yfwg=LdiPu`S!shYHhK^=c=j}h(`EB1GF8K`= z&Z*YD8rwcw2u`609w_JK!M0a9Zx>QtR`WLv(;51Ee*Z^I+kHWuMT-ZuBZ} zKv7YxQH=Ac<^sk%p@HWir1ai5Wyh?{1K zlB?e2Mfj69R^=-iSVd1}cM@OyWY**w_p7A=Xd6RXKHX)*gWUT@yJU=GXTM41ZD*>u)!0t@oJqjuvf&L?Ptqpj|8Yq8FCEspdJ3@SP}p-1;;<%*r}Ob*b%+JFqc*Q7dq zSJ_3#Jj$01hW2mIfLP2@aA3r6eL`6J|zo?Ij-IFdH0zHU<-cPdxw- zL7ok<2YT=;aX@-kg^CS(QAc{gHaMQL_d@7c%^5HyN9tMjymE466 zOtYX*%Hg|K`{Kw9p=$+#(8C zlOmE72aJ+*1ak8ztdkW77JTEQzoFyJ^Kbo6AbtM7{zLac(@wf)&%ghCDq;m~A_FM^ zktC@#1n%%0er5ny~$-mdd zuTlKK0TUO8F{q>*vwvu#>VD)WUov?H2;s)P2OS7DIT+0#dD1=D4cFkk>ZRxoU4mXX zfqZX>EIUAqoCi+3M#uR|cIZR_kO)t}mFgt?+BxWS9if1r+rt!O3PB>srTEU_Whwzh zwY?aUq1?}^=b1ifD7LNP>KMW{1U)K0C2+>0D4aVb|*hBFaNfF0MPLP03oC5 zwh}b}W?}#nwE&_kfF>IN3xulqT3XAFs^>x#f|Y+uvkn44Z~%K2R5P!lAfxO6478rK z94kHpm;(doO|jW0upb-W?)plzMJv>79&a}lMWn;WLr+Tm1#1x&mF?5w?X^kovkKET zb&k(_I7*F*)~WQbbS8)8*hL6dT^j&Qa%^zaK?>d+9Xgz7*?o!zRLS_Zz!hOETvRFwW~WmaXp(PmV|7H^&} zotcWqR-I(pNWIElwKUt!M<#8Hc#zI|*qWi*!<7ltP!b)M1)sJ$C)kLU@E`F-qU?9$u*aWbuHI21DI0=Fz+4JX=_f7>e=<ass~zHBD9V*s|e=g?RGYR4I6s{&)5jT z^5!h}#`sXTPG8Ndefl~g0B7MCIc(3ku&;BXv}yblU}bE^c%RyY&GBzq&7VWHw##61 zk=B#v08}@wU{rRqfpRtiqBfW#vwytkOcrX%I_;W*&Dx%8)N^ZcX> z-YR}uKOR)8AgwhVFCgTQZJyW7{Gy1-IagkDn5{?&ii8RkzLZI}N@q~HKxupxWaZ6T zDV3?ZVmCwu5*2PjH4tpoq?CBEB3X)EwCZnF&Q(xODf2v22%bUArNK~GTkVO?^E6E& z!pyO4SGE=EZQR_;Jmj29HpUW*cbuybLI`a&6f1h4BHJnKkC}NR2Lr&;phmhaUih`F zQ-lh+R;f+_QnOi^Rom#2LLJw7mZoWDRVo=C3yP|}oz3*1F}8))mGvG<-^zEJqJyhK zuq}nehW(;y?%dryAJSn;(|k9EfUfI{%Ixqz{Hw43$^Sw`x-Kr+1`A@tVu^J)=sGPx zMg^b&pb(1Q&D@xIVWR~-mGu)s(+W#-I2;z0-zKDyYM3Dr1q7ST%^PVJNVhV?5K2l! zR3u7EO2K6XuF|Jf>?R`m?cddp{zYmyZxR|}Bgi_r58ngnUZ1q8YCO*HN=~aN&vWMb zVX>|{033oALYj|u2c^QAYqFK*Fn{rrP>!$k*>Tlq%3^9#XUj03zCzf(LjgUG>+fmtRqj{{ABDtc3}yGCPG zq9O8OR07=zlWNbnGIbFJA~1sk{L;*2RPRKFuR1-#@EH_>c|z}YW88y@; zRX~(+2X7P*hE68k44EahN)W)TAu<&qS9J$S5Fe3`HVP3uQ4)#dq5ug^qdpo(Ji02n zEjM)LPBcfr*#!!5q)2E1f+W}g7!zPK;9{;8392m2w`%P-KK@nci{0+_^|+hTh12(+ zT?==E%Kr9sm_GS7o|>!-NG17l62}-^%0xn#wn5#()MO{yuB-w88rCDj7I= z>GLd^PP?=@*O_qb;g_)Ds|TUXS=DX1=b^qqW3@B2R|`)s13a7clS}v~W|LuCVYN|z zpjHX1M9Cpnz}8F@kV6iXbHQ67pG7NUWp;~}sXlqutL@ms2HpXuXeyr%?9EYx*bL}T zbjTKaX5=G$T7nRR2Xchv{ZiXFbJ05e4@IA~cxnAW=yaarV4-CpoL;Be_ExcV+^~M3 zi@R5(9f~)+S8uGvEvu%|EA?~E#aw(F=e4{9lpJ$i-<24;V&Oy~F!MamM;rs7%8NpE zdMZe0jVUXQ(}t?7g*MS@tGK2>rKSY^0j-F!2cYybS1T*5Sj}_Sb<#AbjH93sEBd2( zo^{SSODnC2nR#_94s=2@ z6wox~)x!7+5^{GpPbrQ2ahj%paCdh%P1F1Dzn@Ynecu0f|5E(t{$8NK)!3^9YQnP~ zH0Nw?(nuqXnW-uON+vVTdP6lj+iomQYZHwB@Is+@gw9PNpU*Hm_tU~OhaOXSH z7L$nFDM!}~>*-g=RRGkBNCS0_n-`KWo+qP}nHoEi1w#|-h zJ007$ZG1^*a@VZ8*36$cyUyNKPq~)0pMgvGRW2c1*v9Vffi?hZA%1N>%dQc`9$G%E zjoZtbvQ4gn_m#O|FD?@&UxtDt@JSE{Ks4KaIlmW<`N`JUxMs2#NOQ%?_LKaXwci4Z z+uz=&&E&NsGr%7Wvrrnx;OhL3j6JjKRlHW*Fq0EstZdyF*XC~4A2+#g<(|e!Qq44Z z^)033{0NZz<09ZAWw{}v;AHW{&J^iE$>iHnGPAT9);1xp#WZOk`FIYndSz1jcTe z`5l({ATmOFsku!B=R$^JhW)8l$BUFTxL6b%^EmS$6P{~4FUvOEoDnv3yFS5|?h}Xp z;9}bp6kI$Z62_dY_3>HDNN*{k1Q%cQ9FKbL16Br_IF9 zw_Cv>o_KGI>xC`#_Ih^&hB9EWq~clU6(1%!dP&Vi5rvlAj#>isf+k+A6)RI9(*$CZb0?21gOR1a$4LH{7w;Nv>xtz*!>N>Y@9^;fPEui}QFehS(}xSs z&I@ls=Re53ypUA5qH@1|lrRc9DMaAW&spOwSH5bZLmzyIJ~ieOf<) z0MwxNHg1$5=m*&<>y&Lu%C%5i%8M#Z_cTfvk6m~?)M~mW42!t^Q-{)TMFUqR^jX<3 z?^lbCHa_24%X{nvE`*@~ZXOD>P-#NC`K!s8iCQYj46F^)CmvleB_HGAl^8!a?9m=@ z0Did+os*yTgCb%3XEp4SK*Sn+fs?&}?Yn?2nWk=+y1G{9@^?7UR_1T?$~m( z*!6hQY+L%y_6Pc)t~qo6zL4pf!nLXJ967r|AO&EUy*#sC9DDJ_NN?+;B464nIL<9< z?pB(FC)i+>zkY1`}G{>*R;>I0{212b&O--@|S88co>;X zMH=HDHj?~VXX=>q!kyIt$60t{f5h=k(J6*aUK4MhOr8nt3Qfeqf0lh$=F~Y#wzXET z%0D+?)&>H;i?`X`c#yIEt%I+f>{iAr-(Ry<=Y?{=2f^ZvZ5}I{wGA!Ibs2AUUS?{T z*1tU7!-R;s$$bodYGIg#%J-QZ$8RY53NH#X1TaS3)pHRsk<~R1UD}N5Cu!AaMQnM* zN(y5u{2RVraQn5b;pCcP&)ITGrbW@V9&welI85!7L?!e`ptpz)&gsyhB_36mHSC0S zctV?9@r^ZTQv(>RY_dj-?a;(K22+qhyFpu`q%o~AL_y5M-Kn4D_I6OYb)G~>*rzN@ zAL(mS8tSDDHH^h^GD^nQE~^pm}E~Mf{q@ppd(mJpGC}I zIW*N5MNTs_O0>O}RZq-Ud|ESewjO!4?2z1McrOL7Ul0E=6M=?rZr|iu%_4@2siDPH z5w5hTaBJ}_Y-L8`%?HcU73z91{Jn1ZN;+(u%VDju+g%a;f#w|RK)j?@UUD!n8b@Ey zf*)N0*t`t5E+2A*gxsNQ#DCBa|Jf^wi%GLBnpD}c zRs*W2JtHmMEGIlb!X3KbZN@5R*zQ%}Y)(iD=tq!)G8b{x-zAtXl)0rjuGe(~+xtVL z!Qc@=#d@Gh!3#53Uf}y*$i)Y%nR%!q)X2Lts#6Q8BHXgKruURlv2UV;63^LHZZaZu zjg^$2&C%}XfC$EC5TA$*fl<&n@DqDt?kdc0{g7Z%HvU=Lb(Nuagb|<^*BWr>zf9US zuO%!wf4qwzV6V>H{X=Yn1ars{;XXp~QOAZGK1>1FvTS|Wd3<3a5Czw2q(b$BfDj*$$(Npo zc6L3xys3rh?f;Dd{A3&|dRZ0bz-5Aw$fU%$#!Mc_CyJ@|AQz>76EF$6q7@xw{Be5` z;Yiq0I8=P~W5?{GIsvO^V>cIP2QxpHJSBMF84Jk+uq+&TPP;>0j_WT@-oJDK4CC{I zdOz16zu$}N{-Jfbq!pUH#aNTEeD1zo{cw}doMhQ0#E3JG z>>{oD192AEa79?b)-o-hsjDGPsH>sy#pSv&b^mS;>gg8>CLSe=3y5aO83pNOC@j4CkKAqbv1w1QK9Dl0`i zSv3bC*lu=4Ih&i6l9H;qHaQB9gJR-3T;>0@zM^tyS33;B1_(*rp%S8Y)9*%d3H|M@ zQ1p2tW~M(XZARN^53M`93`8)gb-siSQgk<=*dCUpftEY==YJkL9)`a9Oey;kk|Fis zB{>c6hT*Fg?O=^*Qlpo)+x&y!T4NpX+*cP*#0{tEpG^1Dj5(hK-Pr3(i^=ENZND_} zgel0e+B4>hQZaLVUXfnjQ{>$#gpqye1&N@f*D>oxXzMWIq9OY1ypG>;pSt;v&@Jp# zlo@>Jpuxkp*8{`}42kGsLu}ipJshdWN-$g>BfNsipX7v9m9gSL7MUn{HX24fP)F`= zl`?YQ_Ms;XhjYq6>ZG@}sK!o%#cOt%d+V`5+Fp)(r@AwPOT%C7;B5uXK}8EXkkiw^ zZj2n|9(PGh^hvi(6fWZ$|~xALDuPdhp&OXz!fk{*Z4$ba_dWCWD!F%ja$tT*UMuzrKwr0r;hVXjP_NWQ05V(FP+M;tz$G81e81?M6r z!N4AWVx}M7I>8O>F}1QY_zN-Clqe{1RMS|=%o$XU+MT)5btsW#a0K%r#hj; zrhypzlQ;rEvgr)8{DHoU>L`Ht0puuaZ%-N?B*SE*f3JJBMERQVSHfFull2PF3P=f& zLm!)ksz&`?MY%Kl-lq`_YN~d%o{&weRI9*v|izC|Ez0lxl?= zUdl`DTAg%6U|=7{(vkg8)!N0(f(YlPHbo{5j5k>9u)ngz8JW)=se=kCCI_OF%`+yH zJ~&y8YctOykh>l#aTDVagg-NG2K_wrpkj~W$g%(_&=@-C6kH40F2y@u{6_Q#FH5@4 zW?_Ya&a+^Gm)%)DK=)6Im;tX?^&DMm>C(KtEY ztZahb=5Is^OqWahsDB1>au3Q??Rx?2A0JcZj8Ft7Ai=OsK3wgdSHx?PqUc;XqBkgJ z@&gW2#(#YUNU`}4%bf_b${5rVRixGBLDfWaSRhx-AlmgG;UoS(qL2~f>Y*^#P~7g9 zCVP#VCqOEy{~|}j3k8q>)@F-iWnDihanL5Fq04|bSx7Ql-k95XD~+zw!Uiw4orLfn zK`TgmV$@38N31jNKcGMF_>AsEa{++&6i>xUoz&RZt{8AuMLLF35Y@O}qbwtIpf#~4 zJY9?j{*nfiA_921mf%w_wrZz>j%SuW&*^I>QHbD$(Kg zlOEGy;W|L}kJUVoPS`DUla|o_aqm#qLyY@vU&mR7Q`q__hUxv$N!316^%aI zXKt*wXoc>4RK1HgRyKX54d)6V)=osERCExg=FD$R>oN|wdcg7= z$)~i9Rj<5ZCcV|O{2VXHRNcSA-Wyy>==Av_tr$WqJW9mIGFy||6`1OO{{xuBZqt2n zzwe#m4z89`*zaCw06cbD^+%1>W_j)7#}D~NFB-&FJf~X6s)LM??u2=iYl&*ITUJ$x z@{GQ|_1+_uY;Aj#aj|z0h>}` zVI8z()_1T>6bnTy&~|8L+;r3aQ2XNg&=?PHYptbdDgBYGPzHnF429(wf{aE7H=A5= zj;U*GT=xH33Pt7)vAA3?IC$WsR4Z>*wBz21q|gAUKyPo1F5lngqyb(i2(4Pn_gv$sSUVYYj_cPiaAQEBM~CA zAct#%s~OtY(Bj$hTLd&#TKedRHl8^=iS7;&wN8d{_I#?MU%o>yzRK)qfgjmb)g&`iNiGq z%h$r|q%i6?t%DZdu$N=F$d zoiydQKLSxJ4%9&s#||X3cHI=ak>L}|^Fb#+Bs>w7p+~`XQMrx?#TbMli}-u+ue2Ac zNN3bt$b<{g%O1Ydm1AsRuY_+HOdqhwGfcwUpbea=?-4n$@c%OH?bTeRN(c^4tc^q) zmt(7si_yaj+-AN(Fcy^Gl9-F=(s4vTz{R1wiXi?3qArAGKJk8U$fpk7bW_ch^hZ_En%2o?EqGPSc12W&==L1$aYJ22X=-hy z9%alPu~KM;tKLR#Kr_4M=RECZ+t)e`yZJlUktau4+WPa4Nxv5$ML|uB$04{`kv=w| z!g_tMVn(^{J%PCQ5H(wC7gS-8rsn`=@#s-(aygRKg6T#VPIXC?_>DH?q~$6=xuBDm((L`m=OXuV-`w2`mY^F?v+ZU&%}jm;#M)JlZK*Li6JuRaY!SBSQm2eZjuZy7+)kuQ(|RQk0H0 zBV>(*BS#EV(6bUckfdo=cnLP`OQ*z|LdJ|_VW-8Jl|;{#PQ+-73_rv`x^iBZ=9RA` z`g+yX?noc{`^d{vkorIQ44AB^Td!aIWwn@Q;(?OlKU`g6s;&Ar`8;O!mA zWkeZ0j#T;|OVX5RMvmniaW|K1qp=N$CmCfE)l4)Pd3s`ogHHi@P-&X2Fz09 z#~v#HZmtBuWVyq}YI?N4D%EKMa=!;#JmPL_DeUt$^LY~cU(Y^TAGXB8ShOf0d`lPv zEn*10J>TK9ou$*PUX^RYB@6UEQDzC6d(e*KY_L#N3rxJyc?OZ~mG%CxJIjy73MF@cE23p|~GI9D5sGnrt#;1VjrX&dcr9 zoL{jZaLxFJ6IGrM3j)8D`A2S}7^lF4CM*W}#~-MWy#kquON_BV!NlR+l1Au3m2V-* zvC$ZS%!uTmI?UJ5G>xD~D=7HdmS4sxe6BLE7=+|Bo@^0sv3BZ|_Y{E%p5N|IPWo~a<5}%rPM{&3h|R7R=mkoGd6F%4TM6De2!v#VAY{wPAu-?^8(iE4vP97 zyHoAJ5#;zi(wSy+G=dBfWQ>;#msd&^4zIlTD?-gXszwZ1yM)`}*E!u9&fFjDoKrp! za!1fals*+Mki0L4ZY6Eac7oAWmq?Y!P&|CbXBhk_XM5Eg|Xd?r{ohhN{Fm8qffbOLc<28e3 zX8?R|$2=aH-@MvgbFEAxH1NyURlE4ggj#eB;iD-;9A5lImElpQ)>Ub=x+JxF5r-E# zl-GM6Q;8r?>$;(>xPNk6twrUkT5%OofRSOEo23r>1Nv9?zvn7_mTe)_2Ug|5Dh)OS zVjbqZHN0zju&;r%({zhgc1()d+YnR~>hlhNlquWn7>v>tI00}?sNt;V{yTF~Abvd1r< zVLq)LGn-|tSQBNBZESh-{F~ABrf5{zf%s!8(}#LxVtP_00s{F4&kSH&z0$KM|E~Y2 z6Ahk&R3hpBdym-18D&XV_e}Lo*?uUB?qW-hNC~9YdvdVlr`7YaM3+?VuEm8PtlY89 z!m3I;rRc5W*GUL@5@mR+rH!wr;6}&Z@*r@U8f-Ih8THXL=&Zdg(F2hJ!L*#}&S3cC za6*ByzmZrES)6KJCz+@ztGWTCMgIA2Np_Vd6{oE*tB0lP5u2oj)dVYx5=V+c_l&8u z?6ord)*UcKNTX+VgkblOU%@_g(`<=~mxVT2ZVYu)=w4HoD4dAEjdv&3VpXLzx*$$R zdn`S)7+x_{0|?`2t!mAJJ@=%vk)V(S^Ud&hkxn+cPa*tN7&o5IL9k7V6R@G3H?ogo z;0__~bC<=)2euz}>u@@FVj9Svo9%iS3}{q&*T^p0>uf!$#P>Y?y4nn)kEOA+wOGhD z(5=lB=z%P0qiCoNDEjyQ?H=&V<=NF>&O`moKCZVm+~#ZHARfpicwg?e&%+e`yx_p* zm-dn(xp8qR!E-9wyT!)F@yBq$bG;`1o3mgOK=Be z_&wAPeWF$;3`qi$+HzYiXn6JS;BTZWK)%ai5qO;U1^lx0jHpwRXGG*1p=ZXeVb{Oi zej%b_Fus%Ev)IV;ZME(P_71`+0|&}~tk9(SnYY5&_n@F`oYw$Z<)8#w^7xEEVaLQZ ziVhm}0cB*qh?|_ct%&1-M-1;kJd}(Z4KK(H$x^avwr~*1WaCVKs9vlK7&4<$n@$W8 zZb@G5Et0uvclH}=Q0NfuAt(h>Af0fSxU-iDJ_h7Qhl;o=r4|>d3yX}im-yh~ zC;-pL-IcVR?j2MRIGj4oHz$Cv7?GiFkXW8WO)NJBlw{68C4=pdrQ-Jg()*sj{q^zF z4ip+6@b-npca|MmTo4SPMm9rK=a3*k0H>c1vzRO92ePWg}I zBgglzh)auP2w2ES!_a4VWjZC<5llB)H>hw?oQgg|bXmHaZ1ryGn;qwG>Is>C_uDaP z@%h49U+2D|r&B>eyiqFJ0e`1b_=Ij#MB8+BwkSq<%;3RVOZ?DO`@nm66d53Qa6(87 z_uKQ`M-$enl5ag&ZDaTcc3-jYxMTzn?=i3-$36~>D%71Z+M9Nj)rZ0z0(-y7W+QgU zo)UZa?la6FL)`;PhqS=am?&e)QO6##>qRsg6d6Yz<6uJ}gNX^081n1>_AB7z!LaJN zx0~s9^1p`}SNJ3p`h?(0;ZouY1h7FEKVq!1+i>m5y!zwv_kFqRzU;I5C^uILO9a|n z{5sBOdx5Um-ye?kOFuQyNR{PMPAZc)3%WL|ddtGr2%EwU3T<2-rhcErm4ojAbQ(JI z<6%ww^c0OqRNAhh7q`N?I8I&qZnwO*mKE3Zt?t(S`b+xude5}m#x-`ud;D~A;))5si&6?RH z>LbK4&$AGKg&Ka8_FPD~>$FRIR1QvVdkxKL1DshcZTYS_P-Gy$qj5Ci5~?&Qmatit z`Vb^)3QdGv*iSv=W)01-SEEm^@-lrSbS+*uof%H6r4(o|G&W$ZqgMT3a?DpO8j91< z!bw^m_0|l>7uIYU6J0iu>r;L0BmQza7(o|mb8~PX+^qMY+4NIuow8QN(1iDsgba#s z5^+1U%liGWwJuV#AZs!uF_aH@+z8$|Z#RwGBvV?m_;&x^JB*o4Hb=lyT9#UjAGT+g ziis2*KOL7ZxkO?xs52^$<;i{ds)we@@pZ44JFKQ=^6)F~brQOIXh6-$Xo(UeDqTBa zHw;I)u0nW?H?El`W3)9o1WX=U=xn(Dfn|S$Bu?9ZpoJkX+O7)lKMH`LJJq$>Xw+WK z6{QhNT{^}svU7OOo8M_d9=pb4JH2WpMz7IcEKTKAGBl&$G6gY2DlyETG}SKXxf>Wq zs1xZi5-q!p@&~+AprFKAK62mOK~i!tgY_-Y3>kHfdw+#IAr6j1k)p^YXx)XnkDA8N zS(uU6<7iJUe5M>30_p)M^E$8eZDBeEl3Y{KlPI=~rJmT_S=Zps=l!pYYy~Qo)&v-^IA=n_{WQeX-CzjwKIl_E{BEmr7=`{j^ISiGbGn*7=umy9)JP?|# zo}0knbuikQU4XI=M7R@-h%7nj_uW%5R-I92^4)*{D+NH*ktCuCdsq+=bT8PMA_ms01Ng(2iuDz zrGWCphUShyX!`x~p%8V*r1Ks)2&WGZ+N*W3WhBAwdmF;;1Eq`IHX{#hu1xL? zbsZXa_>5(=`-@W)n?6Ul{)8-%Jg*bRJ)oJHP*)E0Rex*<_0*eJ2bJaKhRf^;uW zPMBJM9xmr>53t93tL8&1_sOn>@i|#U|~~a8qW_>R~k|luSqbJJL;J9cy#@X0tgR)P%D~Nxn*i} zAvj$>eW3kkJ}I$(bll9)Jnxozmhb^zxDm+Up&ngoj|c`7oV~7Z(Fjx-;o~qPQ^pYc z(K9vT*KJxTxk9HyN<16wHF+bRQubng#vxV4 zHr@I_z2NAaN{eOs)b#O2kB&Uqb&?ltfO!7qy;Rx?uscptr@1UMtLm=aJ{ZYlS65?4 zmSDlA$OkfEC;}2`BEHX8Wu<*a=w zaMZ{ErD0UlvScD~?$?@>>6JQNWi^rY@^CUlm7h1>t8tK{ta}J&MW|t=e^O%LEA_h% zEuPzs3K%P;v7CtEx{7XVksrPSWOMZj%O}+T2y9YynDB8wvav#?&ElDq^{H&N|89+J zl7*nEe>R)Y!P}K>!9DfK0dJCBbFDJvm=#^QqWMYdfa(}S`4G<-u*uu2{GqCBnP{>8 zlfjX$O6G`Uu68LQmYvSK-I7UH%A1R!IGe9lve3cG%6`Jh+5x-;-9dbJi6IaY=7B6gr*M}eL0G=g4j}b`Gh{ZQ?=#%cKaGkG6!K_ z;%75*$F?K4AI4f(5%(bCu4{*>Ec8Og|Evo_jyL3BCopcY9~%*LpmXc*)ud8iMs-+mXMq5 zoc^jS+)A$%aAUI-x$PQwnvCIF>yFCt14I&Jqa%E=Y&{bdzr!b27BJ@HlZht*hqZf* z8!fK%Bp~{JyB#z7uG^CLkfHG~pz0A8?~K#JNPRb@H+ad3vpFN1q`6>os$Ccr4AU02 zGSfhytlg%H5`*{nt7W1KU1%vpU+eHAbhB)t(=I=LOm+GHW28t<%Wt4Bdssidv9yd% zeUWCG+7kNCKP~%qMW^XN1~9J@&&8guu7K4hOxLr#aXr=^&IMV~&C;G;+^>yFli+*M z)Y|c!X5BawAnT$?ZyX{?`ilv`j?@bU6ZuX2Ll)BH6u!-wbFFW87|*BeA0p&Sw^ zJIzR1Z1N^p%Jnv$nva8Eth|ZR#s!R5K`(T8Z6xlntwAI}Q`-RDQwrD{Zn<}cy!K8@ z^O;eQsd)<7xa;->(McSYBfu!hs#x!~TSr&`Y^rnbe7@ckT1p_IorxZJ zd4Rl@c7JqdATvmhi!9REK+W*3rdQ1~I>6|C8e} z_B}?7_hT-i5>IJ&_EbEJywN~1_e#J6_QRdU`4b!c+iUB6T@HAH0SbM72ML$i{t^rBIqclHGh9FO~wrs>i~VeClS{sIUu zh&!(>^B)tHI0XuJX1nA2wNx*<0Tw5}4}*lHv2vNkt(Ta6gf910^JpBO?`llEL>^2A zMVb4zeFs3n-~t0su#5^z=pCzkSVUlUboBSI5`xWAqEW6&dQgXM2q0sELXY;q7090o zV~y~SL(6hmhvNWKzNlUtrmPg!on5~e9tbuBQ2v2NXyiO)y&KN6@#`pMCG^%+Mg;Ar zOO)OpoNrI^8=l2v+xhITMW;C3=XRk{rH5889+84t6=0$Mty#oqcI)jGOBnZ&mrYbP z2TdRzg)zWMuo*ml7RY#-HUzj(Z=ZjHjQ4nte@2W`7G-DLY_pmd`Wn5I8SdD%?4%*kztFyV6Y0xteqt0=NZf$ft18s*2T~++lR~EkR7f1eT#Bk z<3CV=YmJd>CNWeaV+D^Uq~gQZ`r$Gfwmc6H5{Ud;ur)MR3?pt1T75>Rvo>^+L$5Q4 z-#4*-d~(HhjEBk6SN$dc=}yjD>2Sd;-X zJ~KMjSMA20M3KxCVCsR(I})(m9T?3Qs_bqE&}HObVvnGBK?XoXv7n-{{RfGyGa!bO z_u~W}9u`->6N8>?^tRA@%$btckivy?rnz=Bag=ADmBI3O6nxPKQ6nP;obdcf0Ssfq z1x>YNTZCXOTQpeceDuaQK+UmacV(vPCy<1&QyHX0!sXJ;M>84q`ac}W4ER{^s>(w2 zs4%U~wIK(&Z{K?_6~Fv4x@vaKbDgB1oQ@kDG^T;Y9io`rW`a2b_v=6JD< zb~DHnhB4OXYe!*8?M=^Yb%5S44a0oOvePyav$S0CwnG&0wP`gvrr)KUE{|sG>Vjf> zT>o#4?eXp)pkZV%{a+~xj;2$!^0Rs@L+fZ^YYqEDhAPVxt&_kj{-8~{M!I52_l8He zMnjEV@4q&^Kzc&_J0FHCGWK?S6F|1S^TpD*3(;t>q7p=#JZU%g8n}!UO8TXMHF}2^ z;LI|Bvmd@`6K^qCVb}9L$~mQ7izW3q$O@xj2@gk=NfeuR4TWrt6u*Dkyl&X5{}lm! zgsKM}GP(*jGJ1<|EXJngKgIq~5hxY~2rFcLj$bJEq5mN&4%T6F{S`k6iyLLi^b7$D zvxbyzY_?LP+TYM?h9@W-#Z?5rr-I zQ5})%WKi$qxib-A!I;HYSL=TH2r4ku9@pVW6oOL`XE6~Av-}mxzWsf6{#$WXly?jw zSOcS=1dFVX9DiZ^_37E};MD&3dwO@BVzX_kFy?4-oL|)%Ektz5agm z;_LjxcE(*k<-Q#0hthx)yX`&wI2}BAf+(`OD`D^cS?~JaY4ySbiG|CE z!1j;Y%#ha;p z$BH`H=t+r)e*-)Vby}d}02nMF-1TVmV1b7_pM=C=!m%L(#0YWln`lgor5jDmbn>3e z8uMp>T6wlaWF~XxD|JutTFJ!4YBF_w%tQzql6O&j!6zG4C1xlIH4`CTq#^+K!aPOR zZOS@bvwC}`&!FS@}6LNnfl<;K6Ai+X4-6;)gOIJ~Gle(lQj)PD! zzNXwnN&;dU+=xZv42Ycj4{;zHbyOv=p8d zs`9mU%eG)iJgM^$oExO0A6b_K}u~s+MJk;I$o)sX%_t^@ovxhI%X23RN4S?c;U&Jj-6Wu)WL_{5CgpB&emv66_5}|$URp8 zavF&Ca+ek6+{mXKJYdA5z?&T42@WKs&^bZ%12vxheI_yF@d@*qAJ8F}InnsVD4Q&$ zUNv4k2-e!@^Q=B&1FfiC!mo{%SR;xJxYk`(yo@;vQ2--ME|qNGNOn?75I7+#gUm6i zJzk|Np%h9uL7#duD_`kATinR2B=D2YZI$_;Wm$*zAG95E-zjeL9^ddNa~74WS;wPT z(nFT1G9~M)L~{@Go*{R|Lu}8?jrj{6FG7EZN^V|^z*v$)X~}Y7qo|@nH%`iob)L3j;%gWw{~#k}BJN zX|E#+ed0JdNPu;v(Yjl9)*Tgv+0;$H;88B;z|v$P0)0F#+Ndm|U9P!1?a~cyk(wY} z+u%AKTb@$$M=N{$M7UY>tma#V!i#RuPWq27<#A4QeY6 z_UMkZ{n@E)oaoBJ`VHd1ac*AQ?uoEZUrrsuJ&fVEtSs)H(f75xK^0&Z3T*xWOOe$j z9Z|M|bvW4ib1P<$AH5Dca#1yt_05ETvNtKCs z#`4cw4xt$G`Ky?-hbu#@B+!czdjpSWNs>5l1(6{Su}J=qXw1z&p zh}lckuBQ40?ur}?0&mF{B#QZS%T=}DMZU@93x?j#zSY@>Pv|0wNY55NEHoa32jjVA1a^m zfI6=DB92rHqgGZFQ6goV>8s4>6Y1dYuN5wN@D0V^5Eogd=@(j*6|>Ky+uxU7z3)}u zy_Iv+)r6sA{F#cq()`XFG|Z}~fr=&a!k`{OdTWT?W?Oiu0Bm%TvF)gqG&EjqPcXp# zNUTU?VvNobzF(3~NWmoSldQ1(RdhWF>jFt37DNuX@-;xZ#0A^F7aY+!->qv?YRpZ%^#RCqt!10G4(nD zc9MPREypM$?JUj;{{#xP@V{OFC@t4cWZn$O6EK+bPlyOUM9`+LGSN0ltYZ2mF$OUt z)Z&l4pWMYW`*Bwy)LRWq)#8Sd~$ z_>{bAC2bb5AGV25H2>ow4LavBF&swSkeRg8O4JNFfu``bxS$X+a6F@S5;VI!-1 zpBtfiN$;Q#dmzPl_8LQJdBrMcrEs!PG!4K#CQP_C;~2<~AB)h<2a^3Lcv1svvRJ%` zqF_~ardb&(UzYKT4+`B|S-j#l#&uCvLs+SBUBN$9?gJ^m8M#Iu4fO}5>N&;vK#XJW zK4iHy-Fni4Phs=E`j^ousX3F`O<+K^wcTQETlyoTW2wODBB&zql9styYZk{H?;dI?5^z0QQ=XSr=OhToeSy7mvG0fk04 zFGxMEa=}9{Qi0BJ@rVON%f|UVI*Pv@L{HC0D_FeH*DqbwemmORb~!?WTniurB6(v7 z9iaiCZ0BZI$SAk3U%t_xFU8mO%5hQuM6qfj1;!#iRh5gSF?zqyh2e?JLFr*?f=3qM zwtF3h`k>h^Us0G)z)DZRHlhZu&$hr@(EzXvtJ`8z-(*^XQ-Pk^f-lR+{QcE8_kF!f zQ$4*MS^^U-JAGLmmJkVllGi}LaISAHi zFR3=VX4sLkxT6+25$#Khkl*P08E$~7?ud@Tj;Dvwo<||9&^3LQec0c~YB6;ZOfeu) zM}mlClk@7}GtK=bH>BYyj?gmaxGXZD|G^Eht+^HA>E9Xv@HLp2spkj%&3ZEoVP@4n zVxInEXNxyNjSTaV1QJ2y4kv~MS2Fhmnks%pNQk5Jl@Vn~y&&cQi#wrNrjSjhl)<|0 z71067~R*bSQjBd&AYyq`KW$*V>r5V38=3;3#ZT z%$N;1-DF&48DlD94$uwS=IQ!aYYQ%4KxV=iMCL}g%Umt=+H6eK}|BlfAT4!o0oYrtYGsp z8LVdC(YpX}>_*Z@9UmMV+}!c*Q-dZ+RQD}XJ0B476r78t2U8>YXUOcy{w5i_sf#I^ z2kG?6ETTs=jVx`G-ZqySK!hahRcd_ugcxKfN`@P!^Tu_)-$;h%Qt?aI!`{=X?rOu4 z`E;L{6|ZX1HY$&)^UJoyAwMg&O6fOoE4C5y-kLdMP&68 zz0~+1%46lOl~B82kRm$5FUaucmzdwNZXZ0K0TG%zp0VI*H`H~1};jE@5l&zA5i{7*5 zh=q-*#HH)ehH$JhjZ=DTR2j#})R?z*nMTwRchH!2-w@(DWB}ljR_0s)zs@uEvfoLU z%yUO$GqHe#70*REhE(^>8-Dlz<+aa?ZTj&aNZEsBDQG30fuHj~tqtW622pB0BbjnE z1iJlc30}Pe8c-npvEX25NyU+(JPz>Erb^DB1L~$6(z!H00E8b%76mokY38NOcENb; za8Y(Gh!^j9V#Qkkg>D}W)2f@}ZkuUFvKn7@(toPoLTpy0a|8iT9}Xy$n%m*s`{ zBjAbSr@#3!CWTsmty6d(Sz0}I`YkIU@fqR2P$z&oT9aUKgXYI81 zbUaFe`0CQ0-p6k?IFNk<5(H@D&1h#&+8_ga-RN587ek?b?HUj8){tO#21T}A`;0EE zGq;WQ>OSXSz?^)T%iZee_53qH`qwchKtJh<`ZMKlft}Z0Uc9qf+UP8KZpKBz6c4p5 zp!S0p+5A-5906XG2YFek8jIkmav5Ev#i#!KgyGvjgku{dSVNt(k*zWaIKRqa_a;f0%MKzNC(fF-s%(*RgKl)bIUQY7VKGA8s~E7OBaKN zT{`l|nbs8@1X^fb{j_YNGb_z<0KknluZ(b^F3q0+_%K&3ei;9nv3^jz6pWqBj%WniFvCm+Pd*>i9`8|S!9O#@FG7^a`3cL_Z<|%1zR>L210Y0?y^h_7^D|it1 z+O}u^LFuq6=?C-G*fNx`!Kt{blpw9TKDrk(Fyf|k+`3y|-wTT#){LS)%QG%cJ_Ip~ zH{pB0>DMb)-~0IL?{73P%UkRtT#1`xtO8G-v4Nc5huM8EqkUg}-zQu`5a~`y#3$gn z9ITiS@_vb-vCvumQa@hgBg69SW;gc}!KB$e*Q6wZ{qW-VI8v~uAcY8leOKf{2 z%oZPXKu-)*3mF_5qTn`mT3g@gcfkLrQ6U6?n6%Hr2|-@UHPeq&Qz>msc|>TO0lT{6 zl2k1M4+DQ@Lv^h%!lc4`AnbF6FlcSp*&mKD^LI5LgDvxEfVeq6<-dLH{5TEOxrqYQ zfk`N$cWeZ6J{qB_Ai^ADRNCnp1xX$vUhqkSj(_9!1y1TEFLKK*G}L>t1CHdaw(2(m zmPM#5%ap5F>w_7XSFn|u$3WlJI?1V^Yg1(f+B@F$hrm<1ve9mye*iF;Th8h&-+CaYHO}S` zApx+11~4FWYej)DwIKSP^p7Tt-wbGO&+ zyKdbvu3W7`1`Bju$^lYPTI-VLl3_((1Ot2cDv&PaUlSfWyq4!bwp&Twl~;9WF$KB~ z#J#_+a3d?f%s?_O`#B)nF5)Y3q5DlwPFP-Iy8-o-^RNT5;wA*0D<>Gyb2N%g^+~8g z?GxjobKPk`VS-Sj@7YJ8uUB=Cywm6}!6o?!#~FgQ7p??d#wC`^#+>fQNc)BZBh5}7 zT@QZ3$+lr$9gYttxVO0Tj6^U|nHX=}@&5z3Ku5m~2Mi(TQP=TgYRjxlPyv+X$Ywn6 z8)4Tv^X4oaDpEw9ap|RiEdWG87b99x)Jd6j;)7^4v~Hq;Huv0h+!o%tu81f>B7ZsBFyH`nL2r1UCY0D1|2p?1jtd?E@g?nWeVPewgsHs6Z~QF5@6yLL2><8V+6 zhzlmC;ixgooxALmK;?cn9f3|I!}g4OlV{O7wa$hkTgQ9>m|{mDcw`(@L?m3uQ}7Pb zv4e)0kzkIvgOd->F~6E#Pcpu==~sO;)lOswDD3DyP*kW)&}c6_y;S>>j6yh&EVB&) zGBsh$uHu8pG0g->f=2@Q-mG&n0vjd*3l6hJP>DV3F)Wy);g-Eih=j;UEToWuGa)D2 z3nvsdG=QuF6C0^BkwOoU?zJx0w8Vk#W=Wo-08sc1(>);aWEfI_T$(tWCOmW85}6~3 z1CoIL4}bgHU;XB%U;Dmqt#^4S-le=PPY5+h7@~ zAXZ)&WZdzSZhFn5JfHBP$id$9D%b9b7?>~Ni^+2_(X?aS5h5E*dmo@M_A8QP-T{&9 zptxhXPS%qU>_Bjk5A`b^CE|-^aOo z@3mG{jXB25hgnst*4q1AIgYwf?md&kK5N&in(tb>=5PJSf6l&OVY2b6l>}zLDmxxB zo3u*@0oPjVL{noOz<|TXd9~GA5`bJ<0NFYKo;LtWPOFXuv;`)OPaTW-!NCBG?d{SD z7B2x%+yfYB1i-upVAKE*^q5se^A44>mlF*0Mt&BmLso;?I;!B{NOf2N9=By)h}P{d z+e4qs&xe&wtj*CTN4DSq67~Q_v;ZPT%(hmuD9n~&<*A5+!meO4ARDLJVyXGsm(8Xv z3nOM_+?smSLVeP69R_-3QiCOvdLScVUi)ilaG0Vp=Q{sa=YRbv8342aj+VgGPNKGW z&H!S|0CFDya8o-9!1Q%_-~fP!_y1Rgn8tcpu1}^~hj6nKZOonZ{A!d>1S#PT%sN`j zoPeHn^dF9{Iw=UNcQK=olPaBDxUSX7iA((59p9+cuVsC~Q}VpiPbWpJ>tB~xSdh(% zq^!Nt0}ujixsc!tTU1d6AtR31>~Y@vnU&-ofe_%;ItrnLG7&2#ZNgsAGjfD39BTgO zbInesG8Y^r#d zYMqWtxpUy8sq;KuORG-De+2{&e>9J0)>=FmaL{UnlbLgW3aenTRUM|#+p_$9Sf=eg zJaXM}@B5TeeFO^2s(!Hwsx)U}NkqlwXRw06RLp6jPQlzMaK2R_1G$F7i3V z5-TO$A>?qTB)}xtsmFB~vl)KxznpYfIWu$k-v4gj_c6v|4hqFf05Dr_Epogv`+OZu z{MkEyiu#;Uoz2@~0)W?1a1P928o}{Pf7w3sYdml0SIJK8lM3CK**pU%=3p*f`h8!0 zzL=S21=FIHQ`La5@An~uuG=hXEMLV2*4WH(7|m_1%)$x`VWw%C)v~2F@oHOx<%D%W z;`-ongDkvnnVidM5~F?X*X+Ze3DUS5bKQ^~VP0%hAGDmULaU|Q7xFmGbCEKW$3<4= ztNCp1GSl9g?J{=!0f<0M-3tyS*$XF-x;jgM-}c^$J~6z+Nf}N|<^l+i$%F9T5GB2< zNQrgO4YlmL5gI)K2IDB$y0@kgDUfAB?nzvOcQ>k=mcS@bXMoAT=>4+mdXX26j9eJ# z6~I;%WKG)^49Rc{$S}nAT&Vp{vF8Rn>FCzA2^{gNx0@$@- z*)odp!-T!d2XfIR-O(Hi!jiVFZV@F0qD`{XM8C;`caN7VPAm~PAW4ed7E=6ds zi13Zz)>8S+AN$%TzwpsdeBo8r02$ngz{YUPWUXNT8$bTqCw{*C;AgkL`8U4usbAP( zHzdh|=KDX_ed))){N2C!vXJ*)6eiRFV1PLhXMkZWyaj{|12%-gkN{8Z&kdWZwkS_?l8-yt7KL2x*F&(ishQs%%T4ixNU;eNDOUl(x~TAh@> zaFhGbInE^9eZ9b)yX~5*eR9>kX^lD74CM&wom6aP=d=(REV`|L62Jg58bc%)!2_(i zXgSyr$Fk||felx#n~)QH9=j62R(K4Y!6WgYu@~M-7!tN~t9{k>b(M~~cZxuqE_rII z0fq(a2o5gba_GQAZmS*&3nwav(O($W!B1wzgUT^KU7}f!ChgN;&bR_mai zTb+KwPgiX`=*!9kwrI`T?xcGO+f!OG%dnn$QbBc6S_?ql$7x!+GZmYyugr>j-Po?u zl;R$y{Q&`h0~t@UtV*4xcSEQes4|O~76jmCb;TY<7MG=E0l$`FRpzzCPt~hxq$B`l zZf6p=_}MSHl{o~@fF{Z$)T%j{tq~Xz4a4Z}Uc8BunCn1rX23LzI_g-rBeX!$$U?`K z4lJd(S=LM;u*Ay0%3`17j;bRIK~(`%R1t`3t-?xXmE8g8s6>HlP#%$vqcjb#Ka692J*o5Db2cxYHK&xC)RcMXLBY&8OuR|6iU@^ipcf6) z6!IA(Pdvy=L0swn7A6%!VCEY6SSM0_&u1U5g{4X(969G)yns$`_A*B`7WXk{GpnZf z3xSO>=A6UgRS#4t83iIHiX2Jyul*{$`j_hFhRcqeHJN+WVNGJIc_xH8P%)b?ux$GB zxyt<(n|#2Qkj5pdedVlgAApZ9CU?Go??kXe5jP$F$naI)eVDrrvRB?D6U7q<1lJ06 zV&=pMJ8h)h@A?P;Y@pE@){hW!El{E~s(|`4=ioZR&ZK=po$x!Cq{{NH$_70vTEev? zQ+vp8R~2^C!f;0e1te<^$c{WgQgEZ+ z&ft5)00^rCwH%@RkL;;Xr@A|j&O@r^+O+zZuz5)Y-;SMmH z7+SHd>(^DU6_45!)RQEE6UivXst#0i1=Vk`DZ1x&e$lcE+0HG2936P?7}PLm(*BQ# zA9MF6^a^6uKauwGpa1x4pZdZ_KlO!=s&7cYY2xBhbWgU$eq?+5W>?ya=KKHd)^3HM zpZsk8jlXsE>3{UZ5o~bU`SnLzBsKz-{;Vo38tvopr4nf?6X$!r&05 z0Zf7o&Of4QZ^H)IFgs&(lN~~$Cot|kvF5gWDBcYHtB$v!kBM(5O@Xu9hd_H5Kn?!3 z>N}=`q~!A9^3>F0}yzO`25K1a9aJ%J;rhg-X_g%+|GvcITW*Y{` z#eHv3kpwirjilRNHv%{kY-oAx)jNr*Fene_M#k#EMoCHb>gOc4&_P5Aq>B1MFL=Ue zcKTRwJ^9;w3(~iPYE2rbx)B=>0Ia?)w7gp;1KhctxdBk5KRFF6N2F@}G;NzWJwMk6 zuWFS=074uN@7Bx@qOfv!3#-fLl>>mn5t!sK)l$wqE=5mHVO35Qs>-p&+8wM!08Uj0 zbOwNFSc;o!7&2y~u3AuDX}IbRiIeZDLRghy=Y^^(R zmcPa2{I#w@k=CcJx8}6fVyx~{Io7=nOWotSJ`7bGvL5sNA4|6sH+|4Y&Gj$D8a>1hBYTy3?cuY4-nB!-T zk=AKCfi~ei1tAA!wER3KV<$9fZKSp4Aor$&cldqh+{2HKX~?}NA49hlYrAv7J^9?h zRlres2fMEI`zwqxonEG!tKzT{Pz>=lKWF2Eqx?%iA%qfw7mvjRg(f0YwLYPsgy69t zppbhk)*zu!h%{7iHUl!Ox;-2>f89Ap=K6P=T(9)Wx{J#yQg0sFyFE#FAll*ex=-fb z1CGxDu#TyGilf&0vQs#F2i6{m=8kD*xNpwi?S%E+v5+$MLgi?K(UZb47Svrpd}OpCb&H6-(^fY^J^#MO9RR8P?RuwWX}ZIEjGR$ReAn7Vpb`h}GoVOR3w~ zq0*3fQY>m0pKC5rN-VMV$&68!pOg92>H}+$bk%L|${Yp=U>wKDQGIMulU0d`OQ~>* zi715qzSpd!lt!9Z&D~4k7$^1I@B9@J8T!4Mw{4rv+^rO!wQs;dB3CL0BqG%@MzMeO zWB#%KA%w}&t`z8~1tsSkIdbHMDprFh3c-P_TD&moM=S4h6lBZ8Fi@Z< zk%$H$XDua-!`O%fqR7YwVyXbHhAvi}8WW+w%$i1`#41oy)ir4IIZCkrEHTc;>dSpx zR^#F;S<^HF7YsL9+wc-s7-L+f>vBgd;~PQ%5r^RB!!X1cCC0oGtd-gOtdx>91K98P zQQ~H^arY)Q!&kl-zT-z5iA!y(`<44NyTTIXT5asAFc1jg9&uS&?P6*3-4#Npc}|=w zgi5{(%y6>#s!hTUy8^laDQ$E+I> z?Wu=FK~zY>jT2lLPNWTZ1hz;Q;u*N|T`NMajeAarDkKbGBQmNBhAkl)TR_K?0>iP#izxnj9Je1uN>2iPbI`X!?{1Ap>_O^TM`{vhw=DCmk{jU-N zu`u3Ld&Iqc>gRU9{$G9gQ~&TaPN~!Urf(gWiT2`+qVZi%_=XND=^HNJlSE+*hU%3_ zW&%9=PC>8hJO75e@7QggPaWy7fpN=E)XoS5kh^*Q%1?jupZr4m*DsQ&1G{}c#B-I~ zonCB=nIKoc_`=^Z?bS!~2N%4BB#^TXNytI!l+GWt@<0vJL5CnV7&T^B;#-iqE2m5j z;5l!H&Kz){ZFgnHp*zI6WuGW>8T5 zbR*uo4}=6b;}UcQ`n}!l>n$hWTw=JiB#KewUAHI#@&YrxVc_ic_O~T{vwiSk^yhZj z?yj$eFa z7Er>OOF;q+&h!Mk4w9e_iP}B$)q0kmrDy3``nD(YN-dXV&Aoz`88RHL^QQxMKtjRF zQ>m;M=W`s-om!kwkNY%1M~BK{&@`Jdot$`t9*&XCp>@ld6EvBdeoUkOt*91`pv+OY zSvi7bizqD2Ssh7@$`t+?sy$PHkEPA~4~6UJ*Yyg)Q)Od;5zOc97v&f%%nT_+Uv1T2PCPaaX8H9T77 zuuOxn)M^da?tsx5p6vUY~5SUKOr4V;@1*X|r+A(9x^rcNBARk29@1S(}zt;9rP#JnXUfcm0FPAwkrVQp@`Xlj^| zGco&YMn03ZIb3bUAP)F|xgxFlqB5g}1puh!*2` zy*h7e4$?^FTs0W57RoWYSvFhVDqLa+O_iZx>Zmxgj}U@{;H5~EC^5{@i*+-^vf8MT zm{MrG6lsK)rn%?e`74r|n1Y!z$G*RS;%nF6`H(DGI5iY2*M)YX)Rh*)Bou~%STwo{bUAj}R~#rxm>&w!ms zQ?0cwA6&Y7U=pV2%rTaEGs-&g94I!+*#Kq^K#Vb~^1K^BSoSEG6?tWjX{8yBt))pm z@4s1Q`!Jhr*TdomzYo%~hdLk5P?Aj;L)FB%s zNxAn|I9*B-;GrqKJ3Rm3{2JJpor~-NCncuyE-@%jcPRo_{MJvr_9MUSI=tDQU(&@M zIzYOc+pkJ|%whol+D~77`m@)c{<+tC<)K%>6YrnruK#Dh{`(*Q_{*RA`3Jx8w_o|> zKln1q^SFJ7&ec5|ZGQi!-u~`ic%*79H=euHZW(G2GBDi&2~e{ukpw*Foguo&Ik01K z)idQNa&0cAlFm1v?*bqfl6>Ud4s7S=dmZvSH~##~f1Yhi2}xe~i9h(+U-_=T1J9sh z#^gc_IJv2!h&E1Q+81hFuyqKr5f~brSs0GgLj~+8%t7@+1VlSP1bahNhaedn zIhaP%hWl1qu{5@D)wK#DY;CD9}QF0LXfyXd9Q%oy%?)z)`@Uj?D+|0pr^wvImjc725!SEI1d&;2_nl z$eH>c(zksu9<>iFo`6ABh+yaky+|7~RYC{sYy(7aay&sNhDLU$%9}r}^o(jfOV84? z^ejC!)ooALky9%d@O7HwcTV*s>lnoY%qbHPs9@o+XIwdbRGrpPAz;nF?s=Y_56`d+ zvw#Sz^TR|~P7v5r+Fqu2r`%S`znXJdp{}E=rb3tMtgEo9$$@T32f-fZQh-6K# z5r7bi2h@NgE*66d$PTvS3&3##MVKSh{-c#B1@J`&RuzfSi&%*cLftyAIF`|05YBzQ zxAfKAx^c*w#*%~EtJptBh31&wIf@YVe2&es+In6 zK)jXuM2S^5xXiAA;9vdK z@XB8db5N>gTksra(zi43umC|0AQ;G5RzfAyxWZ|ZIZoomxc_GnUeuL zsBM5O>}Eo=bs4!Aw+04q11OR8+Au(7h8C)54W2}^$zIIK#UYTrP%`U*R<$7zQ&k5i zb8#~_NMi6f2%sDINECs=(KrD(N7|}hIFiUP_*F;OjA%TvHXwF$A`xt1XChm%!A+H2 zK(0bIh?p9=CSn6WHf*2+frvCz+T#|4kVJ*%`GMD9b1vd zraQg}yz-d?L}=a*n;Kbi#Y&VknnS6}>_4}a(vZW+1v2;Bp4Y^dA1 zj^_`oI}Z%{pk1a%O(F|mUTW7UX329THvk(!euGWGzN!~x?0=8ovzfY}tHfg}JV z*sC@!8^GZM$RQ9P%-o1rvf3HTpxOwJh6oUARNIIo?F$RUd*-azko2m|>DEZhlS9x7 zU<7s|SarF|u*ky_;oa5$*bbx2%z{}MDRoD^*Sd2>u>do2{0{?obr@=KM2P@2)TgKsfLH5QWXvIiOIbBOjY$D` z7ywui0O|>VPht}QbL?b|I?NpaA3Fe{KLbFMPkaCXop-CzxHPRU8mETW)p3nqtD_Jb zV2Y!xU1Y0DIwb(c0>I1K;(h780f0{%_vXVWAOP6n0f5mHfa9pc`p|u_)t`_0`pg;@ zYJRw6ZTUarfZE#yb7Wsx?L|-x^_lv^NTEJZPTgCr@oR>Y^G$7LZGJffIhvmabsD9U zBU2n}4N9FNOu@XvY@ArF2*7yzE&Evdvy|%XQ!U2VxBr~hN0znUU4*bY8fHeceE3ZC;s8O`g0Ll`TK!AsUP>Pi{3}<1tDeV9mrxR(u)h$jRL!oMOp0X4u0VTNfAXnZ3RQE~4;;R)- zy7ox0c7N+u%?U6}?(eZut))~<;xS(h(+cXX@~*X?+0PO93+2@K>@Y%;q-)*o6~e+4 z?1N17zkfB7$e?>oQqqaw19sTW^-o`_XPk;beah9Q0VuZ`dNg$cvOs9BRV zEO8BSrq^|$Hlw9wYr?tifr&I{p1YT0G_w#Y0;8NmO6mOk>^6HrS=+8JC^IaPcOevJ z&t|X?W0-YzwTqUWD8sUuW(XBa)vn_T#g+-VfSy@qRgW*=slurxX4cIoQ-v7UIh@=h z6+(p&7Kivcfho?;@iGb1qH z4*CM~woNanZ-E8|5Sh3Stz)Agai#9uAaDVgT#%FoS4jr24(^oN?L*6h`Wa|TzM=LS z1l3E%6PE}EPYW~#oRN?OuFeB!ASW0UjNS?7g1s9#9tpCyV2NM)@h^YkmtXkgKYm_S zU;Ewvbe^Y`>wm9)WNqPxFwQ7ZNrwqdr%Z(N9diU-8h8N zlSelOJB#V=jAiU?!_XvkkFP71LF8TNBazEjU&dG8cvCHko->9D1{9PmfExxeU`i}R z0`H5O2)l_Vai|X*4GHc-86Xh%Y>bf!U}xLuE&)N(jSgoH0+awZHy*@TEedBKSKnS1 z2JfL8z#&mmug-+MYG4WmpsgF*C4v*GExsutS#p56)&XEqJp+&ETZ43P2PMxAA=>VS zms=W)334gEGa8V_BzgC4i|(xp8G10#k`3Upli(nc5q*HWNf66wqJ4bOV1Y#HX*6DRV$L!4h%-7w$=lYKk5LPZbOJ%8%ynO5srdX}E0XX&Y_SOb(2 zJj}w9!=n4J>YrE43rSc`IlOUvE>8H@ys``jG!~ZQchONfuF9c83w&7PkmJ+BG5$EN z+Da_8kg~ckK4NeSQ+rCtTtx;NSN(Utr(E_JxOd@8`uo!Yx9nd7+ zS+p&49AafCbz?X)tI>idq@zZYjjDC}@haf4lAY>}wcJ8Jd)hDDXJI-MS-|8Ok2$Kb zEGn&8OvFTP#4@?X<`@4qdj)V&cs7UaAD9h)8fd8JXRR{hg7AX++v znK6?%FQs~X1`6@}|NHI#`J;WmAII^0{2TeX|5-%B97DPgu1SKlY=s$6b3-Y$Z{zGH zcJxU)tKN9t>{9C{k1KuO+E9N%RBKkXCXW@8)$Xkty)^~}P#eBT0#`QI9P7S^$G%u*UdJ?qPR4)^KQyzX4d;v1z4BG65)X@N_iJ0wlH^ATa-5V(h{E<93ck2dh1lL69`rl0LHx&L{$?DvJXUTsm*NME85hUf<*-k?7X9-q7cKN zHvk)~0XpD%utc_nWY?D4!8Eb&8KxLrp|*i5i>XB>+wD4$Y-VJ8r$iW8-3*Q=+>%;v z8e7CFcLHtL2TI$1ch(9KT0Ert$Q(;MtU}&i?$_Yd+PKJRanYBbW$|44Lmh9Lt*wiH{T!gnkG{fg! z{WT4Z+B zU4wQDxfHt=b08WvaAtlBb_I;)4O&B=$hW$?V!4IDb)y_quR4BPv4QWwZdJf#ox#}P z1bD;9ib(Q=Ex8nsvj-^Lg2=V|Mv(-2MTRoT6PTcHz})M`>0021GO#3tV}S6W&l}w+ z&KS4qv1e~_>qITz+zc-}y~z*8-MhqeOWpbHuzNroSacI=o%+GRLVH4TJl0`oJ2gPM zZ#XVR3wVGfXfJdQm~!0hhAy3xsS;p;?E#Q`N-Trz8VJP9A*#c-=tJY%qSYD`mhbed z;>j35$O)K*KlRMzvD^qisR|%gV0O8#e+VX_Onu6)h7NxCS&!78w)zgLO2ZDCl=Z{6 z0|--AB|HFq?*kiY~4N9XUb{@Umr{x07m1w2qFb0c~q4|trY?F@_98?o#1_W zJ%5kInAK8c5?f8H+-XT%pDpGkEP!0v<=rrO_8+FfbmmH?SCu<%2|!?7io?9nope~M z<&xP3^Uxm&3H=~~D zp<96q068lFY$O1>D*(#Mm?&@n5Yq?2u5_YWA^5CHS^<$GPI6f1hxKX8x%cJ0)?`h; zPW@bo*E|W|iyW;{+KRK?J^ctf+>_hE<7jdP3Q!6N1qD3skWzpWN?Adrz!5JBbAftt^QaX;ndT7?%`7NZFSI(6)J^M>Oh}VW#(@0!Q3WgRtTZY zKj&ZPa{`6%K|orV;^`)XaH0Uz;5*Dqddy4iGP}Yr(RscSQki=&s{*Tf`2+%TJ}Hlg z$jnP&W{GhrVqy(URH!1htU9W?IWYm)v@KSwXR(}Ls8Dc<)zGiA*(`+2!LKw%D- zo8kmRs1mB_(`}`+LYYOWYbj7YLV<|HB}#n!_z{4nk+YbBxicX~=tOYDiZ7jzh zRX&AT6H(T@{;XIBGfp!q8z?aIFbv`U{-5L{KMcSv6UQ=pW{JcKp(>%9MrTD)<17lx z+3GH$?xha#v|qtA^CzvMnOoMU-uCa8Bv9=y6vi$PRT?lnN(y%{RG0_(I=mCy_I@Vm z+Q95>FCw^bHPBvhu9Ub#dNK}*+NQLy;SrTWabH$ciKwGKQfyOsI`JjY;M_Q4{d(yCtv@>FFpFf z&%X+N!ccP}SHia6ZQDfjA?a_2U;RmZ=5tRf34;x88*?Zku|r1Kd1?nmgp#y7RbiA} z-=~WU!Pj>0KKRmq^Jw#56JHFDhomIxOfU{Y8F<1>PSj#+{Ta9;NMb;AZ!*l^Zw-h>;;%rf60-k$kD6>sxO+z39ky`>)ZU(g`~6`oB!W6J=1DEOV84?^ejC!O<~AnfZw4@E8u&0y`ZIK75yhFOs3`h@tVIJuisY; z;ckA1iXACs?qB?e12t$8RlXy*=O4CQG&>uGc>th?%XDy;cfI2!!-!nEsK;G_aauMa4A zSvfCs@o-*1soySy)dg!mu{(ug;#~(mSBH*JwOU74)^^f8`#8M+QgJ8ds=%@tA1tQY zlLEyZVcMf`EqFoI?8F$Dsj9sy8Oiy?nP@@=E9z9i0Wo9c&mD;7a8Q&|vYF*cW+gFV zHndt)KNCc*Nz*R10Iaj1oLkO|jWU!Rdbsd15Z5&4;axXFREJT{LTB_p| ztsOA?abX+73`4#w(;_#d0}xXuBIQRj(KZO&*VG9n_&R>HJ{p^l?_DJW}8 zuQiRTNG@y6mMaU3F)q0+=KvV`0YJ`~n5tWUS+U5f2dtNk!~8XBESTNO)`nuW67%;9 z!Oa6r#*u3=8WGhE4QeH+4wjdc((U$^U;9=6$PWiP?4mgDco3>d{4(XTPrY$GjVFzp z1*Z_q-RD+ghJdBOEpz-<*)9LsNeU#%?oq8t)-b!%-sxPR>H>4|GZ=#tCs!mw0;p9M z=bhZj?h4&NETU*>-=jghSKUiL3TFjGw(M*MNb49BXTVlu*RQltT$JMGEO*?KrTZIlSU z9TZRl-U3~U^sX1ogSh}=P!VEm1!qcT!=(weI5X&gGvPh)hUtko2pjDj4ug4{xo2pE z3<_%7TlJK%RgLhC!3ldE92i^&t09LBHaHlxQy{52@XvqZosa$U!%uwvVPa9+57-DZ z;O=<1;NNCKQrilUW&M#k6sf833h?m=X%ht?7l+NYn`Lbw^3y8ib*{CotWycG3xD0uutvh|e5*uqrZq zhyD%CTj(XrV`|R_7a%JOyAaf|A?)>?Hyi@}15E+xIgwWeY?8TFgDpEVT(R}cW%rIH z`qyyu=@ke7H)UdjN5IJiGy<#^gj6Ni?gH(*Li?U#i_sh=i8Up;cFyX|*s14^BFT-R zNpk+q8(%+9o!Lg(*A*E?lY5R%@bGbQW+a?6y!l1+B3 zFQ~nx*eD_)DGy?B2P_RO<2CFlp$H{E_QRuI3R10H{6GKMMd)wF33wuYQY205E^q zIQ84)gV11hm0H_cG3}RHRR^>h#Z&cY)i11g1EBB#tlZ6N@`F#-q`a84O9$(#zk%Oyjkh42KeH>0$A) zo(6ipN6O*C`g@f|uGfV1F3<=d=uthtzJPJGLf zd$smnrS~?K0#>^U9{qQsmO30M_m}dN5*LT^^^y0k*fBvXcPg+xs{({_H?MHd!2@k5 zM|BQs0yK%jR^(&p-ect(9Z*+cI3Wv0IR-do$?{HJ?ngiYrG5;SF*z&ZFtMk=m_X8E zXkJb(yo&-?4PRA!b;S%a%P9q0_s84`Yfu^{>UV%qf3mOoNqyH9IH}mtfw1tc!&~KNn&WKJ6y|_L%sgO1R4W^AX0DpAnk^9_gc|xc$#8NeqPpy^>Yn;* zb&Id3g;LyX;a`zCZaB=ISrxS`q^Yu!oU`U!d@{X?BE@|w3&2cj`e7*Mnsb%CAcW}w zVs)D4Tv=)RvZ;a+ zW2}1))PXj4r-?bLs+o`D80MWRmtiuq#S?8IgX1v97#AeBbaI_4(nu{jTh5k=>0rKA zYtCH7am+l9gL`!%)k(I95@Pn03N`SMA!zR9Syo` z2XqNfoU|WI&To9UAPO#9)eG`5nS!^jEu|+moDrhQUUY-B=QQ+w=E?#UjM}Mq;@z2x zDpUaPop45;fsIolfZ3t&l(D-=v{#2jj~}5^%=!b=F5N znFZ)a3~xcVz?sQL(uM0rhdl|A1|wl|;=yjd={nf(n$xAo3&z*v8^Wzg7E^~Xjk~^W zl~r!V-x+$r?pD*|PBwrGm}qqGdX1gjvWoJRV9)wCpq5^NQ?>3Qaz_*qw-yXm6WW?? z-6FTy!D5{fi4O{b?Uk|*0f4}u?f^qsK-v&x0E6;B{hPNx^2_aKKKnH_R*VuOJD`yx zK}tUmbYnVx{p(+S{`oU$H@btRB$m620J-eCapw=ZZbv(F58wZD+u!+_v-a-?1@?oo zTz2vV7!?n85C%a;40{8^vpG}~)870HG#WKfz?D)4Tr~>D!7qtS$N?lY12^CEecyHS z&Nu%2_gp=ExO)<%&Sy zJuE?8(!eexdo}O~?QYQDCHtnNt5%*@JV&}yfZOZ}8!o7O8+u{brU8Sz&S-l_%e`7F=1O}e za)WY9a6(oz?jSVoi9ipY|H$oIuL;1?!9|n9&J!0W^jes&2m{jFIy`Rs!Nl3oGl_2< z-EMaVxX3x{9?(|LdR#LnF^6RMzyw$V`Hfz;l7#Ym-TD6?(lf2rv-B)IOV85N(-gVv zs39T8fN3)7IW^eAYN>rMLYi>X{XFA{HvEZb?5@B2l+}Gl-!lvlYkW2n^L0aT3K{Or z<-J%z&GJCZkH1z}DzN5eciUg)7`hUQac~Yf28}cPxv$3-I=qD69d&$|a$UZn$W5tV zU@RCbIKpgOcHH4B47DJZ^;agRExgkocUc&Yc--+-ceGk}t_>$g))K(wJDC5ME232$ z*8O|f5A>c}05i!t@VkGjQfoBm6xB|c{>?X9!P*_`|6%X#Vr|*7`>y{SqejhIwb$O~ z<9>B_ZoA#>*ljluWFj0(Ek_VxFdzitDG?@;)hHql76Kumpd!>q5h_dcf^nYPlm&+OK|>(r`M z^K*U7U;W2_++A#UMq*3GLiyh`pSkQEKj|d{o}B{aoT*}DWX~u7B71f(Fk>;*3L%W+ zNV8`K*NyC zCh#Xxg+P7ZGc$8l1VQs@LkNMnQXQEqvyqvY<7%i+>~3`(PXXpuQ8kQ12th;&>&Y7z ztwqkp%*W#~N^RMTBx(&sEJGIpfMFQSEQ})&RZ?B-FBYy;mRS)1TFxmYcW>L)d2*&l z&Z``(_;Sxao-v=~Ms zrY6QfA$vBrYP0>B26;X?XPB9)mf%o!<{6DG@ua1$G6F*ymLYALrhoU>@P(fOz&Udz zi?%KV%mOZ~U~x{A34pj-0!tUPTGnO=(+I1MQrBBF`3Wv;mAQgX2BP*kd4_>-Bzw$h zKrh~WL@rQPR6@a#O&O>O(hA(zL;yI8aPchyz?5pD5%HEeLQS=mwr9RIFffvVu?KZ< zrY;&gYjjo^Npo=9xt!o=ny20ElUA-(g81N|wmGR*k*-)1r~ypnb?^>Idx_AU>j{1o zfIv<+@J7ULwc_SV@cS;W0dGmma8hzhJJG200idkHe(L3v4!w3?Z#ii7g_h}%iidja z6@pVks^$#U?mazxZ2C=p@_BSOv58PIv0krQ`N;ajaOSm$wWZ*i*NsX{o((C^)Y@%{qumqVf4)U8e-}V^$>YN@xb(k z2^>#*lS}#th{jRSL1C zcvK@1Kcr7ZdG3IL(3{YeUA-=cE5nVC3C#&OfJSzLRYW%uAxe(kOw~TX^R8=HXixT< zFyM6r++mRD$4*+;2r;oy4_}wKCtM`XS67d2Zo1uG0cz+v$`wr29TeZSfBU>0^2 zL_6i62>`MwFnMp~t(wU3oj_v0Ue9wu2Efq*$Ql8V^qV%104%TRBg=-fD6^mq0H0y9`ig97ax_~9%~_Wb_A(=-7eysk@@Z}=%4eB6XP>Oix|+STuv~T$>rE3{Y^{pl znPYiJ6d@HkFuA!+lRlqzHlAgO#*G$z>!MXITdFG;FKza9jpd9mP-d3CsLLPneqa*3K?7e|L{fbwCE1l zDr2ABa`ykPEBU*!P@oBHc^*|Kok$2(`R$SOL_~;e94DPl2q>|23;J6=;c}*m^Xybz zQpIsq1q#_b=S&6Jn1>Q77{VHaNVJT3d0eztvsOJ9TlxSXgi=K)`W7MtxK3nbt1Vgr z&0<|Ip@^jvd#SBC7XYb+m`cFo;w`m=F8b^N56{H3t9MmZg?SM#ADuMg1|3JA1VL03 zSTwf~8yU{1<1h^F&J|Z)Wt!DbrN4og1CWWt-G`z3+Sh*Xi(mY~$%&k)Ov+ntyugR^g_(G6!%^#4XXGM!Dt#~GR-mNmSVI4#7AYUSbD--T_xD0=tayHL zn0puKTqRdV#+F2rb3orDA*6u$f`O^zLyS_dX(Bv>Lm7~X6M05JQEUa8x(uL>HD;Iv zz|F(_`$q=_a5x^AxY;#T#ZpWETfZuw`$-llEioGxN3CtHfMTAN0UZXeq+|nFI$Kf= zgc7+6nEArC^0)dZ{e%=JCx$85-CS;;Cq5Ad$Tg%@tK8m*aF@QNtZHTzBEW&|R{KW% ziv0#)!j26JBNJ+bRFrR^m#Q6?#C;MyRb6q7jGZseAUtpZ~z|guOP8Qjpd!Ucoz|3y?d; zW~aT^&u@mm`@jBg|J+Z0*)HPAB62^e*eD$@XlNRj>{v(j%9@I z7!{i2WZHokj*6Pk#paZ-V^hJ6LSQ856fPjZnFCbK_JBgJ3?R7B`w%nRv5!_FwhR!M z0vZM6Zs3OOg9uTtNlwWwqTB+oroZhk8z*l+D{^GA-gj<@s3UpeQHeQKsx{=u(yIOd z;$|?3)DHflmpQ z-kQi>;w|iv;>7466F;|s+2 z|GT`>YP~A2%B%9Kytr76kdb|okZdVP4wHWm7DjMKsB#|(ZJ%FK9W3Z%^TMS(5dHTs zDVkZr!@OfYBcC04;Po>kKVxcnQ{|oZ{Ndr|OR?QVNw&6PVLFmSFu_=1tn$bc&$`$B zaAuFbF+wg^&P%e0`Q=1Vf!2WyWK(s)^OF4|ya*~y9Ov$Ip22;bjpTgFgNfQ-5?dIS z*}3zQyH~zbX~<^{xW|Cj>)omPp5W{3^uv+jdiV8tmOv{ArvuJVP`guTf9|b&4yu+sw#G1CE4NvKFT=~!jz_PrYDQ$sEkJGLbGeO z16Upez&4?LW+qjoSu3e0!4xKYej=g}ux68_K%wF)#<(z)`Qn*~mjE|att$D_mwp78 zL{j6ZL^KQob7eLZY0@-Sp&&$<6~m@!LSu}_!;vd?^SY_cEFch3-Z<`;D|pUaF@UCN z5KzgK=CX9eC%<`w5TurJ!2qyK8;8{~Ed-iP=wpm)JmVa*IfbTDfM*Y0*vvwvw#&6l zjLmRo%2qjt6PC49M&4$6wS-vC!?L;N9Qau%)!9??1KY?69gdu{IZ=pp3_ua$Wpiv^ zUP)Ez9d#_gE0hq(aU`jw5;q^d_P6o5e-S_imiO+FU`eu7I+BK%&WD2GbTNItOcJ>s`OExJobOZ3dOQtUw|Vz`aK71P*J zMP1@%RBIv=;C*9_9?_1bnlDDpGY( zbBF^LAf!-cb3m*CtJ100*QL2h8ly3ooKorpa$?y-4fG+)PPK0mV*e zOcvNqhLNaC%EE7eu6Zwn$0|qh8wf}N5fTUnGI0(pPa=N|eyiDkityU6f9306{-vv* z_$5Jq07V;+^y=R;?qo{h{F#5{=fC#{+GY}XO$W_)GKY@;10ZR z9Ty@`1fyF89+Ye7g(e}og)_IGdenxW{;gm6>i7KzEU*3f-};Z1HTEk%^p_lgM7^KP zWa!ZwhR2ZxPc_lWu>(fZC^EWM1{JvS1(|`}p|B|KCEuAKIwjQ%5wX6JtOoTbgj?eX z4NTeKXra9TVy4VcxG2;f3m=pTRtW|Lga@dC2$owux`?;}0*}Cnd`C{;mK5KKqN!TK*sORjb^c}Irw%^-?T-#j`Z|tjRwNg6U8)<8@*2ZXTvj9r6&Z1TdQz}UUfT5(wtkyP9zF@;TTmW#fR#b#wlSdmb6$RZGVEHzm zW?mncyRhX5uhKAJSs>-$MhI4>c(cLGC4J{)&K1_Gi;wQ_ z#>p}Ok^mqK05JC71DnF~E)FFC4LSIE2wMnS&B)3NUd)~rLR3zfw{zb{Y~cLV8ooE@ ztGfT=b}<&d>#TJjv~844=dC?wWXl=fs-0W>@iLqIv*w=TwzK+I7r&+6#eXmdI0vhO zvXAtDRu?E?i4SSw=F87vg*hNlM#zCOw89v39>B9KDCFrPWijBKl&x~4Gqh4Zg~C~P z&U?4TD)T1qn?etm1P&^RKeQ zFPzKW7iaoBdw5ST3883<%9$nbt*CyA2mGStG54^s@hVkpQCDF!O9Q9DoQ?JYRLmiS zx~>-iQ8_c#^<<$H0);TB647qAn>><2@SGQ?C;F%U`|X zRkeh9mSI_lWZ0O&6|4C5HiqXMGV+{bk&3GJZiWP8gvDKpLTsYDXV0OWkTWt22EcR- zG_{AsU|u`CI<`*8l5VEkO89ZqDqh>*wvmAo(Ub@n=nfcKu0SF!AOr_v zN4S6vvTvccW*3B>C23c&jDPPxeC@~HdE@VV!br z8|21tNP=I&OnoHu#82IBq2}HIqcjork)@~>|BwIu|NhdS`jUZ}Ul(;(+siHVP3%us ze{J{CU&d#D;Szi_y+|D2{R_YGGk@Vv^H-xgAftewB+XOD6;LSz48f_h$HGS^5QI2@ zM^L5uHUMtk5K8B(tR*-U;PJot;r~P(q|r%}UbOP83^!?|zGLfM+?~KdXjG`;G3)@4 zVl)?_lq3;A9N03+V2EZl;W^mdc92mOO@yffN5W1Wj#2%>C@~dc5#be6QWvudOmJsF z4Qy!pb|JgPtu1&JL-qmygA%@@*#3ISblbc3sti?&O zCpx)Z0NEJq-l1zRYgZvMAgX?+l3l#gYP~A2%B%9Kytou(OpcI4pcO-G9kuSG?YoZe zTONe@Ec9G?6H<}FcXb! zKpbXe(9*C4e}qlBbCC>;<7jgzoNa_)#Zt=i`i9JN8os)&m#UY3m1YnHvq_+II2_AR zn~f#*kSIKU{0M;ASvttTVbrnAcrnsiroQON@(Uc|x3hp5T4nbzU%d3Q{L|bqr z+jU9^kVC+zTCy4XW~tA2wLJg;AOJ~3K~xl{t>WMoLKsKO*}1CLH^|0`>=Rs~oK&yG zZ$RKy44+aMo5LrN{qqBPBrSG zH*)Xf(LlH&=~Y?8k~KhW^gii@;nep#fjWpQiR`W8ditm+FdR%^%zgU3+>RCdAJSmyCQV&u$NoFZZ{v{e1m< zKl|Yqf8o;}<=wCR#*e)7#eevf-++LUy9MFo0@d2BiY$Utxpg1;$eIB%QBbAYGTngj z#$Wy8^tWIhf8~e%b4Kd*qLHJCp|6}7sMHO_iAWfPV~2|0_$N_rQ%>6pWxK zegb>aR;d?vWs)RJfQ&{4CxSAZ;I4b12M@pwT?HnP!>y6tD79*e3-F)-bl1|e&LfjU zM$;N{%Szmc_5gx3M*@s$QWF@HD@C|7JG|m1n>CG{h@oI-CB!y9b9U86%pl&<^JI^D zyeamfqK7q*L&VULw0ufb8$-lD{pRlaqmQ0EA?U4Hin1m%Enl zqyWs?C?Hq>kVAQ@WNIS-q4MQQlZ0y6d=pm;AXjUKyHK9pvCrf=vN6s;0&P1wkC(BkO9zs z^S#R(kFe5UyCcwBjh}MEYd5$38aKXFSS_OFK9(c9br=^Ts!3h7x@FC6*a)VI(b!l4 z$W6ZvOP$u^MTC_a0J$C4O6MwOk=<%fRZgC&8&~VJV(}JyBg89ht_(mf3wX*7IsfM0 z+Q1d@*Mo*`>k!4Y*W<=Ut&f=BQ?sgZ{xw|Yq$B{U0f1{@`B_=Uue?XXC;wI<$~2X1 z>LIUhv^=kg`!6X+?}$q`jhz3v?kV$h z$QR{LzIW!!RW4`f?xkmLUzG2P&V2cxnL4pny+j}ap-?TSJceZ?R^NBb+Jkv@uZ;?r zlu;STp~RAwyZ5jFi!^{ul;_a4Mdh>=g>Aj4 zmI%A0-fiVv|yH0i6P{IS^&)X92Y(nfHG(qD|^hdN&h;n8(*_!x~J-G_mgbLJ4Hxf@a{@~dS4OQmCpn%s!UiY-1i z<7wk}Dv8)XK1G$7KT_<#CxBRYCcW9nja%>3s(RfJi;77PTp1t@IQ}sO8g2{;QmI83 zQNINB5w4u{_SVv~Lw^%5KTjkeVK&ta9+TCgoeH3rU~ViapR~Vbj=+^^6jqHV^Vi&V zBG=Fcv@=Qsa!L`D2<)zQ<#Hml@b{F3v~iG7?{S0%GY5pEF*9+6j1YlFMh8-IxVeG^ z=IBku0rwr~VCD^9A)esmoC!*9$s;Hc3k+sE2O3JfK&&-Yw_0Q{9!W`2i5x|~L3ZhV zuMCF?+{oc(BEZQ}#n`#my^0`%YsT;=-+2r5pVqJ5kXJwc&W?L^0{n(~?{+YV!^s@d z!%4f^aZ8@nD#o!#W{9Y~`}nE+Czl|;&}tAEyzkSgiI1PeuXkpu zE~sDoYy02$*>8N|Z+!oceDy8Cu`CM!1T|wg8agU2KqrEmf>A+WafAyDj3Y3p8;t&o zU;c`cftgXMWk%|;6HN{VoXng@)hIX_#JCm=t^`D%c6q^Z0D)Y=Y@h}wLyU3|bH$Fe zbtHEZ7;6zynX$l=!ibzrAV~>?QM~E_q0zijTo4?HqzQEDKmvCsB!f8jL@aIuk0M9w zi3On1c&BDim^h1xMbK^EKV_&jssO-j0w>5Q1dtgXdotx6G>UxaE=stRBM?*fw2dEX z|Cj_&h1F=V-+%V{@Xhu~a98w?NGg$oxTsRYc;2T+ZR-8P35*1TqGp13JC~EDDQo} zq)RCDYx>7a1Wn=IuDj5RFh3FII_^-6drGlyea)*>HE=b#&*W)ihIWJSZJd|+o zMW=5?XVa^yc|I1mc)!NhS2t_pVt>MTetm+dk@IRs=v7}-69 z7?&F@AV(-dm2(bwXC!Q%Kq`CAvn|&|)0RN05VE_eE|jV;h2rhCsE`UOn&J>`eLv9b8eY&5 zFQ(cdgpH5YB8OQ4Q_k3ip)F0F5d+QV(9EjV0KJ?SNf#}yRWof_)K81JX3OTn9Ar1n zgbOp2xxT)B|NZyhe*5ie4phrI=j@;V{O5}?6E=*RxgrYVXhmUXhMY71=AXsqeyN0% zdUkUwRB?rUn-wxODFmNYLfa*jH|MYDXAWR2(R>TrT1e2UqMG9kr>ERY$m$eGxTv?> z7yC0J8f|LuHuE4hSZxcowinr+TtWy-CzsepsCmke($0tWLlQbo%jMl3)Mx`s43hF{w2pqY;dR zI=PA8k|h90JIMIk-~8Gi{DXh+r62w0TN#yi><7a|vixIz>L;Z+sJ_jBQf%65vsOf$ zt~}j19vSVR&o%NBzW7~X!X9{X_{-n?>|cNV-GBFYe&nm)r@s3WU;T_R0Swf@0FdGW z1ZOdv8Xn2KI0vzzhbX`d28c%oARRoC0>mOC%vpNaPT{}+Z6c+FN_DrVqa(nHWrXz5 z3o0r9zyM6ECb}7cT>&^D0(wIrmO;~{$Uq=dWejFSe9I04*ug{!XBya%yitn+1qRnj zNYzE)zzMd4u;7#=?r~IH5cO)0U!xb2T3*sYm7s(S~_Gv|@ z+KAkc1n)0MZe4f8C((;uue|vn(!S#;3it_pVG3q#A8~sB&Hnjy^{5iLW_?}7p~_S} zH^fF%!IIStfIwiWYgk0d6XMuv>N){w*Jef#yJ`JO>128#m*3S?YbY`+0GoU5m>soB z3byh%%_fwo+$RT?-=*b;dy%)4yn97_WJ_W)}#XEn^x4ac`Jjk$%a{`X;NT`u7g=LO&i4=HUYq4ljjln@~nzYFQx>Mlbol^Gl;IRYG3E%NjMx-}IG+jNY_opOq3-P9H_TzF z>Se@dnb|wd12F5p)*~-I|LmG!r6)6y$afSsd17kk{A+&VftbEcgU{f_3n|KcPS~iT z0N`GJ$p@>j3S*TmWDh=uJm0-u*is1P?{d?7C0PsUKn4hbKs+h7LdYRgl`2#*gq+F2 zzJ9R3WMIQRw39cCW_#KldbN_NbNCgo4$Iwv0;XAhh-aN)qjRtKEtv|NbMBY>ga7hL znOk&!!k0Sdu0J$}VQy2ttACu7k|87H-~mqA36s}ZSm$wV#CZi1#>yyRZL=uk#l851 z6n76yV~Kq$60IU2LdeJzD0A=`G=y1Xgc+~oc`X&$6qvGSW^M|v3CQNzy{f7VlnVkV zDHlDvxtke0SG5okLSSakUX16nXXG51Ovjva8it87gs>}?*zN#)++@cKp@^Q+Fq9*) zp0vbnwhcyGN;O-F7gbcqxfoh42y6>wma@pZu#lQ1IBt%P^qF~K<~v~y9t`Kc?28C! zp>>P1l~0~!w!HUq&R17gS67z+RL7#*im@KYFkdRGjxok@9EpP2C{k@JQXR(8imGnJ z2*AxDXBx4kr(rfM3o^yQP0ijSu$(vT!~)2QlFH}UJ$ElqY)kYovm`9`Z8O&^12v=} z&sQjVsKo$&89*W$bu_cG#ww|nlb1JgHb+45(o!7@H479<`o-xq3IKG_NkJEY5}_HW zJhfPH*_>)1=Zu`0NXL;XcC!NN?wVHuW%XjgmmwE7uBK@Y$3yzi6z;Q zL>wSgEeJM5sOnDS8JryzC@YbGto@k!NWzdOY;PDhs=a}^5i%7m{z^MVV%ot+(`RmO zx|6o*n@bTeC3prz_#19JrDJ63`^fmZeq1TugT#d0{&MG&sO|zd5fK}}N<`WY?6r2+ z?q=dmy9XkJIuj9vWZ20O9Icotq=_!*I~9RLFF+@-N+YVorZ9mF#h9sq8k}H`=z2?j zspJ4b;lz!f+#@J~W5mfZDk7XAV6DJ|S!5!Sq0`603hjYC{N$(!jX0pYFTWENK{!G1 zzx;InXWpsQ7$E7#jsfflC+Ow(z4__4U;7k5ntJp}J;tj(sll%mp9Ou`C4chhy6Y~5 zpuI}8=pTWESRKP{7u?@#{D*t0pogoU3yPaB{NiW+;m`c;7vK3oM?*FgcHs~qRg9WK zY)>$OL#bjL4Ai3%7|4N?^tI^E)mmtPG(smsAUJr}JBthr)Qljk#)6S3IY5BY9yp3R zLBZngik*NEhb}!PIePaY>V9m zCCHV*5*jsW<4u<$8be>ho#g0l#)ILCoj@JiP65^$Y=}z!v7s?z=VAX^y#D6Z;qcKT zTq=6en9xLZm|0ad^Alj46`T(7*vZwE!K57k6*)vA{XXmW^N{R9Z;6ttl61U z(S@1&jAli+q~kdG&=(u{O(wpDZJou|%?(%>(~Q^xkVBY*igPY@S_SchK&7QsC8|S_ z8kIoIoU>Wy?#E+C6jaBQ5)rkZ8=9s8z%=b2%vQw~%^yx-%7l2f7g+GqqA%lucxJ5@ zmZ(f%K}*w!h2S~spo`NPF;z3ADsrtn&+MpU&UqMyk|VPC)^CM!3;r{+IY(rbbCy~r zQfW2;I0`7zs&OnM*qyq%uHC%ZHQPjo<-4IEr%^`$C+&%eiK~js7suqWRr))J1Qz}a zWO(+RX-a5lg@{dohZJnIK(oIig^GB8vA;ds4!`ratMB_4Fb@$El_@TOtvI9c9FbZk z%gn18Y0)gBD`az7X`kdmxdQ--R_^E?v~}()nE8!PcM=18GOb)5k+blP6S1B={a$a5o6akUyl(xKaAmP-a59kgK^i3z zKzk*j54^j1u95iT7(Z*I#H2<-C%4u(xsvGKF}8G6WTa=wswlPjn;;jAjSRgpxj`!Q z$q~sD;{@$N!nD`UIF76h$x-zJJ`y?r$}z$eB>XY;I|rFp;3JVF+l%!-@m2iKKcip% z>Pei{Y5=BnjJNLO7U8{VGOk$(F)`i{d;q;@_lLe4NC(&>Xzvz{57!^oirwvpzvFz- zbgNqR=A>XyG7wT7C5eebm1+V* z$Q6JAWL680j!V!HzH^5H;0w@ENL``n{iG*C-N>l&Hp{HSp-2j2 zAYC!R`)?YKe)!Ou8@AV}{fr_;ka|s4ITHlxJ3-QvV5a(i3Sa2>Pw>7Yy%0H?vNIS4 zan@Rz!FmHZ`5$!G+Uze=s^SxOtF1Y)#VCWD3J<+qfHS(2&@(@L19EL~Px6-g1<8#` zXzW0E?0ga*RYyXEI`h%k)h-pWs*H4;pkkDa`?x6suRQ>U>N5}eepgi=R|TtFb--QqhHK>bHS zwY(^>`T!soW2W6I0?DVMcmlAw=h1KO({5BV6gL4FT<*^lH41=9@G|*oO(t0Zm^1X1 z&6}UyGoPehwA@UZE;tETbft;K>TBvtxt&?69ti-I{ch3S$o!-IT=ax_UpxJp&`oB* zO+}gNwMk9U5HWyIZ7PkEc(3?s<)Z5;eJKK{O~%Q|p{Z!HY6jp(S%%1ty!3jw4Oqlk zOY*=m11Pz-eOiYZbFRqgHyAC4!A$@lWhf@Q%?1EnD1h9obGq)PCd;h=AarZ;#Lx`D zB&3>tftB2dMRs(10RWSxiGXvjv`L{h4{X_yZj^2T8*{O=$qYD_sVoCX08o#>WFwVJ zD$J5NvNY*D?rd7EMZBiPxvZ$+*2I@(x+ker8H#!%B&2G6Re2xGTD;s>n5TGJx?;Gq z=C`h4#f`4aPI1wi8nCLg=JA>STh_4k1S~FEUJvn0(MWr<(t+Pu#*ozsHg?#7O8JN4% zp%)067LIn-%sZfGUdhW_>j4>C@$Yxa7V;QeVJW!IC;FCZExYZ9MlB!!Ws?^;hYUxc zvISeX2>^E(Pg-z-Y z`STmq0YJ_Wk!6U8sO!2onvGT@OQrVh3BKV_08B^EnJ5&zRlLk-4o)m1Ran&orzq5Q zyrIebcQO#1zs-&CA(GrkIM5#}hE$4k) z3}~}^E^mZDlj~Obr;S!gwcqa#heQ6_|5Shfzoa(u)a-TZ!At;jG@?+_YYr(%UFV$L zb1|4-)_({S1^a{-H^PqPD4=9wx@!RAXVE_G@|^UsH#g`j;a(CF1qBgnLu02q;0jQ| zp@X$@YanxC*+twq8W_Q0q=d2)IDx>rgJv{0EU;vdPm_G8{Ud3ggCnb&!wn$fe&@1- z9vmio5%=E@97T67ZLtA|0wOHdh--gh7bop}Cukbn*j0wV4tbL)f=}X5RH@$!POM^d zV1%x_hF(9v`3<2@)Bf$`L}Y5j;_8*bVMG{#PSZ29r23wos%HO|rdHY`n-HhYDgY$h z^}EOlORn#$J_9<)o30+)s9e%LUI7%Ym>A)e0-sF{r(>u4~I-ZvWhMb zEj5Z;SEc4NoG8Bli10ChjHVi4F3P^-NE`|1&NVt>u|SHuZg8xlmIH6s~zj!M%9tSKFS7j(hR8?a}PJy4Mh zt>e~52nlYyuf(5_exyw#n2#snqv{1H3A}R_j>S@433T-t_Pt(TQtW_+NFbG|xir84 zHr7j$Q32tm<+q)8kMIX6dEB+BYocUwhupf=@SVvCxY=XubdeBY267RIK6Bq$M0faRo1P=?-7laS5MXq7HI?{r$0VrD8h}Y4&VBco_s>3M z?KiJm)7_(XJm__W&nWFxRKN*gZzqi>W#ZdQ6K>_!k#9R(wg>emN++Qs03@CwZUN|b z>f`H`R_j%HRbG`><%PwS5fI1&ZO}@_xA6422Vyondp&1EMFD-ap0z}T- zwZdlHX4*Av#R}{wnH4c8F76pWyOQm;Oa;Gm_E?Jhr#6UL#yWvoIC68M;cxNsi z;D+l{^YJiKp!v1=&N5j~J>ye%AlIh8&E?Ks^@4^hZC+R0{bih&Nq@L^o7)46_%UZE zgq*_yltb{%z;54+ixg`nSy=eh^f!CX@M3fF$uHR*OvN6Hm?!N|F#?~=1SS*la_?%| z((~$mup~4rafO(Z6OJ=+SVTJJIp;jOh7bxA3ls?K?qxe(LLj#;T}8aJz^sD07Eo27 zSczUN+j?d;B4(bXF(F_BLBb*;%X!x{eM;?aS2#tO4Y0<-O)#5D6**PTA%v2PFiKsd zSTxIO77|qG&oB%Ch=>C%WM}sDo7iyyK;5aMK)c-zv+jvP@EHJ=F8dGtE&k0vx7fpD z#%(zDLL2}9AOJ~3K~!~Jmjs9*gud?&hhx{BN?j?X>uay7s>COT5Qbrhv1YDB06-CBg%H|{ zcIm>hRtpKlMjXe?nKL|d(}WP1$aF-2Z}d$QfeHvA)KW_&qm9hG#iL>48DBWskOm@3 zDS7frs*06Oti_ndY7f7yGRSX;6zJ?PtO?G-ytoO6F(zRar3s&Z5AZYZ|^ zxh(^tT?1P(9xy|UJZsUGS|DV%WHDig7Q)Bp(yBxC^=6C^+g(?a}64eEhG zYP#E9RozutFY~>7?>TW|pA~Cu20J27oO|!fDuk;fXTGh>^UjUfziaP^6Z?yAeM@O1 zX5Mz&{bBFNK5aJ3J$tR^HLJj3G;=S+aiOi%fQguJ&jKLMgvZZua%|j0h!hyG>DpJO z9q1*?1B{rIp@am2V^rS|9a@S|76y<3bF?6Z2Oxm}KdE(&0wfytzzzV(gWC>lrhpqB zigG8Uz&&tHm ze~C8^+sN)#hYk2-oQN|t!5d*y6VE>+yxQ+i#L{wh`7&{WiMs*D{IN+?2RvfgNB;)c7~e6v)CGx( zEXLc1*N3}TZ(hH4r%z3ry#M&&2e((r&;i((Q1`MUI0Fg*Dn!7812)`(2Y^jmr6LUArP?iBp8ygr z-bauDHvkL?`ccb=Ob4M8{2J*SUAoVD5J|A$8A>C$C;GAaH3M){-mpCQ-Pqzb58v1R z6X`mlueG~Ty@lNnPKK=*00R$9SvB=e$bZN>irjwb#r4OZym{@idr>+(z*``|PD!H* zl!nMRWPwj@Uy0J(UOiA;xxaXD7G;_Nq{jW+d zs)AY~`0F#73JyH!mTg~ZQ2ySb2wsMMRYu8m*Sy8o=w&&Vrmd2EAS}kYG&-AFXamp9~P*aw(6CH1oR9n?H zvxF*DaB^{~Y`)stc<#S1oB2f|Z9z$vYM%&ZmwA0wmX@6WU_1iASc!m@5_c+dJJ5$O z#-^}dt)OXt9A+S(EF7HY(pe*Xbs$`xU8gh5@hqX}8AR#)_tO$o9utej80%{D(#!yb$E<|d!3sFZmK1%alUzZ)j-(dXqogIUv#a~4Aj zb2}GfE;ANX0IyuF6&e)~5M~F%rwHIYmZirl*T2boaWxf7{*}94c{*haIJIixNskvU z6~faVm5YDo@(X6P^fNrlhI6*1Q;#}PR)0NH@G~=9EZU1shjspG=pobyezRu$c@jz} zg1paD=tuZX#lw(7$2;QqdEvlcjxr%y};ss%%$Sq~3^}a|r5&2BjsiYgs{1mKoqb3Nzs=lh1QfNL^ z@iJgW2tsI56JxAKpvc9G%pk?05(U7>t7H;OTyU|`y~<{ld88ECb&N4q@5(q6g)n>M zO)&%kj(o}|3RIC7oTbVx5`|Fx-9o@Po?|A82mmuX9*?I}RvnMW;dDAx?f+_l(}eFvZ;|P=%isJC_Ban@a(ZMo#$@dD671WTomc_sE~I zB3XJ;5n1R(v{W@Cp$pDPL>EuLPh`J9RLl#VRsYWhtn{n({bYuvs$*a=w^9Pr(i4ZT zH2CW}K|pA@sTk`5V*!8{a9F5Y9N9(-A&fT07)KjpmR{e|G6r6XG$ zjG5F8*uy`uM)(0Vl5BJSK15g&l;9h!t1j*zX8KHOcm zS9dn3*$Ew1F!-DxWIvk?!DaaIjKuz5ZYUZumEO|3OW$5$wov6q>sEOYQ@}$I}#JE z!333{u*7sEX0;$Z5^h-j%gAoyrR01+1eG60;7P6SZ| z(r8YMftlcN-4Gel5!yJ71ehd70g2%XP?7=&@S#W#YAFlklsqeK6&uB|qc_>Mj1d;4 zy&3dJ#6aIu=aN6MZU<_~PR4*w@f`&QjKas9w*MOHYrlkcdYPhGk|0J>x_7O#K&S!x~LDtTw)1%H`VlG%&WYz8I5EXa;6>bU;OhJS|C_clxKp<2wYXZDz!nPj4bmtBf z6o-2#V<;ofoAnZ?zz`n$Y(ARJ=gvM)>kAVMwe}xe+x#gK^lXPid5fX(?CJ??tG*SJ zy=?F4M0`f7fZlWK|7~ftv>rigVFnW>xG`{9pv-B7ESKR5p}UaHS|F{p`=M8lt}npG zFofzq=aJP_G9E(-C10x)gns}EhJ!$jiItzNbqk7ETON+}cP$P8v!kgt`v zRpr7oZK~+Qxl6N3SDBqOQOe}@mS)wh+2PJ>nz60go5&p66l3JbO!XdA#wEtzIHFRG zN~unrO_NH=$K&yII+@w&r0zb>5>a*F6(l;HP9X#lA!1b}s;F71fS0O{<2Z?waTJk8 zni!{emvt_}9J{a%Dz(XrM~(%Bqf{H&Y)`99x>68AlbWjc#F5t%G+$(8feTA1sZGE{ zkE)KG0hc7TSzR78k?jmT&1+zR;VANwp&I18-sU4^R-G?12C64TKn$@g(E~>Vom~qT z#Axy{^m-u}SJn1X!lD6J=a-q8qr@tARpWb>S*UATm=#U)5&$L|Z3HmtSiD^At`7a7 z=;*Va+9a!AynujU=0w3wi6c=(D!oPnsLPzWIt~YV%log-Q)-b-A<11^Gov;_UqF9o zE+$(y2JRE}P$Mbmx5hyP;5{JDtmXnIIk{e$3dxZvnL;!&vbD@s3?Qgl1MkrWRWOM- z90|B{ZVmUX-@=`MJS33^>7>UVnMmA~6iMjldds3D<_gv=%fToD2k6EGq=`8ziC{mF zz!ON_MWh!$s%_xCv6yYu4gyk5jse|!uAKGWP}s!Sfk7b*0#xKR6Pdr)b)zGTN3{)c zaWmo!v);)uGCH^eSqKB(<10#ZVuGcMmFz_et*DP4Pn!@qU-{9}d0)sKa&Iy_D_+HtC=G)_a75SfkvD98^2uYy<|b zx)*o;71?3XFSol+<;YHh?wC!n5d}#`)sN|Z$rOS=5_w4o3S!!uZQ#rp;Sjrb_90)v z#_sARD&%E=637OQY~&!w(U_o7#MN5BAq>ML&QD|>q0zYo8DtaQz7M-g%0+2LOILD~Q!thqa%256ltn zDoblTKJ%;}rnoKDT;XiA)e4#%I>O3On}TKTPAewVS_kTEkaIylo>ir)i73mel5noJ z5~&P}iLjzFou#AdN?1kDe8wTD9;ua|&T?aC$!E+uR=Ns*X^ZQG12f^S3Vi8V#L8Dn zRW=69>wo=PJJ|V;>4h_$EwdD#O?-w!)}vT2(e>J!3fa2Cu;lk8c--o8tCwM2v{glG zeSFMc2(DJC0_0wO(9Re{DdG9I4bygRy}+iq_>4Vt&9T0Z{Z#4M=h||a;VCk8_9(n8 z_NcNmys`q~mPL1FK|b5D&*<~xw$?Y^xy}_P@)@ZDRVZMmCIliBxYr%_^wzwB8x#;| z+J7%%TNAMHgmPS(pr|w>Iqu29C+$yT0*51JwJrC4E&RyiKnG5 z5XndPfS<-ibba4j1E7zZdvfXt8|&?jt)a>KEj+o~uiJdv!dvjG<;*x+X&nf%vg*!) zS-^_DHhnH3FDn(vQM{BdfG|yDw&HG9UGt8|W8KDADo~{nRrf9gu*B+PNJL(IiBX6J zCZH+OAAo@1(*r^EK%CqFD@sMo1tkz6fC5nnSX9y{ZKDF9tUba)D66=E#6006?!@fX zZ*difu#&l|GFKGI!%zW&Gmf^Rch$7gu9_kkR+uT6E&iBg;!jPbYCTmeec`gz;*}#- zE36KElRQ>sOU;y}IyTHLo{hOeXU1RrPk#76{N=e~5KZJMkvNXFrY12HbL;M^T8fJ_ zRe7punsGe)bcBHT&;7k_d)2143Sbe_tmPCI<4iLDA#AtXa}Vb`a#*R|uR6e0SaUMw zY}jgqdKawLs3TpXA}%!$k?FXgW{YwONMTz4$ zE_Mbc$O*n$*x@{!%FCmf*j0ey&M_{HRu&i$wVT$)F-CST#M87ksTox(h&)l`N=Ydd zFXK2?n&P(G9=`wIHh<=?6(BNK9k@^h;LU*G=7A_iHgjeQGn32R;|ffy0`{NpL~Uy} zs3zfFaq2%c<{v0b(k}>3-e%LC>ucd7BUqQg(M`Y%6|)F8NDEhB1QVDIStu)S0ER}f z9x!KdIubhQ0hR}B+jJm}f-9rFKqwu6#x)5afh$!fz=>QF$l2XJ68iubyN7+C1WBX# zMoknDNam3Yt(t*A!CpEHuQyB%enn{1OhnZabVoF*e;~+UcZ~yW*!Kgm z4;wJU)EI0EWr&k2aDsq+1KPu4#~46J8}@sk6}Y2=OOH*$K@kb}aFKLWy&~$}Kmdut zc1{oxB@#Nin;VQ-Ow}8p|K@M+2yYZuaR0A=lRo^nKUV)l^H+sFhHP@*5+7NvNkMd< z0L4qveUcdx`d{{6pZfBk!^pv)+9-2gs1w;WkBRF>`i z3~hY2gVghgR(USN(%NHh#C3+JAnCfEvOe`WV&8VU$y_8-Ngmcs14NM}dDdV~nY5k^|~yeyDh_)Ns@5|>$#iJpvQQRzYf z;R17fnyMGxqb4w;b@(Yzt*ZXM>e>^mYOeYMOnNjU&*gd2&=b(~tpMn`uFqIk3&Itu zq*^Vztgdk34*a;cQ|qOa8QA)waJ8yK9EeV*ld8ITlbR~sUA%ZW;{~A-Y61c#aB6}K z%sEEzY_?gOATU>c6J~9=39R86iKt|#z-Cq|+p8wCwTIWlnTos?$pTQ(fk1%@El63d zV)3x6(e8+7RIPNR$z^io<7TVPe}zRV4iYOGGV6ke8EHDlE39QIh*p*QX5Y;Mgb*s! zRdXW*p2YP-JxDV^gB2>YbbcM-k(rPE@e$P3G)>LVJUQ8gDQ037(C3s=&bgG*Gz~MK zPN$U8G7BlC>znJV-4$2=(*OXAKKY2X;ma> zhP2GgRuKS}{DIGr3Ko`Dl`xw|9b?tYudU2}dA``t&8m{x(yMx~Mj@;hcvXlOk(#rV zvJksi;)KA?W3NM4R!gld%zaxrzl^=!Oac=XcXN(RJo!SNK|n8<_2WfitqoqfP1lcO zQ;Ib}y`^z1ZWYM0(PE6_Xv}AX4vU<;Y6z8Y_tXCj|C5^BUNgHv^8U5i@B6;R&9%r* zyuMN-#%p6IsVG%o1m)rQ1hWAxWQ03;RLTq^+_vad z8z`w*=PzKdv%erb0H*fRaZKnHUY{d;nW-&nI4!V`(gA#Kx6bC~b zX3%7G?*_OJ-T*H0r>+~b0Xz~^bi;DcHjzd*27338NL0LY>fxgsj3L#F7wUNn%D|Cr z>r9{^Xo>f(SD*yRf8p=^=y(6!Z@m1?-xYeJ{yqb{n~xnE8=#VeiXOit@~P{UAxZiX z(Fa#I=|^|hj)(T||JC^G|GT|zyIo{&R6ZT>Ws#TffArP;zn6dIxBpBgZeav92dH<5 z_yN`!mAXO3?6{4P*5{!XSv2Ep`t{B)k3JnZ0r@=O@_e#zn zQ&tG2$f^u+C?vzKpgowfzf>C%lY2;=yA$!qng(=Cd-g%P9{C2tb%*-_8xv;?Brv@- zDEo#fW$i@n6<103$|C^5$+5}c&Y`w5Q?vjun6qplH0aLRl`n;Gs}!}} zktuM9FXjFd!sZ=9w3UDDHrN{H$YmyvV?LVs)QkeQ&pPDZ!pPHa^k(m@$ z00iSDb6M+cO|j~0&uggw%nYg1d2}@(-O{VcZc}l_yc4X%E=+u`uvAzLJMo521;97} zvz*z&HJdsW=l9`@(N^PH3+{4Nwc_(xtBAnF;W}@dt6tc7>t|;>PZgfdW~r6%@yvCq zW0|TN0D$7z@@ti}^TBDdR-`s6XS385QdvtHuxNx8U>4w-XjAL11_Dr)t}>lX6v|Rn z&1?$HDrVKrCg-NtMw{f}rnsCJ!%dS>zcwXw6G{Liu^z&o$Pz2IoGb(MPAk^M@Yie3a!8Ht|{DQ3zZL z6?iD)>RwdJG&Ny1Z*^QNfX~2AK!^w&s43h`m)ivn7*H&Dp0N^IkfSi6T95j60Z={} z(MrPnGTW?VkGa|lcHQNztl-h`V| zb^W#lw$yfEvoO*07QvuO(5shZl~i*SpIi>7gY&8LM0^3Zg~dHEpK|t6VvLC3Dr1D1 z8x=yJNdvypYV>p(%_c`PBC38+3&&>?nF4^wJaL^WcP^lqS9GZ`Y(|kV%gir4pf#7O zD#2GsYw|T?t_-Z=KCjrxJ@8RvI*zeI53^`mSw~B(@CVTaG%#aBVfpT*@Qkw6K!*Sp zcqLRt`BIi=G5}!_+7BVD{1CB%r2z08La|o05Z0EO!z^)C9r`LgXXYwZ!Sae?ghg8& zKy^!W_uX!LI_Ws7+1NA<{j>jh(=?Tw6(u%uUHMryj@8L=Y1CH;+9ZcRBX<-6%|obD z8D?uN@Y4cyg;_S`^2E@3Ty)0{dG5(sG_jyf<3`+Fr9dHDH zsoRZ&TTrJSS?w1bZj zg|R?%2qFv$RXE=bU_hW29WKa*9k6jy2qlB3PmvQ`9KEZkD-#S6aJDUEG!?;tfdPpb z08=JVRzzUOXnyB6KmF!!gXsOQ{H_0Gq^}ab$9_`XxP>(gN;1H%1)pkeenvNqcU-M^ z>0Nr4-lexD%OM0%-TLtP(X`B{)>Ed@IX%{~zBqO9C9EK)@FdTZ+9nL(Sv+XnpC=t# zH4%Wa-q(kxo{0+*zF-~ezCA^DE?fKwpuxQNc?(Q7`;>27P8tN{hcv+B( z0Duqzh$jYCAcRTz8i4~z;Rf9JV~DmwB;$&UH>q*WQ4}xd=(AXLVO}Ipn0*%rhVxzgbG3k74r&{2V$TyNj}w3iEFj2wZGwFiUk{5PKB8-hFS5w%xduy zaa+<0f{%o{>nTs?*-U|>@im!-2OCKuD2CGJiC~_2us$*58nsZKlsAH*Ct#VHD z5%0Q9^Q-@jutbT#hf7;k(|u}XMvESCrZ7i%Txex93*Hk^aX)Louksg6B&>>gE&hYJ zgtTg@1&Ue_tIC-|4MZ>_O$#_xLsc%OMuEda2=Ed(tm~PqR7zdL6_DZ>D}4`Pg`;`F z%xtPnEcus3LNf$5mGZJE%2x!fcFAUVYer5H0+!V{O}%;5(GN8JBw^(hYvYIzfRa+O zAOBDOmA|5=lQd0LqBAp|xnr{jVuiHAT6e5AUHtQpYEiyr1>GF--HoIc;;QZfAu$rsTU_F8UY0twIp&cXqAxs z$g&|FK}r1R5R=!e5v;0LCdJi-473r-HiZeZ!8U>;BbgF$133XB9IjiSXNajd5(6Rz zGzw3YGp>>xRJTqJ2tkc^fQpQnA{o>{8l4QXAvytIh7q&FFshEEBXCq~Jl%`JLFSRt z0Z76J3@zmF&F{YWoxkz=U;5T4vKxnk=HfUG6lB~W0)FU-6a=NL#c(a1Q#zQpv@k7D&!W?oL1?Tr=*K(eg>~;Fd^Xt%IOS1a*wy(XtgI)c&2KAIKqp1lEJmW|;I#>uFLD{Pn!LeaH=e`GiTFM7nzM?wNocBBMicWg-^ zI4T!FS{BBz#v}wEH61%nHnbuq$|ZMKge~Jh4oh!5w>?t+tjEp&U+L$8YTf;z188ppfHD?f ziuG0>c=}go6;E!bU&NRK06RHwp`2BTMKe_-023FY#@eGJ0K^sm#wV;6)B3t;>QxQo z$0-1an*gk07tZnBreBRoQ3Ali@CpDZ24D&gTsbV2_Cj+I#;NBuy67}y!mN2zi9EG) zmE}~Ms5!?RuyED}00;sAkEDDiv((JB;1HH3#y()7u&p>ax<6N?Jup+@rngGGdgZlj zh~ldC`n!KB%WQeqO;ue~dp4S7oJYDgHicyr z6NRc?`17PwLjX9P*Ux0_@yQJ$006gVNxPcX#6ug-yE|WMSnXEFi5>{dmyaGDKx_#> zY`zd=EkD)JU4dc=HeK%pGbQ9%RI9B1T`8TfbDgnikKH+E;OUuZdJ4d;L90dVsXPM$*4l{X z;Eb21EYG5T`2T=veFl;6(GXVOAD6i(^0fF9wCk}}*4w%ormf)HdRta&AgtG606Y{b zfpAtu^iUjS1#B(@7D81!YEp8us-zx5z)aT))iG_B!J1M-6v6~s z6sJG|s5n>kQsh7t0vpYIv;w5mxOsu?4WG z(A&HMOl{%m04SBiGEPEWK7&Dzh(c=+WI-_&6sFRSR!G4_Wg5-u<#mQCs;6O9H?JM2 z(8l7KSn(;qONl(a{V?}1qk)Ti9ahz@Cu$h-5(2NnMrLPMzRKPrVrJfK+LV&~^Z!Lf zxPYs&f|J6`JF9x<6-lA$p1Ja;o8ZMd@Y$+ofNxE?0x;uW3(0F?z^&1iWpq_mOvjOC zbJc3k{)}aUJ}b_(ls${t&tO~~IVhMJydWT~NL$tab8#DVcaG6?1SS?$DFqygIrw>R z(51zCXhN(eU(z}B;VQ=Bf{tPOQ3%U~GV`e8#1UJ5;6uQ?>gt8&X2gu(yY2S=2md{P z^{?tM#MIOgNsKkziCHMcLx`AeUBzsY-vVHxMvj4J%cvV0+u@28?NCa%Lt2u31EZ)=u}@M?AgUF zWe4nDI1Eal2+bgIGhsIgt`X)!q%=4Z_+;9MMaTe@7H>=&lM{>_3WxxNP3B`FQQv@s zJgY^KJ)uP=l@@kTPtHf;7AmeVx)-LbGD-Flydq*=6532L@!%SzJ&|qDow6FCVLKv= ziBVpSUh9WJ6Kv0_Jr~v{gUqyVuW#h0 zeeq&}s4%0dGrkt4Kmz`(45*@?Wz zPH@!R5S_qT4FZP4sw6*7N@HgaE(F)XHi9Z$-LnN?LvnPBfHMei@EcgG?a0Q`560{U z@JW3u$eczvDG_TwSO5knnQWX4$c_ZhAWt}E-;zAEt_sPvfru(x8zW|9g0mk$P>TbT z>oxeKa%vT5i}cZ`Ku;`N(20p%4Kl(rkYHxmz`+=aTwQ<`@&-_712EIDQ|fusrhDXT zp@Zs{anJa45OHipp{5T6rjF$myn!V{5jO2#bm@@&%6wp)oC2^_8asCvV2IugmbWc| z(ztv7>#zUx$4H=k?4)(dL`O;@ki9pi9q=H2JrL1AEC(2$%TRTS1C*J#R(mR;`Ce$IH3%%jZQ?mzZ4$z&Lxj7*Ie2ulqVeATWbd zpeB%jo5D>A4AdZRQ?P|nJot#>=Qw(2$a3AwQl_USO6O?7ln%=JvgE88xMvm%Vdm3%k7 zODK+FmA4fZuS1-Ht+~bkQ21hiTEUiRgQakcQ_R8oHqPCvA77cg=ZL6nTP7;Ns9M|u zab3e4$R??*V8z|ts?-q$iIIp{BFf};SKI^B1SSIRuH$HCdQxI)+jcaIF;+~X(zvGG z{tSMVQpOeVQ9oto^(@4hFsng%DKJ~$m5CZN#~j3(K{mSzV#YYuxJ;S3OJSBy_t|-H zzLv}KNg>EAC0^konrkB>CR$t?%gX0&0iMd7h$;Q~|5AVNUtg<70bphkX@B*8>8*Q{PATTq9z!FWz63$rXLiAfqI`gU~OgsRfP%+#oLSl6}^y$Tejbm6)vv8h_ zGIO=2^;WIq1p(LB*ALY*SH~!^3d0kjzI&;VYgN|*5NAT!>2zwEW-;35IGKML8Nh2` z1BJ8-8x7aY4kR@wHi zOpNzh!vjl1PYxEjhrvA&e@X-Qxre^d;g7-F_U17KDQyfKe3G2S~^H9$sJ5+bk&pM2QDvx&Gm z-~%@@IXPx`C(FcYz5_A|3n*jDG%}B>CCMj_onUJK(E)nxh-3zVv@i^gw9`|KYo!)N z)maiXITOncvWJfX%GNMgX-C)-u|c4ufbey?ZnBOqe&ctQGH`Mb-17}l`juTrN#1j5 zy7u7@{+;H-Z#C?s=nRp^_YA~z1n__V&BHgo)j<@tF&wE+A_@l}gP$D4c2GiMRogC9E$%7E>;RMh&i-{GQ>Xo{k*}VXG>F(~XN#D{`lvMF4kYFdH;EuKRv}vpe8t2Fm|DP_6uC zT-rL_8-V7Tu}BwHCdfEN*PF@|;LIN>OSbysF>!4wV`~bWR{)?1m`Nq|XWEVhGa+lD z%q;JUdSE6=&7wjDn1s6YP%!gl!iDBh01%r3z$dvPoGUi~h>Pe|)oNK0aB8t=2*t!>WhtL zeY5~fT(e0HO6O>Q9F`_{#lxxrAFGoAt;Q8r;s0h<-P!(Ysi{YMBU(knyig-v?er$o z**Z^so<1}2#*C*aRtny+_TfDIX|=C-TlGk60_H_NKf(H9#<>Gn#)4%%)N1Q6M*tXm z1EBTuU}rOa-jko|+tyMX#0We)#3}!~jBVcI#=L|zUYu1as{d3vM zQb~D|XN|%p%~USQZWk@o4a02Gs?8q? zr@-|l7DHgveMle_hbxK)&?QA8gb4>J7hK)P+^aIfD7CpYt8Tggf0Aj+GMq;vuf3S% z>R0M3>kRXN-!kc!=_#6tr`gJLbFr-CrPtj2P&AOk`O zUZY!vDNt!CfTLJNxXOfcRg%fV+xqNYeg0BF#f(rl-qZCR7N$}ug#%gff)bblf)y`b zqKLbrz^9wtB)qk(5GJa4Ru!z|KxYVaUdI(OqcQ;!F-DFIpl#dghE`@ABrqeuN2ADj z$m2NbNka(jrY)t^hHQmfVa8c>9Npc<(Y+8;CA`ogk5x+bBBUzCJ@aTzsufwNBI}`Y zsb*Ybay+bX3^1CFItB_7BQu*jtw=g&o)-`*s8^lrX3T4XO8}}s-ZC>YLS$y6jsDO4 zryO~kT8=DHR-Cd8F){HJagT!gBT^+(ng#P( z*j^KSHd+WlRduWc{*4q+oY-dp6Ux6pR5~gJIu6Hxu-R<96j}xMT;`&fI}j)oa~-FL zV2LqMK$+r8OwR+$G|sUOQ2?5?=e>YJ@d85e;+IYq6?Uu{ySxAOuKNp(NT9$m6x1mw zAhvlc!AxdO6ab8>G0GPK(gFZFvR}h?15Cg=G%BMot5`cI$;gg@2f?-C2#84%s5*;g zBvFULL^p~(RH^Nu4M8&-0Ba@Dhs?KqSK46%af86v2n1teU|{JCSK1z>KPryGUzWtM z+w|h4LPb8MVFMMk_npIGHVC>Cz5YSAdmH}5hK*ePIWuc_Z-hg(&}K6^8m_@dXhQn5 z@4wdR_f+rIoyCaSR&F5%+rW9CEV(FUU?Vaj6IpaVpx^Id0+*|6f`VHfg7O~ZjHKwv z6X>XROO$ok^?6|0rnU%gvqzx-1Vs{LGa}DQ(Rl>#FbsQaMLAJU-O1q?I*2NXumPi4 z18~n9(JiPsNFgaI$TTpM&Q}W`tJkovO~HRxKPP_ z3mcLFG?I^Mx8wy-*FSQ710`_Id`I>6r8 z@ihZZS<;8C9Mm>FL_8-t0w=gLPKpSDz*$EF3B$aB95HOcLK!Z->K5`q1YiSv%y^;c zLHgEpm%F%m@n=8&!Lh>w&_H&grmUHX_!DyyjlG-%x2l@tE{o$qQ%B(U;CDZxd&WDi z*1PmBy-V-XTa#%)2wbXfNeHVz4aH|{Ye_4RaeV}M2G)5V2zd%2Jqs~B3rRdhk>;xE z=IL<)S3mJp7i+{me6yDE?RtgW`zVjTka9}t&~UByd3@v$t~F^q9B9-l0dPP zMLyhNHrwEGP!kUFsG&7S>~aPduaoIWSvtBN&Kjj#RrnmFwbVKFZJDL%`^CIocx&Pk z@;hg|M1LM-SeEE>_~}KR&w*L%hQbo2^YN77ami;vw2LZMT(dLlLV+rL>;41pQgek1vbrjB=q}egnidV)K z0;HLIrYg^i1C5oKgHlSVxBvhvlY^e=7?_$ECuOTz`9vI}X`kIr2 z4tkh$-0Lu7j4{TAnH3|WfFn-=Qa3ZEK^|&x)fFO#@%NK120A^a3wBjs;~BnQNNJ zF*1i)_GAglx$xAMSD5aFIIIF$lnGpOpJ1=L>;sCIP{7RF`~NM!{7XKLr4*3{0i~2+ zBS$I4L!eoA3~ojoiGtaMrvB$Pc~t3%Ah|(%axEr0LrW-K6 zrYVzefMh;`%>+!hPJjZfL!;s-YT&EXy#z&02`oY|HIq#%ML{IQa0PS!e`Ozr{0G{% zS1&&Vw#G-;`;L*)Nbc&_0=SIkDqZOx?sypV_{SDMNbO6(2-_IqfNe`KKN>+@*fMA< z{A##6GQEN}A_v&DBMAQ%8O;G^$Gi)UOx^&8{#{jpN#=0i7hBU{@ejW>z7nz!eT8 z?O*q{=~`z`Dv3NZImlK2U-sUuRhA^n^ZVOczQWuiV(+t0Uh0z7-Kcs{i-w|LXbA>J zFZvpKYZ^5Jdeaw~CqYxt)Pp{R-i0&_62pMh(6pp3)T8R@s>;lB*%x=WSiY9&!Q4D7 zV(*ixL1ZJcj%A*`V@H_V-96lX{$FeDgl0D}1a=3J`sk0pR189IO@0XMnH3HtccaMD zh+QxDAWbtY{VjA#kH3uZQ`>(|``-gba#OoAPH60qVcBG4;nE!$+qh zd886u(K;j*F`bW&=zEY0#RwSao_SBg(72CJ=3Z1H(m(3>eZjl<`bOs{Hv{bN6$&Nr z6Knuaz)>-SC+KG^?@U$QQ&ItR{x$S1ZXUJ!9`#F)BP5xI*||5PK9P0I`x%{TWT+uR zM-V|0K)_%oL`-&guYNOLrRg63Wfb5G`pz}RS@dUJn zy_4(P7I2{nO7|I9HA)5A*1&Mh`)!X(#M2^jX`aCpnapw( zw~jNaMyv>M%J*LzaF9yBq}*T6bwxo>oTfJRo#BvxK$HKyz$v2dXa4wwveE zr&Ox50qFF1;%T8T2q9aB=fIvfY2HRdE@8+8mudIpXP)xSsf5D261&t5fBt6o^Owl1 zaTQYD%G*aDY)K2S>d&wpb9q$V4SlejYlPPx{vz1Qm!Dh_lPg(Jzd;ku98WL<%qi&<>D6A(A!*|h31$S%qKS>)U-C#+~FG8)HRbYa-R#l1W3=x z(Pjm6-Meonur~B+H0qeY0OoQ%G+bsz9f7UmFW}KSrQ2x&AmndaD&gXF06-uPfzJ)d z`OLF?i-d>`ft4NpOF=@vbIHvbw3-7^8<@|{0+Z*}RIT`Q=ha)&N=Wj`V^+H=rvhx3;a3rw z6-VZ|Iz?h;+3n11;34N6ce_nMw0T~qX3e>~E!Mhu+Q?L)Ib0b>#~ebKr`g<7N+E=< zTJ7Z`U#i7=RVOYd1u)OEne~0YoD@4L`AclUP$^qMTE3W@r<7uhL{wC4C9SF}Uhy9h zP2+?b?{8U_zVERC@xl-(FtZ0Q!&Q9G2MQi&7k5_zx7F+a$~{9$ry_cC_pamOvnf>b zz|97*;FU#}jQlh{4RL@7stfjQG|s&sVrI|I#5rekbMsER)l4tvjkK0liFCZdqsDMA zH)aA`%tU79fz8Yd;;GGBu@{Bx*-%3(nsLX(WNa4~>*_Eb6@ir{EnT2i-oizf?sk8VF7FbTR9Td(gCd&Gd{8j)6VD|>u1Fv8G9%6dg1Ce@xoL9U!IzUZPtfJedk?M?ILP`TbX}7{^~Z zv&er;5I~g7lzJ=>WxzE89b~fcjnk~}|5o)BZ~nj^BJEGgM%qJ8#J%tgyG>4Fllr}3 zH2h|MKg!JyiReH1*&jwcIhLRP?2G^P&;R{Te)f4}fz5yY=WqV_FTWVy{yif>|K91& zAD?ji1Hk_3zy9(kKl?qfn?8ZW1>$3}K``s|53qaV4(Th||ABxQ$w0u9;iku;=s+Ra zLD=WcA)0Uijn+qa9;0%P{x!HSjRL{ddRX=e;}dBZ7k#1`JUR z!Y6>q8Qeo&yDR83#YuEj&Dcjbhb?R)F}dv^f#@Fosl+>?|4aCD#bBI-ZsEykA%_wK z3AS@M_Y*Xe2)+IS_Bqlc%8n|LSjIm1_=@DMy3u?jnP8pIpOGZzJJU}YZ_Pd}?!$m5 z!MkKX6goi?G!j3l?P6rc9vF>3GkcJDkH;O|vSO#`*0|nsKA3#TAs~2hMiR~jr&~z1e6hX1P~}_!kryq< zniSfc+ZG*oUd8jWum30|<2vaEl03ZNKL_t*NvNP9e zujj8n48$(dMoikH%8-Zio4ID&8XqjLGN62sp%l^f@uI0O;FxFWxl{k}fyrpsz&3qX zDDV<*UA(idfh&}luNTHQG@$8hi;eQtk)h3AU$tv2KkLO+`&+h_Kk!a%OrUFJ+w(G? zNz&@8=jTyC2*?8Rb9BpGwOYAxt<{uY$?@;NuCQ1UauaWES(eS;Hj1~b>=ekBg{xaD z5QPvddp2LmRPo_$R#a4hieLg9$jCFYFRNE9R2l*R6+dmniW=A8CFo({8eP}rf-1Vs zYg0EhRyC}v4yuT9;~>0%onm#kNs7FE-q@s^v+Tr{1)&oWs^Dhh;>E}L>fF6#PASHS z0G73iv)ifKs;%U4oJ6GWdt!>aU1?8IX5|_Mr>h#DCsksqUh~h0ZJnLc({f$QIZ$x( z)9Hi~36a()fe2;Fs^MhLfk;o9kxzQ+xFex#zC}t3RVKDg#Ob6tXE!%9ie%>8)i#vb zH1DLtCL+r@oh(W$Fsro?+>XK)jZwNzIwoFh*~uC-1sQAxkF0hiSx43Oaf+LrZ6g8M8(}n-SqPIfhxBmQuB!n1a!H%cXX&Cz23@aDT zR%jMNSacyGUG#K1Nhhn(sB}5!MVIw@QyZU~-s!UJ;?6^GfZUeq3@*EcI%`_yU3O*{ z%k?{+_MO?(^P+m#V1~n$We=L? zfuL+KHk!LJzT5MlAou}uDmTJA$(g zCQ0}m8MN<68ScHjo_T=%c;81Ava}PqHxMyK3>c%xJ#%DxGK<`Q;pta${DS=`@ijP( z7)T%CNhz5|aUmoS%z)#qz5nHYzbE>Ame1s7XSyRiK;RC-qoX5el%vYR_*~!oZzAq{ zauCHI5>C#nm<7{6{fp24?Vo=M;E(^}_y7232iVN$%)Zp|UhN05@BjK=y!qpwee%bD z@r9v-s!(G&nfo%DCGcfgN;$h0U1#x&bOPF2Cx97A5#hU{y8~R}Ek_x<2TJca z{s0nSi@-#tnLDTfY(6mtgF-~)Q|I3kN)7=-LE?!iIy#3FU`C)*4>vPrVMIhR=&0U9 zl~vLaGOjgkE^-iq%Ll`z3~MB*O76Wj$va3zK96nn@!;y#soaR z<4-?j8~^|b5JePMC2~=-&Y07~E1~!EGWo-AWd9F95BolDUMa-JgUGwYJpi>`-#O|KHO;2GuGa zc}mi!1wecysOqgXtYL088{2*G1l0I?MPE|{BgG?CiSNcG5aFsG%3HDJoi(0a7jTZK zSRW`Y831PjE_7QZmCV${H!N`vS7A$uXV(N+T<=!AdA$`?R4}WA>fFsWzM+;L0ab(J zB}yPS)iwT`T9puLS*u2=6?tUiTbY$*R7YK_d$RJQy2olBl2y-H)o16{ z&eHOr=V2`3JEw3yc6Cx#=J8zScF5X5YX+6i?<~zyEo-KA_0*m@s!KDKE*st(alji&2)@6-UOeOp(h|6e875_bu~ z5E_@>dBY{m{pEQ}|J>iui$-D3)AMXES;L(x`fZ$NT~|?;%ZvN^OI{O-6TAz5Mh#Nf zD*ezscEIymu7S~WR&t%Y`Kuh9o9c57Y*)$4X3)3J&J_UKeut}9mvuCR>#9fp@ALSA z0O|vuzW7PK9)_?|uy%w#I9mCo-qkmscjub%T@`l4^)4yZHMM+^VLcnS^f0!kaDgEdUJz*Yc7*yBQ`}~)Xr`JR7L`q|IvuRSA}#s7 z`gAWR@D{3XOGVYi#dB5&g+LW&Oq;9n4XdrzVVgho!k)S=?sl6mr}ig+u5!2SXLZ`m zs*0lO0=x!T48TdX>$(EM_WQv%@8i|-al;UsDPKWjL*GyHEFyg$by>I)7Hshf%{N=N zo$QjQVHg4h5y_q#d+ODl(`IlN`*=E?hJNtu(skv&w+M??&X{xYlIFgOr*zTSMF5+T zAS$3NXl83XG538xO%pK%3Y(Z~9D`V>xGdF1O8Bye41z{$IzW zj{G`|)#n$5P#mjm25h? zP@Q%aIO~haPFB!Hyev!hoI{@Hx$paMiP2Z^Y91;@J*CqwMswHG$x_q>0yuLI)KRp>O0#1DtRz{-S=-q577Nc@6CIG0W6qEz|a{7wi$j4 zEZ{L>o|ReDA=W?fJTPWLKWZ0E6p3YFg5sU~4dDq8mnUH%jKG2Eq~0@B=3X`FehYyj^4f$;Z7({WRgrwXHz!4%s2ii}X1Rz&8N`OGz z)L@Zf02F!yUf2Wx8PWbnulTJilO2U7jVvx8Gnbwey%LVjPIOBUuu1$rbVt3XhZ}=N zN=gf~NB_VU;gsfXFAu~~?a<%+)bORuuU$ITC^RWP*~`6obVQ=X-3ZAIaFthol-~Y| z1pTYupXc3P-l^kn{_M>^{n_Ub`srVO|50yQehrJ}Jq zMuI7cx_}{cf|Btm9)FD(e z)0n=G{nxM{vpNfSPPU8U>bD|aDk9JkCUP>kASoTxk3BsoK}i_*1X0=%PG+cX14VqN zn1tDBiRhe&dWDinHgxO&L(xTkQU>Fwb7EQ411y?@;%wNlL?Eztrpg`-k@rvg{)cQ| z5JY(~8yq9SdOWBQY@nII4z>Pf0(LgvG0l&71ZKiX-~Ot<{e2LWhKR*o;pYAdyUE=VXJblG%4p?D%}`RXs)d-w8~oq#+#e%GF_-!!zpgr)}>X83Lzk@rluRyEX&f(iD_%+vMfyG zW(a4)#x~CDI!a8{3nc3M;l*kq<8nl(-1r)WN z>>_cJ z1XHC2o=8sW><-Y^0tRlBPH+MD>`%rbfP;lJ$vrvC9GrEg6Z=6lLJ}L9!_yt%Yk(aG zQ|f6jehOi);-Mv`_a zA^=#NZx~Dk4g0aGDcFri%=#wj!Y9A z(178zyE>Z2dt}`*a zi#uU)GWFXV+|MA#3EnC0_Q#`x02X^tKNxk)4!A=8h*9^rQYfhWOE{ji5Z9%$S_o-|^1W166Mzzm1`Vjw6H zUV&$$Cz}WE7q~-N0h?WVH~_CeP``+ee{?&(OUtZ@``e>oxZyWrB9{YXhB6FBCz1tj zxIL7MpbWB$xjthB?DH8%If)O4Sr|a&rTV@LIG8`)kYO8sc3DA%&N#|Y?B}@ z832iI*;e&d3DsAmQbmH)2*Gj_;BR#_LCw$7i_0e{>xQeSwCH?`)@p55pG`%HGnWF- zdVw}p;2Om*)?Gp?D`=cXl|fi_a7B&Po%g+K+{yC(`eZu;Sc)3Sq7>Q?;^Dh;94D4y8@e$_vO6!ZC(YHp(6k~EdaV518cCwbym3nGrt2{ zLI9@4+iOM$fpef{pH*xS+Hoj<`Q?eZeTFK)S<`uce<4LVe{^wdo9&qZ=zP|cqg&MV zGA1ZTwP4~Ii`jOqP05?W>$2PioHQkc3$4~A1o`0dsTYbXOq8!Ov^72-jVpBWGH=Sy z`?0?3FQJ^RV^@(1+tlKlm(xpRCpT>l^}mK{UDOa7Q1xOHo*nXngz$N*w==tDZfpsk zAJmLmXlEopn+p_cn_A5W(z%wGo!FQE&H}6FYi~VC!4fD|bE^z&rii6S;RQ#T-{BMx zPN!3```d_*<%}ACFay3Au-bW{p7kZBp1U(s`3l%#>gAlVDe4N$x?FRCh_QOk+TL8< zZ!Jr%;+l=u6!%_5#gi@jWf(rQv)I4YK;`Py=u9zy?b-Jg;>pzy7b@u4gi$TPLM2Mi z5njo&n6;O&jS6kjqzxezVps%RXYNxxh*dZCTOj~KB}Z*D3g_akTl+5Odyx$=ZRUHZ zjOk2~FAXHG@4JAG8JD^?FV>(9$qLm^8LHd+4M=T&hGsf8l9kOtI7cn4cx%OQ)qh#( z?Fz7p@oCptiG-MQ@sQ;;a%BN$UV|QN<%AFl7`4UP4i;bX7hSHs+r|-Lm2`p5FmA2a zynw0=@NLGt>yF@TWfF*2j7voD%sb9qUV|qB#8fEQdM~wJ#{vNExTn5Y2X|lnPs?Zj z+}()T-Es(CqZREbL<~R?R&uljzW`Ze#9NwiRd+Jr##`|7394l?EMSS zBPb9e@L<#>q9ZM;#z5jb!6a~HCYs21z{$a+K1UM;`MskD4Dr-sfGFDy$N;dh0=>Mk zu~QpFe(mT~0+O1j&x6w-tfLR2HwF{93OK=uR09a?C$ca*T;3slKgy$91mCM4MbvD9 zcSegEdhfsq>CTaa7xNBKg)u|*h5_hgG3`N#1eoBiP6h=!5V4HVDD1?9^?VW-&8$qo z9E_7-aX_3$M^9!Z#qV>JdwB1p0MyykAUjq~wlidK5&#DCj{6Bl04YG400xs;lz4A` z0L|b%8UE(ae({r^{YN5;@K>|G{+mDl#h?8A`wl2Y^8=883?me11`#qv0uKO@xj{%& zFgYi;?=cnv83af~vs#oMLZ>->zQ-?BZr#;vC-T*ZAHv-+K>)ooJoc0ndqjf|QImrd zJ0UkLhJirt#JJJqk&-%r0ZoX~)5-kc%*EQs0qGaj0}%ivoZxUA948T|W?}0on*uz@FY2It6-|dKTZs{>jaC3}gRF@Xq{(v2a}AGe8U_5Evo@{K0Wh za&fRF9RQHL zPyL;M#AXP&W3(Sa-a;pV%+@(O7^DZLL_R=BZhvg}9Qu}H(6sZhqu4K=Olg^RaTpv7 zXz@YsGP%b6wxezbRdE!lers1v;j+0~A?ud7dXB#$ zIQb0JKIB&A1wM7|Q3GM0KUN6g;;3z>|BXNp&)&Nbd4(5N!Uqq0UUDv*$Be-p=ChdUCT>n-h>dFDG5hI_6!B^*qX4%)!jO@!P$!4C(T= zdv`Aa$Uu~R_4;&HFjd?D6m&?wsf4Om>|AwHo06*-A(kL|i>?oETNTgQ2YF>8A%w0` z0JRipV=)`HxMD7CnOpvr0fm~jHf+djg(>yZ++dvzd00hY6oR=IHP!{4Z~RH+O9mXO z_j*+BMno&lC{Nu&@P<-txNRHHD^1qLGN``QO4P#5p}RE@u)MRi;UW@Zt^LYd*#?zb zk7g7C$^`L+N^ToZ0NFiPu;^x?j!DU8W}7u-2*J(E#jxbOUg7TW>{z8_1wyqfZ|&(~ zRLwARZj_&)`O+(>w}=OsO&0*gwcNT4Hj`MuLmP(zp4}HOAuktQXl-_YXV1Aj4lIAx zFo-#X)!SETkL;v~u)^2>>h#G!gXhe!lkWN$N=I@IL}fMYq+9HQ-+d>OszP3?OkyPJ zX&h}f=~F!JfysF=`8Crk_JNg@N8?wF2XQ9*#E_0mnqE8Ivzp*ZL1qvPFgRfS8_c~i z#P@59T|aA^2MT4mg1TofWrH z9^enKqm!DjD4=(;|Mh5hAZ0L+6e1v_Ng?h##{w6^1Spw3vP4(t5z*O_aiR$Jqmr7d z+tE1@KycM4@~AjQo*bAlu)hNaGldU5yZH{X5HD^6prh~lcrx#cAcE{(=begSKK4A# z8bqSolT(CcL4tMQNSus))K_9^$iM_RoS0Q58ieUd)7@YFi@*7kzx)FLv0oBC1>#@- z+28);=RW~I5j_c1R1L1wK@|q#;4~RKp>rLGCijkMgp1<<9Y~&B56%!?+y=J}=w}-l zEO1WZDay;JRsU3em6p;J-=6CZk7cW zjI}S;h&RgmE|Mxb2NBFj6y)Q9B81+v+|&3f0Ys(%ab)@m^vZDnPQ;7gk#wKLX&#ks zSRt~&z6V#MlNt8$9xm#ygx|SGm^nUWeLLzw`g`-6@%`()e4SiKX4V6_T2yg%$ZW#$ z1duAz>Yqz{1C(%kG(VWmk-Etq+)X@>{^f1Ffq$wzMI9hd&`!NS_9@Mud`lONk5ubp z`j|eZkLiQy?71ulAUhhYP=eU|^{%|IgZ1(6RcRr-7&`E5D|bbmp6&m)?b?e1npz7` zkV~lApY8ZI+w*4BPb-W--S(YPLU{H9&pO)vwGLMZFID(r3s!=W!}j_`?N$5l!<1+1 z>=o6@FXTD5qMg1=h8F7Z;)NbPi;ei(rImgLY#1?wb;PaWiIqMj@=>>f8fUSu{jcA{(MCw}9-K z0_Ae4+Z-O{?1hUpbO}Id7#G6T2zE+!MQPBQMsoFS)EdX-#%8cQ8Q=z{Y<7#=i?$70 zIcx#p zgUi`L?&i+94rAjVtq2cW>1;qK&!t|V?#1C($jzm&-YS&!utp9Ag%FqnvAe+xIhQCk z0Nj@1TFcBmTw}-YWD*Pv<9P?2Rlh_sKJKB5y8;8zAUH6>h&Lh;e$!)C4u%Mt;O_Iz zeO7x#@&+)|gUF;RBFV_vqVkdAlY0j~i5Z(1*4W+z0Ajrnm=tOexM$2xdw35Q0=X{+ zL^sTx%M)viG9``9E|fK~`(QQ#qlm*r#0;z$dW-<8N02IHk0;Yl7_$Ooorp7Lg*m+v zOzsSsR6p(Uz+lw?arGf8RMbEU7XSpcjf!fY(F?8?&^rRjE z5Ju<#TEG!bA``i>L^mVq;N~1%5;RJTfV)Pa1QX^HftXGTg3F#Kw-F49Pe1+nAO4#^ z{RIHm9q8fT{^>9N6$e1$h0H2v=vkuH4u(EM9O%P@*Y_s{E_D?=WMluWnHG{YTs)+0~ z`z^zutPsXb}nK2Gbt1Uv5`3wh^EA(ya)g=LsgF~4=%ILR6t52f#vC2x@i1kP_1;I0F>|Gawo}s zhic_?dOQIrCgSCNRNE+;4FK;-TwVZhEf$Ci06P`0q5y!00AQIG04$7Z%vcP;iXqif z@;_Z{=~~0U@_Kjdwgb5@7Fc|0CzVkNrF&0y9l)=^#WXaT^An|5w)m&=dkyo#1)zKS$` z4Ro+HuTS1qQAVHbNnb57+u#NP0CZfRA(XfQrABMci`8Pc=Pge= zmEYmCMwy@xCWyi+C9TGWYpOJ4lWPH2JN5j+#(skcXPop58C+&=J^f#&&HV7f z8PaNUy7%7`x8av>$#o`t_Cv3W7A7siW9&-FY9I+ru>AC_JqJm-?n zOejCg{1T+Q9>Cwe6<5O*DvJya2)d}cjzzxys6G2HNC5hK zALWY$aIsFF@!YV@>6z$;i_)IW?s+*~H)PFdCoCa!k@B8GKyk2jK_$zkpXtIt{yUn8 zNKYqsS5@~MLNN9MUqE5?1Ru_f!9Tap+;wN9Ra_lauj<)65K$mAJLCC^ z0CJ5O7`6y~Au#j0jjymQ5c#rf)_mo_O}W!Di?t15UF&N^xwT$w=i(#ZD~f9AULj>(;aY1&xY{QIx$zRU4NGZQ>jrCGC-tMyK%b>*05>>w zre@6yZi}#h)YjSAR@4gAs$c($HQMh=}xZ#B9&+1$NzJb+wuNVtjpgn1yDIEm1r zwlh8Sqy~(76c+eB8>tT>i`u~;!tY2_Q;g(_owJ¨GiFl!Rqwg&B4wDiz7E3}7s3 zhrLT8hcH`G0a7GPiezNWVxUJKh@Sw!2aqOp7P5I@xd%fi0gL&LEvfGyq5$y$Aa(+F zE>9Q}5W!jG$rWZDu$V6d6PZo-;3u~o#1;LzpAd!J37tR+efpE1fBtX&^h=`CU;XJX zfBKhym?#7HfX{jmbCC%Nkz5682V;mXppJMUho?_i?g7I*xI7UlERuk20ssWpoMHqr+8~ffZ!q^@B2nO^ z0v*3E^w{?gqd}}6c@QUt0}%)+5Iyy{SMJRY${pd!z$OzJBkd?o5HVYnjf_(e}ko9dp$W;@Kd#Z?!D-*${2@ zTo&w>@CtX}ZeQ`J`i*Vg9mKGOn<8DQBn z69;Cd5G3xhdGVH2_Ufx7hZ*h&VNvy*RkiHx-M#3uvabOUO9(=DFZ?SY6uAvT$nLo) zzcwa96oAd;PzYg*byyNHFRGg@TOiWYsq4C8#@G+TD%vt*>55%grKO>D?IcYM!3|>t zAU7VMR;*LG$(pl*n+?N-760ZUxhmo>gs__IRb~{z>K>Eox}{2gsPwv$udTD|)2zZ= za&wuf5j%@zS%FrqmD#yRrJaR6ZF;UoX;uE-m{*I^wswX~(zjKy*(YvTYCAA*7MhJ9 zD}>NBs;I55?b!2C6`8Hu2q1){K zaxOH=%t}y#@+M1XW<_|F&C43|ur9@}IC?J&fI{mI%-sV8H_vbin`P+vkq8CKWvS%V z@Q?`RP9>Cb&g-Mx(&7-zZ1ueb9Nzyg54Znm2!x!Ao2}X>C+>1~dv>M#?xp1Sdps!A zaAf}+y=WZv`@JfOJtll2{HRDEP#Wa;c6I}0dE6y@iTNG#0Tj&U5jQ;x@IZ0{d$1!5 zB78LT3<9N5Zw!l&ir@SA2?S&Zg~EmV$pA8)?X~oi(OyJ7eWLP6z86d^nCC&5k&=lK z9qDn#F%v)0c=O4t#S%M3sLMW$<3QvrPwqz`ip-2h)ms6hkE9H8Kt+WZjzx?BNAGMz z+AEvm*6m3MN+fFJ%t%T*;kTr(ffHOoaNjW|i^-Js{HW-`rn(ak1|a6%+!z1@3Q^dB zu`mTN%t&N0L>OE@Qz*e5pfzAEdm=%pBeP=coVS=fJ8;`@_Gn;O2L^m_c{CruCIs34TJ_-8LEeZ(>cugUIhfQykUiebbbu4nT_5k^tooI%~*PY7)(F^mM$9qcvLGF zCyv4ZY+iu6qgo#*WdLEhFxp>LGeu^n2Eb3-Hx~4%IP1>ar=Hu%rOGVYeOOry{!xTLV@f_89=u{khU|Q`il%<$PJa5=#4hE2_19D1O$99;C>= zifU%9x@d(W;jCH9Z3!2WjWSSW4C%ZhD#|7+`XFl__+)HNDiWU6m44CY)RNmO%AnDX zw|%{eZ4^dT7xa#|s zN}Pc*7wdX3Kli9qP{zDFPkPa6g+>pxiUN|i<5MQF?ehA%I}gaJfXhIQq7a(1;6i=Y z47*jWR?#O~b1sA?4i4`a07pihmoiY*QT;iV!g@}5MqPnRTD4l8bz2o}8>-;TfmLf3 zeg{JE0I*~s1m{2<5rtOg;;2)qnT+A1~}@Ioc6%qIi{ z_|>sZMc&pGnzq%S*Enk3OTG-L^2ILgoS(uAg z#}^u%x3w0qT4R+9OU`xrUK)XL(fDt|tW8B1tKw=9o*xmAXLrri1?obTOXqs3ma<+5 zxA>h*tHaw8A5_i&dt5Bt;qR?4Q5wY6q zxqETiwV0j50mveNy z;^8Z7KA0+2vnm8@#Xi*fzb~yV+^T#XyBCbLbs3Ec$qS*Y2&@hESGdv^A+a2|Npf<| zxKw);NOYxB%bSs1WkcMU9Ii1ROBL>`zpYE_PBe^(iE{n3;I@r1<;LoBZCgXcTDIj) z6v9xQzL(e5D7;n`RRxY4th@q_xw#wPIA93`8LAVjT>D;5;mv@t$iCM0yBE@myf$N5 zjG02K7u#-_s|8~55m)XuSC&NUg~fCMg`D%EOD7$G%(-x}P5c!$$M($dyqJ6N0#B)a zDXi04POjS9O}&LP&w^!VP$6HdQ~3~b&cmC3J%94gx)2uOv?e9v8 zM(?2}N8wwEN#qCSld434GVk?CaR-LuK9VQ@g6$;we~j48^P`Mkb8oW$bRV-D6iVos z=Lg=4C#4Z4B9H8@94Y+ zsYFr0SW|FK##lXVuI?kayxK%{Rh}dY4kb zv5QCy%+5m8TL+%ln9yOQo}I+pf~LEfCQdy?XPyWhY_B*l-XRXI-N+hE+ zzTWG>*T!z`krifz=2zR`4VHZ{o%gEe?Fs-7mw2o}5@#~^5}vC+uWUH4G2;63iu-(H zBXiCd0OuN{Tvqm5Ph~0b+MoSzlh&nEN5A06OBC4hP+Sf2Hh1k%we854eR1PDT#n7=^Kx?cd71&_xZ6Uu zVI^g2OUfIYzof-XRW};aH4zxE2vi|l8yQKbQwTx2E>{+_p)Ta?W-B+T6~PQmEX6C| z>Q|2+c&o8AzH*t|EWFb3!iK1pd1hE4aItEvV^C;FA#SjdGj4sG+7(0Tu~!45tUlDHPY(5>Z%E4G?ry?^NcK=1Ud`8a4ZDB#R!3j9Da83mK|38wTG}8h$0ga0+`ve z7iCr`28K*1UonM&=8OOe#8uL@dGdm1CfY7VA(U8(nV2&2?(2WGeD==?4CG8+tfq5O z7yb@-2J{|#xh1gbXT)F6>9&vRrU`%@)JXUQC>d+NQ@R(z{P+pYZ*QP>bA37*BwS>=l7bMDHN3M8c*<;uC`m9bm$f zgOqLs3I;H!Pl8(|kh}6;@`@Lt3~4m~mm+KHTCk@~F4&YjRi zyuk8IcQ^gt&GvflCxD3nfz0d*#AJHMcr-365eS&z z(aGFn3C{;8v=e%Q!3jxC0HNeY2K4kW+vmWeD@2|M33^nXK>rVW@75!^lB9`!ZbqXs z7?GE%I+yO=Y3*ueS0k<7_i2B<00GjAo&>A}EmoKr?di+8R8?j~kRC=e*MpNzMr2l< zodLRmK3xt}Rs`wvi@B5G{_(TVU`Zi;k0(Wn0tM5#WtkwXP|*qOs(^OlY!pCAwe5H! z@#F+11_n2#a^OQW?N%x$oz zXV8VuX`H_8?#1Go&@4DCVez_PxtYVjL$Ki6eobh;Vj8Pk=PS?3r|3nb4rqhAQTjLpdnEQTslsp zHR#ibzz%U(d?ukd?nExh`N99@JerF~d^a`kSQt79EU`rXOOAm!oi14RC52!z4J%3~ zhaFz5am&|27%9K*)2Q`t-o)XXh8g&HPGp?QH4(t^qJz3a7>acv|^T z(hGoT47d@WT7J)F+R-Lm8zk52!rWiOLWi2ebr)7qG1O(2DyY3%FDxXT!fX<*#|sbc z^6a&cg@6rIvJ$Ohu?R&K&e7cXCh|IDbyHVAQ`qDI7T#H@qD+#7nHSc66|&N5pNvJ3 zZA%9$w4-aT7GdFPm2qmOrkb=gDbH-L>(R`&_MZuNEdf_dx}qqTH{pc1;nn^dNwv}p zTV9fv)|M$(IQerEi{%pou*3kG*i=I;T&A3+IfvXCyhW3@Fuk}`_cjI%5kTq}Pj>lb3b)f|ZNqk4LU08DYN_dX zc`_qg0T%umKrH}hn5S9R8mPaI3uscaWv`OexnU+EZkpL~4;eYzG;3*9B2N|hF52GA zEUf?#ky%%}(!sDuGUZ(8VD7FL9WRNAr4?VGrd6Z8x(6;u$23isbO8l7msTdTLSI^8 zk!f~LthkK3>ok?J^`c!DE1p%$r=^ez=oIhE?73})HdSn8(QEnD@9%QC#2Bl#RFUpl z=|zkFRIOL1sUTL();lr;EFj&?T3SxgqPH~<-vUnM#cePzAYdI|3Sqj2+v@LE0A>hm zBeY-CqQat}zxe3K9qA^S2_8m*YHeC(=-jk&`L{8HS!}C=`P^vXGJgCG|ebdg^`*wkWy-zX2K+`*fbFqvR=VLy+mr6ZB^IC1@j6agk|xN>yPS!KF{}! zWe&t`I|1g#2W*8Q_h8&i14qN9Ci9Z_55SMd$#mbI)0DCuT;O{_%Q086(kORR=w-s=r3w;h$5=qGoI4< zV~qc=de_U>ij!!2gcByFJ0f=<9G#F8lvvS=Ae(lGCrZz(Z1U_L&39q}Oax>3SO{^V zrm(XgB_hUt98ZPlh6#za>5#~GsfF>+-24C1^o6VSC4EU>(wFqfsRQ;vip7wddOEfH)#WdU6r{-D>lWhI!5zua8uvXs(>QR{Q}jRC3rT6 z!p+Am*zuB#lWzf+mzgr&sYC#nsNhyUCof?|AiTsZ!i4>(6qelcn!t#Er_$hTvx+Xtn+7ZtQY9yf~PGe z3(MYl9jvV@^KCPhuPdbW3a)i^s9<+n|C=p2aeK`?C7qE$90G-$vs=!dx1m&i*~u&I zXfv|z-Y^$w^Nc(@5+Zt|)0(qW&?*wk;Cc**#Zvq$0?bm+*5T z5Rv9=?uAd(#&(w8-g*%NxCW0dswIZwl%_&KYM3i}W$qzo08P_WE?CjXN5+^EGsiA^ z&duWJR~_Z5e_TN~(&dspU-Z&6&6rZZ+s#C+1#8Po!-@l-nVru=A!MbLh`C|T%j;NL z+y=un?pFm@U5W1X+=yJIPgaSo1(rodpTkl18A{vL$%%*8-nudrP zX;v)n8agcSlTKPJtdsVAKV7DMyU%%XAj|-T0ydS2UR2w&=h()avzv!m)eS^ca=Kr= z2^MM0oS1~g%!p|m$6eQz0$FCBS6Ia03J*&!7ZFiaRjnfT2*}8@{~(qy0vUM@ahQQw zNPg0ZnP=P)Ff$H|{Mmd91ozp<-TVLj^!Oi`IZvkMZEOLAjo$w+I2prWkey%xT;&Mg z0f-9kdWA)HRsj>>AOnE-_r#Y(AO+~yX*BFQ&Z6m@T8d{OS473z=*d|?&&*=}oA{N1 zzUqZ68Azc!n|b=C7T$-DFOv40y?BOF3Mx{(_@)ZE#dNTi&gm*e|?B7mE4J`w~H z-;aK8v|~O>_q&lA)`5uK8$lvmoM_bFxf9MBqXGxUBz$tTY6r-X?VvEjL_`q-3kaUh zPv#@+Kz+~FDKkK35k#X&FB4&ci(==P1U_QNKmFe1P9!jGVrAZZu_#|0jL*?|c}g zZxxMej64ujz^0LW5Hx0L+`&&|E)P9MsP3Ge39T{-l8$eQPl^*`4>-{Wc#Hm>suK^5 zB=~;@pzo8s`Hi7BwVnsipm5k-hcvpW9t^4Qqu8Si;HNv{$ zM5VUPt3xcLs+rHV#|}Vm$1`I zW46Yx+u1qF=Nx=<6&j;dte8=`a%D1a3^i?4Ha73ijcJ>+w05qyOw`TzWo`hl3vPz> zG69&z3$XAR=M$w#g~PZQs%=+GmQsdGy`t%3ZQWlb{uuhHZw1Q3773J$;yUu@|?;1h7VuH<=6o{azYH!E$69v!LTxHq3)7}7K8=g-s zVudO;a9&v2aMRiKs!bP`GS~e1x{50Z=Cz(I551S5)~32G+3C9FFAi-Gx>u^JqnNi> zU440Z`KP#4S9n<|d3{{I-j`R-dbkDMMTofi&bf*xGPrV1wc7l)a9$_0{g*k(TJXKn`Rlho)2LR(Z=A8HYeV`ctsuxyW z`EtVH+a`ofBuCR3eu z{jL;AAxvhooLC42Ni6rl<#KUzBC^SBGHE4me!*6tY96AX7j^S-90Bb2dpBq10vFc5 zbxAYNG-MR!QRaf61qv02w8@B8E*o<0y3Wl*2u;&aAc?Y&twQZ;UZ6vB3psPcz4YTa z7Joo)I4=&H#oZ4SYW&SYE<-S8a`UEXJbR3B`z~Q#tQMKJ5P%#)XdBUKnla7c9AmV} zVjHo*k+p#3a>p{7dYJ6>%;s7$ue^Uq&wTv;Elj!{<2d?Kfw)hZ>Alefc{x>uTh~e6K8g)HNs+m!Cg{}gPwOnClN7@bht=r zVP}gyIRuk?-^C~Oq(TG-KlTw8Th%?&#k}uD&vsx*(CiW&U?`D5$dOF%dpfI*)_r@p zyGQ>9W1|c}oF+m9KaoY?NQeNd5PL+=IJ@Hx-8-U=<&nBc?Oyl~ggr|z1eTz>izE&c z3NFvCN7YEu#`rF!zz-KwRkVgq>H5Ju4R6Z~m>{~dt-tN#xAlgJyA52|2Ergu!25iR4wxQKTnX9F>OOgoW_r#tbJ zM(zY^696AoWMUNm8jSX)dw}Wth@Hm=_*=OT$pe8RpA-ZL`*TW;d z|EIp^M1Mf{Kk;~hwkAUC3h%syoJ?CFh+Kfy=^YUzJ$Jik(;jag2%@Zn!6Af+F`Dkc zB#4S<221?b(i3>6s{X@2;^A+hf8fJ!2ml7dPUYfyN4WT`vpm4xsx~6ec2vYC)o-Jm z&c5rE?&LJO04MiHlM8FBMOzH%nD)Xd{cqCvyU1tK$LV-M?7bTtf61uUm-HolNng@m zXmZOyCIFP{c58M+m|X=n#GVS!!LL~9>XPfz zw~GAhhUFT0s%Nf!4`10kRJibUX!5FESIFiz{~E@x!s53mwj8*dVF;U=a;{}A)_Jvs%bx{D!&U;m z;A%7U49bhqGLXyt`ODuJmcANtQRFGMDbN51GI;hp$FSRsV%hC`_MG$VQnfhZxfwT2 zt|~~Ceo9opg6wYYTY>fkoWjif0=Q|q1?;GNtF5Lu5tS%)1#}AwD@vLsgiwI6g#xo` zv}5tktAXmW=Mu=S6{!`KRG^Rojn%gi(zch=DaOb|EKPA%BxYL_*}W=}VWuFJ5}KwV zCU@USR|=#hm>`zvNkGn-nf0QcXID5kFX4c4&RAe3FGMx~fVp4NCFh({nrzzldsiuiEV7#7Rw!39~{2$?`SRo z8M)}YS4YbVU|kLUqVL{y-K3LZ7l2+I_ z=PWD*dRyWl&J-;GpnzGfAppn}GV(M{#n0cE+D0lpHY3-c$2>pJX8TJc8DR#d7rL4K z6>zoGA4wAk>~9S0Vv^n|PGW#~;=z=tdoX&>%H)k;cZQ=&Mj}ZV$1@Hn5wW~sN~$8F zXMZ$v!6*R8lp66qaRViKmONv_?5)3r0W&G1x=ltM%^h$EHZ&=m*f(-~<(cnFTOgQR;F6l8x_48hujL|3ePH?&9B&yGs@fs&AM_BZD@;Xy{lH zv=PFndzQDr52^}!V%#&F(5gkIi}{X;2v8nLU4-%Qw{reY;@&2QCyMV3lhH)hcszk3 zpys4-bQhr$odtc5_=cbUv&F#tYe1P?K(4JKXnJ4?38T16Jh?`-y}0|~x5)>>zlVKL zd5kz2+)X=a)QO;wllwP1o?Splkp07(|IzHC%uzDnly->FF~PHt2lWnzk)9g2C*lmIi9h1}6{-H*-TyC4e->S>AO2WBhqePyVzA9V z`EI~W2%_DtWGg%rZ`S6`qF1WG!Z(?Jj|;zMCH2g!_L8R@U&2BI@XJCxDL*FVU|G`4 zB&pTbR+wdlSyJ-q#p=x}F;<#1YiX4dCRq&#fOstso5DBA0s*ra*>)_Z z7tEm94om2q`OJo-W|LK$BW(iwX|r~#*ncA|RrV;fExb_k#+fJRrGw?2a5*&d&a`%a zE~{vrPU{>iysc98mZq1lR~4n>Gh?e+4N|I}hIJOrl{Op0&a1AK{Wn{KuJP=-5i4Ws zYO`0Sfl_V860*>6eecXPt1>!;xK~GNK1j7yTgqWJ!7}}tjTqT4IAwDLI1s#I40+*t zEST1cYOO%cbtzY{&F%eDX)T{XwKhjzpaToSv7kTKe23RI?prY(;3Yg$OIXUS@XHlp z=C+(|`xiuNd&z6SSp@-Wk6xC!Y>8j=WczfxzF^rWtYAvGuIuxuKq^~$(F;6p#^qkc zS}L6Z`24nGgRgCh1vW&jEs(Y8=?V>n_3R1=UYl!~w6itp7}X8b3)HVn$ZY|)<5KI| z4(|pu$Ov1TmEx{OWKCO%uUF;juSh&4m>h2Il|l{Mf)*iQmWaz?`=nm1;eQ=mtpGH{ zlN$ouy&=x*oG3P8IGeQKEsEEEuuvavmLSUlU#Y?&{bKyg6DO3g6DzK_8U2}JC zI9Om}0I`dC38aWcf<13r1;j3cs5oC7fUf{EG z(9DXP>cUc_UB3e`)30oHMVv#rhu{mHKZj7FA7*4?$~hm8M`%2> zSTyO{5C7Zg{y(sU>^_+zpdgRG>=cby;<-3K%)N5k%o& zj4s^U#Jq<@_ot3J#nBZ}k}|7x9VuaOeQP`sB6V-h&p*i_KpzEr^+DttwIB|b_kf7A zLYRrna3+_F$=7oD-iKt(8*#@f)Cv5)gJio4IQ!-|74cJij z7DRW!Ps3_~5Ej|yj6fmeT=0dN&-E%V@)w#iazpGWjGi1YQ)voah!^A~FwOp42pPE` zRskU}7d8+!9Hkl#udsy5j-4n>?#2E#O@XPRsOCQVIp$2vo;`c!rt$1P8RpP(2t>S0 zB9^9rqZP%dI18?^k{V&qw=omTE5n?(bAIJ;ZN%3r&{GO5bg;Rn%Y}t$RUw!y>8oL; zE_!Z(87uLPs#E|fovNa5Oytex{wl&`KqXIwqNoL6fv(!NEigwLTiV=QD_1M$Twl;G zjIcJgZr<%W6c5J&np7fHg~o`od+g#kjBVTMq+Q?D@~c!9FYL35A+j_qO(lX=M6U>? z)#lZ5ii_g5AH#`aAh@Id` zx}zyOMj^0#KcW-t8Al~1Eqc@k!_Y}GzQEY!?42@o5vm?V4Aw^_73t*3%m6lK)xZK6 z;6yyB61yUrXakwlBU>Vg=1 z(CFN=b&w~~9Rx@QasmO5@F%t%OQeT?3sZ)Xe_%v)Au%`s7r~B^%!MONC*~+H!nbfq z-CMC}0Gv9y7!hG2I73l*K6rw|?Q9&S|4OGn8urxxYw%C%4}=7;&|ua=q*GFcrB;dE zA=G?yi}&tB-yi<9p&@bAd$k657AEywgo6_sOaSe=yI+sb7mnYahqrf!4wT492%|Lu zb#EjdT^UdpF*J;cvr}6x@?~w+zh!S^T za2({4lqfxVa}p<)F-oiH`#a(DxD$EOw3D9uKiNa$&w^?VM*z5@P;E4lE~{!!C5+6R zCR^XI<}{)%%B@IW6)mJfdy%!e^19}70hWMtg`vZR?6bbdtEWmKvw+l0gxOGXY>f=K zu(U2~`)%bq6*|l+=2dWBCFt1cL6rM`F^0}L|_C?ny zjq~Q{1t(~hWSSecelAxnHmSiPR~09UUF~MEZrZs_iM)>2Vru}lnM-pyOD|^XRx#H+{no*KxtsN6O$NYItkqpp;jXC| zyi(PC!;G8f$%gAUYbac)3{jJ3V|!WUg!d`+XkLsu0dK3bt+wuB!fT0myz1j|f@yW{WrGy!23J65`)!S=9WGW{pFF(*T%;6p= z%u1#-^OtMT#sW;tDBD5^LQ$QscH01Is7sv%XQ?RI)e~lcy?pUNGc2B%1wze> zWd15Ww#c+?;jmgJfIy)HKrCol2q83F1mg-cMxn@TA$tyCVJ8M)KE8R*FQQkVu*T3V z%TWqBFGyBtc?N)KvKpzpBnly8?rGb$MKh~J7>F^V1XV^3Ar!&8g_Z~eOg3fD_{0C= z-~308L_P ztRkHWprh{OZt!s@(G^kP9M$|F;+?YLfY<=S?trKq-1VSON;?ol_sJ#V36i4UD-V!_ z@y-E}>0$wT|glD1Nd&#hUKH;8=RwoWc)Dp8Apc<1~J`( zDbfenj%a5@>}Kc`snbWIfh8ID2c(2f0Z}mT)f&~E^B@`>?gZiiXNM>d6?WkYbkHvSMSCEA zNng^J^dh;O_8j zuv%SJKnoQp4=}Sltz*Xx`(y~~OOX-=(Kh&zO*YGWF&8niz#&gF(w7$&WNEFtm$<7r zXUlmrOArwHzAt)Vb1b70kFvx%C{dVrhSo}_&gXLjOnPZzgnQ;+z63-{Z+Z+Y8QNGc zq9ZWKU1m$>WRN>Lt6Gn!5X8iZ)f$K}oz(9k<|KlT%KKjT&me|JxYAB>5pWWKCQ*U` z+_@WM5YHg#WjJHk15lhPM1|YE1L&aC1Bnsg>bete%m(kG``IlEBWZaNe&G0>>wz$w z$H}_8&XZYE28bky$dgfIo=kVr9WjcCD0VEFL1g#TscVD{kq7lwWHRj)EpY0P6w=Y8 z_J&9Rc0V%!k3ayQ#N7Fw;s@vsdJy@+a0dj{r~qUFB!ZGVtOcTA0GQzbo3H{T7ii;n zFqe*=42@DukO(t=?C@kDL1P}=V#nXBJ~{|Ei99KG5P*fu0T_CLk|ebQBSjk%?}(XY zu(5$;cq3v!rz(u7h|E92-ZCa4cO>%zj2s3efZg0ML0wE$gjj%NX2O&5o(&_IVP@of z2TZOF`iqzmHLgOOJVg@+gzzLB&B5YkA}Ww)GwRvh20=6GuBSmU!2wfP10(<-g%5rz&?T0E%Igj;Uo3^^ZB8pjxj;fpXj0SXF;{>0sw_t(nJ7PBp2#|nTq9U zeoW6~s6vuz1VBy$aP{VPStu7akYZglgj!uLzV$ZM+%;W&ym60lJ7bZJ28MJc4bYA)@!O$fye2XHoNIbKY$ znIwTW>xpXQ(*5PNFt7}FnSOIiUhEyYsbyTzg03h+*PFWSYGx|Dxs``OWeqnAI;?y; zYz-bL=_>=rn~i|1|mQ1jdv z?PW#fmH4anyZ*42wh#e6SMqBA&4sU{HlHZu2HAWq_vfLj%00U=!Oj2IZGOF;>pTmc z;ih4)w)3`|ueEbwLft^3^}`A*u0Pis<80BcEvmIPV2KF1c?RBMV-=?>dRyW8+Qm^T z6z@4AaL%Q{?pr4KFF3W0l;45^0AV#bG7jcwQg|fH$k48O=ceG80WpfI=pk+=`t1%+(4Z`wD7cLB|R}kaKQCJUeDM zGPqmL84YrgKnlPTdyy6vSiRqgxzvS?TVf!>g1>}?%`}^(s$wlV=vyGBdS4cJrSQMz zJQX2YQYp5&RaW}dN-|o`R&;5LC1DX74}dgH0ZmY3l4r}WaLgV6 zPM+H)`1H%?Y90D?hKMQR0BLbP06WE`@Xi{Cj{x(|@B#SBl$n$xA;EYDoMAm=XTB4p zGr7osGo6K4I}r$FurdbqhU~!R=B-3eGLY`nzk-SiAQ#bR$i1drFDEk>aUG+nf;-`( z(GC@5z+m<`cMKv*oji5e zo9l=m_FQ1_6->#9Ppy{&nOJN-puefq{uN2s_AGlY!iz-gRqK z-X=v0If;uw*~zGZIq2g0t#DLuEbgQ;<(@qEwF#3bVd=#OwpdlFTj zgnZClVfIns_gO;%=r_(62Ru5?XYfhlugFeGzoGt*WP1W8vxGe`2t+CB5c}Oo50jsJ zd1&?gpYHm06RtuN_I`jWn+Po_Lg0U^`;0(ZmJa%9h*H#qV&^Jpcc zT(gAc6y`s#pbFP}{@atEfgygD;PWa(wK==&?CSRDzoGC~P`9hAt`1yf-u}BLQf-TR zjrN7re%D64HE8v8d7Uwbm*aBPy4TteuFARcfXw-G19#Q@iXPtd=ye79E7QGJ^rx}Y z+O&#(Z`$*T%dQ~E>jTTdS#16W^ql)s8GkQZ@dEX$9~Lg;4WyM{op=kLm9K8Djk?^X z5D=9}cyK}>P=I^h?A3q4DSIx|5&&*afy(?Xir@uHs?tB@U{YB^4iZ!FVA&hyqMZdmxXH}33n7IHGTJmXA{7uphWU(z71{d`0s^WR zq|*!!RYHv~0$w@iSX_~5tduioLnp;?7w6uK24VMoEXqy%^r*f$(qiTD3*tk!I5E|zCc-qR$QwZ4T zwO2ON)eK*JNDCWltMFBh&+MlVYLtNOIFii47U!`GVU9@Qxws@!m^DCx7e-rgRkYGI zy=VdE3jAbqJfd~TW=xrjr)S8>ZVpDEU}j9bs>KCRplO<Ly^F2fXBncu42r-oJd_;^VVuD1nH@zHHc;t~rfTz&_ zn#3bUNZ%7qOynlOku-JeXWdcn@koiHI7xhV?;Kx))Z_#dz?cMV8hiPu`qnwA9at#& z(96jHcQa2>rZe8UwgmQ=BQ!Y_5RRaoII|2uW4ISdWD^9;N{BEAdbPbVcm3cBwT8il zJ!pV6%*o+!04MVu;ltU2fD9$-TC3=U-V@vzqwV2+M>^^oma_otfMt+JkQ3Mf@Z>B# zJ^(!c=Ri=x03)DrpCq0a0&$I^DeYAc40D?VCycG|Gb}<9fs(fot{4RjFv+tk zDIVca^)k{XY@`Cm7{LY?<~*9QJQ2I;Bf)_^K%g=DMPbxUqT!53!HEGBAnXVbpKlN2HI9iR+Pcq9nh$aE1QXZWa;_9jE}77#&CfT1IK4-%-e3~r5& zZ+m$^vVoCsP;PrnrX2~6-bMr$79ExL$`@xLBM?P-PB^e-VuE)T4=Mv86*3xOa3e~QVuJ5nGTh8YO6=kvb${S7 z$sOxYWQ{XH)W#G$na&a7(7nfF^3aSsppjhz`?n1I;h2H%-W(qOL=TNW3##QC_R!@F z0C8VW<}DGXYB`k;ngC=iypjpHQW2UtHPd>0*32r4fkLpNX1%tQQ(q*~O37LHSz522 zGjH^^GKDqgENQe6htdt3?uM~NEdW2C*Uae*EL5*jR9PCvzE)v{+7q^wzTg(2vT113 zT3fq6w})%aYbC0pitMYT3C){3NT zqr6o(rGh>$x7IIEt)Jh1Z`I;I0W+;Fcqy*-^Vu1{F*v^ z9A^1>D%ckVGiw5u&!r-tW%_e@(s^E4NTmegz|5I)4H8%7s5p=#6H%E^v+PkW_0FDp z0l^pUe}QR=S6wdp_nVnUM0uvCSy;$Ul_M4aVs@k!MQ|3RY(|J`?<(}Rh_NnkWGJ=d0{Jzo zBOVb=(^R7zUNNdRSl)_c0aJ10%o$4|tLS^q4RaOtD!r@NR<%<7TwMaoPhzOR8Bv&j zI8o_uwU!&;@232EcFton^QzA60z6d=v5wBng#B4JC z<$EBKpILVnBj7NwePy1A;N3-aC++=wc9{iOjA?6EFtIp4CWLk;I|) zwPN`H*?ZR>$&qAD?{za;ID;9Pb?M98_6}*Wz(RjOzz_qoj926FgG< zu?8KW#W@O+ zO$6wmZzDf)ii3R} z0I501;j_VjlRJrwlfD;D@RaOEB*8Oqqhu1NK7AW$1f0<)zKtAQmGLY@<`Mjftz}lV z8<-PD)dSd6JEn>G5#V0mck&5fN7IU{9hpZ!0CpvUg1p5%uyt@~0!ITFSp2N;-onRBDXB(1xc3g^MDQacKqqQS z?{h1PI3h)&m{LQrVVMWqGEAV9j-V0VM4-1D!Baw``~)V@4Gkb^!IIS*@gyn|NQJC( zg31Ti?$~{u`}AQ@sjaf1#mH<&j6#p5NEhJ$36>aHey(=<%GcHnYKe_ zS3k_Wg4JF@S}UZxivMM~gDsf-qKlQvi=J1^w;$AgM3>PnLaj9sa-~`zf|tUKQZo>L z{Zwl~FlLLVfiJVBvxb_ewq=mH*9^p(lekZzBBs2GM*sv0@C6@iEX>`5g)JMdZWuyf z@J7=XbM!#lvpu$>OQG0u5>N;=$+03ZD;^MPg}CB{nF~M&xwx&JP@wwbU0ze$79<3x zK$TT3Mq*f;$d_Ny%2HD(VEr9yA$nYWxGLP)D*A1dft#i(zb;AyuCLEVU64XD)%v?8#Ex!Rf6dDtXio2Y6#IkD=q!p??&yXS0DEUYwei{UDDbZ^~N2e?qD zH6O5^7}eXp4xCqKw=G$LQ9}(>)td?&N-XaAT2MuBc`h1^5S)6 zGm}O_2-C9&} z^klJtH$!}M7qOnE8=*(z8>6T^i$UQE2b}cCI7~b%KQfB|CO2x&LI<*0pv(-6hK4zl z%k@Ou!F^shLc23DrmE4fVxT#eA~+Xz;}W%rMu{(GJsBr z#1-01QF#y`SUZc(>PM2Ke(Yp?(4!kgd?G)199wUV%8+hEiow7DDJiLdCIQ`%^*}aJ zL&JW@^a#krSwL(ql9U_-awr|8&1NpFkmH28lkXJ*oB)Fzg&!eNLGU9qI5|9a@~qSE zz{=)P#^fhbV#xq85`kPM8;;yPo8AbL;s_Vv(LsaWw(*l7C5R!iBq+JXh);^6;~BUy zu;~%}XMsQod;=s%aw9@A&rS_FA!Zx0b0aX4KKW7g)bc&RX18FFyBb&^Tuhq?Wfn!F zdK7|7QhN&)aaSWSG3N;cw8HlZH)P7@68j0nekcA+u~%2~$Y4W?@|^s5lIMPUZ^VF# z&(4S%A#Ny8ZHbk^=wU}jp7fU4*yCh3K(FNDHv|Ql`a9vll#PhtU=Umhz$Cc4qB|c@n!BB=xwFZ*OiN{EzqdU*qu?x@r7XsMcO^ zRKG626!qi;0J4fu7U|YbT~$Rlha<509|d3&OjY64Zq0e8Re3!s0)XahWwq4s+pDyy z3sqgh0s!d=Se?S^-}D+lmBVbm4A*8Y0H~ZdU$jEiuInr~TH?$*eOBI;^Q#^DPFu9K zMI*MGuKhz!9UZED5?`%Tv_0>xHs2-cuUf4O)l!XWuin}}M(XNgtkq%N=e=Ioc{rtKTy7bndF|c9FTA-Px9C zYR%2E8!0xMs(g;E?qXMRanUMPkyo0|Q{lVXptUVmP2Jt5U#lzce9e|~qn=B49`Z6p zy9oDJ4R$+SPM-CAs}qHD{ADNX@~|t@DSs0+5K(K@FH~#KvtCfGE1}l)>sKG5Us957 ztL@$8r`MvDm;JqtSa!>QhJU?ueF_(dDlCN(U)%O_Uw@Hq;5DihUK>&Q%&zwxUW1X{ zk`0BNcel?P{LFA(M)J9~MR>LQmu%}gq)U(U>(wtu`g)w3D)47w-LG@SOm}D3Ie>7f zfxG0GVO@s`grh zLgB&=?r)_AVku=!4@5yR_gaN89%Au=cn650qd=EI9rEcIEXH+5BlFWrb zYq`VXr3$td)2j+TylncEP06*egX;6OzO4@TRl0@MsH*@qRSoO8(h#fVg<)Neca7Om zP(leCFe)GlzS4>c^%hh_VU?Jn)H;K;QXWt%Dpqnqn*rs@R<8cVP6xChKdeY-qg}k_ zNbZvsH;Gm?^V-Xi>JGw2Ue;QQWq09kW2uRIbw?X!D*G^aGyMnF*(f^~d90wVMnbz( z#Qoc<|DyHi09cAMx^F72E1ULBfQFp`S?zNRZ~Jr`$hPuEvi1_T+7_=a_rQ#D!QeJZ z7*@J>ajN+8RdzdAwcJ5jZ-ef>NJC5U;=zNL1~qvz4+^E#fld&8j(58+l1Fsch<|ijbCG%#90p}9lTL_hDJ%F>JwQbZ(5i; zL}2a=bllz(u@BK@WB^k`XjGgq`qVIYN?Di&M8f***AzIy84O_pSV5)@B7kCg5HK)8 zG8hUXd1PgXB|8yro$gJeK@AOv6aZSYDdMDdgg85qJj0{g(Fr1?#KPH4+SYVX2mld` zAVn>Khl#-k5*2p>XXm%fBTURA^9YTG!Tksl24GP=3O@?6^9*m?$w(O(v}sW!nrb9> zmn0BSZ+-$?OefqiM)L#1VTqB9oY1(RqVVr#pz661Z{d8Bs9;0*4A*1#n^p*pcAXu|69F)+ig1sfn|Ss@Z`>obte3 zr^US}kpRe~bOgk5&?c*aDP`}}AtFo#P)AaYhACwb5$vEKA~wB&xLPAH@5IDG0S07I zCqjfgLXub%y-^X6nMN|Rm?hq(;gb^>Q0tTjLL7!)>iO}DR_jaq(!R7W?ei_qt9m88 zg0%KafF0OcU(|N~@_m`I_X;|B4UL`KKLJJk<#vUf!qxwGORiqL@KGwS4P#GEU$QOW zHLCIwyz7up_dT@7IaTL1zT z@sIFoY7B)3vA|^Mlkc+~S=(m|1UEFj+ z@Z$A}{fvrMiB?(7vrxU>S9AJpb7Cr9Dv8K$i*;A6a=5O>fz)!d{;F4ZQT>=g2(@lw zP2CEsb9n`79LV6l7EZ}I6LYPc=w=|Q-dI_crSWXUyksC&`Oo@#na@=;gw^02Tiv=# zB~e(NoA$?Ib5h?n_f_Sz9juxyxKN=|5Q3S}E-!eqrt%%z+GitT1!R?!Y{Q11y zb+yM>o7w!r+C8tdLehggf9v@=oX-%v{|39q385fr+%EPK}5{qWdGJ zJB5*C^$+GT0l-A=kN`Unva+i{1|8^a=Z`Ep#lqf@8CVlW(FWSM5ShT=nV6|S++D~U zWfAG2Cjd%E4Ai!8BC#|nv54cX$#_D3n2u41n2jh>FK+1I8o}9BNL*9H;-I#cR&*K- zQ6NUitT8l*k2>5){E79AGcXwdbz(eDQzP9orW=Te!xRQ;WhNPs2-YcsP1#4KBe4Rm zeqML$`r-c`UzLeLC?%IxU~Btlj{f->8zrmYtxkCTD3`%!o{ z19Mh9nG&GX9vCi2gEvCYYIkJ)gwi6a6;J|%)Imx0pbPwZ*XR-!A2^oC_r(+-^}d1@p+3S8k6LTfqkNhT3`m=M{MS%g1`uz}$4DFVe> zaT~KTL0L(uXT+{6uFa$;5K){Ep(gH$iHyiSvBNbmKSBi&f+tsTxltbnOSdsA2>sEa z5cVN^Dn=R6giPIVWOq`PiCo&}JXj+~_|Z87Ik_qh`k1?;lMf00M)+a)@fW&h{8gw{ z706W6sH$hF+7s9FlAHh(TH{$%Bmr2JDT|uvyzOD=OX?R7j_1IZ zfc5-(i+_E`PBzy|_ zy&2qIns?s%lFpp}-93TVbLMA+kiVw3QLR8&iXQs%EPYN$H2As@SM1;g$9bh)t@8qD zy%f}32zkQwk~7@7+V5`jGjs^Ae15U!o-AC_rB{K%&%C{e4NHXoByhCt7ndX5z5N;9 z^$H?`~DY>eVP-g01z_a(Q}hSIRk-SL1oLlO3mfiRyMjt@EFr!YEuy3G2iD-$<)G ztCTX&bIk}#Q)1>rJm@@Ai~w@ZUdk$oDivdy*_InPO;c4K<(wrRIMCucU(p5yHxCw2 z{fG>NYJyeZ%RSMvHN;f{Q|Z;l3#x#n`g4_CuH5qPda_w@CaS~Pduf%GdE`(*k1wZF zDFNhehDCdYQa}`T=G>bOXn`Z2Tr!4ONtHakWDH3PA6x=;*69}LbU)5nbXOu!sQ?17U)I?3o z7AR=Wt8dyl;4KEM&Qtq(0`@`xmDh>dia9Qj%Y3^PRs`wA+-nsFDy3xAin{7vu+|Nz ztY@2cHz%f=`nS%}IoicGtCU*xG60sXaGeH(QoPvW7glp2D_SC$`&Q^P8&tJvnu4=x z%*@QKGFbq&TF{0j*|M1lix*eb?ZgJw1l|=Fh7hvloO9DO#fujY6f|oEWTlj> zdH-jsktT$YQu5;NUP~XwczEug{@d;e|37L8namWOKTJ9dj87kjhmKmjdBYDkc&G5j zrUR!e!c3T;&}?i-1_2?W{gi$h2p?FupWb%e34DS;U@lo%1P!bO2l(6*Oq-U(;FGt^ zL!3-O+DD0_yF&t5BhaKr$P577s~r_+Il&Fw88z&qN%G+vkwM{N7(gOOP%;OQ?3VaZ z_4m;plSe~g%>;raC`@2*VkC#yU>ZdpU60}da-^ftGnqit{VhPMYyhWcI3X2|&wxN- zVyZ`xUd;#z?h_j38A@(7S`b&YZ91{Tve6~uHYESd9ovr zNM@Z{Aay8iq#%YXNZbckAxl#$+!#eO5h!7DieiHzMhr@ls&%|W@g!*3Rb5;GV#Set z1o@=G1akus^9XGmMQEC=b5p{g9H52e!KSa0Cy_@;Bh);pG4)E{xGK>>FzDpmb^{tU z1(Z2V?w$@3kLX674&n;xRU5O8{E=h;Zp{*$5c?s$W%)tV4asaItlSGX_8?$$VuG2c z1fV5}Sv6~c{CTograMhT%j`73bwJm7gTW^~IsODWx!3xW56uLcYvp2lLwnbpnSrm-;^TRj3q2+|!1^l*P* z^yW|{8}S68dgp0pz!J6>?D{nh>Jcdt>cYo*)e%FBx#%DEOj;o_iQ=()=N zK)urK9xa7%?XHCl7;US4j%v|veJsg?7jf>dl-=Gh!n>NB9W*=-e7y!=#u?~*mR5aM zDJWD5!yUiWQU7PxyeyBwz>+XnN||*I6quRKLI@3UfoES54-357v6~wL(sQcRAkA|; z9Hw#Vx^96-TPhy{)&s+V5HPDUb4pWvm=}>kWM!$%M+j$kt%6OHwH?}do=YjsK@KD^ z&j0`*07*naRC2NHnyJUT30(K>Yjq$ZvW*#e*-}I#~3MQ^hz6IG}})ukS*N^280?X0+JB4OQo!|d*x2CBxer2DOo=1tR7Fl6qu z%E2lFvYdkm09~!4XjNA&H4xp2NM|JqfvA}4VwYBYRshw4zm!F><>nNEVX@Y7cX+AZ z3wsx^4egociUpUw?>xn-#LTm;8Yr0CRtlin?`5~9VKW2RJ=ab`SabZ!@>^Xs;VNDN zFwIjzIf!hUDKq1>rYF3VP^{KQAez&RfN>aOj47o+p>10?4+!;gpn$S!zRVq^UMU_Z zO!HJq(X7?(vCD~S0LkLaNsOqdU6IWqZ z&iN1zOkC;MK5a7~)EL|>=iCtIc@97bw4GGH?q(iz661TN$np;~JvyvULpQutX4A&` zIr7a!u1ZD1kMz*KEAcK`kXPDIb?;XS>3e7euw*9|E@(5bag7+OUknT*_B;nYeo zh(0vvKH=kc4`QA?#@{M4C8^~U`wl{EFla}}p12x^8xkaSI^HK0ov3?IogD{7aRksK zoLJcO0OX|a2z>(3eb3VoARws^LJmC%J-Qvq22jWCW74BIlpDAwJCY58ocJL22rU8@ zP5_LY6DGuD1#UJ`%g;uno`eA_j5O#e(g4uIaMQIPRd2|$@`-g+kXQnbYVV0Zs0mw` zT!fyOGD!x^Tw#zlPe!IkR~XbS0WgKL3*D=}G0q|h5cNhAB&MWqI-Mqog6GMaTlr*^ z)AWYmu-LUv@VBa|Wwk1EA|0l_^LHFSS!xtU0-vTyS(yZ`U^7=u5Kr2WJPHycDhESR zJ#c(d24hG@FeO&VlTSCyS#?rn<{tED{*B0wj$U!6fM7I>Y63qf2G}js6ulFojt(&# zG{xKa{h$UMRSyQVFv!6vRb_LcnWTZiHMvECKlKmnBc0xovrmznhpC}ps!0Wu2M3WlCDEH?C33-J;C>*dp=HE=_@3~CvNQc& zaUc#!MpJVCXw&;Q@-dMZ-a`k80?gBplz^5}I?$<1Lt&pl0>i*FkwT-%a~e3}&`KP7 z9;Tk;2+5QFm=t`B;NT-Ezy@&kD*uof?Qc z8=$Ho@}2CZYPhPvYO7fHih`+{`&5zC1gzhZs}N>yV6-?lRU4^ltF*iOZ{L6ykyouD zSc~G#yJ)M9Y&yTLZBfuvg;zOmRYR)VZW5%$Y>UprTui&Fz{<|+>=iVy^AwTo#_fot4 z>#{3qi2$r+J%9DhW*~r?g=#HYEnlC%D%HxbQ7!D4%k?As3$e_8g-fx|D=XvT?W>xa z*OAtXZLc9kI7hw*99KLmgctE_v4_j?z1Ua5c?K?oHlH73xO{st(*5$+n9&l-)qK9n z+QQ|Gh0m<~Gi}eXu6WkfzOb9~%V^JY`?JLDEYZ3=WCCzrzdHeY}PbQnrE!m^0e6r0URj16_gOD%6y9ZtXgT*G*0nwD8OQIMFc?C zO3s^}t5lH`FzYgqrfKSVLqwMI#;x4!oZJTlAe-r|)i~*JIKT^5BQPvPqgc+^7a4R% z2*t}Lq(Xp&uw?K7m1}HfQnb}8tQsz}YUp0^)|O!hRD1SPi5gKjC+GoLGcgr&b9XPq zRFBI>!RpGWxT?TQv25;MKqcEYT>w^D9BmM)Qn11VJ8Sd`3fm%t!bS&$Vr1tvEStL1zZB~`CIW<&r z8Fjq9y{%){tnMBUQD<$MrfC{Ar9i5hJqt@IrQxQ3>I2mpj-lRC8)|aSUfhcx+hfjo z97g~oq_cYQrGS9>G*3*-#MQswix)33#t_0hYe6x$DyXb4-n@D9-}P4U&#?^?i@?*J z$fMeOu*MEP-6&^yGrD)cA*maZnu8{px``E&C665`bXE+&vkrem`o6=zX1VPL=_EPs z2QrceXkZ8IojG|-G#T@~5$T_QlI|G~LE4b|55&J0>5~yjXs4s{J(&pWphXFt*`x+m zXnYtR)EW}ik3Ztg8+SG#=ra?+k7^0d1`$gJRY<3;f|$QgPenOHqeL|pw;Pe@dawO& zh#tYSPCtV7cYPi{&qNspADfrF-l5(%cnL^eR-dUQ{K8YQH!oNkB{;I20c6+IGv06isL z9*Sdw-u}$8OJvpN0>8Yd`frltee3{9_}Q z=o_esM0Zm43ik^zFYR1l2I9y2jJ#xqrGrODFLM zcq{p-cb^L06il~We7^sVG>#n)hRA+`yU=^}lq{Iz^oEBtJv{VA+Tk00m?nP0bRs^0 z=HVeg4kRiFF^;T<3DYUQW0QUulpjSKkwg$R70F-!;g`C7ebH)tXBNU)q z{)F?ZZI!TW2221d7m>I_G>gNLtUR46jP1X_^qiJkJ#95D&vR9^2M)#!AgLH>)k|ob#*- zFXoN_4m8f=As)ic;~cAwDX-fyv(9Q}6|pr!1Lrp5KSV0b7AWtC;U>;Zz;L%&YRuJ+H}eTQ=XC z5hDwW*a z+-TKfR-h&#%sgjZ?pz#-=1t^PB~dwNcb|O*z{Hx>i^mu%FKe16V6n-!T9lxw zX6A7m8)>TcN)A#Z)tu|mY`D=`i8zUd=H>=~s)|U#s`GN&u8uml*|N@B zm5gO7#1v!9mMM^$R@qb~P<85vDWx>ev%8yGO~swk)W+6|9pq3cUfl}<+Cy8sjMJEN zJ|2%D1T`&ob_Cm`VRb|(Xk%n)bk=E_%nV*iumTW}i__nLR*Q$=QU>|4n@-LQKdGv@ zvi#Pxli}dqY(^|PwIe^>xSL9l2;qzghG{~FiGZ)2x~Y3^Et-8bLEHkhPu8D6S<_Lw z51gWafXSS-|Bi+4A08zAkskl2_U`Dzy~&9v>CkCARQK*d0S3$l{-o(f$cFy!BGNSc zFwwW&ZFsm3w{Hy7JI9^lQIIT&)4jnHNH|734pXD)qnjZOMp5K(x-WeC7ZINZy^B!b zy8$gyVaga9m1otPj?ho{GJb&FF;W*ldjBA&{|F4gry(6-31Cc5Dz{>TxvBMn5rC#Y zITZLk^?&laf59#au&Nr1D~Q3*3Lt4Bs2>RlT0prU|DR4_cmI-IMbczZ^-U{Ja6)Pn zx1e#tAm|2t6aC4R)E<#l=_Vz>od^~6Bpd~fihQEuC(FoNz>E0#6E% zj!uze!XxyMb+r437$3d=3XBwH=o*a9-zZl(Pwxc7|Dt%&Qnp(kUB-R-q5~~;$DHZ*EH=vtvy^lvn(1hId8a>EW`kdKy<&Zlbu+swnaR( zGc2RsC9@o(wajAOdvyT|)kSW;-h_5?!aCb^jEh!or%m&V+YGF^cs#Ys6WMTi9U8&X{ zkz8wwR&w-e5xp}d!J@C(e+XQj<-2ZQ%2<9*_!E{&bJ*=-A7|OrJuBKM6^p!zdoDoK zPR{c(&b`9uC4*amU3f|Ec9;(@AQ3(@ndQZX7dyIQVV4-FTpqz|n02*_pAi9tix=T# z&tYLMRW|j~j_N$-eSv~qR_rV7<-#4ryf8}JTVid@YajA@|KDD}qTma=8QvYc^P~L^ zFV?DrXGZ+$$xzOlpWm+YykB{Fy=FlMLRe4N?LQA7{Ool7s#-Nm+5|yF#LSgMWT29) zDrnlutCdpr1?(DTot20P1TQ31O3|E|Xv@XhIE$~jZwHa*=b>pD0L*Nf=^&d`d0h=F zXshxWW}a0Mf|*%1gEi9B&MU^Mcxa(oYbCw_XwGhKW;y4Y&n1o23^-m(7FKRjH>nws zn=#Xz=9(tfG>vBqOkNh3@ddrPhZ4-J(iv5)0v|7aXb#WM&vKBaX*_$CFV*C=5JIIt z^`zHXx#8Nw^YDB)9HbEd^E`9I0il{YEf=|k5Q4!fYN>~;X_`R6+^Q6)rp49%EB)ET zQ-MPN)Kf!D+$>)$FzdYZ!wsqzSSg`|nv`0@u6E|f#uxduCRN zkD0|b))&m2E!Wq}O@czs*~~Pno6mVJR@$~LRO;voiU%jAnvohpK!L+m6$Q*(rBVSQ zr4(aaN)VLlTt)?D*16^$)&Mr!wPSZY$e~)WS8P{yZAn2bo;5epRPMP{?W}*`fXbd& zxMIPkX=>*wC7o4G56xlDbJ2o=il~UF(k>#(mWe4IVksrfDWz1ARt>m0Gz~XqR*z=G zP2H+#no91>ETxn!6OsSp|JMA=|FxDYt!cdfoo^QZ{Mw){=)p($0DTJ_D2kDr8BBX| zpF-s1L&MtC8idiZ>X@Q;npN*ah937Uzd6EulHv9p)RKaP?Wu*ptr1n8-jnp8=cFKM z@unUA;ZxTo!>uC@_%Y&rvP3ZOebTR>O|;}PkOHD+H|X4+J_wMsm-J~M@$OsDto9qj z$1|s8cjxF$7BNs*H32m&__)_`qXIm@1?Uz6(}S+a1;v>Zc84E6^r!eH#^=f4 z__LwW{s;+95vs%ln~a}y`o3+6v{4EA;s5Ho-x@lnNA!;>2jjxjn+tq^-8dUCrgTt! zob*3~-a$XId`m*6lA<$4^JFH@N8qD5`V8m+G?C2&{P6$&T`R{?-o^MGKxS<}+#Y2% zom*joK)-X16#HyR_2$G6{iH~LG`#Ole*hco$CRFlgiKwNvx6w5NE%!QQ!tS9gAXv` z*8e`={jO<9(^u6s4UMa2K~c^kSv9Kl=m)d!bijju=uUqS+z#oH#fbWtP9BqjfEkG(4#aHIy=%JlI`}M+Z*t+x9jO${x#< zj^Kp;PWgjd2l&8%O=)Td&9RLNZB>l#27c@$3LJn=Wc=8oBXQA2?%0y3SsMDMp@{y2 zw8Bq1_;-{2j=Q#N|4+yNIP}47BKFCssj<9eBUShh`Y z9#`4G&1*xr-u&g{?@-G%)Z3!kR7jiq&x=8yHw~}Ru@!Y)$+fN%`aaiaAz7P>@Cr*^ zIA?|3Nw^}l(*T%HNr1mZls`wQWE`4!9CVB$u#7@>d&g?2OM zC}EwkUwKvz$$rfJMe2xtz!{>L|0 z7z01ifIE#Uh(5vED4JZDhF;(bs1SQe903DB&u&NXjp{w)sCL6GBlbzD>tqt{42(`N z0iNJG8QdU}1~WI+Pk1=0eoyUBLY~w`zUeha|8ckv&I2%lgtSqAXstu!K7B_f>8A|z z>IauDq6gll6yZM@%?tvKW+RN;UHC}w@#7Dca;C@W;UA@Y&$s_}(jQsAfvakC_UKjO zH5tKm6es}md3<=n^bE|@2@fN>Zy?lY7?gyeW=QvL3SsplED?jX|M2j=5GGZ~cMsED z+kRy<3O;1Cz(>^^rG^qDX4gke5%S^T;iK}O+v&D#pC5ksyYAiZ!Nfo^Bj=<9nxh2P zq1Pi>EBav?zJrhb!+rPex75D#@k5V)%c9WaESAQOdsShl-V8daG&J2aW`{yOLX{s~ z--;yQU7C#5oW>ZD{X~wWgNVd<+dupSYCQf2oyzI+W+}(D?ETkt( zczo)ccXS6D?|;HH{L~UzJ5JOApBPPy?-Xbu(cX4o3^2FHhljp5fjS-0>M(g5KhmUN zYrETD=%(>kxh*z3QBu{XRJ$wMRZ?5zOY0NhqJo*uo$TudR=cbE8ao-Abm!NLUzMC+ z>j2=ayV;la+v|hs*CuYy8!l_=dCB4Cy#69kvU5M@N0GfXQaBHAso3b}b*gxWb`E08 zJXC2|+=a2zqhWn83%e)hMcPnT+dp80bB9%BQ^h`e#TN9u&RI9NtCzQkr*_)0{nOnd z3abuW>DYr4MW)y`mc@TJPHtS5853h?3(FYU6!tL3;n+!qdOWj989u|%(z z*R2)@F22|W?GBdjeZK1A!+8{c0|Iyeu(TTSI6TAi3bU{*Tm)Ph@Nhw+fI=l)9^Y$> zMLUP1m-?N(z4z`aI16Dur){}1amN{!o!Jd8K0Q;0{Sxe$R3#U*>WRWdcrUxWj&|Q( z%9^&E&3)ASC7(lh+t7B1ZOPiZVtngSLaE~odZh3kXz zGuPI|{A`DyPW8)O?`2aP?%AYFs|FwLf4g7lj!p#l-=iH z{}=O;*5UH6%mvjd7ZCZpT3IeD)W1h-hp*?@{`y-frMOoKOxY%|6!+rGH;qz_!?%2~ z;>A28U@PJVpl0C}cQdyD_v*F|b?2rzZ@$ATAp{YrGMPQpz+K<%m);43vkgb+e|XaVG$ z7iaOEI%%83D!einfRs|xGz}U6I%|y4&8u3f;iguQtQxUWieiyT{HD9v`mEWJ^}bAjym+yaEmz<*3533pW|#SNREzYUt3xk)4AIF?cl@leTBK-e<%YGDCsq$Wt# zw+Ijs0QuYhMBn`%=0;9+(!4kVym&oQwW6YZ`=9ck{`aJ*c)7d115jPbh^Ub!9%7Yf zRn9d{lV+7hs=TW@njH>@YUyQW$M#tDbai?c?3L$3bI`2mF=fjlQe&=3pwh_Ua0np~ z1#X&}Z#e5b3`6CQCj;l%Wj z^d{pT=tLhCO7<1CeXo&_lSSAc8n9y+{RZZi2r>wc=o^W>BC4LmJK)hQxseJ3@1-R} zYV2kL*g?j_gONb=2C)HP3KobZ2w{pMhBqBj;g6%*w|0837=_dU@5~f}BU})lF&q+W zbf}RjAaT-9(*6d`jP^u!GbzL#1}7$&c;?i=1OiiQIVl>W1~{S}qkIENqdpx^zwi6L zp$~%&?kA8t^U?C?1#}!lWdQkC!^5AsjiBE}K!-lw-k3kS{iwr@w44p#$4100ItH`n z!3$(|3~=T)IG>P@dubibir8b5y6|EYaypW3JPFK@2rTjC1W zjnnYVXRD)@u!L=G?y*AvJX}Oi0SGnVthzcMbHP~WTkb8FSnfifsbFwH7|YIQ3h-8D8r@rn~12vNY` zZ+K|S>CV^X>If?<-}0<*#kSVRwBoHcliQ-7-=D8;|t`%ELf6iblFz6fx_uECZ0HEa)aUid?Sm~l@DIvryyD{@skOBY! zZr+qHE#s+rC5er~G)i?&t#%I7xDqHdlU;MDt!l3&r9OlJSgokF-TB*kx>kp-si@qw zl&0{i<`hC{mNy_URrgX6CAM;MOVPc?-2$5OXpLiU#HXT`R{PJKh>Cly)v-iRnOhs( zYAsyi!)@VBt%GZTSA#E&tu*6a%RASijm~Thm2Kxm1jNzIP|^2&Kv?mISC8i$hSeMg zpjcsIbnwYjN)6DgrpT51RIhlF&SB{wJD*R zD$vYkop=2XKy#9|5Vtm~&3wm^mxwob19>5YX`ZTAiP8jOUDs8w<+ERK6i}!YOd$aI z^Iz0jJ%swJziMMCb;hmRhU%{PN!d=(>b9&%gRB7Vf*g#mu#VO!Jhd?CuhU zBhPtm2$G50qU!pNY4MW+n00Pkc-FZsttBF@F3EIV>KZbOF}8I4w%yH7r_(r&?jAXE zWcvA^*NQGiHFGzjYYq61v(QY z-WTm*55SG7p=TS_LC}#zBpn^Bxf405Cs#n;9~A>!ryVf~A543Y0)v=17h-ap)Pm$b z(@0j}#5mCOIS-F`+?kUrnd)hzJ>N|x1D|Z7Q5EP!7}{k=8cu$=H8D0FIjZL#YW|`Z zvO?;27^BDx8&yu6ZB-`<;jlXHf3>GpHAJ=B?!vLt!TcC(}8NWg>nk?e+XM@*W(fhE}| zaG~@&CBy73GLVQNfP&evBV@%3odDj^z2V*6a4Tt;VM+N#roCf=W%!MP)B>z}jwxk; z0D;Y_n))d}3h-GTRbKT|E`5rl0zQL?pbk1t5pseOd7}P=tmyYl1+G54fSLOaI)Tjj z9cY(0jK?1I!jWO>zVGk95&s$F@y+3j``fN3dmLXu9vw%PT~nK>PKv;etTe%2B_e#u z5+p@+kQvgw>SG?WykvKkTyjpJ2@Id|#G-0FoxI<{7^Z5wfh%xg3e(|T)+b4KB(8?r z+u)WaokVuf?(ckq~o7n1LV@(Azc z<^63C@Br3hQhFE<@l7sJ3_?SH$_Kz`NJ08A!^ZwB+nY_mEf#eB_eY(?eoV=>Y ztLGs>|F5-w6{^)lQu6^gYoPLbU=>nrl9J+?-j$6St9_%`1Yb)#-%qalwAKz7cbfyY zkfZi7xBVHo7Vm5$tJ-IU_L8Q!X{TQ5GdA&8`?*P>+G=h5TIJOG*+RRnGPYW6#EnR8 zTa&KU>1*4!X;9mEsk*A1{L-uCtJh6L*Od;aUiJx_jI(Xj)HcHAx%s7DPSn~~Ue~6= zHfc??$q2i;3L7KUMGjWi**g2AHV26t4V|`^gw3coIZ%uGZIdkaEaNP0X0k=0ZF{vH z@>V7mHp(pC0OsvtSa;)XQOgPd-R|;uJM(P;HxXZZ)iVE^E$i*;GGm(_F4aHl=1}d~ zjbdxN0BTd8U5XffMB4=bn~PO97d>p^;pPzlx>xvZXw?8Zr@}if^lF_V4;O)nUv9AL z+2?fu9oNDZtfs&3CljqN!S%DxJGY@rn}5%X*?qr#PaL$8sps3ar`{$pJwr<$C0V%e zk*#>=W8Jw}^R7m>!lSLK>*};u2d^vCI8V!kJzY;=c-HOBaGv9*y4k)R@AVLty{?U- zS8(bYRIQBZqu1iumVoC|7giou&unXJqFl$jp7BhwT3%}iAYK4ggFdt&T$e$uVyIPj z{Ok%|cQu^n{PGK=UJkV!a7_gB^Z(-f#yNNR`-^uu^;tQ%uFOlW;<|pC_mB|?Ea-M; zFXyv$`&-e9mOud&O%Kv464u)ESz(pEFi}gbqO+IKtNZNX%-MBT0L&~gdaZu`OH=_X zg#%SzvZxwip%5r8m5yus5yI*{Y_DCgR|sZSv``4kpFSdZr4Z&>-Tk5%st6QxR-$0$ zXm5D0t1hNNpEWlq=eg~((wudcn7Q#dghgeBP5ydQ3`LGww4tsRRn`LI z+t0?Knu4r_KsB<%f!j!1{kvwwYv6{NgNIe9)ym~2 zfNC{Rs8}MROie_JFH)eE7q%wNyL*&HP1X!_4HYqSn<4$4)bTZ|sE!U++VPjiNfx-fV zD74uoA`X0-PBBK%($9vpPSc5_G!>W-shbt6o2ro^gz(cp4FHD_0^!$xRsQ}jTO@qP zOhgO*3ux(Awbm92)~uk7CpHji#Tv9?VPV;&U0Z}}3Rtz;yoZ58CtX{^BBDiaZ*H3e ztodY{Yt_vVLiMUeoAI!Csb1;lf96EsE6@rx{J2}5RD1`3CHWqf3-3Ep z6@qik25^DE7?@t0JgKDgSVI&rJplz38g2PKmUPw+8A%2 znvQxSq6UMjq!~u4sh6XI8ScN%qP^vhS3BK6xN~aO(!)X*A>HHi--2 zo!ZM@ZWVE&2#x)HB`!`U(mmkE@gem$EO$C(wKPapBXW{dhW_8=>G+s;{V+geas@wV z?l}SKCRsJI!=W;q@GjjBC*pc|EW>S=b(Bo$Wgd?_styCDLu4G@je8z`E&6J7BZ}T* zPaj6yshZ%$UfyX2_Y)F79!BnkC=kyK8g3s{hd1M)PvTs9QW-?2I(c?d%LZoCQRpNN z2$8U0XYx)DP(1*mMnsW8=M)swb zB46wWFMvSE$Ee7zq&6PS$okviK?Rm~{a*C=li?>L4?mOrSNFXPmPmTwh#Xa(c)EF? z>2Ulo9uKOd^tZzMehiO#GrYW4KPm5enV>rzpMFEXG(KsyKDAHnQ~T8ZiDsx3Fw}4X zTbJAJO~%%iytK9&udd)u`?o@k)h+dXVALM2Phs;^gQU$}MHi-aVOzM`^Xl<4(zHF- z=GnE+jUZh5_ID>Zow!5DB)N>S8fp9t0vSA(C`s}un#z#rX z)(!e>AY1&j5zt*Ga=X-!}nbNZ=>KPDxW^KkZoYW>{3*xu3rfYrH1>Rj7 z4{7srWm|#Pd;Wz+Txp}W=X%yvT+i)h`1QKmbrXi=jS+{1><0k85p!+dR$G1CN*dP% zSp;$l?gQQPqYdTJUxVp;~Q7Xl;u^tpexN`8L=!y?&KSS+P}d#>@d>))@ir zzWQmIxM^?#f)xw0cF(HUM%>yNn~to#q=BuL9nQqX7aZ0I6bP+SA;l%Oymfb)rj|gz z%vAs?notV?)s}8+(N4OKx+MXPC~&A=Tj9&*5L`3D*5NnW0!7QWYND++MX5^-Q@VMS z*z&?+j1r}#%Lfj^(lV-=QO?}fS!(l{b0#JxetdkasCmjEgw&^IuWQP+qQ$C3ii?Ws zTtJ{D=!?jrgCm~ugbHG61d^HCbsxuZ@x2DBsODDYc`n6E>AHkk>F0kIMPdk6tC_o% z`PCoQum59c6&OQ6fSZembi%}K{adlDxrJK+h#bq3BLODvQ_qo?jR6!WYo4dMMdmjs zw)iCjP!T2e=-WG@?>9B30EFP?^E^L2Jpssb4nO;|T8ie`MWnG^02N*_W?I_?At-2rM0 zw}>n(Ix6-6^-Id^3MDxy?t;#ISlywY`3APiN z#$!*k147nE=1Qc5teW7a5csGNvY3X)qKVyvhU{6$74S!coHQp&Z^j(OUI5=gf+4Y1 z^eplLb|aJ=H-~q7k)!bwIYA&0_SrbG0qC=K0v&Cfra1H+@IMR!bqEOZdeGA}nIeGi zCi|dJF+dnzKrGg)mo&^e6%n8E=eLp}C-_e3?Jy7t!xi~7?6c)WaFNu@>v5z!6_H!% z&8LS6FK>HQBFba7JJSfxEl6j4cguYtxqI`?8+Yh<5W5?0yW_WqclJ%+-?|<12z8hA zHFU3j6k&kwX?7=v?FR;ZP`?xL!{H9dLc&JGg;Nr7&3t(GhNXw(K@w~*okq>mSajSE zwcC%)<4*f;2a@A-njVAqj>(`h$Y{Pdxk+4IVj5nh``s}7lzn%1dtei? zonwZ-AbRK1?sS~L`PQ-+JsS02506UuQPWRu`v-7f{W3#c`#tAA$v^Yv|ChFZ6{sZq6D0UNbUQpw5hDO$i>6vF#w?J0brhhb4V7>f3Cu&m|fA!6u8`0Z^UM#O-{AdI^leQu9BoSr`QIfmCdv56kAo-(&5dO zjpsM#_XZo96T#x;CGBz9DCxH2U6R^1t81x8d98Q2nwHI4T6)-?Z3QOUWxYPg`3&dU zpl$NcTF6C!)-qPN^$<6=2fI4}A#LT8Ki*a=f}fpt+kfA0;S88)bDPceLZ;3^KWM}u zg5rX=F8gme%N7h>Q-h0CVjC^A4I9FS3tVH7XDH{g=jObZJ#nEwTd?&E3H^}b=?C>? z=aYtOVX;-qp>(ahaLR<4xz=mMx9CqD$)*`oY((qqw4Bo70D@C$0yM&AB!Y zp7o(EjPOH!d-nT(i>}u0Y?#s25WaWPhP3F4VSy-wi-s$#6l^6~>nSd3L|k8>usQAb z`QWyz-lR3Cjb~MmFJLPeDk1nq3t69C`g4E6nv>;c*(p$cAz86Qh!2Q4dCO2= z6WLo&R?sN2I zF(5>aO<`AS)z5x0=NvziK!HPWRIl}E99>I@+;xd#1ZpQ@UT3qW3v;us>kK3!QR2$T zT135@TQMyXf=!)pc_-^&@R=Nc-7!c8w$i38ZO6lHti2NsT>? zdNg5HLsAj8v3iEX-4j@lW^$XRoyshp&4YWEgefPH8Bosx>wN!2fWAk*f7s{K`{^@A z79*(o(G*3~2w*=3SUn=al>x!dLZAV3wnqNlx%qsR$zE9~yy5;R)}xl8;s znTqETFBA}vB_Q`CZ!^E%!yPWTBht}$(wjj{#9?_qOsqQ~WgoNy<=gD@$-??S-lyL%7 zBnkMWJoU-wL8t&iq{h;>K`(7vI315$I?wqE{ z?RGfY_$BvckUPi|kY0-Pl0>p8k80ys-yB^09TQv_8Tt51@UTyg+c+c^cF{W{!f+Dp z-s@?4tZ-p`gZ@t0lk5j6*oWl1UWgJ2d2%`-`}{x54YWP7}VbVhJI;$(rSHbpW3JPsr?h}Z0NhX1rFbPyz+=uGD9^4 zfG@G!%kJS^pe=&rInug#60Z+_!359f#t%`g?QYwjxWJ(2PyLXNWt#wXRu~1k?$x%> zo0mM(HHEd$n^P~3&kxppaE-Lq*s`mxh0UqIcTvJ-XwP+6Tb%S!3C{|Hwv)5k-!|>C zT=yT9PJs^!sa^GtMgrE z*Q(b@aZz(^Ck5wP^P8m`&PS`8uP)qMatyqIEkmF)+gfA1HhEs_K^E_!qdFW5*b01x zRuPgw5yXqXk{F934A*Z!oGrRP{w6UtSr!0iKFeIK!NnmIU|es}`vR7y*lj zsZpDTPTV|lTmz>7lwy%%V@xZ!Sw%xF&b;~Wa2DgBR@DN4m`W)W$bC5)RbRreN@+Fk z+HUZ()36;Xpd}e~UALxUEiN!~VrtZB37ZGCB8DwdzGZ%20>xSoQgvYgqrt3-%EXNX zxqGV^sAchEwyBusIdDjl8sqDvTcMb_H3~NC%*<4&WtO$h__+ZfqCWMFxB*brMh{ng zR^Rt)R6HuG)m9OYn2HuH%EZl77(z&r0*7%N7j+oO%vzrPs%~5P=4z}X&-8?kpS-=DEe+BsXu$EM{);>g{n8d^IRWfmHP=KM|YlvKH( z_Q%>}U_ahZR6q)Ljf_oR8vJuvc@E z&bYE#FACY|P{uA>X{nvSlsSjCczaNA#KH~BC$b{kL`+t5?H=Nq-zWdyE*+Gl8*ZFkYDQG)@OU=+q6v zO`muGCZ)q6AG4FZmtlV^FH`R-GUzvtdNWQR@|&HIVenh(2M)Rq(sN3o$19RP(Nvtr z>^40dkNvwh4-n0Q-F-iiq*vA z>}3;cg^l#)N-MMpz-rM^?GtuB0l>T|Lf7OxO)ceDqW48vvq-2mNk)sBX0uPb9NVO= zu*s!bq)FF-S-i=X+I~IW4zkFm>~iXsh}4>Ig=3pn;rfP(H&UbR+1o^JC2Y&~je?24 z7oE1Pinx}CTkl)eA*bD?pId=a+jT3jYS*Y`pKXubto$h?_^)>@gxWwmdv z2)-}P+q`SqY{-6jiZ&N+>D%VF#3q-m&YK1NV{UZGoc4I;R%fzMD}q&D($OydIfUhw zn|Q$%uJ9T02Hgu#yr8IORI53suG&gfR(7+cLiiro+WdTmKNf8CJyx;|WUCC?v}cl^ z6>Q-;gXxE4NTs`4i(`C-1s&!e?ts8{ufWa$5 zK)QkK7Jb&XQACVqh<07ZaUqqoDH-{rZN;p`8&M$C#flgZij`%Ng@7|-@>b@}JjS?S zDXWW7(R>lJ5H}}aO3B?3u$tOdywxOBXsa*;lDM2Da&;$A%aFQSOn`5K9RWsO@P**L(4q!>Jp^|BoPw@Dy5WC zn7HGvC3&@Y^<^L-G^7Q<+z=2cHrra$ST&a6?hC^zbAxV8`qZ+hn%HU$c(P&$3odMd z=6V~p`Mot}OS_<<$THAOJ~3K~zlT^M5zbvrm~Q zM3Iy_c-2zIab%*DQV1lG5dvz>^X%qcYY6C4YGpCIlu&CFVP^c^Ur-3OqPW>SpZ@lL z)uR68pU{g+-~LS}T}vO^4ZGEi+tyOik~MQ!6j&U&k+`;O8fk5BoCOzFUo*&XE>(G& zPWkm8C6RhIU=vYFDFy;ljIqHmoV~$qCHrqIZu$Q^O|!xbcw!R3k(8B;I8T-QBzmL5 zf)nJ$1csJuN6HC1_-(~RnX7pkfUI{ev!@R|cc48X>wUl^WJF$!j?l!|DQCh-`3?rb z$wY)s+7HR@1~3h$6T}Fl4?N}UuRsqjP=LL^-=_?MJ`o0CSHV6}87usThC(H9D!?wn zU3U%^$|-q*WIQsSdfy#S0KGOm;Ap_GPZ@n8lR@&7qwCYbcX3utI(iYkqI*@R{m z5Nn(F<&irn>b|L%yxoBx{eLijYA3=9^^*t^mF{$=W24dbCsO8sy@kWTrf=P}9X zLr?t;(~yLOKjiW0IE|V|mZ2Y>_P2Xhf7I#lri#41f9dd_4gx_@LVlbl4UV^9-|u$< zhP{ye%d6VdQR6$IQ1v@yBqGG#6Ks>NDpoxb9Z5KobD0xqm=$sYzlAkclltlhx#CR0Vt>8 zCi?YVNy*=)MP=;yXWQQM12xyU8%)EwMHK3FFR8*UCDtM46P1Iw>%uID5SpXH(Vx}m*GYFg9vdfGwMfl!h_C*A`PF}1l|CVa;w5p4Fgu{K zN^IgOEgH@t6(NLHOt4uR)l^uT?8vIMi`x`orIgkmoCDEYG87X>iXntqmu!v5an`xz zh2iW~B%(&snl!0;&6h(>Qu5yI}}{n5k*#h`6X~Q4#5+W2Q(P zm|8!rSSM1<+RkQ{bDrn9zWPIsBF*diyMMt^07Rw=@Hc;x=j@9D6lnSS6q-Agh$v8$ z$i$7?HqhzSTPcM0W^Aj@%(Q6v{NIK9?RWmo-YCS(%(VsQ6RlxqbDjee2lC&7-(R9? z!-*!5l+?59iDfq)|3R_>q$cQlx0iB1;}|C+=ES?~*weIo%#q~;I%Q{)8$pND?KHiI zS0~7Q0PjH`RFU(I#B5v`?$iSx5)T~450vtDBNIofcLfGA^TQVF; zvq~Z(k~`v)A4c6{r*{}F?FzG)?g1ouOSS_OJ1Lz=ck=2hd7LTU5YJ?H*vrs=lk|n! zn=!}ZSkxU#N=WjszfFugx_iUpJ$M*(bbT^2h>&zcV#O)@11x5S9zD~S!v8hvPXuqL zj3L?neqdo$$>ZZV-Vu}#q2l)SQC|!I3y}bN;~JQZ%LIb z^6mXD(c3qNDJP)c%RfST*bPfZ%mmW0hyI$;Ilp(mos22*EtzVb^n+?0_Fu^D8`nDJ zJdPXr^rSIKIb*kBs1WAs} zPmkk0@K!wyDd{w-#{KOn+aHMiL&ie_sc_NnVu&x44(ltFF)ee>;jIF#`i zhxC6L9$%%OTB599iKNf=0pR?Y9}kbrxRoc<7iuqAj@EO+=W;(`8i46|EYmcD=U&qA z#qHn&(2tM(;r+L2^Y99w*8^wk^K?j>#_>^Yycvd5zP%lAlO&1E(8$Ro&$i$D!;Qt0 zk9pFE!=dK1}U&PQ%?m zC(jZ2#?l8Of)bH~pTPZSWuWqSs`+?x(64ngXQp(casrO(JEt^oFCruYztciYGNe3- zxsg63+Z7BSCjU)IO+QhsPwi9t)IPNzZVT0lpm^4aY&0^#mVooRjl;vG5F4E}dfXx0 zp}RqpOF>DO%l`B%JAA$EUK!9?*tHd2Eo}p~wxDN=1Fob!xZZf(o{OQjdUm1>R{MzlsDO2L*zb7&KhmBV z{nlx@zKC1x)q245OTx4LuR+@;=;}P)Gt~-bcio zS5v6f3M<7*;TS8b{Or&1&3_6ZsH#;%K-;Z>uyW2eBBDI!R*|p)4y)D%)l$FO7|pEd zBpU`Yv!)tj;ymYOY;3g)m-hwh4QWPPW6^SXUCXpD00vc)c>RPN6r4SH8 zj2r@?R`0|fE=k51J_{YDlUY$Hr#Mze$00G-~Q@a+;Ior0(^PE5Xqu}0FEEeNp zASNPi3pUhB(yj$4V9~tRCZ_%IQ>{r=EGZvzz8UDKK=KdJ8?o&E-Y19u!6eh5dj&xl z;uB6{fD%%Hx}%3Fv8#UP<7oB|di)8e9x8Mzp43?=1E~l`$DkTWpb!GdbVGf}IYTY; zLy|i|R1a<-B$guxNtn^OM_>SBkii5F_@RP!&{EvMGt}G}c2b^Lf+HX&j&YEa3z3TQ zd-4}dPeO@dLP<4^$NGSSWPjJgM!t7m=WVo^D-BOah1u z-?0`NKnJKLMoxXtf=MNtj*|-M=sy+u$K!ZoI3+5Cog@2H2@k;ijLIxbc`#gedG*+UMPkk>sS|$bLr1YihDE(}nT|*jX=aej{ z-Y~ueZU!mpnEYnwPrwV3lPZimrs^>6Nz;k)>thaJPf60?z}|cu$2?AC=s$ZslKh*T zzne6Qc8N#X-vcoJm5#CJ@63b-9>@1IBoRqKpMoJN#!<75<_UX`y$E~jE+^UOT&{6FZZ(R#RL=dJrVn{8cuq=VNDrNI(Co8M;*xk8JP675qfzd zyJ5Q_cDUQ5MylF5KvIEB5Ev<nifC|RQjczRJRTqI zQS_y-I~YjB0h|&+m=dH_a*kIqiZ{UdQ*w)b zZ`+#zN`~bX&FIv=8LFF9Y~BH@QET(TRBnK?cZ@gIv&9G3%!AJyTlM+QR~E%hl6P#C zO6>CN)^N9&?6y|HbBN>O8H|^+x14)y4zit`tz_WJ0Y|_&ioSX1bTxm4&2Ae5V|z*4 zxkc13!TFoYS!H7_Y(Kk=?~l)J&?R_&6CrNi8%gw0o-0aWR5z6GpX zJLmRe1JUKRSDm~@&fDSuOP@DuX-VR@wFB!;!0MXZIuoy_x~*{AzHoE-wikDCyl&nj z%i7y)X-?j@UCz<(ym25}c>a?1_Gv!W^4sA+Btc+sTBd7}6rJs~ttui1pu)>JQ$L(d zi;aaj+|a+k{`I2L0?z4F=VcbKHZSlmW&-J4x+~TD3eX7Pb$zI;qVIH)Gj~o>szjrdpestF_h;D4dhCuVhWASchELhtNp|U-UULJf^;FqKvcJ@uJUr}+nLOO8bYWb5H`~iK2oIRN7`bH=It6R zoYKsq#9Ax)f-ssHHOAQB*7`=07>ikC_F8A1t5*P}Kw7_Mu0Q#unYSY&GKtiR6hK79 zJTjR(g;3ma&Y1U7idO{8U;iI{-!E{=s&rz-N-?5}25g(eCeNjm`o$lI$o$RUthL@6 zM{{!k_{lGYsOvg&55NBFQp!>%F$Amb=BF3`*4%K15JKuYHv=Hj(fK#7s_M%>gu7J_ zArKHmY6xYT9F>>@QPqMF@Y6pnfB%=Nil6+lODTxVfA_!FTIYGLwNj*(KwnV<2MW|I zfh}37XlXEuh?=en0qt5e!qrLFb=@>gEu1U<{692`v z<|q{?sNO!#EzHYnt^9nlNjmu|CbQLoHKxFn!MJoOI_Cm zz}!iqn@N-?Vnt{7X_}a*ESf$}A}J+m(kd;dIiptMm{MB3pQqC)&$E{jLP&itT^9ha zC_1+Z3>0qqK|~tTv{I@&m{6fwh^Umw-Q0X`i3%Zbl*oh-h?tmko>k{?{;M+T91w^? zl+LUWG5_9Qv|pw4&EGTuU<*@QWLXW}o>5>3!CwF3lqdH(>r5eZF}C0HL`*~?&1K2U zTq1a_+ydrnT`6-2)Qb9VJnD3QM=DP*xAsFnL3I=wb|B2w9L zf16ZqOh%iS^~UKmfR664oPU+f|C`%A_?BKyqyhf=e)pJgrwmuY`#9z!o3fuAFGQY% zdh(MV6&5iJ&g>e2pCg@4<6YLbfbWOB5RRk5bjW^YK_rq~N+`fN*)bU$Md&mo+5h#;>+4BSZ1F#>hs_yr4 zgb+v|j?p)v)Xn3-b z$LTcs?S0~Dx>daI`@QJtV4d8~s;}YWI0feu(Mt#GsE!ZAURbJXb|_>g7}Noo2qJmT zdPwQ^R*uBk4;}dH_wVLM#QwII;S0g%<{v~pAH@d}9$xEc@BAqr<|Ge{|AHxL|8l?o z-Jy4v8xlL(X?j(B@-@nGaknbGd9L8H$kQn=y_phd5 z5J95o$T{I_mrR--CV+|F|F=gS4;J%*OuF9oJcuMD2#b>hKD>dxRbf?OdH??XYok#x zU?4f}H4%FK%s~EvX)pT+!-JPZ>7B@}DUl=~v#@EWgya}Czj^A|TY&Dz#eAT40TDvw@yP z*I%~=K3aTIySLxu6V)q5aQ;?*3v@0mTo}`emWUB0Y#B{GYkStV3S!p(oN>xobadY9 zY820o&`#}VSK9ffpM8j1CUqrYt7mtopS@<`D%<|*g>===iyDZ}tZFlqE26WW_l&XV zjDW+{&lO@}dyvaM8w$2v4A{^vEcc)dP6Z0vS#96iH~q$WO|CA&^BEh$qV=d3am_-q z+J3cG2WsV7D?OJ2T*kT*v879aQzW54f!N(If%=tctFV44sDfjDxp z(s)o4jI_}1lv4A%wTgc2B@G$0E6mK(oaDcPRPID#Y^hR2L>wcExzF=r z8>D8Ns&xXmlwux!`lp^!jFHbuI&PvcZsFHqnkI9vL#e3KoT+g7>=#v%H*#Io7mx2v+^ z;o+}{3_pI(F|S-bHrFlpaD!(NM^w+MWuDidato%wM737xB)C_vWu99kMVpJi`IoJV zOkCYBul@(GRU~#I0kHN^{pJ5!y{az(A43hAwfP@auS-1PCfej)1~gc z>k?m5q^E*K#)0R8Guy%gy>0Oj4Ent4SH?j-~-W&XSWrP0K?u50bD@BTD= z{g(g;#LQ+^-u-L*=KpAAnBV@ZxdnfWu@@=kwP=i@MVpHgw}_DL9L22UoLeY>UEj}h zrnmp9D%np4| z-1u;e3bj%uWsWflQy}K%Gc`Vs?VEJi4NPGHeJW<1+f}-hgqfGYv)m3GW0`U;rPey- zsi-ooG`<+SxQ5cMwd*?6>OcUr*fd>gt^55xMrrp21yGDk96Rw^1K>aZ3lE{X(>MRF z#m8L4zqEwftndEpGUw^^nPLoRI!Ovd&Ci|!fkG4s2n#I>pnwJ8BKD%yJ%rE}cgy_y znil@&lbjt$`jB-zq)bAlMI4O7?33{QA5*LeuO{`JL8y+S3?GDNf&ido=krYX%<*FQ z3GmKwkzveK4)RLUD+fC+f*oWS?CGS0@pR#yX(v(Xf!vN~%IWgx`Vr{iuc%Lb%EW9c zba<8=Nw~+IF+ZM0D2>Pm9d-Pcc}(fQ#L$6`@D7ru2|m2{ahH1KgXoyyE`-PYM5B-S zZ`D4J_&I!H>17xOglxhdl7M7(ymJxYg#34(rU&G6qF*I8$0ad=4@&R@!6(w4=IVAa zhmRjLA1KkllmzPO>EomOEW>fQ&kR?MjK{36jlR{Vuizu3vR=+=;#sYOe`BORzD<5| zI!ey~Gmdn4AU}Wm?Ff68hX8$(WCll76913mX)sY|GnFBIa)ONhWHS%<2b58tT_f-; zfLhKvO?m9&#flBP2cg`HPa}ak_oK*r&@tOMPM^v4y?hqAoAiwFq8WXn`-fS_s6KG& zZF*Ey;k}?!8{yBxkf(f?AJ4G&;WHj2%Ik0G*W> z43aI=k)#@T zroX${{yTiAjUcm7kiMII)Gime*@Z-`q@H%sdgCa+uAHwkgloZ8lGH+GemQH}E_x&A zc;TcTyXz&E05J{#U3yW})-20~5`fSpU~wyN1gn}eHpWx4Ja1&57hE$2R*&|!X0=hP z+Agzewk@2{ZU>;w3V`|qz%CbTgo8i;Xcz$08*b6sq|Nc<<)q@4nRVl>9#%tvFEVM_ zE-o`x0E8usfNy67UMNVE(pI*1-Nq(cR>^M46WZHE>lQNr)b{{g=ug2ONfYpA!Iq~awy>z>G(ss)CIyF>_R&Z)d4U=jXKaE-fznN6iauzdW zhctvJh%p2TL4F6V2-_$Mi?ud3a46iecq&#&&K0v*b!6)XqOh_X(B}N>zoz)uK3@f8 zFL*m&!dtaE%&Hr#gf7u;2#s9P@^KH%_&Kad+*Z6VL~sD=)lWa*@1copb>9lPM9o{V zty}P7iRDM@rE7JA88oBnf-N$G_{uC>8uUf8-vEED(>XA|Enkj<1qq`N zA`w#{gh-s2ITUqQ4;%u~5=!BAd~!fQwTcQW=Aq$op)Rgl+@gJj_5?1runQ>wwT1u# z;H@92OYPgRp=nD`z39Q^a}5*%;Enu9Z6JkJ{20i=FAeg(r>W`wDr)%IUxZ)(WrH>r zzw=-GPwtJ11ym1z_rC!^K*eGYG#9mZe-}~)kgpj(TrRy5Sei`W;7H@xZ-|hMUc)Qtw zX`0XHGZE`N6H|=R+@RV$(5KV@1SZmAv(EE05ply-+=>BFx&SK$Ed)Vm>jAZzxx2+E zy)1Wkv2wXgMd!dA3OW(<+L%H5`d>!o_7E~F?WMxC*suQgVx@@?iD~x-|8rAK2BOPl ztmdE~UDv=huXVmmYNeFo?jpj>%-jIPE($~dn3=Ai21l9aY-Z){pVnGaN{BJ`eO9ej z;!poPF#(uM@ltB7^wU3gvrDadnY?<}b!7IGv&0CX%yWnwm{DuaQwV`#^y;M)iLvp9 z05J3B^knW#v_zR?5|J3lP@nUJS`o0@4P7Synn8YCg9&IcD~b>#3Q_1&;;w5L*_^X# zF)I?|F7;lW*EiD3WoqQ9*i76hc*UHjc4CauF^9+v1@rZp;BFPD?pA%uQ)8d)cDv@( zMynn+MlmZaQfpOJTPS|9?;jQ&VnqYjs+pt&fQYKu!l9}aA%vg(1-Tb3ERnwcOLMF5 z{%lg6o*o-~*7Tdg9Ee3C2kQFd>l2I@PdZd!CGPnekrrNx)tYnu_~G|uxBQ<^G85@D z93r3G51cyqdz#|w`U9D90a{Y;|^k z>Z?0Et9F(nlB#`+OQJ+RRH4jp=fN?W?xlZsxI5(WC_+X|tfYJ4>S7SN@8xXybeiEO zqr{>IN-n?bF&I~;nb1Kf>Jah4aisBncpZd-DXS}Br<0z3GY<0GJpR^G>iLt}Aq~lO zmnA(MF2qUF%zV)4`Dr{|9wW(7^#1{W5z&MI03ZNKL_t&>`GZ1u7!~(qyD}Y!C!(0G zQv-Ay{dgyLhX;Zmh(2LFe|Y+(jRk$6vEyNHI!+T#9x;6$#N0n9!N#Z(#mba}+i$IW za7~7@?8^NxGrc2RT=K`$iSwBRJUk?>j*Dx4`c$0$z2&d{{Kq)FO6ix9zT!bhJKU!` za(EdhJ7-GxEs$h5>FKknVtSg~`y&ZYy}X*9f_s)!4#Nc`I*#U*NQj7Z16!e zrF#)kxAUjpOcYgKVfg9&P$odLGF?O-2z#dIlbb%hO7emGUhqfv4;LBU0fz{EJa_r& z^W-FHe}6ZO*!KgGCFkeUr<$iT7`W?tJF;9%yYZvgZ~_YM4|j4%GD}R{_cT>80MAvinFYqw<_+L2B1Gx>e=uY})Op#N9Vj5$fnB+a~`{D4foh4yb)PaZv zs&YRBr!4Dq&Jmz@#Lq3h$ao=Q5qhzzdAsD;6!QYFG3IfFpv_U zj3@LvnhuajT!?!(sYU3;F#)c2_8g~^{mtL}(^eqrm97!$is0O$PS@;iWPB?iRcj3~lE{^G)h3rKkL-$|wU+rpe21k_x1V3| zx^Awu6rk3|)mjStqF8HTH}2K7jupOdERq)TZ-KqG{8uWop}3sE6fJ6t)I5;Ubo{4NVU&&v+;|9g^eBcQiF&Ui@RRF0gtu9QEP=) zUmbaBZL2yrI2y1JNhkzf;?@Ta94T-hukc3h3Sp5!U2!=O0zwV7dgV%O3@#2&wbl@P z?TJvm68T(FN@LOyGl;L@8W+{!6~GD`GVck zYSH+Me;X>AkrNSxpZ&R(k|-3bb193-_b>j(b~`rYOKYv>EihjQG^;i%@ddmH0U?x^ zKGqaM1GZ`fGr4<8$-Mar)rB_I;s6qxIZ-I8v-@018|h7K7ywRPF{=QDtAiX<3qVI^ z?p7M1**g`N(hlzx{is6BLKHj%u7+!N-+Y6#Iw##q1Ht~K)XbqXN15Uy?UO@ zwu0EmiXj9u>r=Aor4%NTWgQW*>%4lyzXDN=(oFq_VJK!1!K+J*v@$(gKYFc16h&eP z6_`}rjfo>uAPRxp%7Pz-1-w($>K=$BigaB{T{SQBY+g&zrvB?hin&)4=2}eM8=l1+ zn;n~3ZT46xB>*wDz?2l3+`YI9b1_$)-E7ukR*IR#h#1Y>y+$UE5<)O507_A}rA>%q zjMAuoL?Hl;b;T0febN>c%&grPH3SMF=d3^s1i-Xh4*y*s)^RLFMWi)CWZvMv5Se3a z57gE&jrnD@E?e9yutZxZW!5r2pP!#c^Y6a`k%x@&5q%)^NEcHQ{K$q+`k3T6=kpGu ziZnst?pK0Ui04{*PGewzNu$3K|-$nk_1hArYLvMY+pgo89tpq^mepFgJ2xHKe2-g9=QKBP6ryZ+uy=>hZNk8B+%&r;zGY11_JIy?wt11m;n-T)z{ER^0NYN zud=;);J*ea=fnNrz?8KplK_I5W$fiJ`K!@YZS3WZBpV&Q&GPz3qJIr~W&V&754ae^ zEx8uK8-?`ZhXj^E{V*aK=0?6B^qz`ge21<-XLnNCq zDi2a7(#vkNQAZy&t0w7xYCU1v>nMHyc^DXA(!l)el6Mv&Rr5k>-~DZcwk^-zFtb`#%|MC;0Nvf+TsdOn3cZ|SH7}=jzzf=x z-4J2gtYfhwy|IP5&3v1}0b#cXR=Xu&oj0`bOpPhiOp9(&kX=M1bi zQjH(frJH72$w%#7uuZe$)$HlT-bP1ib!=~;r8V7`q_EWi>N?H79?-bZT_g7<0AU!e zt<@G++gq$E06882c)7O!I%BQ?xLX=ZpQo)oeV(_{F2}CA2>|t`ac(DP3p13ih7Hs6N#>qOi7P;oo?xuc!-LegX+kv`*BiG8d zdscb?VSl~RzRxKpfDi@THCPJ372B$QLJ6+idKmm)44UUBuwhsFWpgMsl6m$2$9GI!^Y1hXj)tA9gE2?`nUqUN} z5SW(Qwo$!(BX7Xg6$RT2#p-H6_B~Jj<9{Oo-mIp7{BPW?5}7ukSqUL9ajhOgBND-C zo#z?mu}@$|tsG;mE+WlR9f0Z_MZ#i~W{oaa0V1w$6;+ryMh3JjYU}FOZefl~xINT5 z&85AxM2;JOryb_*k+}ly-gQYNQV3obf|y&GRU`9UikUU!NfvS?fWW-qcK~KBs&o6( zDKL?T(2zR>^eK6*kz=iH3yIriv&hs-7a}(>u8k`Rqz#e~2_dMJh~_S@4L5HX5C!sD z8v;_9h2sjjH#K?4(-fGyl-A1DKx9^!V?)Gv$3)!rT2c23l%;sJwwQp$EFe_WhL!Y@ zvEK2e81wRW>ShZSec=I-aE$$~w=zu=2MSH{CXoU~rmR{USQ(>xZC3P=*u4e>CWg703t3{+`WCtG*qtrxhzZ&HAFv`GS72q5iL0aAZGU}k(<>( zj2r_Y1dg$~7l1>+3gd!&jwe-(JpSRj1EkEd4&W> z5z{QpnX+64ev?>anDu-DJ)6CQ!udkj<8T4oMrQx*G*Vfr5811@@{*(OJ#!2NgW>Y-%Q1Ck*W*uJ}gUm#rz`gtlfb6?WikwMyZ~}caRi=Xz z;7K?i024mN9xnX}{ksGOxybWq zub{fj0OL1?cbOgqKLTZE5~OTN`J&TfK7W3~qwAkQG~ta3H2BjHQ2xK~{eN)!{y!FfNI#?> z(hun$o?-_OI9`Qp&9$nfX8OZ|>Z^h*fCwBzgR~lRidL1}hF;x%#$x6j7M|7@1g5&7 z!5evJIgvJw&rP}kj#pp{8>q9Q@K~5!D-r`-KQEl2)jlaiV&M=eaDcaYYej92#ETHG z##-I2nT30$FNk1Uoi=vXqNZ3mS@@k=tVcJZO(TBQ>+B)mHotn!xuGy593pS<*$tXh zx7Ms)$#^}5h_7J*t5;u8txbs+Uf@Il%@hS8fB>)6XjQv}TQu0~&E;Q$T6D!FR~Rd- zVAU;LwP97^=FhO^aNEdR|6hrF>z3R4Z-v>AqT28&zR3kxiEh^|S43+=zm~t4!;;}` zHS2Z6Ev*+o3rL3QHF&MIEC(#D7GM%7bqExgxQot3Lga>+G^ip3nx`Bh zw{~OZ21uJ3h0w@cn|`ouS=e>}8ux^Vh--D7=LS3$E7kq#BD4?%5peA-X72l*L$F$F zt)-Y-nM-jqX0Cw5*u}UNzPhi0Xdoh`*gWS_3Nbep*p+Aogb=!}bN5JWZeGmXyjB93 zmnc16N;Y?Qj?1c808&as)CQZmhY-3hE&4&P#BmY7dL^b{sHg!UMhPLz^Bh8L^s6R; z3;|v}5VeKR1!{4(^8akuagLkQ;XMG-=+wGjZ@ zaBa5(5t(WuSWVM3PkFY|eCry!t(V@caEuF|d*!N@Svj&WYxBEU!hJSdv0BWgoG;_$ ze16I~i^#g*5&k)#TI}c1b}nZ~u~8uoFEWsx_s(pP0hHwtLS$(ob`)_J>dn6bO!Q$) zPd(~*K0}h&fOtlViq3haTsG3h?ac76(3Zu+NB8TtTM?*jGAq`1-S1ksN8nZu5r%7?{amWro_}zga2Xa@4=x9Bl zuY1ojTt?T+X*T_=DfF@fiqM(-$k;g*#LFRN)rS<%m%M}KQTK}TfQTOCa!x{-eEMd@ zUE(SjCy?SN!#y(#j8x97AH`D|X7sZdt5z2i%8X8(`qZoLCsfdw?&|=4I_(9QLo$|L za~kYCGDJJZY@UJF{ZL5?bf^9~Pi$ToqZ%|HMTqTblHK4J*PTcqM3w?)$SzMv{YO#| zbi}?#7V^n|awnH3HHJ&dz57TER=(qOK9LGK#MV?i&0VKo}z}{n?w9~0$coOu$Bo8iX zs_#d493Eb~L#ESv^*Il6KrgZf=kwEKe7L{g>(rg|8F>`i4fng@$ik8c24S9HXJyIA zP(6=f%1?Q!wvnFys4l=(UOqE3vS#deR|FF+$ zfN}+KI^=TR84fN2RUe*3)NDWIdOn{|Prv%~t1zBsdVPX)Ml-n#hrjtfJv9DN9*Z^t z2$liV{wn}W*tN#bTI2&aF$A#&S!;*2ubdX;&=pvTB+Ut^k$3t5KuA3R>aMJ=tG^8J zowKHe%hMLYnl!$B5q1KsPDuz@&6So{;l_8k&Ac5)YmjLG0H+QBb6{+ils}Via{{OKrPa8@3GFGS>@&)jR_WVXbkUmT5;L8O3yit7dh4gjk9wiiGg(so6Ugq6nSYFlaDDgf7l zZBp8TYSVQN&%1s*mwEvZ)6z%n>J%IGskMJyyJGtlt}RaiE1zpASS|qM&;ig3GtlnlJb1*#)}tk}6eHBB_o0bAw)8bAN&Iv?6Rl=&yLq%}MRo zLejZ5#tQ9iFw@I%*!H${_7w!I^|k@8CAu=X!rJ~zu7N6Qr7v}SH=Vfvf9v)dE8P}y zYouEg=?nf^z-_;81z1b^JBU@l&B0qce0kB8TD5Myg|u$0+!u1;%>W1-D6ZvM(XK_G zxc25cW^S+79>+J8-w1hLLv1@NLhv@cLPY>KuADnUg&`2JP>9qX(ZF?d`RuOlAcP99 z&0mIqAk4htkHu>im^gB+)y-cF{_knB(kLg?X8w(`#1uBSN~@KL zyu#hQ(e8+tr~#7A#N8`m>KeS#pxXe1<;2EyQDzQ-%#8tF#dPl0hKHGXEe+vn&%5U0 zbbG%yc%sqD0>DvXvq(1sFwe8CnndZkrVndUM^)Y8B({i+s-@XZg+L-57T0Yu_gYbk zHr`n^3xN=Vy9K~&Z2~$%Fw|lt03CB#ViGJj#DXReHm9d{vslqU!QEQ~iZ;xekd2t! z+^x_;`hk0G>l#fbO%y_uidxLEpj{yZMB+ffY_b9tvg6_uKSS}796Yo#?eZUo9&z4}@tkC97J0MsJ%St;hs zLo_xs?}{}mPIDth_^t_nP@?;#_>WcrHdn1uPuT>i#B+AK38{%ayZ^4k>>DK zYc;RtW|zxctf&H*b#7n2O({tn-Hka`H}{%zj!aEBiM4nQ3~gQ0F@dScPB&Usi|lFc z0cdvh0Ho0gYefjEI;&2XsX>IGkhlZjW?k1YN1`B{wpAJ}79+dYW@SIlb6^f3lt$Dt z3nAn@KR-R4pPy%)iMd^+34W#Px_<_!mW)+XCNSlL$%ISq=}A%*IN*?SwwUAyHQ1#; z6Xe;@BdI7E9P+7`UJYpwr$R6kQkof`$?k+C5q{RHCKippJom>%6nH*p~AkJ8$uv?S$A}1|da68eU5wKB(0x zXCYHLil0?G$hS&+(VfY}{#xYZI*)lTd74m}1_D?>kaf*uN1_5`enk+b3%mdVjc&s7 zc-FVX?$|Rjd@%Xc<9W}CZkX@c|@AKm#e5rY7~2#(@1;L$*kJCUhR z!F;EsFbI?>?}eYU?s9rgL|zgBL(&mo6L1-``FQzwg7=f^5q-yfuTGxNawydIBy<>p zS}$sj{b;|2e3Tq9?vQZ$lm)LGN6HE^J>LQO>6E|y_^VH!er+fAex8QCjNT6hJIZ08 z!`t7}L*x7ZSo|UVkbX!%qn_6aGQQ>tpX}ae9Wf>S(lw|qv1sHV2B-Y~AO$dk${8|6MY2GcPwH8|muams* zY+Kyyx&?y1fV94I%c5sPxGBkt1(YwF;KdbJy4K4wEC<~F+K|ny_g}RC7kfA0^vn9* zY*<0ho1GLWhOp`ReCgJ@IGbJ1dNFXe!E-C=TS$UoJwDV5snD^gtna~GnGw`T5h&J8^3`@V_(gxP+lt=zpQ-;Bg$}k#@U0Z-x>{?_+1y*P7Zk5m zxvs`uv_|*z%3W98Ypon3LJ;=`n*!h#Ll!VA6<`X*Do5^vfEMpMHA6sSf6aMD!*|y9 zS#9c2tLt1A7-fwB*a%$SsJvav4#*WfXl+03%qiZ zC0|7=Zn{hW=6SAO zbIwKQc6T=}TayGfVc~2>F?!Bj*SS}(9+}%xN<$ctrGcSvdArQ0I>RQ?wa|oe{ zokhBZlSmX0)XdGy%)L(24 zE}Do_;tSy(ILp%qAcJ?&kp+ZA)&o0|8Zl<_9f@-~^u;NXO<8#yC*TYgmwZeI*XXQd zrplz9@&#~Y8sx!X@y*=v@|kB97XaE|~_<|C{0KN;s=a~$Rm_;a znRL%`A-L&&@*SJQ@1RM^k}067?;xDylj44`iwqa|PLltD+q8SF_fXFU>U z^T={ZbUEw0fxnsTmB{BrI}DE)4*)=uuoK)#O^-c&ZFG0I z6Zb+u5_cBKj6Lj`Qt27?(2wVLAWy>ub}s@rM(YNt3Qh^YkKt^(m-}bdA449E-}Jf% zCE=`-yH|%RQbvNg;N*1qsKX$S_lH;74{9>GGtZ2SoYY*;2FrtdxFg8jTYUUmwO^dZ zPwXE~r`@C(^d3AyL{#7){ZE6FnoGWTdiA8U^si<7q`tFZhVEbo>6HM1IL<^O>C!U; z5EGNno=nS8RYeRSBLXfC#=*rzTs4A$QB}1&tEt-QJSr~c9cyRij)4vz;6u_h@Zc&S zQgw!?%pkr8YbG-F@z;9j2YG$&Gtp(hVa!p_<6r&XAHV(jqo!x-yF2*}+nZr{5;NFN z2HB<1_rI@)#y_69w!x1803ZNKL_t)qR&5c}c5eV6KeinJ5PM){g2-CY_LUcJ=pp-u z>u2c!@ZkV}_XB{~ciUNU*Emf9SY43p>VniAHkMPsN){-SVPyujE$#X?8-SQ108R`* zFS?by-q=O0oS*=Jx-BSP1t9ylmE7h%0L#}4Eq+h9wnw9kwM=ZXZTtKv0Jx6;Y$?Xd z32K$SnM<`QFT5e)?Q+X?+N%*=e=duqOaN>y+jaodMF1>UP8Qvixh<`8yzb?m09f{| z-@C6uH2vi zw++(j-wwW2NO@VQ96+FcJEry8qCr?&gE(O2lr3$`*UNdft@>EF_W)q(*a%w^0#y2Vk}3YT+zfK*rr38~g8u6xM_fn{a~`)*b^O^Z*>| zgmC@2M4art|1VVlnn`?!F-S+d9i^^8Cbb1_W2V?FnP}zOghky@))@=dw|n6FClDfW zZVNZMtB%Dt>V@@STV=2K73xDyI?yU z0&iWg1nt~-b2q)bF}cD^e5&=_)qDMlrlCcryncHw{{Froe$^`w+A-9CD#9YUU0lqT zA#nwT8w^E(I$E`d*I~KbPaHtRq1GmkeL0+n0w_=rB+ruADczaG&hxy%d>mr~)mBPA5Wq3ASA@X95rS2R6|dWvuccOZ3yUytlR(x*5Latm z2tM45^4-0;dJ$bgFtg2uAHWh$!EYi@1i));fgl6mfY&O-R=w@&)`oAt8egnb--W)( z;@TLX7q4Rg;N~$dR#{;&yQ>Qlwy-d-FtJyNbWFhkH*aklMXZ=aHm|}|fv($y4Owq! zvpE7{pa$pVQW`wO9GW$IGgb>Bq<(NSD@99Tj-@C^hN0_HDVlSh=Xsvzc07g9b!o%q zDmVa*ZgxBzCz zXH_l5nrnM#?qh){1Vf0CtJfx6ZA8L0up4W&J=#JD)vL~PVQ%;@N3rQLj^j7qd_#c{ z5Tk5i5L+=QkZ|n#p7{GuN>Dzqf^nDe8Aj?dkn!stme~gZCzt~~1c+XK`5$*q8PBPw zj7L_HbkN>09VJEL0y_{$lo$?yj(@Z3Nvt6ABOZ@((BXCOV7vl76Yr7`@sSvZ{(hox-cODb~2sreUD!TwWMaX%|>h@b)VoJ{i?_>x?i3Ux2aq1kC14|G( zPUG~5{9bW!jfpS7F3TYIpE170AUi#>e47wJKNT>%>bMg+<#8nYY#1TJ;)y;u3n>u_ zC<6(1=Rpf_yps#K_!L!1ofw6o2AJ+t>k{$9GXxF+?!Z|9wF~(t;J)t@;gt?^uX4vm z_N)>GtjuhCQxZNahCY3UPpS`z4%s1z0TPZxcbxBSn8iB9kKD^acf;^r%@{pp+}%AX z-X5T!gJS^iaR-`4@H@52+$Z{wa}RlAwr78Td$*tt0i-WF2@hsD$xxuL-X5Nn58Ny8V8kp0JrZT1nt47z&*M?_ z0vefrV$+3qFLD8wM0amf_r$Y5?MKxl<7l3SOP&sP_g~rAeKTe}g?>EQ9m{ke870A? zf&-W#mqe!NIF7Gg|Ez-)!)TxG#U@Y3q%+b%h%q=^dU_Oe$~_d6e>GAWkT867|GAV2 zG$t89DT$VRFahLQ^q{z8N>uR87=5BKe``%yh%yjVWJ*DD9r{P)gAeye7v@K{qvFDN z;{aJ;bJe%N$C1B|M2fWTly^24>Aha7^0s=g;HVqjDz)e z#{ob7Jv}tO|BuBV(huo}^h5dwCw~35&ENwO^?mFc8KG7t)aGeTVX7mdYHXOn z6}(u`%mru&fddKMLM^u%G%QEm;1})9o$zJaxIpzr(+8|8?aMJQm|S={Lk&OxaoA9^ zhBe&mUHCyOvuxdhEpse*&n-~(U7*1Rfi1Ae@1kHEY_z#Dt%Yx}PTReHzHYx}as%kl zP3vti&*!bs~`Y3 zyM|CRAR)+luQ1@i4D9;eYPD&aa^COv6augD0T-y|1}3`zN#c|y7M@iS>(9e_1$`d=sGHys1h6y<|$_)QnNNPHI2>wZ5prP%F2 zx>CsiE5&N9UYUuRQ4yHx5(qN+f@?Sc=|Xj{X45=(BAv)>Xby_(W=#<8T0lXXO;`xQ z3?VcXTlHGq0)nGDDj~!`hPpwGt*Zl32r)Jr!U4oh2w(1w9)xjq${JkN_4dNj*UAk_MAUaOO^`(W4BIRHCQFgWN5Zch zuhYXH^hlt4dKegLaQNGvbaH_@_~G#Im`~qe*x4laLx9vIv&vTjs6|&|o|ARpPAO@= z>**VP{43=3BBjD;^g`j4I-(BQ=%?=!vD+O zyERFUBw2dLR83)UgnL9rX4a*vXL~Nooh6qdyCQtyBmXUb2`PM85z10{8E&(Cx@)>B zyRtGX(!)LAFep@w4+g*ynbk|~l0CB1UG@;^i2w{{26F`L!_lKilHNg^EX*1srU|#v zTUN8KHq`E`mGi5}f1cMrKJE&^TmPT%g<*wWJ;s@%Uj_+DIT*zMT>B&X=yk`LF`wq$%CllN{_U-Gl z9t-%;-Q67SZ;egB9xtfb$TEWi z^$vLKU9Iy>-@JSJBi%Iq zQK(i;SvWss)+}!u@mbA{Sd;55S=GvJ53G;f1ppszf#m_+9YFKq7QpVanszV%v&t#N zfJHbnpTD7xegd%3u_$Y*XvmeZ%5!jSvg~+0MKeYK)93*7tXO0_%{~H%I|eXao+Z~? zyrnkpc{Zo0+v}FvxvFxik4dtN>#6J8<|+y^oiod3Bqg)FxKfT&O+fzJ?*x4-Ft5xTA z9TUd-67{-M)pLbN0OUph#Fp3Ly4Fh9(VpA0cvY<1=gBo)#a_xLHVD)#y6bP8JPulsKNpoE&qCT)LXQi5y zbCa`jPL7G%q!EjHYx|G~%xbu>N!d9+5!R%fMF7OZ0e=SN=4UV6i}j;T7IzZc=+(8F zslIN#T3jt2Ng;qhv!&AFR0UiYd?75sRvhNH>L0DNm6?ule%Jcs|YuH@FqTkt8 zhjm4U&BVvEP1k|G;+_Q^Vg*BCBYAr^U~|hhtMo-xa=klj(blJUMYk$MDll&-0`?v>7d@be?3d^1C8kTqkVdbj)+V-?~ z6=zk&O1NIx74vPDzwYp<_%w$ZRvb2GPblFk1N<>;I&WKC!?uB$v;n)-cqlaW+vk4{ zR7=M(=Mkmsx}8m$YHDDhA4d`45aMzv1Q-B!XCiKQ0OBGVTCdf5-5iL(1aOQtO|s@1 zUUu^ZmaR~12Pm*>+i9}YNB~x?Z(5Mb3c>==q%_yxSd1}*u*#9Dz_kFYex_ot5s2o6 zC^9p1WDc7L3SO9tF#{NN5@{?C1z3?*^@%6K!tqc_aW65(%P^!i^?mO^+wM{TZ=6-V zl=;g?RNO^m9C83`vQ?24C6-cfwE&ByIC$1csaXJOzPy~rcGuS0P^C`OwB88eD5Kh> zS+(9us(};$gh0gg?~9cZDO8pRz)G>n+^uOEn^Ynbf)_8F@$^!rQf!)lFikp5Qz>P) z+cC#k$3(<6i(jewwcwRIm!f73v-ymb%kr1O%%^djs=l5AfD|J)^7Qmn<3j^+l1MQY zb5otwOm0LJqezUgk>YMFYc}}Mh>C5xdBj?%$5Dq6H3{omK))^ zD|5Xu*XOaKlcVS~+61PGqO1_1lq^a!S8tuhbB((N(4;f}O#y7q)$c&wGIgeq(YwDTeb@F!N~Y~gN22{_#L6bEu(Bp~kuvnY?u5$nP9T zXv{m7&Y{Et!2GqOOLSpTxBwT=XCfs*!rRMfPj`Pq=uNewXhj;;m{NA{tbdffW|gFFlz>Efp5W@| zhsPJHO!N-i5^nCL?Yj2O@q+$I$f@;CzCbsaiVh)r3;ECwQ=3@irt7#9QS4RA5B=FXp^%%wsK1>?n#92gjJXn39Swy zEXL)KWWdF7t9f8KQ6k}ylwdoei*%h>dN{x9`$2`z4?jO2k8i&FK@J(VKlgOs*&X0` zMRG7|uz#00Stl|yZ+?Gr$RFvR@sn2Tr}9(zsr*#_V4=jpODPg2jww>4K&5!`8gDf( zWU%5bEF9{ZaA83kD@CB04TTznwZ$%51XfW*O}bb=%(bDeZ>~&X{_6wL6tbZLvPS>k8SG0b<_ILAP+q5g9_|a0H&ydab;*0!hVO?Gc*EY&^-gCXaVV#_q@hD1} zUyY!0D}zs^OvP*gy7ZB z5<(?S+%y3&AeW*G+e!d2kAO|nii4(wPhrEJ>Q4bCAc}Y?Z3y+ZzA!HX)>?d_M3Jaz z2*CPc(--VTn;BOtFF<0RLm-!@)w22O(DVO-Id(f=0`6p~e~n5Y@))IQ zNEy*jAhYSi=`l4;{T4*xz!ZpLePbul$5EO_ z$MJIMIm&Q8r>3d+sY)GH6{Q5C7^RfL%NGg@6SPvM+690mGJ+P@$!gdsQJAJ_G7ljz z69IwAy{L{k4@`8q3_rYoKTT6=TXT=ZRBiRmV<4fE(bVs)?Nk0D>IP2q0Au zQODgc^j$-(X6@we-n1ooa%~2uLz=SgY=E>+a2*WX?N0hL$ZK>EpXlyy&Bzgiz|%@6nODczOX8Y0okQV`h1kC`0$Hz*yuC7=C5# zXWVMC7mhP^Um|76$q`^ZI6)zF%W?sWnwk*h6B+34OQHz^SWB) zh-D|INq0l?i0OR%Js5uakh;{L@A&QoTzkDGe$wHEt3gf~fVZi8I}9I$FF^nDi<1ri zV*j#%{ng}%`}3qP+;`bD(t~GYTvTuL{97LeaC><$?Em?h8FbeE5g5#OpcBLHI!3zd zkGn4YPW183o9|Ta1o7@=Lv-oSnNLyL>>jOufTG=BIzG_8Nklf0s{Sza*>>H2yuW2; z8TwWZW~Tz$iSQjJfBDqmPS6^%gGDad-l)v|p3JYB9o>FPy=rUjNXZCE^mst7z>)BMek#m_Pu z0zkSI0NP&-p{kmOn}9_WQ&mN)(Nb(9Fw1uIQngoQ-SW(Hs)~}T5{Cm88!1m$4OiHB zDqWja&l|4>(p3jE3&ghiGF}%4TR{PAxSC8wVJ!YuRgQ$kg{o@Df&^T1@DZ@+n5sor z-M(nB*VE04p#Us~S=*jsdA;^*SONgV8^)qzs$;t?RlyX608F{sU|o-`3$=B)X49@( zZB0fK!#Z4x_^SXwcTJqcySQ$zVlnBi7H0JU`Pz%>Ki1H7%-8&7S4XV^z{e{Wn46bA zo(u@}q}N8SU910@24DL%J7>wvDAp6rM_m(^!N$!>`Q!j<(tEm@pA>16O;YECm38l{ zxmfK|m0ZmkDz{3F`UEzNz?^2WCc|3S)w4-07c7^4nyo%+k2ZHA`uL*%NtP-Ai48+I zL<$r@B~+)U>lZf6&}UXug{_pPzB$J;sfHY<%9Y|8OZ+5V=mUc%25N z*mWo>)!JOX00L1Rc@%@`0zgZtF08JBsuuFo$y{m(P$?ElO%qo(ylTC;Yh&upewDCo zdRJznu0QoMP1VoQqcn+G*1u4ImZD2`-HE9tbOVr>iFrFI>^bDT{+U_Qz!6}8Ehx%? z0mzf>B8P=r0g&}?_p;ksr!S}A<-Y+CU<4RwmhENJ09uZ!XJ7ZP^~)pd7f zTE8GErIb>f-(%E!)a)L0m!z%=|mEPYAIgKGz5uJ zRX1}aFh{0b00w= zG^ybwjex4^I5P2NxVV=#wE!e?V49{$mYkcTs(UFYL{)6Z>s_W4rw~$V0+HtI#Z|Ss zm~rGt93m4DN~tIH0>f0LRRyJOcg4+1dFuN}Z0_z>IaeSyo6J0fU~Xj?qBL%UP6_}a zMCLZ7dae+H)Fi5as>Ub?uu@c&h^twcyD35lp%h;NRKx5M#xVfq#mp{GPgcB?@_0HO zk4FH^JgJ5d0>>&e1Ba?tlNeLm4#SYgapu&2`gbop=+DF_1zWn~?!N0T=J%64YTx0Q z)y!RW*rnmEbfN=I*vGrJyC;Dg3Y!{8)iRt6aJVSJ9Vtm;5IejubH@It`=rJl8DBW# zIP}B$hr``#D5>onEID`bDz|6At-DbeX@HV5Kqr{{&>#zSWHPvspljO~r{nK|&)P#L za!dRuj_UF4U`nHFZ~98olV@V0)ZY5=q30;=YwBK+k@&5Hq}>Z(l%YGOtSJ#3sT2B3 z=-1F!?cFQjRy_a(!qA=DzLodpx8Q6l47aq;v=e;+M{cLI|7WhTRWo`r9@#ooG7Ri> z**y*N73*&&d`WV5Ie}X8^9Xt(koF0Z)t}rX$wlGthVjboZUtY8NGloMwiJk8zBYha zAw=2HdEOJ9CGEuTa2$01g7j}7kIJw1GSWV`ewR`YB*Is4Z-*jnkv_R+^+)Uf89GD% z&|?ScO$%_gmO4V>3HIoA|MITu`@U_Dq%n1L(Vg|Dt_#ySD;`xZ(4tmE1`H?7A4ET# z`d&o%?lbW>>N}%WI3D(Gqywbow$)=e>*Y)N_um|Mim|=B7jP^0BxgN+-lkCzf!q)3 zL!4KHP@FEA05q%+-`{r^aIs@#Z&V+dDLF$j+Ag7?Nan_pnL2Y<_Wn3HlPKig zvqt1Nyu0-2!91(pwENKMr0o-W8kDpAEvaS`YMo4Q24{!A62HJ+m^e#De`DQ+N&5Ucn;hT05xqp)zkB=k z&3C`i_KnEP_WVK9=?*V@{qmIj!28s4;=S($?d$&d`|~jvM&rWzPnv4|RDLQym7mH# z%|d)-1~aZIGv{4b#q*MSC0P`zcl@HM31PK1Ss?{hNEFskxD|EPJ-6iR8G>2iPMK@` zB=&A&xQ;7RC?74?ezbfHe`Wx*N^I6B#jREg3)H}D#_}W8UYoWqkyl5jWzlxk;9N0Q zn7go{S=UZ&J}lke(4{(HbXA#s1ofU7t8dD)D9%5?=CDCtYxADbp%osjSotH_)Q_^H zXYlJPZBvMB001BWNklQ`eveCfw}Y6PCQ76L*k26q$>2qkcsXOBI*QtR}l5{ebK;#Nui=9_|NmmoOG z+`(m9P?$sY3rxLu`RFawpJdrdbcySwK8~|fyG_bbm`TS`nudv1rUQUCMp|XTOsi;X zRX@cgKGBw)D=ewOjJwDM7?(QBMzQ4^v{V)x7CzxzVUcwCM)MV}-^;mewrpqM2Jq^= zwd{k1d0`<|v>X_#3Dkn~%BC;t2Q2u^ONmU=oGys+IJ#K@s)g1xDoU}9IYRyFruyQmV;eg(CupXRLz| zye8)}E2UVkb*@*57O#PpArNs*Qt68$gPJo1X&N&R6s$NqY%&y3fTO}?=g0-1fHozH zF|4UJiHdt8!ZG@s?9u!FDaN?lwGSUY1R|yonL-FPd^G?dg4<=dcqx-xK!}l1$~X)x zQry+d-EX=ZVs>|P8^;kqlTuX=H*H!I7Zf0mqv}*)E`VSYP(w9^XaYbKywJmk4^QVO z0K_C!4^?0C5g9;rKzUAi$;@U`WX?GcImalIjtIkSjuyf+O_6!MZB`{$C0|pWH>H?+ z6|YsWSiF4q_Pc4Cm}3oiB&zc4Nfvz;1xjt(#CU#ssu7Nn-P|dCik*z3;3??uOw>y^*_V_+gaSd$aR#FkuFEo%UzyL^`)%*+qg&0T|jqpG3%bZ|M!_i)T`cW+rmb{eL6g3&eW@yeDT|bhw3N z^27p#6Ca?)j)za|y)0mQH~IMGlXPa-&Z79(-E3@}z#k-J_VptpoCj%R0mG$Wr1 z5Og>y*i|5B@S~hzJSD$J*SYP$nLwU6!UciuCdWQ;b_?M44y3dv{~mO4|GCj4qXROW z6_S0Y>bv%R_7};jPo8qWSA2#JqFLpsYsKk8ETEmagD#l#Vv61sHuO;4yT8Exg(7v` z55yDMoiKBnEZ?wP2HguiGO6}LqSAGytqHmAz!$aB_r}tjDL`f~L<~@H>h8`Wf01aP z91~GQnjE{`t#l)Da_Y_b;axAu@9%EE`TCaGL4Rq9TW`8FYF}JVEl*HCp3lAAz|RSf z`?hIaaJHQOS}hN~T7UEUXGdZ2jNU&S`$p{0-3>?#?hdS00|&eO4P9Y;C< z2%^C~CBJFA(_jK_$y&kg?Qj16-CGm-4y|`0UAmzAOR`;uHseY7An77P~=L4la5C_bDIkP})n>bHe0ub-#Q8k_4W0cHoWTI$GGfnFW1S~))#k=4>D>ZlIVxv|c_^$&p=VZJL>-OrLRW(_% z-vOur)>{o%b4UR6Jl|rf91Lo}oCz^jeV<)tR~-U5{8{8cTs+j~b=Z=59rGjmTxP^W zi^en167{zEJny(rhM7k^kLlYgp{~N5RV4Lk*$DAA=poD~;u+QY12E!x)Q{GGB`KAL z5UsH0(@MgX0ey;rmff~etn!?gEH+HfInnyLp5j?u&k58=Ew4XUWz+LRSIx=hMzGep zRI%3l5r=xtu&(Ruu=!AHUUjGo^t{$~ZRzsi$FS6PGHfQyW}i=0lbcR`8f+M-%#1H= zaN!ngeMGy;l@1jEWiybWTnENOF?cAL0#J&te}y;AUg2yh9_B=E@O2&_&^nRUseEN{ z)x8Tkul<1;3fD$%^B0#;Hs1<>Kuq%=aW9qwyv(WY{-n$3K25gRMbY|!sNrgn-L_cN zKvf|ZLRg~$W#Kzv5m?c}yzJR`Xywu~+ltE}Ty)upf$CN4yXaRwsh2q@FEj=T_2 zBSb{Ym(r^nlzYx&DIQ~tOcSEp6o?y%j4&0CfgE#Cy1SWqb%qKwd%Z^{gun>Y$UZfz z1`R-5q9v+K3=7(;R_MF^-rOfucdwpqO`FW@hlhvi`BlRxiP)!!>R%N1ns$IfNKFEY zndh8SN;Zx$gi=bAQk1AUPhOVOl`-eoG)*I0RoCTmaW525QxL|c@hKL!!0cws&6x8z zP4C`*Z#FS8No+)z*osfnbm=cTDHFGCyFcv16atY?Qy52yqB>3E7?>sBUQWpZx~Hr=S4lRwywP6m zxa;I#`wYq6-%uJ%BI5~sBhsZd`JiT5B>{!?l|oWFl9LqQwjXOjYCl{1bz-XHb&Ix##I)lqm* z+^X*w7uMvR6S*Uao2OnicN$G5U?)Dobr>2yydy-_B*q4~K^)rmJ+e3%kcXIX&S)S< zIyag!@*ZNs!*D)>RQ<`d$!JB-N-rSq_N{{i*b9jvVqXq8BeD6Ng9QLJMrR9d@WGZSI&TcWK3qU&|5L_{Nj_|C)^sOMN3(}W&?E~m8QT92?{7G}? z{N{9g&7LI@OHy>E)X9g`wJpB1+#oG4Sddjo_2i;r5Pozt%0X~Ta2A8?4p%3j^*|CS(HktY-*b-|bYVJ}dP6cs5wi(QUF-eNtIMm zhs%KQ(4UM_hezCX$r$!#IGv>X>%M>QZKvqkJ4JfYpZl!YoDzP=$T$nS_g(vC>R5d* z2wAj$%NbAFQfsdT$Fv_b-*Fb&U$VyJ{-8Sa&9DE@Uz2_(;$70ND=wXCC;j>D!w2t= zntpbFkh`CMj_ipn>pSX!HhKOvj(cgxQ|=%I*h_MkQINU=&~-p3DG<121yP@Gfka&v zeLM|7d(mu?^)wtGzWMk6!~gWZeewFJkNzJuFT+etVDOLBh z>BV*bZ9N<8@+tax7GSvHLyKF}>N>w+URQdx_5=l+e0*#D+i}Lnl<+?`YPKw`yLNFq z$mQ8?AC+hEq%(f{F^Gm`&jYB#bvJ)D(*nXWzY5^R74>4x*$h{mV+<@n3~q2kF?bE{sfpZtKKC`1K|N}j zg!4D9HgXXKRX;A@5XL}(n-E(9;8TgI>0URV4BVe)X&bRp>g_>z4hgJx6km9Id8G4St*rztg6$pP$5~E5iK|=Z=lk+h`9h5pg?U2hcK1GAxxO_7_Qe!rz%$o zw3>M@aeeF6w`r=5+5niymoPwV?t<0)C;(OpFGsF-hyn~|k-01uZMBA~qnX{HI4*>% zFmnh*Zk4BcDKobSp_CFrtSup$g_M;tRrjT^bOeCAn|U2fv)S*gloCRiCY>z=H!3Y% zax50J0uV901m;k{k((xk5Mty~$}~;Yz23}Y&8}w_5FKT9YOfNlQaqq$)1yrUt}qpV zV~kPiXfaWZbW^i{5IKYpqDYO@bGNIf7!%ChCJIPxd%0Y^V4BpXsom`YaJgJ^&ar9M zt3!d{UNKX#>2y9zl=@DnSyX9mla6C-nh=Pnh{&W7Xp}1G-cRoK= z<1q@To?LZ$PkcB>hVS2f|Nh0pJdSf>%>t|FbF%N=e)s?F#_&&|3^H{4 z$o-u#ySCKvj`X6ROX`WqjhXIUdX|pJy8YAO1M80H)?kYF{acchvKqbXnZ#H`9)*CT z;cjGa?%L6Z#@P3id)!Mq_-RU<90_nedd_3Q4$xkCP&=D~k%YXrB<6j4_Cd%1HjZpX z&md7JlJ;BGYCQkJ9R?P9V7)iFu&Yc!%mW*EzVAKa3t42DR92!bOv%t zQ}ocruSA{*$=QiWplF-clCr=QP~{{8dJqrfaDxgtj0}w+4*A4($rfl5hr>jjkPW!N z8`T@9M-q=JEKI(K+`hVh5^JRWjJ5Q`tG2xu+^wVBWc{k`O2U*q4)z2#!7YoBpMfM@ z0Ni;pNc~IIC1RJ@B}r}TdZL#H8BAN2@tC7vl3g_19J*k+b$L=vEp>*TeGpEXVER2$ zx@!*)r}tTJHHSg@_1y&UyW{WAy>`-4)gpV-$_3g%2$~0tZ{9X-_n}R_=~vwz;@;BZ zAiefO+r3v3qozAtG=tm6)A4Xgcyplc_s%!TWKVaz z8^HHO4qV`_$ftAj@aFBCH}5o`+b&B=olNO25ClqtYJdLCVLyC#`s$ni^?&@@e%tF; zj4$qg(SQE>UrTy={rOkqf7x~yr9JU0ku0{y;e9#^BrBqxI%iEo0$YZ41gKc|q3?_9 zfPOqa=3oBZ@4x=lo8$5K895!MUwwyP{KYSS^YE|R{z6iI@$s&0#psg9! z+!zi3@}mN14gxG0?xq4@I4*tk0wBE*EZQaMswgO6)eTh_C%e96u9BbGX}YSt_}c!h z@@pNaISF;Rw*1*oo8M$(6`uS^I88k%08IJ$I=GHub2ZzV7tz~FX6u`P)i11E2P#wp zulYTBJ%9j&Ip|>?|3%YuJ^B0qw9#bMN~#i#<&&<=>(~Gw?!x*Rt3}uBuy!5Ky5!r+ zsX{DkwM$mV>%i7)SFZ?d=GD4e-B^9K>Pc%p%GKou%T=(U0Ps!k%0`Jc_j;?-15#=L za22Li`?Fb^S5M~va@kapnvdFF?d0U6`$hHc2<5?8qRVTCKsm;pw>CSvh9y;=dpmBeE3 zWwUOd7m%OAtaZ(Y>xXUIYLkBCyelW$mKFcudcMl4)+Uwp_w`dXATKDTTw%&H;Dv%s zD!uEC?OFS;1m~mCTYqlKfB2nuSkJXAyML5$t%&erTD1Vd>qyR{7qWfzKRy7_SJTZH=%+;M8IfnlR7aofoPhnihx20~RLCcjT z;xbFGstnOXpvi5TtkN!;aZd=$sA{l42!TR%GUdq3n`h<9?54>$1R|>XBb!@Tf6m$b zY?{nnRc~%?RHp){j%LQpW;TtZP8NtumAVDE7b5p%5{@CZ#%~)Qx~Z zWYbu;)WM8RGwJA)1txPJE*G0Lro=Hab18*FCz;y}WzJOnm?HWolEm+fj@Zs9>5@2|;a&%m^V* zLv3NxG^G@H>GPoDI1Iz@e)qd^7{;6t0!zab5M|7nB@z=cSIc>hv6M2IP18g~k$J2J zVWrejJw6_Pc=!JQ&pX9`mZcL3a*5pz5?MJSv5Y6T!S2Dup94q%2; zXAHHpW4|>#F@*7h$Sdhm2Upw@^-y+n3NyPfVBU$EI+0FDZtChuZF0DJb^tnDyfw)I@I54ud}q|o#6A~`Ca-v0jI9#6k`c_#<|9pT~p@Hgl4uYg~E{p%O5 z|LrgS=B~Tj-`?;1(8DO7498wmkA9E#m>_-c4s+m zC%wb(rTsjon-1Tej$g9$B(3mHFXxngIduQ#-Y$K=yB}gNCc-^^514{FpAMVU^ymiGxAC>KiF!yL}(lcxXAbey&f8D-4SplA<$@|ep zuD)9SOs-X-QQ6=v6cmS-N*33{3u-Lq67(0gMpU#2;^@at`qB6-{x%y)+sEUxbZS${ zR&uqe2OIeE5t_uOR0{wFVu0ohfPqTj>PU5M&J-LW)SA~766OU ze!Uj+fG_Z|JRh;;@KU|utrUY>S+9{*`IQzMiciHxpRyM#rGPk4Lv4Yy6sSgH)p|+*A zeU(N{W?dtF&H#pSq!1brX`0AfquZ(&YAeDb3X>`V*)%mZ_Z;AWY;<0Ai{#vD*BH;H9LLs;q1>b1w)?6lxe_jI#;XQi8hy!Oe(@no$U29s`A& zn;V;^$$Xl$m_-p+?ehqLn0N_s1;7+YB!*yu(=;i~ZenKRI5M$L)6>)WbUNi>7*!*4otbUhGIIz) zNA3IGCL^Xx-#};_NZ$W-m+q_`NFoE~@J?J=ao;*X1LS?*dnZ3=j*`BF{*3S5 zA@AC@14VLj@4D92lJ^hZpG7`EV?OQq;Go1VLIgZ1M1&KRRUj8qQcZpTJK@x&Wa5qk z1cXG|Gc!yRI(6-&gY;&%&I9SKTPy9LC%JEfDnu@-l!wd7N$kD0x1d|-h4h?}%yQPz zc;s9XO*x0Nh8?|A;NrJJ!;}qrBm#9W`5+AHK|&KTn^I~of?Y>16#MS(l(0kR0#_4r zcU4CMePGo=o8IqSC(RF8Ul{sM&Zf80Mc7>@Im!g-CBII)N7ol3JJrMIcT+14CmZ&e z20_nCDRTtmc%Vu><8;L_gM!()%S+!<;&4YGNRhQ^fn865=Xv)yFQcwzk}|mI{;IQ zu{(Sw=+wz|_wM*x$nLJ&cWLK&2T|9oC$+;#Px1Kf^#1p6e;9t7kGK2wyx+fbe)0M3 znD7_OANt(Cc@VYlTRDAwI=uaNzTbb}9mU|a=Qn*$a9E%lLUC`1#0Ej!nqV1|l{gyRJ0KhklMbAaM`Ft@2 zEY?o3Tiki@Y;jV5Zr!r#Z!MSg^Hz@&QUKtyoN87BRgF(ItExk!{c3gkEKA_5DYI+e z>q#ZiwYK`YZ}HWV8^Y?7RrOZYmMdJxyv*(t>k@w!8Z3Dyw|kbgM{5wuETfa_fwSdS z{aJt8T+PVp;7k_-P`xkap-us-_0{Ie0&oQY=>h=LfJG%&FDT1ZvM^ub!Pkb>5ty$? zmCy|iKz7g8$8|uo`m*I~^2+Lsg{u40TJ6>7BTT@ekh0O&AsQbQ!1#Cp5EdJYnxrz_ zT~}f}JB3}fTD2WqrBwmz_IY@DwfVtxnE=Ett_@iKJ3fv8q!j?uXaIbi0FW?%<~9O2 z{QQrV!{R@yGRqt5=NMLFwZg^iDu4*9XV4mS7G{_CZ3NsEV_}1bHv7|6r1Si@2p?@( zPX}z4t=sbHmh$ZLOl>|sDl9*?ZNsdD`3QJ@T7Go<8o9OzwKnRYu_4j{B>9%sWP(qlyS*H`lLQ?Pc&tgkU3B|7!UWXx+KnPr(QOFIpdxki}!Z|Rf z6e!if{W^eUy;2+6h~fbbHFoalwwnvdYgJ1KG160 zUtwZpWOIW!)bPVfB?B$vv>}Goh3I+_mp?>v#|w%T?Thw)_m|C!zb*0pg2MndV2?k8 zvOWP-!Zj|JwSE& z01?$QnmZFQ5kioSpsYfWxFNoy7k8gbQ)+dxMj~&*9{e!I001BW zNklCO)<)K-#){0aL_so>nWL1;Fw9O^ zlOY6if<)B7KyuV2VfY6`m({@RmWi%`ltT*c&rhQyRPFv zO=8Yc zW<7v5`U|typV1GH7TOAeR)Qc%n*l~GO^^C>syZvH^6TEX5!b`rNg5B&F)fT_c--pl zg@9@ZIcW&Qjq6UD8O=z#+r#&~2LUlgb2GQAtKF*)KdeORswy`luB58Cn9~!nXU{Wz zhh;Ct%xv`R9*8(l2;q8nZEko0EQ+{t>J*MPO_PYw@?n@4ML1VN6x_2^JelX5rDEc$ zc%1Fuy&De0H(!1AaDN{+n`gP;zq3UJjz|#<$ru4%*!~9WUG8v8LB}559B(a0O{LHn3hQ28NrHQ%{&u`V}Pt9!)%TF}7`zDyA*u z5fY(MFu*R1-SzDTZ{S}^>{UJ{`8Hl&Dzy%nGeFULGz^;H6)?&@$leS`@XL!%m6~bC z*J+z61qh3q8mVqb9;3d2n09}T)b4ISQ?$eyeFID)aA$%tNYRUfaB6&S49H2+8#F%^ z3C=alwQ0m$II40hM^$m#2q1K2kpOp4+-3L{c&B#3R*6iOE|lLM_X=oAuV5LxH|?3O zz{yEfH$+QXm-^^%}z+wr)~S-x^Z>wkWc|f zwGFYm<{?djL3QZOOnb+5jHLdSY}}B#X1QvkTtFIlEfSn=sByujX#!X*X)*v=01@0D z8fp8MYc;rx?jZC@D`-$8?XQ71>Wl>F{Z0F--QFDZ?c>8c!#futwEJ(r_3n`xc0_5( zv?cPyUBq>413S8|GxLPb;NDE6*jWQTk@MYIlj^ zPov!TdUN;sVD>c&zuNVz)3As7g+mQ}I^_MA$K%7#zxY+NYrd8CzWI=Ln5ymXv6CJ5 zpCA7!-Tw@JP1{dXy6)sxpMBc?@lSu>cYhSy7;TfFTaK;ReyD+x82Axs$HpBj>O1$Y z(@pZX`@VN0$eXQigz(!x*tk~unUQ|VJm_Yi{)ZfIA@%Rd=!c6<10iBZ7x&Oj#C3y& zb}|-67wH34W!=WhuOT-qR{-7p?YplZjz9m)|M_P>t8aIYxBRESppX|;VFZggBWu_T+v{yp+2+-v%(@23gL-6tR7X*`OyNZR()1D=MjGg7b6gt zFYo}cc4IE*JN{i3S~-VvVb0TjD**}ldC=Tk>v`q>kS=U(YK2G3nstt7n_pdEM_JS6 z=XIWOkkv@O{GIdSZk=c7_Dqp-)-;_}__S_*cFgndInM43kv-wCg^xTxHsr##a>)4% zRAFXwzYh6wJ{v>4kF=gzTwl(}`AO<>-r-Ol11%%4OjcfxbTw!{AMW=Lp;R>w?CevP zJ!D^=RRDPr>&+yw0Izd#mS&%j3*PeV6MV{+a@tShX@VmohvGrQVSOBBlUp+M7!UK> znyRA43Ny)C*8J;;t!DEJ`keeRlzz^`9E)(YT zg;+pUUXabor)I~iGY_o1c(l_w{0fEiKIyy^Sk1|-p!-_X$jpj%Xw^Nfb5S@{v2NPL zn1Q5Ic5Caorn0>Q6<}wn7&lUB#TW(voAO+9so59NS-IXK(O_2BbweX|n8Qi-oy+(P!nZ>nf1|#25onSWe~j zY9^ohT*P0KyXCyS z+*Vap0xD-X973^t!fY__s$*422tmh@xT-2HE?^-9Rb6ni1DJGDn}n;X7O4c;hheZH z?(#fZI-O30Fr=iSL_}k1n#MiUBJTO&;T=(kP2=XnFl2L*s%_h}Y zo6Y9xYFF37Rh2y#vwUQj8IXy1wpS}0Ek;^WO_fMkcP~+*CGBH43mPp$S~4({u+!>H z@5Yt5Th6%zzvi4vIz_G|=j=9#RE1y?k=Y~_7f<~c*EbLM508iA?)v7`ozAlvd{>Jc z^Psh-X`l;n;^>O4;h_}~>L3B|2f#W@>cR?|$SY?Zv=t|am{e#7@$Kd9%^;9;k&vQB zw4|NOWe3aAqYtlyADLecoMg-~Co6;)tzJAVXpoYT8}_Ld&~2JZO8lgWQ6) z?KVVxDcgf$!lm{s)jhLx{vr;JOH~&PqUwzw&4~GeNa1j>QSWx~n3AbNdhi8N z9-$Ji#vMhBDjBobXs-6iFH*DxhR znw&tr+1umsw%s1$Chppu>Sq5q98tlKsu!Bx?Z18#>7d77G+P5U2fe-Ae%#q*%Uf4} z{rPK>uG#HOUmo@m`iSOw`|8ljXS?=cpfuqExb{RsNeSKEsXH9Da&UPmk%?7PjP~Z2 z`@G*DcI|7q=R+x6NaRAKywV?NoK{`jx~hxvl@` zlONONf6~y#FtQ}`KZI56cV;`6EUso7;p5Rhy=>nJ!{nXgW!pyc?bbH%2f%l68eoji z;E#$6AV!-y-#~CVbP6#a&~6xqs2?UY*t+bpf=U{flPe- z47)=#QsGa2`{n2V>+Ab34}bEbFW=tL>+UDNp_|4(2Gt7IVOFZ;8x26ct=D(gQY^RP6$7w$Pak+i2Q;f}G-FvgKYfp1 zeW1=(K1JD-_UDfnp{JswDY>O>J~q`?eh10&}GX4P0F#12EfJ%fTt0F_5Ila&!R1^Zvn`K0N{oJguwuyjQ>Sk zhp}{^$gfJu&OBuR^<{-c8WwjIfbKP)4-~&>o(8)NZS`d4CEE(X2mjSK0D#Z%oi6WX zy$sd7G|9^fDK9q0e@C)HS`{S=ayl~uIuAX|`PqNx<@$3j_8e@X_z*qGbKXNJ&;7Q_ zx@TU5<)ulKb>2#1mK{T$8(Of)dt#q6miDa0wVpLjunbhrb1Sn$xi9jfaHjfM>6M{G zs4a>i_-Y)!@~qXRYaXq+Apn6vT)-l-KN;!;DxrLVtFu8nTX3J>y-QTjstn5h_L#u4%49`yowG7uPyejX`&hB|ZT4nmCoTrQc z7J}!TpH9TtZyZ4=aP=e|4JBxoL-E^M1d21snosq49-jeUU`CqjY!+4EEUGAizH%CK z$c{W#$N_bqtMS)P;_q77j|${kL_&CqC%?uc~r6e znkJj3i31_$dedx*86L4sn$kF`s*dh?9MhP_N~*)@lygP`6SGv4*`(8`BL&)SFXF}4 zrl~)5NyjMlrrE?8E9R0#F$3oA({wm>eczS)#inknikYiP$74UdJ3MY;BehUfA*1U~ zZkEzGP1C764Z~2LBW<_ai;Ih9v$<$5geX*89Q{h*=hH`F71j)wQdP($3_c(P&mNdE zP&8?X}-ey?H&kg0si zHFX`Bkr60_N`CT_AAkGiwM|pS)f(&Y9WI}LdnC8EWod7cQX3)qbJn*$RGq`^X8VJ> zd${ei&h5L(RE)uZ$i^-%B@F-@BGn! z^HSOeMg!Tj=p(p^-XWR~msAZ2B2$dw=_m3@vIqA#%I>#J+>wvn3w1Z4#*Etr5b+M} z57GTw@Ce;$bB%5v( zFB)S}n54A-b|=!I2clUz-W~Ry8mpsBAchdxsclBIKcH?e0+(M}`eS1UxIt23L9beg z4C-o1-Qm8Q@{5~HMyWd)U$Bm@xl?CP9ULB2AG=hEnA_!c$2V=Q^s1G2$8>!>J`P=X z>}s<<9l!0mZrhIgZ@zH)=9qe-4_&Uj`|8+Tc1McRz51wXcegg+;o+~2onFPu7dO*Q za}%q*>LrAUlIqkU?Z4~~`#UCwN4^|I8j)k_hW)quufKfU-G0-`r^J_R{lnqj^v(Ww z;rgpDA8OnGwNeB&pZ?%-dnf=JD>mg=Wl%+ zn$7n3n~L@MUaR$e`M!K#zAt}op{jggML-A@i02h`k*hqF@XXvjtS^Q$rxwgG>zN5i{UX|W+I{)&8U}do0{*@pC_J@(CXzS@E@yuS%+^u4z?4<;1Mu7pqWrX|T?kb6 z=OVB7!rW}ePqXT0A%KNw6z~zkY|{LMsC<_H_%stDH@M|OSPJTzA@cL4=XM=AgE;5n z3r@&WE&v^riwzT1$UYN8S{lz8#Gss?Ow&r}-@5!=8#+fk=NNHeRtp1qfU97#~O0ZGu{dr*M)y&3W+2B(yFbE4DT&I4Pe>pP3O5EH+_Iaj= zkQZO7?C>er2v5N+qr?nmWSdoTWv@VsRxY1G(gl3y_x!d3xTX?%Q>?ObMxa2e6H*m; ziKTw3DgZR+N|~#n5O^VsH2<+i>CS`s-X(xl)0gMS#{xY)lLWMyFOFfe53KL+_MIy; z)NnU|h>|zR=oT{z(myN8~_8V zv+%?9mbAh$dXBX4oS>bzB47ZbYQ6i72}deVzXo2U<19?%#&QYQ{m(ao)apt@{*7B0-a`If&GL2d`nV;TzM$VjbkSdrXAbaMD z-5nI9s>UIOYPN~ssz&kP&qa?n3w`IXMe`t4HqUNVUH=Ea|I>f{fBtI`ss24!zQyK& zha1;E-CtDlus=kB5};6#kPZj^@}orWz_@^cFGbLj8BeetLaeIlien=JjjZNcY3t%- zaUk%G!qverts4%?mxLEho3INwp1OT<0y>Ee!Iiaj>B*xKiPj|C=oa#h1?0pcl*GxS zE5PDx5H^Yp!{p9-HkNpkFbRNWa`c_5kQj+#YPM==<9k9ok{E7ZiGHA-ysHx?!CMlR zCJak zZo7D~LF8s1EjYsv+jw$rhT(&)j4YRsYok%TO4bXCY8aQ5xoT3TsAm#2WZKoS|6IEy} zG*~0(>P`qe?hj*s6vCI}%+wEek6pJxBcNNf*}EH;FRk0`y9dTiysVm*B8jQ{8-7gs<6ZkJr>aYT@$e(X*j&u$-5(dcXv6!;@7W(9{%ij+(7>y zxp{rr{&plc{nc)fBd@_H<$lnx1C^D=2sju>CmIIbR`u-i3M7* zcx4hu)#xKmmynY?+N!7NLMgU5sb8TzwK{dgI~YThwvYpX8oC0!A(%kSJ^qk2Kq_Dh z0W-4(g9tO?&f{BhQEQ|kn`$FzZ4F>}Hv-sxya702uZe zz<4To7|WOI(!mU1css6rDM}XEFcxjmxbFbyaR5+K*j)bTrnFF!-*w5bsD6r!sA#o{ zrmX0miehN7wR&oZg@9FH1pv%X%cHgbMK(2?hE5qkwW)wP>y7r)T5Wz>I?O7qdBHn- zZ!rM5r~q(W#5+F?pU&TwScsWgd2IfSK<@X#Jw8nPP z(|?;?sU@rjJ|`k9=3KMISYD647-l^!a)7E0SnRRZ1cl2k0YG|m0PP1A0PQk>rYhPi z0BApax+scW*ED1R$D9F7y#p8?5*C?WF`Qc4D%Mv;gD}rXNl>UySw4&4YhKJxt1}5a zC14h0g>u?UQPM3By(s{&G(EMh^*Vi5pKSq@%$vo`OG+ktbpTb%0BrDe{L5K4*SrW- z%6GT=TCkj`<&>FE03iVF2Q`3CKl>j50RIiX(076jQ4xbTS5 zu`nx!!t4OPW+j6!M?i~I%Ck9w0Rc<_95}A)><|J-z_LKY_o&=DvpA34TMsYO&Xx-{on3k3kJ2y)J2yUbAt2vsNnq)!cCqB5vJbJ$jX z;-rhz?i{7fLMjVB!e@EcV$S7Q#a!8Qo>m?=>#%0RShh4|e*$*%04&EF7~qgIauuk~ z)npv-XmCY>cWZB!cwP|7^u1n71d5+3wE>#>tC_eOQOw%|XPN(cn#C0w2We*HY*V9sjPddD z@$K8U*fE2=3uluV+ugw zYs*Ih+T!&i&~` z)xQVErq+N5iXwhz1QIuXRCC?$(ZvBdY!5M2d|Qc$D8V`vNyHo89CTuWaFP@W!VP;@ zQ+pp(Q~?$ts5TI1o@9_=NYapdFET;NVzs?_>FKefc7p# zs*urkZQ~~((oh}Ly6ymW;JRsUV{`I2wNP}Cnp0=Ma0Q0BgP=zoI_vd;(moBf;CI0N zMAw9owau_ba!Zzx=xzmsFfNLl{D9yMAh=Ups*?EVEjgklCG-#b3VMI{`sf%y+qS(Yx(4^qZ8WFmk%+d8%Ilm^u_?%&e>{hg(q0{~G&Ewtf=Jpru z=4~e*b!qzgm_UCcyWiU0-dx`7u6FTu`;(@9K}~zJZ5S01dm}XbQ*Z(`%xY*FjDt96 zf>vnSs4ulWf+q2RI7SBaG7)WBS4@+G$)m(cvJT7*qq}N=LF0fS_06%nB=cjsN2eVc z*c&}2Y=LA7fkpwG-&l;A+J*-8hO~BNX}=*%O0`oXy;>wVKrW<;sFOEPL*(jRcf5rQ z$y?Aj?qoEwR>aiBfzt&MM8AT({PNG`+Wo!0zz@QqGi4R1kq;d6qYvM z>rY;q2s5|JGu}eTd2y1;Yp?&Ip;#Gl>G=${O0|Ui3=ssZv4pk+tc8$620}Kh4kRT& z?>yWRIRsj08|8wZf&&!hxVe(#uH+6|9!`Y$_ydYOXGUnVwyv}k2wZ{W%w>OxN_vw2 zlr4W9J5~ska|r8U=CkRWXT-5OSUo`{AaDq46nkFgw90cjzkt9XTGSi)NzLa7rGv9K z*cl*OhZ$!k_fO}^^Zw7GIV*y!MJ!gNOcSyLArrq}+p-OSB@8T=_1ROHV;MLI;Ow&JIi2#$v*i1BY1%`Q(^3r@uT4>z(T=V;I({e0Bvb=+PI*MFBa7jGS|! zX+(i9rFjwKPY!=V|I3vgelEYA@SDoQ^Z%bx268e3P%%$t!ptFTH=ALy5D-G(RfhuL zOr^yOgz~en!Myxn;Xc#yZdjPq^gNbOLRd9l3@|VPlY7oNE(6L)Hvj-207*naRJd)e zHUPGG67}nPK4;a5nM%-K#oXsyL{BSL=0nplZ6{hFq1Tu>dB3uXNt92PD%0>`fJ z`%YEMC6UIFxvH2lFs8(n2-B4Fs9GS!tSl=}TZ_}eG!-+Z;=xq>o{-UOnvyFp5H&G+ zhN}8x#jL6Z#(t=p$RQBXyT`{<-={PTDcNKhxt2OG)m-(e&l2q3`>{;cz@0rfDh`U{rAw$-vt;Z%PXn7cDVo&-ZWN z_I=M)6=Ni35lQ1XrWBivRGh|SE~a!$#+0K|fOo=*A@nAtrOhn&F`%$zv585Zf* za?60ZyZbb%noX0As*`HT>R3WSIg}@q4uF}nXH~7L%CqMwQy|OEMA@^s5y;(LjjPJc zYN>V7imM{NWukE$kx|#RsuDBJX*hzr>!i$V?!1J)Pc|{QBrqspq_4mEc7J$e=DMov zAO5udP83m9-aro>BvPBYxNSdje%#)^Jnr+>+etyvMgzehCxb$HLzE0r9yzIXG1-Gq zYuuQ0q#Ixo1LTxY3*J!&Z3O(-YL$jW?yeMNaN|K9&~3IYYX|Qb@@*@Z!hLt2R1XJ; z?B2Ax8{qH+JL#-3!%`L>*E1?S9`h^m>pR zJ03)cHCl7U@lljq#zsUs9`qF?spBwM%c7b=dy*Dtw@u$Db-OeqNKx&b@ZGL$a1{|9PqcTu9`x-uUtVeY0&=z4@@{)0 z@j!U^;`5t*_cssU{POPGVV@2hU&CJreY|V?PNuKF_yU%a{&f3c(~_I_Kl|cg|8U}V z+V0XNJKEd*a5_BT=2hD9raPGP?Ok_b2{^pI6WQHvU;XGKlACWH^w53X-Fthx`2pP# z{$SU{_*vbvRC@cW?L;P_e-fEw`-hieDwpIJQYke-wDK5CFQI67G=k%r94;rfKnRf9 zMWR-T>ew7GY#NS6j}Uexmk2WeDRQM?Cq*LA5s8m44tCNbceqOj>yCAIgv75p-->mD zE#klFrVkr4YDd*dJK;6~7LVfM@O!kRD#;C|3d5eI*}D?1Chd*lCK}t8 zy3`9GGIgk1?`^7w4kAg7NmLl>*V)+5# z;~#};m5hhf0E-@GR&Ox?To0MbKIV3qz9!A=06#|(g*0HA71$1(sf zIr|0xNDuFQk_j+-GZmFqSuU1rfb|ssSPB68w+<|!B1QHk05H6Jau{-RBtxJ3~w*(;FV?FRPX!S*Sufn2{Dz0JUaRShNTcmkC-rE$j z>D&Bxu%zHDZI&mlQsj78w<#*EAVvO00OWE5fTCbAGLx$c!0<5pzZC6WF}I4B6_&{= zV_RPlfT{)nQ(#g5P2JP9=8J$u$vB7N1i(lCQ3GK6Uwi@J zUw-~S0>Dqc<65n16LLlgf-BZVOVn0*np&Vkm@`~08QhRVVLc_M;mj}aoOTrA6lUP^ z9$0z$_bgCn;Xcd$KtOl~v+@~c`t^f(0tEnNl=OLJzXG}z@{$3cf~8QXS)dZ{7S=9> zGh?RgVd?<{T_N29M*@fPa5~!(VCcD+i(`Q}rOt3>>i%?Lm3JwSob$Qorpqe<$r*Vz zQ0F?7`&(Jp&fZMxAk$L~bI_k;k~5#FfOV9gq-t0L4Ces1<%rHu<9zHPghdJDK*&Y9 zg#Z+v^*oD7@?tJ#XKC8=499X_?%1mi>$y^CesOL39BGAhwHpfE%Q*yuOtQGb1IWRr zoJ&tifM*GKoKSRCfk9Q^3M3&g0xuR<%ji7e+F$F{)6wLR9VEyOu7gjxc%@N+cL;N| zEu9ZOg)vGci@(af{n_>9pKYdo zpjhWb!GEpa-?gGT&Ouc<8&M^)LQAPQ0BT0e`T2Ljvdy%psLXv_r~#e5SWboFDGmVH z&AmXyN@{lpa?!#Rmnh2_g>dC;<~iqXnusfATIDmI^EBDRq_kK^t?o`bK}tm1I2Q6* ztk#P&_oiw3VJJtG-8Y-IsyGcp8po8zt~-_9Uhl2}JiL3Drs?A1;$pkK+-^(jmh<6o zNNK#ke_P_(0K^z=vJwhsW<{n{j_B&@DlC20X&O^1zzcv>Qoz&dvPAR81LCI9$(X5W zno2~t8i(F<9>*~Q6UHK#(yp&4Sk5V>I>x4nSMvu2GQd@ptwdZ?prR6@(n=s&Z;7;| zmE>jmW&pIr(3KYhU1hhhet?DGW?@mq7Q1vJS`E=x>ClRYN)TVpFt_ZEuxQrK&ZzQ1 zhY(8a9-eN)&rZCO5VQEN7hz{0UO!O+5h2Vjw>0A(;&Oh?oNIB!2g)Z)2+ZW3iD70% zET-c)PLqyf3GiIQIZ+&}C?KQg-ErV21B{ z>5jRPPRT_F=58BbIx^`s$lFGZXzDhQ$0$pf2Z^DAJbEIsjpLr2_OXTZdJM47l?OkHP=%=#x~JQte*L9NNc}I=HoM(N z66Mf+F+Cpl`}+PqGY`Pa{Tu5dmWCu+lvoheEi8Pw&N!qknH~TH^VUe^_M^Y z_PE~)_J<0;u=;R@#pMhbpB1(JetX1Ce(pO?Ei2%IErcXiU-UG~TrF@eZl+ z-s}gE$ovR7w(ZTJJ;#H{wKNo^IUbYa{&3vF^fixdVx`NJu!+Z{ao-KQ7YF|E>OQJ$< zV4zQ`qkquiB-E?dpvF>Q%H|hNO5C%lNh1tbGDMg;1J;{wm{eV&oYV}uNv;Wq?jRxu z$lK)ApU>Hg}KSdUS$Cjf@~*pR+!)(jk;a5Q-$Hmy1)6;|1EC$ z^@0AgOZ(d@-cP@=46fg6wZ1Rkm+#B>)js4TykfQ4Hvi*q0^ zNQ=%a=g*-}anA^go6?fs?b((qu3EUp96FZIH#ytm4EKcRTjXckA!LM{z0kS5_-$iF zV@2AN^E8Wz@-(Lx2n3SAbqE!}#g-dBW}o1i7Y2dAfusQUva-sK+1tpcC9dr~Gjc4T zZgnU-vmu+8NzbuV>2ay50KYQwg}=;i7pk}jrhpmAoxjUX#)7CkQ%&YXzL(chJNHb&K=Yvzkdh@kr!55^3Jd5RAVJSqgVl2?3{AQx!nKiR2 zU|RF*EkSUTjv9jJ%v`xm85qYAp8KKq8L5Yy^O#bz*)Uh*m^6(n!c0{qQgP9|Y%bbd zRV6E2;UhXt>2x9>ZZ=GWKvgxPlgYeTrw4$R{BwbrC=ju`GgE1oi9!er)OF27O}R>Q zrVzH9&BbP;?jhWwJQ^r$>w1U9U4A{SrVw6ST><#`gIg~-1Q#^3@bkRp4J=KZxwfxm zCMj#je8~lQ#{B0J0AGBXN;%I<7?y!uH<&Z)%>mh1D=)7sQl=b2pgD_TD19nYrnRbo zXE$8{IWL5$Fi_^%Qfl2L1l6gGzk3cL1j@{_#MI0!;W$wOr+y@_xjD-ySrwyK`1F2k%koGYNzs@EqeTF-_@7f zRP;r-M!Ub+?L?TrI9yrxH*IU+9dD)OmxzBZ{_)k#D}}Lj=Go~;o{#=6 zeN#nzBR9>KHq34<(-0im`7z2?bWB2sgE*@I){0Cns`^3Oe9dUcjAewslo7&%|+ z7Dyc)BZc^b+CPljuKo;el)+7d(P;D8Cm$K7mIAj*UIAY^Dz^S7mjHeIM}Pd0YGoaX zyi;6&1KaNz!;PRs45ml(23kp+Tz8NIJek#sQM6*X@dl=7Gkaqu!UvYgtYS6=pc~Lc zVCLR500R0koSj%bwUo>w6ij3?L2HP^;UH2*>{)$4BXDOiOTth@QH6|-N{s|gGHJSC zIt{pJ)P&urg%hH*o=mok1M3GAM_|Lw4IhnK*B`}ra*r_@H~p8*r&sx z*S)JlheJPYD87Rvx2r*pZ5QE?_EB-b@R@BU=tNv$x^i{1ja!w{CvAKO+jcM}W?Zx1 zr}W#1Cx%|qW73OuJK7;gYy+nwTzG4u z#680xjk&@U9AOt^L0i!SKL7LX%g^8Z@aC^3Zdm`-fu{B$@3y}wto4sUwX$3T0M`Hz zF99Gu0zkb5z}rgze7OaXb@`TA2>`xmf!T^k+6X|84uG$&0W>c!08n*_#R_Vc$xP*8 zIsj+~JkN^Qez<(%))_$a3IO610F3Vfmh^nn2mtjJ0~p>Z0J$J6sqsp#z~Q0C;+Ir) z0-!r<8i2F}%o3`2V*r9=0Gp2|U{(*=k=Et}0jp$bTSOE^_){FLGJyIz0I*?sa4H#i z=JrySD{^JPECeh4X(I>=mTfp-5n*u^08|&%Iv4fDqG240?CYt|Wh$F% z0uZmCW~zt~=R}Zo24?x&Gz0)+pMg0Bqd0}FYP%&HW(J_g34m-Fz)$`K1NiUczXb4q z#R|af*MEl?=(|_A4ml%G&NjyZ!I{z|XN1K}eO~9x zT;!Ioh)%cX+CB=>R-rp99~D*;e@p0hthT&Wykz z%hCY`Rag&s?wF(anujV7Wvar`x1~d8YM3JO$_P}=afRh(^2GxPZOH!4k7m}3lA(pT1yD-kQ_k|Qq?!lg66cIxJ0W*&7xtUgV zy(+NEW+;JsVNR=O)f}qnIYTN6;bOA^aEMJ zwtE0PMx2EZ;;c@8s+RNe;(GCI_!$EZ%Uc_wCH8lIH=K1wmcYsC+3gB-m`^KTuj~-c z(Q-*Uv4qM72P&ec4lKV{8QQuhEkT{b zI~L-`L?yu`)_Cg>e7PHhg|PS%n&&wS(R@pAUlnrzM5fAR~7FfJgy?tI(ur3t|;Cm`wk`-7VIvz366W#vjoo z(lz8!OcdIpSHJ9}x!uC_B4LW<9w`U$Dwz;Fw3gkycde1PV5E)4ljsI)Bnp>K99lty z>CrGjH&N~K4w*d#HdvP&3Fm8>E z@RUhm5I{|mpIC-buOR{(9Vvm71)d1rC%_}TrIxulx%7n0q>wXX1CQ1f85u}I11Jg3 z46{@Lh!^U>CWeh9h3+~bbC8@tfJT5ITQ*g`N_3|!{+Z3}8TY?rEzsEYC$$~9lLaAB zQf6^`z8AOx6k94I3E=t(sTp7?Icz=??Rdlp%@6tP~Bt8-i1b<}&IqfAL6{5zjPtpHHk3AR!atuA) zBb_;4kNKt0pvN7=sXK}J_#sPwV^+EkudKU4e&r%56$Pk7#QSW!)H`JX9Qj%1LU`Mc zpHK(3aTsIj-ya7Z@%&l;bIaQiE}ZaT{P92e;k)7VVt@SQ@CP<*yY44u+c*7g;CH{K zi^fN-*2nU(d@LW!uPh{}6_rBurT|*_(d02~bF?9#7I>+sp)%l?`!Qk!dElRF8k69) zK7u}BW;ejkroeFQ%YM zJPeP=dNrWmxL@;#H*wu#&=ekmng^Zx;N7si)nL{Ht)>nEIk;A;!2=v{n#`&-)EY3` zy1xM{{tBvvg`7^u(u!MoSdOvD*Ew4Y=Yws<%O>$xn4xfm1%#Qx5hl1?YTVNH#b*Dv z-u|7J|LMPc{K>}bX0!cydU>WzsI>+zh>l;I2>$;wmhg%w@#?Ks9GL0)g?6n^)3r|*7dmlSNDntr z=X%yF*Limq$c0t*{JLge{cAHC^I1|==e@91*FD-+YfK9gUwUI{Eq`s-mY!)<@k(;# z5Buan_l5u<64Cs@g@P^Zv06EVC2cCqy+pv`>suNSn)+<%jar*-s|o)W4HR)ib>=u( z1?SlzIY##?8#Z%dZVjmyMOd&>nvBq_qSm4wLMZOl-OQSQ(9DXNn-Q~@f)L!DnI}VK zm>+CZgb=Lg?9dOJD8+3uKhAR(vR=6k9PyD+PcRBcT>XX4O$a2n|tziHXh4 ziy;#4bYt*Fy<7)|0wbUvTMJpE-Y)?T+gVrDH$L`-C6MN5=8j^meK{PHy1?+%CR zUQ4C4IgcZYcroH{|K;nu-~T<?#U8!%Fh^8>WpWmXo58;Wx;2cPUxH5P z9OF~y2e6<&K#ouWOCm-7F3W4R&jueQoe5xwfbM)R03#AMOfs^N?u@-t(W@id6+_91 zL8=i{pa;RA7DOFVzAs2F{}gj%o!S~KPB3#EAz?wL}0N^m&lZW zJ&;wvY&0h4V!UNs5#B?0+>05QZ^x8UexAGB)2R76$&J#zdK6N2cN4}|I3NY68a?lk zM~|J1AUAAXLedX8y$}b?+J&2)fCTSbvOd{C`y1A0!hj{!1G*yvWC0{Za2TYz?!>cT z^t1u*ph+RUya%6^b|lPx4-_4HkrSxU@QS$@cv4-Y%6c~5Cc0O+;N%pUPrybw14-M& zDRu(PASCxtaZZNFQq)~i&v;|B$-GNAJLH;zBFXhVhHcO8M1rEeV`N9{kagUsWT>hS zr1D|huv^Ya<1g?wjar9s$T^O7;~LQ2Lyv}okDwl$1#$}{STuPHB=6s2>>VYIN%*Au z2qhCTI`>d`h9=+!Y3s-!_0j{QdWNg)`;p&vfM(!u($j8Fs`(T6mzkh6_A(l}PEO|P zx&b=Id2}A&o$cH(Li(#8LSH#x`8uV~_3a;ef1@}NFxsYLjC}I3Qm&BrCclJ~E1ZVo z?~Y^b`{UIKIQI<4}bW*^uK&Dy!8IpbE7aP);3y!}oW|M?pL zyWe^VVEiyW8v5$Qm+TUYt9THzli|k%9l5* z1}yPRbL3VlZD(8NRNJM^vjR-QsJOS~T|YPdK)@1u7B9CW+&h4^M-`wYPO)&QK|PlIv3E0`y>++0Oq{cCVK{8~I&lN?S5yV|-?fi$YSmT%XCcgyY7&>HyzPndtYI8006#nCX*6+J zuboN>z-Rx#KLzj)fA$XmeD>cw1t9tXz@PpO0r&%a%S-z`UQsJg0BgCQs0~9k5fGs= zf-Lv&mwU3npm@>O0COHteYBwqY?wLDynMciBdW9Jt74{F3jtZ(e9TM28epupRYRp3 zxX!3z1}rsPp1#-1k=E`DE_|U*nm$aw-j`~Z`>J-$MVLVkfLdoo!NW-MRkLQJ*+r;T zm#&yT{6NWdNy`7Gk(>T)5m!rv4^U8;lmcv}!2kdt07*naR9p>dO&!|?H-uI5>fD&7 z(h3v8n~_bJ#cqq8^FcG}T*-Qu!|KJf7j<$ewDRs+w?ZZ%WA zfUQgaulsIlKy7PMt<-j~wmMb^$>kHP*I~6J;PU<3cvb)a521$1DmcAcFWB_L&KAzK zI-6z^8UktvZ~y^yC3CB&fDSdkw@?4|5dO}ee0KOBe)sr!MYxsjHf}9&0Xy+sxVjBb z{WsvL9?w{00VRu^D$K7J(U8x=rA17Hc{QJjPgtwER?Nj#oMXIKrxi#-z&1hd67I>Y{7{(9}r)TJ~83TRxiyTOzxbGBGCiHajK) zU=E@wPOG)2PI%tET2c3gM&a#?pt&!-BEXwX520C5%{($;ewNYPj_%%8tLv1gii%1x zR(IxTRze8XyrL2_5ql{B+>E1`m6j$}-2?MfPlcm4VO5xonP%qhfv7gU+dTClGg~nL zlfEnv0=(FyBa4#>v>65?M{^4yI4ToQ(PK;qp;0hu(St-G1TAH=*|Z!nD<&d32gU&i zM8T`70tg5(Mpbopi9(6qy?y)s{d+y@rt9)Jw(gCQcUM>We3r!JHy~Hb`;JkW@4KyU z^A0?UWThwBRrEQD6AY=OT$M*yNax=bnrR zOrEa*HLz+G$vTp<02yXEi-63s==~r<-kuI@9Y>>b9D=DZ&cyy+w?Hv}3v4+KmPep> zWVosUd@q2ivz$}~WQL=ohu#UlReNr(d90?=_divCrkWi01Of&4=)~&3gl<9isk?!3 z&O6%Q2*lOkTbPR+&F|HA8BS{M3P_?M>%qM1`s0YiQZR18reg;OdJ%c68U*5Y66vAd zF$kuXwC8R-j@a|i8-|phs=OCwcvcfvvV7oJpc_UqgK}X|>c2P+ui)K2{=!esg`QZ- z`LylRFWiI>U@S4Ni=vN1k)XosYlR__1fu9^H$`RS;Sep)0K64_wu@ikoZgM2o}W1n z*Qf7)|9^h-?r-Ai^QZ5A`D?mpeEWaZeJmf#$MUiKl}l);GZey<*0jPR3tqVhxG?=B zUsJ7V-ns|5NOSzkdP|RQ3KzTC>?xU7LtVCuwQ33L8h!;Lnb1QG)MPjTUKb42HgeHw z)m4?Ng>|uswLq?=`t==TU7lXA|6HxP-tp;0eN45mFs!-v=wY{nuUGw`8B2u^$kBSc zR1s<$)-^Di=8A0pP2_8(tgFkIGz1eGi<$A(<6fATd_xCa#%LjT>p^_@_k$%qL&nEP zQJXHa26m8x7E0w4*qV0%Gpu}2!o#jWJEFt#`Y}hljQ(8V{OKnDnnWWL0bIIk-ix}R zuIbQf2E(<6Ye8D>Ay~^^UM5KllU5EOX}6PziNoLg$-gcC@CUEoD~F?`+t>}%mB1Ea z4(SwjC+r;;C;PXxgoo1+uG!XtTNi2*S8rkFSv$S&9J#?}I>*>!!Xb~E!AUY+rE z{&Qhf%M?N@J~?d*4^Eir&xJ`Xm9)2PHQiyI)l!S{E6gG+JTx=bRfCt7*y^o1*Vz)s zw3u62^2IqyDT+DtYWWwnntL@zKs5`^uV)6J&0crO&kDiJxlLYBfq6Q`wtPv&a`zay z&HPyFl>6@P?$$!&TTFXflfvZ$u5&0=>picvp{Q1KDRzlbbK8ixdq6Pvrqrsa4WQ6u zxC~ys)>_RjUwaQPR2-!(qCn=B)gyBVu(@V;BVzMHfhMFib2n;&WdsUD!tRwhx*LmF z(HLVXB`~*d(2D8Z32FIkB&0Tv?nOjaQ~@N}II6oh@f0&R3E0wdiLo`K^;lC;Rj)Bd z0Fh!#D|7Rd#MDen`h+`3G?X3y(sx0(a0qR6pJBqzP}d}| zTZt)i7TE|o$4C(E6sZ^6N))BY+7U?Qh7=&_(i6q4crrxv6%?gJ-`<KRrAiFf_Ha%)p<22l5vhknR6aMY{!v%RY0%UMpD(W zV`R9GWUP_&KBH*PBBo;=HL^NzQaqEZujqZuaf93=y)hS%uz#uEn;HDp@g$pXxd2v_ zKzY;~#y~6pse!rJ7`eMQ-8zWqC@+$uZJ;paw2)^Iw}-OS-0r2 zjx8 zaHUSk$mJgXTySf0&=C

#@(eNL8%vm_%uosQq_!EiHtXS+XUg|iEe(BATvld+f7 z-#YdkjqkAS=?-HjuLjntr^t3i>0~IWf3LcSAb&7WG^W1yK@VVO+-2z#U?Ky?PCp@J zm7jLwmiVrhqvj4U>NojA{NjuHr+@S_qc`8@pKID2>HA~;bG^PFWgI^ItE9hp(fuD^ z-M#v%`}Egz(fI42TH)r;me-X#VAhr#{sw^Y=K>%;eFk8;$*WEJt33dC1wcatrU0oH zQFOj70J>)aARU@OCIDz#C?^20a|Nc~FZs3t7~fAVX-#MwY}5Ibp#sQv74sZ$!&m2} z<*)y=0?_*c;Cz<>=xU&;x$Ro)F5jUoa%=Z{1AuyU1W@}s0HMuq7z==U+b`YgX9hsiy>bA6QwIR|^Spb7 z0MPynpt1u9V;k=FE2;tr$pE0ud#DUd5C5rC06q#Z1%5S|Rf{bP(~M7(#?3SUlfG&A zWdLw`XUmc%uxj~lZTi1d9sF<^g7W9Bx>#R-+2wt0r=W^TkaO=w!|KERnuLx92wpuw2XFBqT zWQEnjbtTK;y+&6HD!Q#JR)}^kxx+Y`kpD+*GYOCwU zKfqWE?Fs>?^PlrE7S{g@YrN%Cs0&9!ZqMLM({qu*sn_FyY&;bil)3cwu#BgjxPm zR|=*jd`ee{>I~4lq~V^6PzdlPt!YL`3v3F&{k-W(3pS@gp&cD_>Ul8_0g<_wHJ#B+ zEJK4hW)=cfw`CeWcbCnks0NySry&q=t+l!l#}HtpAP`Wed00cJ%@N&l?-~|aMXHB6 z6RPQ$!sh*;ay(mFR-D4f z7=d}>R_!59!%GxM5CVl#tjVU9AL=25W?5)Jt!bAkT9}tn^D8okrh5&jwFU|dijkYh zx1vU74`fAY8TAmDBQsU6%xyZtP%Ac@q(x(l)(n7Qd1k^y!Q4eQZDF$ju4X_9lU=cC zbDQ~SCQ1N=W20S>`CJOm(>}HwE{e27=0~8E61x~e*od4}n=C8T5JD(GQ4MI`L}KEz zpJ`4XD5W5Ph^&+f1OzP#uWb@@)T%{qZ$Etg`7a{PxG)5BOI`9>i@Oy&TaKFzGwV41 zb6g1i|5^G@6rzQR&>@dL0?$~Z@VySgNdebMG0J&3s4Fl(cK?U!0 z*twjrzsGSy=-mJr;77>4>IUha1_C1+B`(D_ChsTTzl>1ZI3^vHL5kaQ*=Ix56R@Lsrlzzg9s zY@hgcpeKDFhs=_)>vQx+qfWFsAf${J>MEUDDpxrvWdn)shXgj26ktz6M`Pm_Hv)WvPLARE7cn-!X@ ztD*RsDhdx*TkX!84lSd-y!Ex6oO&Cru*StB`f!!Yl8eGC zJfK>5BvJ#gf_*i>L&eMrCsA7f5F88hnh2MNS`mzzUS&Goe41a9Yp7lqwV=0&R<3B< z*UbRBKt;a~ZtIf|Prvuy{(E2jqv-xczyBcHkv10C5t>j-AqsKCfQie0yUSnR-cClU zd6GD90D^g;yY9_?)eOlnGZ86f0U+XHg{K;b0@_qqSO9V}i-k}t+L}bvq&;!Y{h2RK z)2Tqq40N*-tx+VKomoq1n5KF_m`!kQ?Xdt6%$%b%jMezcRA-rOwGJDPjTpr`;sW|Oe?Az6T=-uaIcuOQKcBQs;My%t^hI3 zj?MtUyf%|Nacr!|yhbMGpyq)BM-D)(L}9XMlL#RcOmq2dHX8u$wbmM9Ea&rOqQ;7* zW~$Yv=y!L_z2Edo7Zly*TWtLhLL2ny!3PBZOvJRoJRNQ2*bL}I!2=NmR1i;}+R*CC zFe9O90fl)eFEnE2o#7V%0^D7 zlZBwa0S?6f>5u+`r~?AzgWHZA>hF3}By!FKW0XNZBb++99brJ^fobnY-3n9~mPO*g zE++2jq{Bh_BYCG#v7O_M0)hm8jbRI6k>j8OP)ZDb>k!gS!}UyRAc(UZ;Se2^K<>$I zkG5spneD|-Kvad`HsOTv3aUj?9HUE@ZAd_oOxT{hkA2QO^mjs>R76k+M;9SvjJICPifP1c=s??}S{5m-__>Q3CpM4g|2-Z(2nh`}NXmTZ!EbO>kO_h#G|(sWdk z&bco-x)`yX6i<^MSx$!MB46VA$dp8H98vj6w^yK8?m(53jG8?^Be`wgRE|xePH?CC z9ZA`BPx2KxF>ath$4*6bt0Dw~8Mt(~7G#&65rsu@NOGg-$OrHhfqKdYfsATT65XL>)PdnRY~zC$E(#l91Uk3E8b zTpZ}HJR0{``&+`5v)YGO=uPuZ`Zs-lry2+*3^!=n_JAUpko6}Sg5;N-iS}9agA#3B z*pfXhdkvX;>2A%=>XQ0fHPF8H(p%mj#iXxJ*GPW!-VJ9N4lYq-FnZ!n5rV6eQ@7QU z^*fT@Dm};T2j1VhS9Ov1uS}EB(ZD8O!LB=Ovmaq+aPonA%G&3Q7d?OR<~ zljd82I_rrR1k+Zp0U^{Hrik=QC{hg*ws_DFvt*`Xb{#I{Zsm1(*tSPPtw)Z_hi^@v zUr&9wPDZD?23xDB_^-j9wH#&5w%VQCYC|gkG*{w;TH$or{ea32F|dIvf_tbJFX`ep zbgCD5*Ei9ti>7JX;qVA8q1Ht&wnkbr6q^m5>pIpwzB+PdaaIivVb+q2wfg*O2$ppo z4NYAc5GxSEtgb?()nOCrBcxSB2sEd*1yBezRGO7pm;lx!ESZk0If2Wm!e=pBKyBKg zcHGt}-^^GZl%tWW;UzdZcbfBzi6*w@?N&VM-w*C0NLXsCcKPzgN4%V6L$wq6O} z_7bC@adn@##zb%sYW1c_@>(UvVpEWihROh z0Zc7$3bis*t!}jvN7!VwY`iQoIfz3j=2NixY=Ubm==n?>-3oIgCMyL9fkFtuY;kRZ z7EskF6#=2KC!*lQv5jx**eKkfUI?KS-H0>+8c}FhXtU5*8vu@z$g7z*nPVFt*=ztb zpWoErnTImZYPBft4&qBYxe+K^#A}lrFMyfMJc+b<5-E^*VU83+6PE?%CKZ$@YNeV{ zi~w3Jy@<43C}vDt^gMs1RR)nna^LpbVHjE`3yW2^Qs6K*A}XqlIW`xnn*lhV&v$os z@7}#L)eu6n1*GkkLMW={UMqws7xi=QL{it4^SMixImf@PMYi|Az4_KH!fzp2?2uC- z+OU#B6_M~uPBQpWh?Fy~_s}Zcy%@-2I-IhKGBApGz!hOs7C0D|sn=cwe1aK>EJFcF zIsyvm$KAj^5#;Jd%}Fz{Fe$tP5p+xGB#C{9ohal=#!bAs$;iD)_H7}F0`K~$g9{~9 zbjj&N5K1LMfy5A8Dd;Vv+Hl>x(TrYsgLErgmDqSM1XB3*S(J!-Cos%(zvo-(PZ>f| zpi#U-8nP72&r*Nm!;aV~m6SI~XGUQp%7pH{NT=h=z1$d4;Q-n*BiZIeheWq?&eWD}eq~i<72N6!ndete7;($cZ4p7;@le~kH@KfneW?ga<5#Xd|0w{Nc z0=Xg~VKy?jb8pa3T)pGlG2JpS`lh3MPowOG6jIbnV$Qlv z-HAnQ*pKwAmoE)_H3n`~55l)D0s-YbNq@@zJ?d{UZhI+%9SaT#_r?(ZCHkv=^yJ<94@c@8+R-7S zoOFzmDce(Yuz?Ia?e3td)58D-pYUb;`J3DP&;IK{p8Y3cwtxUdCo#o3`L3V2;+- zBQP7yY`l2BPVX{+`@ehxVDsz%z)oiXa%g$v1faZm4In;y4oud_r$3m&{r8_Tfbn$& z(7gnJ^t1vfM*!%awgya()Bw~Q2c}Ta^IZidvr_xMZm*@e&-&@-MYAF{M_V(^ZT11c z=E>zF`F#LjV*sG1irJXCxn|4`xaPPl!=>^%|Cnjs!{$0{(emk&Gl0530YFP(&szZD zz6Yk9do(vXVOC@d1<}Qp5!0$Hz zY#_{oKE4gW^gJ+b>%13r>D#)B$?sn^-=+p)8+0nU0>|66fcM6YyfN;XZvuc4 z0pNfAT>;SH4nV>QzX2uiELnQUN?JnvgM@G3k));ibjM!jTakw=17SuWD@rwk8-Qw< z2*tFpUdUHnHD-l2rgLeA5VQE@fy`>sIn_!R+Ev3vfi+e8h;J+y3(YCE+ONl6%cY|( zU2^HSuYs)vL#+u^i+G=UgKC)BQ@Eg?hs>-#(qUb;SaIpq%enM`YWc+bLVY+q0H#r> z?lGeoP(lbjhHIvM20GwL0=4-1)q9QD=QOvKuKJ=LTq=F3r z^a!2s?T_|?bOUnr=zIW);Y7@s!aBR4NPtfi*qm*I2O6u;J`U7c;}UnhY$k*Tl>oTg%uSky z4a6KmF!#o`78f@WA%vzBLkLz%plK7#R4X%6X+ImMnR#NvXN!_$+O-+Cv=G#$NE65C?jiD= zyxy9}(~0htsLg)}Ea!+j0w~7n6*SFJf?BCnQfnZp#il<)z#PgB089-E2h>`<(VUhq z9++mRQ;9+#4pVkjXcK<8SK=5#Xq}G=<~YmxrlD!Vt_6p+0e36y5Fz3aV*uRiq;8uI zEouxainLRiD7e=^p;kmDujIkqTcrM!I#10g+RS(6%kVXYUnzx%+uV$`B8pHmu6t{+ z2ja#<14jTX(aa)X?o8yh#>njem@Zo}HpyFTKbNL!Mlkbcjbx@`7G+~@OEi9CzJa-! zE@R{=j0}OvC5q4A!GvJ77B_cqM{JXrRda;U7^14ad;89dnpY+;afn=NJ?G5C)K0GI z?w(>SUU5DX$II=~x3?%Pc`jlupH*T^w!(e24%5AOJ~3K~!+~*|C9XA|5<3oxmFwh$xWMwHI;) zuqUV@u|SZZ3c#3rdRZP{t06QGIR=pFbO z#Y#m}cNQWeAtWauD6oe)u;*0ZBZ)hm%qt@al*J+U)`H=a!S^J9jLDqIRi6?mI!M_Q zwk!nCgwf<$)YPsMzjg1i1(yRTCpl%`5od!V8I&RSWXYA7jnrKaBUnTQu6PB%OGF@5 z25mg*gq<=;D&%ko zgN#`SY}6$)PXd6=%w1rfBrz#DscA6m9bh>@Mfe_it*9yv9UxC3M}P!9m_3sVAg2Uj z&DtT!Ng)n0RvLFMUDA{Dfw>q-l6#?1eQPcxd)Fv@1vMl#7?4R$9SC5Ps07iTbt8Pv zRz(0llk{$tu8*z)+(8HcNr6Z3AxbgISH3rNnS_`i!rfl!WGRbNqSMi@^5`Qg27x8* z;loSlpioK0k5|XRfBNIkuax@Xt#yO-^r`&9T;3fIeS(NfV$;ZYM^~;xB;Oy??4 zuj!)k?f+Hxv3x8a%g6FpE+IN<^TMpiO}I>)hXquAJ>$s(7GoM_lCqR`W4M;*OiHe% z&jQH7wN9DeHH1~#_t(WrD-q5`K~qC;s%s_D3Lk{o4p!Hqm{le9(oRemqA{B=hoeth z`8v~Db;A13hg54#3xS7fHJa|yW}((hd{*G^K^|0NQVYX+JRB==*0ilz$3#GI)Rwa} zQ?0s4gepR5C|S%le}wYTJ5x=s^NS`)$rNhKb7D6;lC#T_+R|$eLL0eH+<72 zd#E5Z1PA$)7BruY-*ni1%Sy8ZnmcoB^WPCOh2X9C(L$7X3P`GT(p5ES%o0##&Xa@( z%?P?l$=%I-*5)|J=;t#t*9t8qa&)(pI-*4(m6)hj2GERP6gRcj=5%XIB2fh*v(I_z z61j=_7FS&hLJB}xVAgEC4s#qB0Y2L#6St_&#$p11*c`@TV%TxMJp0^ZVTN?f)Kbxj zs=2q|u2vPV{N9rfk+?OlR`@IwB4&p*__g3L3Sj2tJHdk^gb+DQ&6uzqW&*NI+ZQ4? z+u$TwYG`hzbymP2uP`eWXtC}g5EGkQ0GQa_>RfFT+&NDP_X|0ybB+~rboW{-aT{iz z6kKgDI5xlGqC1OCP&TLC3x^6&pun_*Tq%kK@>vheOw1Gjb6Tsh++89AZ64hk0@vyl z=u$U*(Ye=9n=z2RT5tf7DYSUFC9}VwOO6#K5c6a?jBce7H=5;U6^;$mF%rd9=frqtwXbn47T9sy7#61GpT5mQqR~q9C!lyZf8huiw6V z$3%g+OVQ4%X5_}i0SJ*3Z}hAjWxv@FQ9hkQplasz+fTKwanSzW$4;*9OkeoGls+UR zHX?G!*|7y@&^~c=-SwGye{0xZJ6V$R)%#vqG(%{>mR&?nYR}X4JuGY9gNSj0zU1!q z&cG>><9OnJdotbdRkxQyQUD}8N2-GN2E}j?K1nYImK1=KxBT24Rmx z+6lO4jU)vG!L>l06OE+u6fp1Zl5W|d5+xl$l9*iXVF}*L6+xkVNO(_35JxY_?y?sj zK!X0%SrOfh&MNPF1dxsW*^QYFkXu!Blx-l5iTwpfHN52gi43aG8DL6;JCLj7JzSAo z$!H(-2vOBT;x~pZ@jc-HpieiDYr+xmL?L5O@a<%^WA&YgfCe~As-B%B1I*x*?vcNj zkVa(|+Mty7STX37aE4>>s! zuoa9xf$e~evXEp(lI#po(H_AtWPftaqSE&mG9}?oQOP1++zYM=qWWCf_Hvi$ zJ3>(12=Z_ZLFD|zkrRah)v<%$k$^~qPB}?Zk}j*VNuNeZ-5KbGPUZ*3#)l5wS#*p3 zt!nCd3wh_XOMG^@SM7xWe{wDNsv_*Jz0zJKC#cAK=I!>p=zM*1CJq zPSWckU-6Jxg!&t|ls*0QM?d}IpZx`;XMozXJ?w|a51(jPo>B&$bnyL)ul65)D8koQ zaC-U<#qfO8gYp0KssC3me=St2djZUfqs`T2`QZhC`1C1&xD{aal+7H#)pxG|SaASX zpLGDncM70;mH-@nTL5$~0)X_y0EAcpP+tI456i!DFaWVdkH^W2?!yLvp9nzri2*o> zV-e%rL;%}YPXOfKzXGN^fz!K!Idh#O0if?b1JFI&0O((A0PH@ShO4Pyp8R13;HL;6 zzhMCBSpcv(G-*-=aQbR`GzuWUbpUd8k;=CRW}8C*z?*=T1WB$g>K;2^{1n_$(y1<0 zh1S|l#T=Z^)8G^4r1`_|Q~>1^01(eV*ti0SdjmkbGl06w0BSk|fJOj_2B5Y?e`Nrk z+vfZ-7EQxdESk90NWP{K>y-0_ty4l0H9;*^8n1Eyj?qVm(BnHxw2&tr^0pV z;i*?!tbWtVwL`3(7Y@uqJlO$287qLpzf=MI?Z5XQxBC9W|M8Ci*gpY)fAqIL0r10r z1pt1&`3``QIsm_Ie-7X+zr=4s;fe~7hw0frfEl&W?2H30EMS5Np<$!ybiqaovZhmmHQ!=vGls@L4goL?%tw zqS=agsk7Dv)67P&e~$79>OG<>Vg2tURa=9tRSyGU<=1P+{~B7Yd%TW$BQ@7%_O#>Py?#N z0}w9jlc6@zoi~uMV8^h`sNgi=EhqRi+hu5pZ*!Mk4uguS>^Yvks#~B`O@+lks_vYp5Oqe4Y|=8a8-nNnPLeBAZPJ0mVWH#E~i*tZCH7Nt1 zd0yG);PU{;Op%t5dueCqYGEaw?8v-eyM|0ALPumxShw282oQ7iY2wee zrdNc3(ByJfmeZMuVq}iY^Guk_3u5+S)&Fny-sMM+ENBT*Vr4U)}g^U=-j zdSz8sW=4d&hq+xpcFxt}nwgttRy7F{B!rs0NJM&=n_asPa}T>e`_6Za5fI>mKCaYO zsxRU!FCP4EJ%C9}7ea710-0wU_2uq;A#P^I75B$uQBDFUd-8SoSTAmG9iSD=P4!w5f8DD!M#wWA+&Y~mL&Fk1R#Zo5oO?bJT9sV zIWzN=mq4mw&}Ph4pkRH^T!msUS0*R~AHyocFcF!F>0$NpM;`?WM3eyzga8J#@0qz* z^$Y}<*@r**Nv|4XB%)(VeM$&{M;o}JO4D=<%&AKi6LMx*Sg%A(`1*f+(Pb}O3mwQ7 zE(fflp@uli0!g&H7N|8OCd4Z7V0F!iN(^7xhv&Rf8mI-9Oo71AJXS4zp34IDL@#wv<9F`VowLU^?m zIcj>M>;`dp5jDFpm?~2Ez1Y?ejYV(}K8Qf%LZk=v)YsAoC;@_%dV0rvOWbL6Xlw|; zOOPv;Pyk}heQLkCl1~zr)~*0hi3fr*x$35gNA8Zvmnw%ww`NN)cN96@GF5lG4cB*~ zzUv+__Y`l~-LU1<8IG`5&I#RBn^uH7)vAdv6ia4r+qJ}-*7u5)ku|t){R*pR_5Py8 zGRiZMaQbt#>hrp9@Kouxfh(5kU`Qi-MKoBVL+89}Tda zu^wLCnbvhnNV0~+1KNukjjis0y|inukAkJbP#*|cV-M$Op_ZNEmf8quoUcu4?wo4= zF6;mE+sg7ObytA;`i95^mfEXY(Am~q$fIid{=fc+_4nVsBx+vjtD4$Rld#nHMw=JB zspZqAe*XN`zyGfMzt8Wkk!r%eS><~FVJ%;@lD_g||2HddwOVh>+w!)&EnitE_Q=Ra zMe8*3Doj-COcOK@63iiZ2%d)kz;TE2R-U2)%VOG z3?`U0wkE&!597acpYMP%)@X!5dG4E>Xa7$zV#R3tO9S@4oOGR_-d|b*Fga&Ul!`{$ zb{Zm_jr?!^+cJr?%yx`BQY+X>h`9hw);Y_kB9u z*uwGWxS%TpDo{8BtmT>+uD7}O)+z81o~H{kOvYPf`Rc<73CPH)%88K!HFo_EU*NqT z{Nw%q_TCq`U1Qe-A2Tbmdr^ilG7leJ1Z2v_!5qdg4)$+}R?FOnlyg7`sHy=>5D_gF zW%~&tgn%(z3qS}#DlQY;kKBQ(fk^=<#_;ahdJTY@71d8+DdrwSu<`3;c1Z)X4^kd^ z6UJN8Fm9xAhcG5voXduf)?-nv(y>Z3XkEZyu!3kr+ zzEaGbi6%}|oa{?lT64?pF~(v&HrfAM-%}`{I1@r?Pf1CsW;{-R2nFYbfKc+lNmT_d zqO;|E1}kP7t4w?J<`nfHg0 zz)m(>CGRBDki2plI?uVF+uU1V%05PP0vI!30`R^sxf-*1U@GB(fx;NrXoSEbgpiTB z*z@-WcP3&6JQw8@S5-EPBHw)f{hOOt_xJb2?Aeh~a%<{Qi@NY#wCEUOI<~zeSfm!|N0i;rbTKbx7@P{Xe<5>kX*gO zGB(MIH-^+MJsE%lutcgPX2*euq+XgFBG~l`amRdAzK-(Jb!oCoZ4EjA+@*?9X}fGC zkS?X!dGi3BHS0stYi@3#8<7h@2#K8xwFn#v)apTm&>X~B;-=@rLf51K*NFQD_YOo~ zxke_{CX(DnG{Q`pT*V{-`x+P8K)}WV%gRFJE}aBM;sWX-!#kL8-ASz3 ztrJ_S9NjnK_pm1pWy#+4Ngs*5M0~}*QIaT!R+oewV$bc$d2QB1K2wdJmK7_ow^rR( zpww%I^q!Wz93Z!PcuaQd=)l}sr1nBsf#<5hBSRDMt#;qM;~N0bO6dq(z*X=e0L3zy zMfrrm-~hN;fUZ<}xVi$C<2o@em_(s$E7IGPvdH~`Hqf2$0kl$A=qC`?783VhH#8uC zo2J={1+4)*Y@`=y8jX70vlF2%0h`PhBw6edk4SaJvJ*hDQdQN3>JO53myz#mTx61R#C5-YA6XI-1Yq1tpy7Vgw&CBOQs^y3eo-8?^7a}bSe z3-vzAhq`~t&4%GGKGxs<-XGU;_o!(|Kf8POv+LE5cI)Qm#rvv4@FuQh)tP?MtUte# zE7Dq(+IrjFeWR{hD6TvGX`lSRLHRqOT7xeX137jYQ14gT+ zVf?CMy_5k28672-3XGbpo&nfSfWcv^D3ptpS$*XItPdDO9 zuUcTZib}PEDk}5zGrbxvgJQF_|J0^2zj(?3ss;e!wF96F13(XNfgyaLSd8W34z{fT z_%Q(B=m2@6SJ7!9pcC`*aP{n*vA;66-N4i(XlxLnI`zOLRPTT9l``U25`R?h!sr9qSM2rJI zdSeY2;f(A~{PgU4n+6RfLn39TKof`X(?|vf#$*cs*kR;1_3@T@k>!K?fA44ihyUge z|4k0zc8&XpV->uF6y+@L05S)5lVF-XgdDO}Avnk~Q|KAT5WfCT^(X|Cus)(Z!jXYT z02QDka+)RqKy@+(ALcCpGJfA+q)1kDMmbx5w48-m0OBDKkBZu;U>ATxIGRbZrV628 zGF4?}BIjIoMT5Dkqs&~KnUUC<)w}hc>^vC z!Q6X2ySp&=i55*8Cu}sZszAtI;!+2V(z%KIsW$T>YbyM_WU0&rW)-EF4`NAKEX*7Q zw*eGvIxm1ggPB(q0uj6QQi=6CovYBIF#ZwXnde%mqPU@fiL1)YT>C<-P?}v#wHAxv zN+Tj7CwH^rrjHPqDZBHqz{q)|ctNV+@j%ENIGayFrmNLTD*j2=m5a@DF3SCk49{PD z@qD-6b3napwC{^rO?#zY&2vSxsB7)IUV8w2e?-n|&J>s{BJa8`#wao3YhPk+QZ%`5 zq=8oIHSr#TXh`hUigCAs>{-!JlfVj!R#DRf)shSlfTOX9awEVsyozzl+GqoGS0ViXDq7m&o-fsaN6 zzjth43L)@;bg3Ha=2J0m(?bYFv@nK1nLxEWt?UbxmAEsMWRH$ff9m>3n%>Yh!fpGY z=Fh2L5fKs#lF5N(k671e36&=nF%o87C|Sb~6)QroxNMME0BX&zK^u1n5(GpaxG#xn z_a&&Kv;-p4y^5OG01HfHFIcH{K;vE+;ONm-YWmy1^E>-jf$FqwoD8wP|K`v9tnGsf zOgBsiz=)xiQtJfr>n&`l(xWx-B_tUdF*u?)NVbY=wnK-Fpf2&;EI&`Ob6r|IK2bjBQm9jd-aH| z^Ro4)BDZitb*TBMwpQ9ubpS6F0#~CHO_V4$2HjXZ0`BQ5If!Cnk0ge^6K+ziF{=A!dUq0Ej8`^*5ls;_#UZbA@ zUp$I?xvY0L@2=XvNd6tgUhT2zXUZSclB0Zf^XfsfZkpBKRsi+a|E}(Bd0XC=x8<*2 zs=lQEo6DC5#Sr<7ARr(QU}B06a{}e;=Vs)&FscBWnJ!Ihlqt3@YE?-`}j}%_Z`i<*bg3 z6Lpz~c24NrP~9f=F|!<)cCV`DmO5=S?hiPOQFk5?)7I z=VN$QhD$4)F0&bv8pm{~apGL3p$nr(un0{koDO^qPzE@Kv;Z=G;lst|d8oRJ`jh|k z)$cyI&@1X095Di#DgKs=n_-u_PaJ@DWk5-|CM_QstbHv#Rd4+XoLHauG3^1)%Tk-um2I zIW~_b>xC;Vs>&wQ_Yxo$$Q>mCVpT-|5>8QT!&lhF1<+`~La;UEK~!G&s)ZiOk!B#?8lsWN6B{Mu0d82R8q7HF)^k#hzWw8m9cS`L(~ zmquJ=H=+WqywJnJAAhKos=+leXZImev?K~J3n5SleL803uvmC+?g}Q1i8za{ZE*2- z2b1@GW`?_3ABN!wmfbVR1|X`|Q6LVay%q^r?-qdG?Bi$83d8L^hk&Bglf{BUXb%Tr zW|3ppg%DyLQcaZWvV&n<+5R^`s4A<&->S`JpbfVn8bbqdXpxAe(~|@ z-S1woWg)cc1jyaX?F%yBCQ1z&BdwpWK(C%Phg$DrywVhFs+^Arh^>3=@GR?l=@#^0 z2UMUQa;sd`=7dVwt}StWAbTX7+#U&bTGx#l8M$1Osy2_Hjqsh@g7^SpNt@JE)-55% zyp6hoc!G<8P^p9Q3!r-wsXdego9-9r2$G1^^#dboa7+r}7pB(^KsW+UX3i=G{SK?b z$XJ0M1ooeS!6dm49x)}YiqHaH10ZvS)N<&2DQa4a-~f$?_lk$?+2qJ+X_SN?r|1M_ zT~Zy>?kdWbIh$R%N0B9k!NTxJxcD0%<}`X0QZQV4%LG{R203QvoRputs&S>4^#pi?w^` zRo!e&p}OY!mJJHs`vv?MyX1AnO6Csv!rG114ohiQD_=?cL|xQcXigHu(aKitmc$Ly zW3*fLy2D6$%{>4BAOJ~3K~$~kQ^aSyyZE#3|3LJQ*Sz^yfA$yo_l^IZgoV`atRg?Z z`SyFwZ?b%FxBs-ETVDShx*x=Jq4mDTH|jd=bOC$%L>EWn4UteL+6M09# zAYv-QrEmghVfb_!+FzBs#Q_Q?h>a&v0k5`UCPd2tWWK2RH z9v?QQ3V_{J0Q8X)* zdjP(<0f0&YgmwcA+4qWVP4<~tOi?yX$;&XRv`Sy5c^f>2%QMn4Wv5EQ%>@8IR=|)m z1a%J#7HN4jN&|*0igfDk$QLlUgYgCcFV_m-v&TLTGyd7d zKLpSt0+3|~;Mdas3E=nQ-vjX9;_F^2DpDBr^ZjJkVB|Q1k^UNCXrm$;7hv$nv%+zkPGh>1n^BQJIYxMX>n8INk z02nz_$b{^}NV4au&x_-@kQ|#D1~aKa6ZfV6P9u2U(Rl~wknSvy5QD62+Bk)vBA*Pi zrt0VP>Kt9=v%&l_CODtZ6SR@{^xD zdGfT5v0BKcY2rCB%44`6&c8tj=tnqJ(2Ua%T8P={!fDE8nJj1VgY)gvub6#k`Fye` zToq0b+^lskw$Y7C-?0w&xRm2F;zG$QRl98bAdv~w6>ifP#-I`elp{goX zMTTe3Ia8n#QtBmcHw0u@b_$`yelk}i6>Gk|xqWqeQzTu#{xAMz#r(hi$Ny1WF5R;p zk35=xQ3&;N*&Pnqb4e1qSS~q){e8<6n3$Lb=J<6l?|HT-@LG#q4ueC8DV3in+tyDAN0A{x!5a5V9SsM{eeZ{IG!8F&auGJtK0l)<& z!Z#3Ci-ZT@C1k7A2rkhYuhewOxTiWM5vdjWkjNlw_(E65=nL>sxPb&v1XFD=Q}=6* zTdTscCO#|IGl3NH_X?9P< z0#)5OP|MN01EO;c92hGAhArcQ1uVx7tD4jh!9G~PQx@iqjwTCIBF^Yy(;Q5p6a~p3 zY6&EiL_ti(CTqFf)zMzIdwsN8A8OgDeoLB*-EQxY2y-mVUhSM3EY)t+gDL|ZxCb1O zYGm_;rw0}fmZ&C2N={Oue~5R$+Ua1rOeHCY-)p;I*|r{u_a+B6?;Pw)K=)onw)XDQ ztX*H$WbE+0u8p>J%BfpIza=^bQkrRs>O=U3K|_@UiD z;H5|0w)+R}2WqzHT9+01b&GvtS~ovz_unx2OuGyAUL%u#!q%AIu|yR#c5CgsF2@dS z*KT6-g9j`vZ9e`p{p6GHJ?;Kf1+C%T>-5Rzk1sFv$MoG*_q@j8k`il-&Bsrg{QOmZ zLVv31-8)NhI7ny_IezU;WLJ5q$*K$B+*dy;5_-n=S;!pH23RW>T|*}!Ix?B=9!2J zN$JOp4pcMaDjT;K+Twr#UDtJoj+w8nuAe>o^!obx$&)9`nIvlRs|vH*%{i!=?rjGl z5J2O3rzXu2()^S3+WgJy%%dy$bkzLtHyKmu_}s<|Gdb1N>pTv^w9jioFq?tAfg;WH zVl!rZDif%(u@a2qkMoxIv)7~5R~QVNioI6ODWxL8^S-ZQ>{ahl>W;?{f@>d`3iBEs zWajK{0~G=Sk@bdvF;`>g%?q&_jn(rMXz3;YUkIvY*_tVkS&tAX6m!1pX7KDN#`Af! zWyG+>hleqiy~ID}v1LOBNg}B#WMpI-_b=?JjVt7h|kk;+Wm5 zssdnUZe9j46yJBEBh-5{FVZct5`Gv$cJFiV*kvB^wu+TK#3*-NFgN_7o;Wt%$g?Nb0aMw}#p1;HV=y!Ad|o zsKfxjQrbs6QK)b)R&`ow)46Y0+%%I)g1*@AZ`$2b9=!kl#UK6t@4fdk-~8@(-+5ZU zM{;PzpigTY%p*V~Tj2&n+5aByFOB6ANS;=Nm_ z_)$*>_(c`f5y3m?r4wEH1>^`@#QF&1q^76@3as{i5h=PHNGrmcT@&rW4OA$a(jmfA zdMu3^WMi%KLnT?tcJC2PE4p=m2()k_5qKopi$loORy8^mF|Z(X8XGyN0J?;zqqjt& zruvxWpfGXm&_cy=1tb`$E{NKeMcYfFd*uIofNDV9vGX(jZT3IQ3uP=hK+E57_( zR5~d1+PNcTX_Bi08?l?#E8qnIYD;(m)0h02z_Ls|$nY4uVPsVH`P<=Xi7Qu_$fH|dL1Z_?f3 z#UFkDqZjQH{o&`@J^kj-+|!@|DAG0n$j7rkmL-#;zpMe!{Q>~*8UTL11u$qF>~tZ8(NqXyJIb5~c1*W) zk8-!hz z0SMQ#HEMDDqLUZHP*ebvj~^AouQ~z1vD}IWV6X!NkQeFHs`7SM13=kcR(E{`z}L3` z^5QVxPrwFpblfvaM;~H?>;B&SL~iI6qyUe!S7b zA@Fll$b}*4;hEMc06ApxfC>RH2hk85M-HQ)iyW+|Q&E%?!&yqqosH3Ug{>70*U-L^ z{)BN9&XLyGuc1?Oj1}f!3kbPnYMhC-rqr4FwEZio)-+;y9HyVbzh-0pCAc#K^QcPX zkyr&xI4>a62yjP5+b|8YC_wUpe$UixAp;(A4I?^AX7kPcuWkOPfBKW(U8Zal+67Vt z<6sn&!?B_xlM*Shfi&=u_(;_;NFOQg9Jn_(0Bs^1|$cKIcTQ>6^lM(%G%gu-gQB zrW@gWj^})Ap^d*zNa*9X{btj=riYqN>a&iQ{)Y37R&dhv#WUI@VKi^DVs@T0fMOwE zb_k=O306YT5fBX7eYhA47z&}}lym^uz1V?;$$Wh>7dvI~LGxmNTLFPf{%TlvY(iHL5GEfg%FUTswMwGX;K;XVxu;> z#WC|y6&Y1kA)^2$3Pd3|!OT!ZTO-mUB2}$Iu)b#zS08wsI}k$Q-^KYaK#xZ=i!r); zX@;5geJ_=0uO;s%kdcen2%kzsB02gFy~?r)?2e&c3tXC>-y{OtEKh;e5maq@UoL5 z3#sZqdG2AU$G} zdVP5E%kO^j!;gRcKm1wRu!EWd5-ai2Az+7ILkvqU_Wuqc`0; z2(F-=seEucAHgb!GgL>E2wmd!TXwcFMJE z4N=f0u%@SC2dghY_u>bZ{jPhjmV0xEC1>yKik;M&SpNlV*^)w+#_hdjSRBpvFFFJQ zBsf76f)m``J!tU3U4s)eIDz2qu0g`!?vmiHgAcBQ%isf-{XhFX`|i*8-VgVA&iXRb zT{TnP%c{F-t>3Z^rqS)Uc?eSW`nud$lS1}q%r2Q^QZMYU6c%@1(6XT~e&$3TVQKV~ zVPM}k@^7m$gJ=!h5N5SYos}X%eVn#l@2?t-@3ZSlBLcY`@{@~Er4lFbY^~mXI-<(Z zS~W;(iXyF_oWoA6PCphe2rY^Eupmv7q!#|!mI5Q{XO~I@q;g|KYoV%i(Q7HL@v~d5 zKp6u5-iJwsSMVI;-?XZpFf$mk(*1!=v;V+$@mRjVKJR)I=B=tNc*v$DD0SV!oU5> z8ShxYi`Mt?m*@lg)yd-9iR;v^`nkOb>sOKv=0>Q@i>$+9kNSS0q$>ErP;!lfVNK5|om{In4gcDAczL1dY^|oC z!fH+SOk2=Kmd9o*wf@uuQ|!)beGg`|XxO$QxBJeHNYYbU(zhE0Yd^?yjd;&!n)HS& z3Z?|i(P>H5+|glZeS_7p+A%XiEd6&d{BNqnZ%^XGOs{Y5-O3am03`x&74TMIUC?&J z_Lx@WM@Dew^p$64C3Io7TC?D%f9C@XNFqcRs5-{w-2c#-{&<`x^H5)*9A>-p|_ zQ38}wch1D~YE)gC@!}BgrDX{{7YkZ0cRv&GD&MjC9q%fWu2BFt=w$Kl8Hj>&CSCT! z@5O}UksHOrK~xxQ3X(3`;|o1d8JHiR_BWaOq+gc&BTbl}88q^mGui5Dnt zh~Fu{7XFPdyX~G#Ea~gK%#VD>q8~G@RKojhXl3ruqd>oeJWO9sM9km^GbJ5Pf1b@S`yzI|y` zuQFlg)cBzktX_ccR0e6&^=Qy6M(b~Uha3u>8T2apW@7#Py7)iqCzoa-PH~S2i z3XOV$Iqh0Z;zPo3JC5o%FYwDcJQHQ9vNFy60$3nQPmVQMwDiz8D_tSi{P#>GoJiljjNx{;oh`9UQ6;q>)`q`y@oY3JO1q?5`Wd3iD^rr?Rp2*E%jbse0e4 z+=;+&Aq)s#Hn{H|+k%d_p*hW*VYc!tai1{rVranP*Mk!hM92fxlHi7BAs=5a*VFbC zr1UU$7;ngaosmB>ZpS~;?U3>qD|cWl&Gq=ZYWO#8UhZnH7458{5o0?mtIX1TKdb9$ab?b{U>{AJm%${*A)qe zW(B{1{V43HoAK0ndSX&r1j}PKaDDJ3>S@8?Y74J#lx3vG8;7>tzpc^L?uPtocB5^C z9@=5^)A@598=c_SQh0)}BFJp~QVP~)nS)H+Q=d%Nn&`t5)fCpD;|q!&O6rr|F%&L) z`Zn?GGpx>I-nu9>g<suGRXIskC>20M zIDq6`fc4@_6=s@PLs|6hYGxms=XHJy z+7IOgy)*-l_6(HbR^$z}W~9bp^qRF`bbRAQ2z3F+0O1+p|86h${WJ zQAn{)Marb7kL_!-Qpflgw1C_voB-M<;s6gvFMyE{AfRvJ7{TZ1dz@USJ_^9&%WLwA zH{Jf{&|JjtIIMt2ze^W@-^SS}=A% zP&bj`EnfwR%ybfM3VV{%XMqrVN0sn*(|^C0D*4zH`=^J}jPry{U-%H@-qMu8*^!+i z5J|?h{@y=9gFK6C?m3v;V(KsQ5N|Iz}xMsgxCL({vsxL>jroE!2aI0(`^9 zXkeW52qgN{^-LU&>@!U|OSL){Uw%sgvc$6`yuEV?=d3Fo&Y3c~Y~EkGCfE1n2vwy$ zhO|0H!rnbUbB(Z!=zo3Kn2j?!Jz8Q+av}&NG7R$l740VWN&ZW--rktPqR(yFhSAf- zlgwJHEn&v#d!j$YpZ~n_l9-r%2cx)>LRQ-pIg4k&DA1q>iD>x#{#3X_)9GQZ=YKHj zgE2h7+k}d65~J8_Uvkd{^VrGJ&knGiGEL#xi&m_k2TB#9So?TwT)Or0q);QX*!tR~Bw7xT{# z1{HBE_t~SxIL1$x9N&q>ss?b8Mc$NthE2t#DXUoIQR@{Zl$r6Un>@bH*|TR_RWw;y zlpzFNq+s!=@$a!4^wVM2O>LFRCPw7Yg=Rq@9mc(C6}l6n9XfRW*zy45AqG_Rxl_~_ zefEa{JkGyyPI+8a>xF+hBk0UWU8t@dF6GK2Y?Bw+V11)yE0eKitsJH$Z~#YhsF>aNlO(Tpj-zaILy1((Y zLPHRYOmj;Jep;FNtJ!ic+{7&>=CbB)8;|IHRK96gDsR_$v+u(Qp<2)J*_bYs&U0Ce zm$_n1uViXa7}QLS#~P}jF~tfr%+}VZuu1rfDbE;~@y@kqg*hHye2KvMwR%-*zj)X+ z_FDzRmU8x6h|!J$rzuoYeJzRHl-74C(R8MC8OLU(GnhV~{-8xz?H zw+Ua@rZDzDqDGRgu;_CQ(`KYd74ik7s^BjXXAWeqn?#l&-*k&RNhYn335?crJ}bRD zrTBoXh^0t8#^c6Vka`xR`--KajiBWReJlCJG~U@lc%31&UD!>CLWq0skutep)7y5{ zP83K)qjA`gTtl7qRwwwY7jQ)8qh_=XBbs2I16DQa!jC)k~`L4hu~vaJ$!|@IrODGYCa2 z$yKJ_&}6=`qMDAhBkV~-ADn8hcQ6ixkuG%eh~YM2`9FSmATw-$fo&S@QyyVD$baU!wHkQ1+i#fd8F4!NJebjX<0h{1EM91CXN#^?5}@<%&rx za!~hafW`}sH&d2)#(>_{8A9QAFX5AecSrd0)qaEoZMSZW6N;;1noE*LLLznMBVw6IGJ#0fV|CsU zY&|xRZs>TXHM}?;tea+`i!OGi9<@P#=CnUW+%HgOKlg1^hSlGV(@%c+ubBN>R_gq4 zb&qU0@+`jmh0?ZMH<9z3Q6>YrgnGqAdc3sf{ej1EGM~2l4y-HM=XG!_+36MZ+4gkR zjC$ncq1u1qbY-Rq>JBp_eIPnXNRs}n5NR$efF~DONHg-Xrk(PxR~8#Z9-YqJFouFZ zFs{31oi72O-j96H2!TY}-Hu2c{X;mDo{DLFtvSu+i8IX)$|9P+`GmSQ&Xt1$8CZq) zp@)B0qUd-9G-oj#pZ?^inr{s&CFleSdH_LtK#tGjr=u=S_`_ZlhrwgcsD@9B$Mu2b zPm#KT%)JyE1R(u6Be65`2(F)nvLVA{0XL#HApt~zJLtR!wdoa`$a#wXBQ(nqYENpp z3RsS0&W5bHgbKE7dugh!UZI?IVXE7Ub+%w=f)3wuxPfsn(+yHkP_~ z5^P}XUTShG4GWW$IG6FD9c)v4g~Q)!3c!9Imq=WNe05Y)hoXn?NkkF{I5oow&W0JO z1E$lf8$MC(U1>6HAmQ3;$1hVe20EZPrC>*+2_VT-QtyJv?m|rH?hFnT zPlG6otMif6iWY_;I1=v4^c86PDLnyT*dKurM3v!&e*OS6H*LB7{#~8JA544tn5=t8 zhR~8xMTydJ&hRac7#?&Q*T^u7(=ys##J>wfoks(lfFG`r(u$=_C-ju61y-jIEXCBo zt0VTJEE5Nu!JIK>t9cVyU{Oz;X|jt5KfmUOl#v}*0RtA8WY-xQFc-mbAnVhL z2iycl93LTVSrddkoi_rKAFI~^rL32)E;(OD**SdSG+;?h>9B63k>_7`v~#cZWxIl;X49+cMuPR3x&p|> z$Xo|vHE8U~7Engnl->H15-6dWFEqzkO#ge=F>D%~*h?g76;QI^AQ^xf%|0w)|2}_G zcW=4W5PYZ*D+j1Vhn>$)Ddz>=o1*1)>Fx6S<}flx?P#Z#poY^g0-C%xrUsyQr=i2kLZ8VK_qDz`R-D!Vg@@cc=|e;C@u z1iVUTT*X$m5`kq)dvoE8WWV*XrSy#&YQsw`wNfnh)dP3RCaN2AOsP}<_!NxDD*u8H zm=IH-scP)J(%WNRO^pMO7kNd@cGTpY)w_2va-zEHm4w7IiW2?XMm*_{lfE*BNaA;c zNBK1tB*f`&(VnMR=~)836tB2r=|A$#KBN~V4$~rfow{SAD7zI+?JQImaWvZ`ClocF zmZT{C8uqC%DlvnRLMlHIW$g3TcSL0eA2=w!Nuy$(q}4iqss+%#9gR73-GtMC?c>#7 zV=7Je{SKHA{Bo}SNzhlVtx?oEWtxOx+I(8@Ua3S7?uTaEy86waO=m^$WOq67Uc={M z`(9@6m`X;bs_k*G&iU#-Ty%c1hrTcI?poTj2Ej|%juz{@Kga`*Yi5g8FSQDo^rx5qA&~ zL7}7w{rBZ?UL)kZV}P-3+pEcs(aaI@dOzT6ygi^z>zmAB4*#NRR6ygkLgep@y=3&L zj{3jN3qJsHLx6IvNOfcIDr%gXlR1J|M+cIo0)&|gp!XAIf^N@G4Im;wC`+humhG`d zRUUj5XauP$$TlPAPI#vY*0jPSD$U97VZ@YmTE-d&?% z!&LWvF0^TBMn{|gbiwZhQ3y-VJrDEP{^B zdyJc5Xt|wiG9hfsmIaZg2we37PId6P#yfp*1~ z_q1?G#$Y*R)Mb&RS?}dr)xQj11fP%ZKpA>|tS^v@M!^=I_?qRXKB3gMLSta7Dz`Ta zUZE80EaLc@tm_vRcLG!+0(^P~x#!#SIHMnVgY~KwD&|dKefC%#+%j$UnikDFx+dlA zf#$a@wthTiEZvgV41>3-gxw%qN1x7~`-D}Bpb?LuoMAx11Z3j~#(7=F&&W8!Y8&Eq zlI(JQeBXa*<-IICVbpOB{Pv(YbWYq4^_htA^zFI~Ke!tRhQ(Zfpe0-r0?W>x_I!aT zHQ1xRXaWc%n~qsRcO{1RXJ)*qFb+qLKZs1o-!xJxe2fhnVy*yK)!68!xXe+{^b8ou z1+~~1$)Rx+nC!h2cCg?0?|M@9!cfHforxq+f%u$k+a!`~6Sx6%gJv)ld?fw>a{e}1 zreqfyXS(Pf<~@e)6*Z8t!(zOPSeQ6@Aky{<%=eAvl5}cgBZ!Wj23-?s0YIYP%5M`_ z8{VyEzl|d@2vzA*=~Fv5x3s_)BekR3k=;FU*pb%mYj)r#l|V(Mxk~^u zeBY5dF=+!Hb`Wj7Xo(#+?QGp1#Q>3l4-c|&k^iEx z_+PKi4FO_T^KCl^HR-6tTT{7mq3?!nTMV4o2uXy=pnf9Gb;}~Eh1yef`Ig6opDNDU z>aZ+@cU~@xz72NOCMw~{nLAm&)vI=XKDGM<^hKxeA|qtu9_*3Ya4~$da?sI}Fxk`K zGaRyJAV;)9J5$ehn2WF zDA3#agD%g8UMWBH%PX7cRh^|v*D&)nH-!Ski zUwpIR)=&~umTOrI(?|w-jqCSJdcBq+eRi0+Hm8Zh4I+(xZ*>YgUy;MmwbQiD?4_=T zW+)L68DvF+v#x*7tTSJ$vKC|+cV?HXrT(1kYz zMygf;QbdIcX}4u|Iasu=g10vePfrnw7oa}>k&oPKb7nTDxcT>wIcn2MzThuECipwK zHx%|8xyLdS>02!hqyOS23^!V5n=W6g?j)>p6^-vm)CNlmiPxuweNNeZaFE-iZ!P8G z{kW{sgtz>Qc)Bp9vr@R#olnDVo=?h`q4k&}&s|SHyg9%4cL&s>yU66L)yzbjVK|?= z;+DCIr3>V<5W#mf$t;-U$C*@ct434u+@#IPds_uxR=FP#L(}7o^<&c%Xz(ya%*|o_ zq(ew&=?tNl;(Dcxb*p4IACCA;*2L;upE(5rsHE55Elo&n(QD? z`UCJSES7A~7xE6-D!P6=cxrIx(nAbDy`3d#*c2_QrRORV!dIrHyNBvATvsiRHz(>- zbko!n{I$$}I~CqM$}O1dkTs@BhEhUf_zBF4n0VaX8SY03UzS>KAhJAb2)kuo0U z7O|7 z3l(vgAj9*V2g8UXiUL`%=vulObHk!*+Wy}?*wWR0c5h}!1Ap4(#Mh26SjN9XlZ%7o5liVuP#mj{HqUuG z7q6bq-^>D0yCkw;x`;5FD0iMXatNr{ZKFtyVloB}YF4V@o6+Nsl+~<#iLgf3})f@w@w zMiP;PsY6c#;7PNJ#YOoL7^W@uCJOpnfthe_1yT-T_<-z@N{-2jK!*-2cb%+V<2c}! z8e(tt^u)+RsuC~gMjja?s?FRx0?IoO1bt1nL`{;5cR z#jwi*llKa?K|q64^9p(E8f~Bb9I!iZ|a#z)g06{QB z%Ld!gv?739`miZ3rPy=^1j7>eas)q`wjIh%61sKH<+gAQp((Ic2}ndy8KRr1-Y+KEd)9 zM{0du5NtjVOp&eBEYh4dXPZI|5`j+r0>-Jsh+XxZvNn734fOhkUZqG2DBEBBu^;&* zqsX1Dt#}qWMM;vu(b`W-96~1(AuJ=y#v5c`MjKXm-~FRduR|$bLRhEuld{|%VMh+N zvZV>G5p*5L=Gy@-9`D|Lv$)!*oRxu)QjM~u?3}Hv_B9Vqx=|XFeiKHG$MH-jkz$G3 znrx*i#aOs4N92%xgKBoMIeh5a?zCAtrm_C}Qh&t~SD)ly!MRMpo^pl^EnkTK2Orv^ zqTdn(lLY6tsGQQGb<(}o%f~dbA5$}sn}!h%iVjd&X{8R2mD|%(>T9KN~KAj}#$YeUI zjt_4#lx@7vcgObjas^i){Apj1|CrPIf+Bm|{I!zG*iSYB|D?{G+*u3z)Y#wDhiU@f zu{K>!G&wFW3bJ`W)qH=P{`0|9pq+`Ai6=4J_IT*S9xG4=LS=n=RTG-)SL1sVoqlAU z7Hw~1~bH_y{u-02>7O}%aIMX ziMG84TYT%7HYh_;(Tsi_x8>v>XbK3V0hoyBS?9N6 zyAJ>f9iM8~J_f@4S;l1An);Xs1R^a`p@*z?&EWw}Tk;eZ4bPV>A-#PhBD6pKh;(45 zA|k6Y#C5~DAd~?8x5JGS_(`xG+=|t*WZz_?(t~p^D*BJP2HnF5`|H}U>Gx}-se9j! znvw%*nnyhx0jMKxh{4lChj?N(m56B?yag;{Mol{FIvJ)w1(0|TqI;kEF(%<-k6(7LoT*SWV%uMN$Pb;nKgZ5=vdQ?)cJ zdosY>{2qrR5^Y);Vp@R}E;tK!NoDX2LzoDuO(&esQD^KdWoDRyFA#DekLss4j=xSp6i{b)RpbkXI)|)p zT<`4u&3;*;D^uNllLK)kunSh3NZIijbtmwSwtZhINPBMsEzUY-`7XwC$%sfYxa@qU z{q(r3BnnFj`VdR9izf5RJW{*39A6*Xxe}d)0`Pt!nxTFix1ilxYu!^OCf-b$rbu_!YcD6hK665@4Vky{h z9eC#HdgG|LYWOG<6j3zNMK>wEX#v<0rH*gA^PoI-_V#@ycH2nt=S>6U=)VRBE%PJH zhK+OVQGug5lIb!jb*Yt#>?taFB#lY*b|=Jf*b)b0)SG1ux5EYBEmO2GK-51ue5bWA zx>QNkpqa>Ms&-EC#zohRd$mu-UHWr+Zs|RI=(<4bj|C`i*flIu>RP;6Fe--o$R6-1 zWyJ!#V^nMR-2T`MEeTo0ujeSVUA4D~8qL<6`;A*AGlTU`M0kRc#B-_k0lEV->B0VW zWk5!q<{4$`pgFuYYMQ))JmIM`f58hB~Ce@~yKd6thq_ zQP@CQ{xMfyX`yt5FYEi6-lgMx24^TwZyHjJ>yb!9J+n6Gm`3u*(I$IcZGIBzDzp-Y zl&n}g@u4u7CloWjF=p(?pyUuMW34+uK74yYnH1WP!QJu8-O&L0Ss;#VdsN^b!$mXRtt#8!5wF9%rKTU?d&2<|l3D9gZkDAeEc zbHVIwauO!kBjBKY%uSc57&=Wgx9_zm-jzA2(2Cav*j^<|2ZkCXI=OsUNVY`4@19he zq6X8SS@fYtwv@CI%*@glalN^`>yr}*2FjwKec^1G8{WB#!(|G$d4KO7Fkw4$HzdX4 z!_KW|pGgjN0@EijD$$BK?!^}0e_nG$#Ofia<8#c+HZ0T7JN1rXm03QmK(^`gN$8x+ z5n4LRZl1uvVOHaiPR+xOt;jAyYCltnAQZHn*{<(dZ^fv<71=1o@%;naRG?KJ-7`A- z#k?q3abw59UY5ezetVAwb5x$@7F=qnOyuPLj?f1H8?3EBULa%S3FgVNN4w|x@%iSj>sRwVauPdt?!C_(J zS<1pEnq00A$4x2AS-?5tx;J@K0Ed+7Clw#XXTtuXy>S`UG9iwY3}uKP=H5gv&bTo2h{8i4 zN)PkGqA8n|QBZL3d=1PaPb zPF$l9k2H`6m=8izj}dP5i2{3VAlML1n96R8E_drS`UKIa8(aCXOF->~xMyWg9KeaZLgu zQcE7I)3biPW0^lHNn!_SW&kE17+ZGQFeM|9*{LwQtVm$T*F>xGr?n4v4O>4LA6{8C z6nsf9<|R;W!th+bH{t?Q9W!L?8QWqsPvjeoT*`U zKp-|wymql?h{{vcN9mMSuA9zNLId94m^}gPs8V8dtn+HIDZ*8$Axzfs71OQlt-BUF z0dzI>E3dGnKpJ<(G#z6ni*=xTW8A;SlJ22MNK6ms>YASM1LTL6&%|465QT3mM0*Ih zW_MZ-JC9ecY$G{ikPz|IR_zK^q8DCi5ZH|J7vV{{wv6%*5It{qJtosljn?kbSx{Ps ziJO7|voispnSX3r!&t$2Z=nMy5t+he8!zl@yk<$6a{@@t=!g^}a&*bG{k6-z__ zk`{gu^%}Vu0xvs&`ZeC>@B*^QGGfc>((hHe4R5PDNi5E071WMP40F3##Xrz#Xdu;e z#&2VT-uQy5cy$}p%Ba7G!KEwAQoXv>6`Hrh+6e~Z&l0FRyeIfY0*UC9t8Yqg319pFbTb1gvP2;w% z*&?=1fX?a9vdReBZPsk?^?g|SGHF2_Mn>Bn_h~+X>{ID7k^0*Rv=hO1{Bf>zDSzTg zBE$Od(y(G*Y7DwTU=d!!_pAXTA$5M0QqD8`zp-<`%y{9~#$EiuR2_34v?gP^P@u4-ud0@ltTX@9?b8-9+N;BHq^k-=kUX|N5;f z#oSPG-+bV0EIVBym*o-r*972Gdcf&b%Up3dZZ$bp6f}r*AQg+;*ODxx0RW)6$VrK7 zP%p9Ik`K@qYqI`v{}?@ZnV>|$t9GeRHKBYJa_g4<*vQ2?{;6xaFv!8r?Az9_(&xa! zwJdL!+0Huqd{!1!e}pupFBwBttTJHD<)`e`cFYC1-9uw5Kj*xZbXiYe?-qBnAX2I-1i&eRDjmtOx+6^*VcHHnATwAgRdw;ZZ zxBywg>Ug|9FgUrJEOTe-A{4xFJG}u@-B{M`%sV)z=5|KRdq1pn#X_EXJaQjyJUq@< zx&Q&9cibfN$al$TryXmdVn$deQ`%yTuk_n3ezxqjc>^9tv7Xl9B1n`4YmsE|5mDDJ ztRG=KLqX@`F=79v&Kfo_<-e(5tVbjAp9UT*b>@E>mV^`={yG2k^8e`%48QoFo<0YO z!hQXBcbcB-av$!xV4_dTRq%6c9N%C*ADpR>%`<7K4-q|t9SoocU%-{v_lwe!&WBhZ zt-JeRLc`nK=WAu*hod_0Ht*-TuDg!4%K;Hr|JdlTeSD`|$^wkOjmR(_yinGAP_<^{ zNlT-BE_}A+xw~!kP2OQ^*TouK+xw3OPljrflWJG?J>% z|K}=o<4})y=!X|bcD~X`NN>#mt>^d(6zgd z{`-DpR5()~|NA;@*ue#Y4-?OSvDyzZyY51tHnGYb?}oabcw=K@pO<2vz_#<1aHHpK ztK6prP8pejsy62x(Z^2zXM>z1FWeNR`D|S&hkyijj-tR z^W!C}?*VixR@D7;JUEP$j-)f}tK_$TbK-<*T&z&=Vf|t4xyC9-ho!-1`37DEzjyRm zhp%C-``;Nok4Jw%@!u7_?Ie53?`rlpdG2~9d+HzS>1ngKA__5jj$YHoQZ#D4f846_ zhTNA}2;EPE%WlpT!}bw+{>^I2B^8p+eG$_N0>~nY=-HG1ZS2#zm!jwHyq_=86;|h| zFW{-{dUC*ZWoB6qW)PcTuhfn%RXUeWXYU$KU*uBATSUS3Ofyob3C zj*h7xP7hkJrx1gC2yyJ`{w2i8S)LR?qG9g4v*M6s0<>*bBZe@k+oJ1zUpec_!;}#F3ivUiZHQ)f&r(7=Ho{ zBJ+7pR2CLSF9s?5AEm2_zg>Tq`&dEt$m)MP;P*%?a+yBSelmOr0!@pbHV0>2sw=N? zu#H*PU2fbzUe&LBXPpQNBjx*VF%Z6Jl7a6F&!29doAN zi9WqsI}a5(BYR$amX!iLUai5`P8x$Je0J-AK;M}UYt5ZIFL&JL1-pYa8QpKD0@`yR zPhtDOf3*F7iNMd~MFe2URMxJYa7WL3vk4*i)xhfAxW}mFGC<^^W#Y#7S=j$b(n3R* ziQvSqiFrly<@T`J53_S$qN`$Km4}<2PpkZ{hF@gS;=E&+gMuUM^p83Gk5NKc6&v=G zea?c&Zub+FMc_47BF!Lj-^ZHy@SpxyvCk7$qOekbg1Yv@DU7!ovJ7 zYrJ`_&g@0A_Jp$L;pB8_?pLccM&`AjFZ!GdFPRW|DDAq?^1sUUzoinrMSSjSdSrAI zX?uQH^|+fZ>Vm6_VyrJU*rM=a`9169@OAxZt$bc4yBlHeCxhFHK5>dZ)cIdObomQ! zWxO!8_rLVI6V-RE>v7I1*Z2C^(f`5LpX(}m+v;gZ6uz=2`i$tmF|l@vn2&LG9_#-Y zPMdQJIlaMOKa(~R#5B4}-g^0>#pg4n71KlLYq0Th)Uq7H`l1aT7u)K}FBZIZ-L@7R zwtt8o%KASt{2${jSmP|#byeQZT04*Nhh?9BA9zVzpe(4u{I5<`(r#T?0iEo@*iYG_ zFvqpiU*wecpnpvNe>p+j7bp0S`~LsVt^c19{ykm(zdKw0AGZGgg{>?6;HA}7zv$Q( z*Kc06nf9-l(NN((bAa1&n#-Psf>caQjA7yyMF9$AYASxPOp|x`UmZFB(-C&DaX442=Dbw=uGG%RD-6cb3sqVjqxcR?% zn2x_^F!@pfoPX2Qe2G?t4Eg^)v<>-Bn>}f 0 + + colors = list(colour.Color("purple").range_to(colour.Color("green"), num_colors)) + color_rgb = 255 * np.array([np.array(a.get_rgb()) for a in colors]) + color_rgb = [a.astype(np.int) for a in color_rgb] + return color_rgb + + +def get_panoptic_colors(): + colors = [ + colour.Color("yellow"), + colour.Color("blue"), + colour.Color("green"), + colour.Color("red"), + colour.Color("purple") + ] + color_rgb = 255 * np.array([np.array(a.get_rgb()) for a in colors]) + color_rgb = [a.astype(np.int) for a in color_rgb] + return color_rgb + + +def get_unique_colors(num_colors): + ''' + Gives a the specified number of unique colors + Args: + num_colors: an int specifying the number of colors + Returs: + A list of rgb colors in the range of (0,255) + ''' + color_rgb = get_colors(num_colors) + + if (num_colors != len(np.unique(color_rgb, axis=0))): + raise ValueError('Colors returned are not unique.') + + return color_rgb diff --git a/simnet/lib/datapoint.py b/simnet/lib/datapoint.py new file mode 100644 index 0000000..a48ae12 --- /dev/null +++ b/simnet/lib/datapoint.py @@ -0,0 +1,442 @@ +import dataclasses +import IPython +import copy +import sys +import io +import operator +import time +import pathlib +import pickle +import shortuuid +import urllib3 + +from PIL import Image +import cv2 +import boto3 +import numpy as np +import zstandard as zstd + + +def get_uid(): + return shortuuid.uuid() + + +# Struct for Pose Prediction +@dataclasses.dataclass +class Pose: + heat_map: np.ndarray + vertex_target: np.ndarray + z_centroid: np.ndarray + + +# Struct for Keypoint Prediction +@dataclasses.dataclass +class Keypoint: + heat_map: np.ndarray + + +# Struct for Oriented Bounding Box Prediction +@dataclasses.dataclass +class OBB: + heat_map: np.ndarray + vertex_target: np.ndarray + z_centroid: np.ndarray + cov_matrices: np.ndarray + compressed: bool = False + + def compress(self): + if self.compressed: + return + # Heat map scale by 4x and quantize + height, width = self.heat_map.shape + self.heat_map = cv2.resize( + self.heat_map, (width // 4, height // 4), interpolation=cv2.INTER_CUBIC + ).astype(np.float16) + + # Vertex field, quantize and transpose to make vertex field smooth in memory order (makes + # downstream compression 50x more effective) + self.vertex_target = self.vertex_target.transpose(2, 0, 1).astype(np.float16) + + self.compressed = True + + def decompress(self): + if not self.compressed: + return + + #print('OBB.decompress') + #def _debug(name, x): + # print(name, x.dtype, x.shape, x.min(), x.max()) + #_debug('OBB.decompress.heat_map', self.heat_map) + #_debug('OBB.decompress.z_centroid', self.z_centroid) + #_debug('OBB.decompress.vertex_target', self.vertex_target) + #_debug('OBB.decompress.cov_matrices', self.cov_matrices) + #print('----------------------------------------------------') + + # Heat map scale by 4x and quantize + height, width = self.heat_map.shape + self.heat_map = cv2.resize( + self.heat_map.astype(np.float32), (width * 4, height * 4), interpolation=cv2.INTER_CUBIC + ) + #print('heat_map:', self.heat_map.dtype, self.heat_map.shape) + + # Vertex field, quantize and transpose to make vertex field smooth in memory order (makes + # downstream compression 50x more effective) + self.vertex_target = self.vertex_target.astype(np.float32).transpose(1, 2, 0) + #print('vertex_target:', self.vertex_target.dtype, self.vertex_target.shape) + + self.compressed = False + + +def compress_color_image(img, quality=90): + with io.BytesIO() as buf: + img = Image.fromarray(img) + img.save(buf, format='jpeg', quality=quality) + return buf.getvalue() + + +def decompress_color_image(img_bytes): + with io.BytesIO(img_bytes) as buf: + img = Image.open(buf) + return np.array(img) + + +#Struct for Stereo Representation +@dataclasses.dataclass +class Stereo: + left_color: np.ndarray + right_color: np.ndarray + compressed: bool = False + + def compress(self): + if self.compressed: + return + self.left_color = compress_color_image(self.left_color) + self.right_color = compress_color_image(self.right_color) + self.compressed = True + + def decompress(self): + if not self.compressed: + return + #print('Stereo.decompress') + + self.left_color = decompress_color_image(self.left_color) + self.right_color = decompress_color_image(self.right_color) + self.compressed = False + + +# Application Specific Datapoints Should be specified here. +@dataclasses.dataclass +class Panoptic: + stereo: Stereo + depth: np.ndarray + segmentation: np.ndarray + object_poses: list + boxes: list + detections: list + keypoints: list = dataclasses.field(default_factory=list) + instance_mask: np.ndarray = None + scene_name: str = 'sim' + uid: str = dataclasses.field(default_factory=get_uid) + compressed: bool = False + + def compress(self): + self.stereo.compress() + for object_pose in self.object_poses: + object_pose.compress() + + if self.compressed: + return + + # Depth scale by 4x and quantize + height, width = self.depth.shape + self.depth = cv2.resize(self.depth, (width // 4, height // 4), + interpolation=cv2.INTER_CUBIC).astype(np.float16) + + self.compressed = True + + def decompress(self): + self.stereo.decompress() + for object_pose in self.object_poses: + object_pose.decompress() + + if not self.compressed: + return + #print('Panoptic.decompress') + + # Depth scale by 4x and quantize + height, width = self.depth.shape + self.depth = cv2.resize( + self.depth.astype(np.float32), (width * 4, height * 4), interpolation=cv2.INTER_CUBIC + ) + + self.compressed = False + + +# Application Specific Datapoints Should be specified here. +@dataclasses.dataclass +class RobotMask: + stereo: Stereo + depth: np.ndarray + segmentation: np.ndarray + uid: str = dataclasses.field(default_factory=get_uid) + + +# End Applications Here +def compress_datapoint(x): + x = copy.deepcopy(x) + x.compress() + buf = pickle.dumps(x, protocol=pickle.HIGHEST_PROTOCOL) + cctx = zstd.ZstdCompressor() + cbuf = cctx.compress(buf) + return cbuf + + +def decompress_datapoint(cbuf, disable_final_decompression=False): + cctx = zstd.ZstdDecompressor() + buf = cctx.decompress(cbuf) + x = pickle.loads(buf) + if not disable_final_decompression: + x.decompress() + return x + + +def make_dataset(uri): + if ',' in uri: + datasets = [] + for uri in uri.split(','): + datasets.append(make_one_dataset(uri)) + return ConcatDataset(datasets) + return make_one_dataset(uri) + + +def make_one_dataset(uri): + # parse parameters + uri, _, raw_params = uri.partition('?') + dataset = make_one_simple_dataset(uri) + if not raw_params: + return dataset + + params = {} + for raw_param in raw_params.split('&'): + k, _, v = raw_param.partition('=') + assert k and v + assert k not in params + params[k] = v + + return FilterDataset(dataset, params) + + +def make_one_simple_dataset(uri): + if uri.startswith('s3://'): + path = uri.partition('s3://')[2] + bucket, _, dataset_path = path.partition('/') + return RemoteDataset(bucket, dataset_path) + + if uri.startswith('file://'): + path = uri.partition('file://')[2] + dataset_path = pathlib.Path(path) + return LocalDataset(dataset_path) + + raise ValueError(f'uri must start with `s3://` or `file://`. uri={uri}') + + +def _datapoint_path(dataset_path, uid): + return f'{dataset_path}/{uid}.pickle.zstd' + + +class FilterDataset: + + def __init__(self, dataset, params): + self.dataset = dataset + self.params = params + self.samples = None + for key in params: + if key == 'samples': + self.samples = int(params[key]) + else: + raise ValueError(f'Unknown param in dataset args: {key}') + + def list(self): + handles = self.dataset.list() + if self.samples is not None: + handles = handles * (self.samples // len(handles) + 1) + handles = handles[:self.samples] + return handles + + def write(self, datapoint): + raise ValueError('Cannot write to concat dataset') + + +class ConcatDataset: + + def __init__(self, datasets): + self.datasets = datasets + + def list(self): + handles = [] + for dataset in self.datasets: + handles.extend(dataset.list()) + return handles + + def write(self, datapoint): + raise ValueError('Cannot write to concat dataset') + + +class RemoteDataset: + + def __init__(self, bucket, path): + self.s3 = boto3.resource('s3') + self.bucket = bucket + self.dataset_path = path + assert not path.endswith('/') + self._cache_list = None + + def list(self): + if self._cache_list is not None: + return self._cache_list + bucket = self.s3.Bucket(self.bucket) + handles = [] + for obj in bucket.objects.filter(Prefix=self.dataset_path + '/'): + path = obj.key + if not path.endswith('.pickle.zstd'): + continue + uid = path.rpartition('/')[2].partition('.pickle.zstd')[0] + handles.append(RemoteReadHandle(self.bucket, self.dataset_path, uid)) + x = sorted(handles, key=operator.attrgetter('uid')) + self._cache_list = x + return x + + def write(self, datapoint): + buf = compress_datapoint(datapoint) + path = _datapoint_path(self.dataset_path, datapoint.uid) + self.s3.Bucket(self.bucket).put_object(Key=path, Body=buf) + + +class RemoteDataset: + + def __init__(self, bucket, path): + self.s3 = boto3.resource('s3') + self.bucket = bucket + self.dataset_path = path + assert not path.endswith('/') + self._cache_list = None + + def list(self): + if self._cache_list is not None: + return self._cache_list + bucket = self.s3.Bucket(self.bucket) + handles = [] + for obj in bucket.objects.filter(Prefix=self.dataset_path + '/'): + path = obj.key + if not path.endswith('.pickle.zstd'): + continue + uid = path.rpartition('/')[2].partition('.pickle.zstd')[0] + handles.append(RemoteReadHandle(self.bucket, self.dataset_path, uid)) + x = sorted(handles, key=operator.attrgetter('uid')) + self._cache_list = x + return x + + def write(self, datapoint): + buf = compress_datapoint(datapoint) + path = _datapoint_path(self.dataset_path, datapoint.uid) + self.s3.Bucket(self.bucket).put_object(Key=path, Body=buf) + + +class RemoteReadHandle: + + def __init__(self, bucket, dataset_path, uid): + self.bucket = bucket + self.dataset_path = dataset_path + self.uid = uid + + def read(self, disable_final_decompression=False): + # Lazily initialize s3 resource due to pytorch data loaders + attempt = 0 + while True: + success = False + try: + if False: + session = boto3.session.Session() + s3 = session.resource('s3') + else: + s3 = boto3.resource('s3') + path = _datapoint_path(self.dataset_path, self.uid) + rsp = s3.Object(self.bucket, path).get() + buf = rsp['Body'].read() + success = True + except urllib3.exceptions.ProtocolError as exc: + print('RETRY: urllib3.exceptions.ProtocolError, attempt:', attempt) + attempt += 1 + delay = retry_delay(attempt) + print('Sleeping before retry:', delay) + time.sleep(delay) + except KeyError as exc: + print('RETRY: KeyError, attempt:', attempt) + attempt += 1 + delay = retry_delay(attempt) + print('Sleeping before retry:', delay) + time.sleep(delay) + if success: + break + dp = decompress_datapoint(buf, disable_final_decompression=disable_final_decompression) + # TODO: remove this, once old datasets without UID are out of use + if not hasattr(dp, 'uid'): + dp.uid = self.uid + assert dp.uid == self.uid + return dp + + +def retry_delay(attempt): + """Exponential backoff with maximum delay and partial jitter.""" + delay = 100e-3 * (2.**attempt) # exponential back off + delay = min(10.0, delay) # with maximum + delay = delay * np.random.uniform(0.5, 1) # partial jitter + return delay + + +class LocalDataset: + + def __init__(self, dataset_path): + if not dataset_path.exists(): + print('New dataset directory:', dataset_path) + dataset_path.mkdir(parents=True) + assert dataset_path.is_dir() + self.dataset_path = dataset_path + + def list(self): + handles = [] + for path in self.dataset_path.glob('*.pickle.zstd'): + uid = path.name.partition('.')[0] + handles.append(LocalReadHandle(self.dataset_path, uid)) + return sorted(handles, key=operator.attrgetter('uid')) + + def write(self, datapoint): + path = _datapoint_path(self.dataset_path, datapoint.uid) + buf = compress_datapoint(datapoint) + with open(path, 'wb') as fh: + fh.write(buf) + + +class LocalReadHandle: + + def __init__(self, dataset_path, uid): + self.dataset_path = dataset_path + self.uid = uid + + def read(self, disable_final_decompression=False): + path = _datapoint_path(self.dataset_path, self.uid) + with open(path, 'rb') as fh: + dp = decompress_datapoint(fh.read(), disable_final_decompression=disable_final_decompression) + # TODO: remove this, once old datasets without UID are out of use + if not hasattr(dp, 'uid'): + dp.uid = self.uid + assert dp.uid == self.uid + return dp + + +if __name__ == '__main__': + ds = make_dataset(sys.argv[1]) + for dph in ds.list(): + dp = dph.read() + IPython.embed() + break diff --git a/simnet/lib/net/common.py b/simnet/lib/net/common.py new file mode 100644 index 0000000..d45c29b --- /dev/null +++ b/simnet/lib/net/common.py @@ -0,0 +1,167 @@ +import pathlib +from importlib.machinery import SourceFileLoader +import torch +from torch.utils.data import ConcatDataset, DataLoader + +from simnet.lib.net.init.default_init import default_init +from simnet.lib.net.dataset import Dataset + + +def add_dataset_args(parser, prefix): + group = parser.add_argument_group("{}_dataset".format(prefix)) + group.add_argument("--{}_path".format(prefix), type=str, required=True) + #group.add_argument("--{}_fraction".format(prefix), type=str, default=None) + group.add_argument("--{}_batch_size".format(prefix), default=16, type=int) + group.add_argument("--{}_num_workers".format(prefix), default=7, type=int) + #group.add_argument("--{}_random_crop".format(prefix), default=None, type=int, nargs=2) + + +def add_train_args(parser): + parser.add_argument("--max_steps", type=int, required=True) + parser.add_argument("--output", type=str, required=True) + + add_dataset_args(parser, "train") + add_dataset_args(parser, "val") + + optim_group = parser.add_argument_group("optim") + optim_group.add_argument("--optim_type", default='sgd', type=str) + optim_group.add_argument("--optim_learning_rate", default=0.02, type=float) + optim_group.add_argument("--optim_momentum", default=0.9, type=float) + optim_group.add_argument("--optim_weight_decay", default=1e-4, type=float) + optim_group.add_argument("--optim_poly_exp", default=0.9, type=float) + optim_group.add_argument("--optim_warmup_epochs", default=None, type=int) + parser.add_argument("--model_file", type=str, required=True) + parser.add_argument("--model_name", type=str, required=True) + parser.add_argument("--checkpoint", default=None, type=str) + parser.add_argument("--wandb_name", type=str, required=True) + # Ignore Mask Search. + parser.add_argument("--min_height", default=0.0, type=float) + parser.add_argument("--min_occlusion", default=0.0, type=float) + parser.add_argument("--min_truncation", default=0.0, type=float) + # Backbone configs + parser.add_argument("--model_norm", default='BN', type=str) + parser.add_argument("--num_filters_scale", default=4, type=int) + + # Loss weights + parser.add_argument("--frozen_stereo_checkpoint", default=None, type=str) + parser.add_argument("--loss_seg_mult", default=1.0, type=float) + parser.add_argument("--loss_depth_mult", default=1.0, type=float) + parser.add_argument("--loss_depth_refine_mult", default=1.0, type=float) + parser.add_argument("--loss_heatmap_mult", default=100.0, type=float) + parser.add_argument("--loss_vertex_mult", default=0.1, type=float) + parser.add_argument("--loss_z_centroid_mult", default=0.1, type=float) + parser.add_argument("--loss_rotation_mult", default=0.1, type=float) + parser.add_argument("--loss_keypoint_mult", default=0.1, type=float) + # Stereo Stem Args + parser.add_argument( + "--loss_disparity_stdmean_scaled", + action="store_true", + help="If true, the loss will be scaled based on the standard deviation and mean of the " + "ground truth disparities" + ) + parser.add_argument("--cost_volume_downsample_factor", default=4, type=int) + parser.add_argument("--max_disparity", default=90, type=int) + parser.add_argument( + "--fe_features", + default=16, + type=int, + help="Number of output features in feature extraction stage" + ) + parser.add_argument( + "--fe_internal_features", + default=32, + type=int, + help="Number of features in the first block of the feature extraction" + ) + # keypoint head args + parser.add_argument("--num_keypoints", default=1, type=int) + + +def get_config_value(hparams, prefix, key): + full_key = "{}_{}".format(prefix, key) + if hasattr(hparams, full_key): + return getattr(hparams, full_key) + else: + return None + + +def get_loader(hparams, prefix, preprocess_func=None, datapoint_dataset=None): + datasets = [] + path = get_config_value(hparams, prefix, 'path') + datasets.append( + Dataset( + path, hparams, preprocess_image_func=preprocess_func, datapoint_dataset=datapoint_dataset + ) + ) + batch_size = get_config_value(hparams, prefix, "batch_size") + + collate_fn = simnet_collate + return DataLoader( + ConcatDataset(datasets), + batch_size=batch_size, + collate_fn=collate_fn, + num_workers=get_config_value(hparams, prefix, "num_workers"), + pin_memory=True, + drop_last=True + ) + + +def simnet_collate(batch): + # list of elements per patch + # Each element is a tuple of (stereo,imgs) + targets = [] + for ii in range(len(batch[0])): + targets.append([batch_element[ii] for batch_element in batch]) + + stacked_images = torch.stack(targets[0]) + + return stacked_images, targets[1], targets[2], targets[3], targets[4], targets[5], targets[ + 6], targets[7] + + +def prune_state_dict(state_dict): + for key in list(state_dict.keys()): + state_dict[key[6:]] = state_dict.pop(key) + return state_dict + + +def keep_only_stereo_weights(state_dict): + pruned_state_dict = {} + for key in list(state_dict.keys()): + if 'stereo' in key: + pruned_state_dict[key] = state_dict[key] + return pruned_state_dict + + +def get_model(hparams): + model_path = (pathlib.Path(__file__).parent / hparams.model_file).resolve() + print('Using model class from:', model_path) + net_module = SourceFileLoader(hparams.model_name, str(model_path)).load_module() + net_attr = getattr(net_module, hparams.model_name) + model = net_attr(hparams) + model.apply(default_init) + + # For large models use imagenet weights. + # This speeds up training and can give a +2 mAP score on car detections + if hparams.num_filters_scale == 1: + model.load_imagenet_weights() + # If we are exporting to the robot, using a TensorRT compatible version of the net. + # Note only nets trained for the robot use batch norm, so we use that. + #if hparams.model_norm == 'BN': + # from simnet.lib.onnx_plugins import fix_module_train + # fix_module_train(model) + + if hparams.frozen_stereo_checkpoint is not None: + print('Restoring stereo weights from checkpoint:', hparams.frozen_stereo_checkpoint) + state_dict = torch.load(hparams.frozen_stereo_checkpoint, map_location='cpu')['state_dict'] + state_dict = prune_state_dict(state_dict) + state_dict = keep_only_stereo_weights(state_dict) + model.load_state_dict(state_dict, strict=False) + + if hparams.checkpoint is not None: + print('Restoring from checkpoint:', hparams.checkpoint) + state_dict = torch.load(hparams.checkpoint, map_location='cpu')['state_dict'] + state_dict = prune_state_dict(state_dict) + model.load_state_dict(state_dict, strict=False) + + return model diff --git a/simnet/lib/net/dataset.py b/simnet/lib/net/dataset.py new file mode 100644 index 0000000..4ab983d --- /dev/null +++ b/simnet/lib/net/dataset.py @@ -0,0 +1,81 @@ +# Copyright 2019 Toyota Research Institute. All rights reserved. + +import cv2 +import numpy as np +import torch +from torch.utils.data import Dataset + +from simnet.lib import datapoint +from simnet.lib.net.post_processing import obb_outputs, depth_outputs, segmentation_outputs + + +def extract_left_numpy_img(anaglyph): + anaglyph_np = np.ascontiguousarray(anaglyph.cpu().numpy()) + anaglyph_np = anaglyph_np.transpose((1, 2, 0)) + left_img = anaglyph_np[..., 0:3] * 255.0 + return left_img + + +def extract_right_numpy_img(anaglyph): + anaglyph_np = np.ascontiguousarray(anaglyph.cpu().numpy()) + anaglyph_np = anaglyph_np.transpose((1, 2, 0)) + left_img = anaglyph_np[..., 3:6] * 255.0 + return left_img + + +def create_anaglyph(stereo_dp): + height, width, _ = stereo_dp.left_color.shape + image = np.zeros([height, width, 6], dtype=np.uint8) + cv2.normalize(stereo_dp.left_color, stereo_dp.left_color, 0, 255, cv2.NORM_MINMAX) + cv2.normalize(stereo_dp.right_color, stereo_dp.right_color, 0, 255, cv2.NORM_MINMAX) + image[..., 0:3] = stereo_dp.left_color + image[..., 3:6] = stereo_dp.right_color + image = image * 1. / 255.0 + image = image.transpose((2, 0, 1)) + return torch.from_numpy(np.ascontiguousarray(image)).float() + + +class Dataset(Dataset): + + def __init__(self, dataset_uri, hparams, preprocess_image_func=None, datapoint_dataset=None): + super().__init__() + + if datapoint_dataset is None: + datapoint_dataset = datapoint.make_dataset(dataset_uri) + self.datapoint_handles = datapoint_dataset.list() + # No need to shuffle, already shufled based on random uids + self.hparams = hparams + + if preprocess_image_func is None: + self.preprocces_image_func = create_anaglyph + else: + assert False + self.preprocces_image_func = preprocess_image_func + + def __len__(self): + return len(self.datapoint_handles) + + def __getitem__(self, idx): + dp = self.datapoint_handles[idx].read() + + anaglyph = self.preprocces_image_func(dp.stereo) + + segmentation_target = segmentation_outputs.SegmentationOutput(dp.segmentation, self.hparams) + segmentation_target.convert_to_torch_from_numpy() + depth_target = depth_outputs.DepthOutput(dp.depth, self.hparams) + depth_target.convert_to_torch_from_numpy() + pose_target = None + for pose_dp in dp.object_poses: + pose_target = obb_outputs.OBBOutput( + pose_dp.heat_map, pose_dp.vertex_target, pose_dp.z_centroid, pose_dp.cov_matrices, + self.hparams + ) + pose_target.convert_to_torch_from_numpy() + + # TODO(kevin): remove these unused outputs + box_target = None + kp_target = None + + scene_name = dp.scene_name + + return anaglyph, segmentation_target, depth_target, pose_target, box_target, kp_target, dp.detections, scene_name diff --git a/simnet/lib/net/functions/learning_rate.py b/simnet/lib/net/functions/learning_rate.py new file mode 100644 index 0000000..814bb25 --- /dev/null +++ b/simnet/lib/net/functions/learning_rate.py @@ -0,0 +1,28 @@ +# Copyright 2018 Toyota Research Institute. All rights reserved. +# +# Originally from Koichiro Yamaguchi's pixwislab repo mirrored at: +# https://github.awsinternal.tri.global/driving/pixwislab + + +def lambda_learning_rate_poly(max_epochs, exponent): + """Make a function for computing learning rate by "poly" policy. + + This policy does a polynomial decay of the learning rate over the epochs + of training. + + Args: + max_epochs (int): max numbers of epochs + exponent (float): exponent value + """ + return lambda epoch: pow((1.0 - epoch / max_epochs), exponent) + + +def lambda_warmup(warmup_period, warmup_factor, wrapped_lambda): + + def warmup(epoch, warmup_period, warmup_factor): + if epoch > warmup_period: + return 1.0 + else: + return warmup_factor + (1.0 - warmup_factor) * (epoch / warmup_period) + + return lambda epoch: warmup(epoch, warmup_period, warmup_factor) * wrapped_lambda(epoch) diff --git a/simnet/lib/net/init/default_init.py b/simnet/lib/net/init/default_init.py new file mode 100644 index 0000000..acac9f8 --- /dev/null +++ b/simnet/lib/net/init/default_init.py @@ -0,0 +1,25 @@ +import torch.nn as nn + + +def default_init(module): + """Initialize parameters of the module. + + For convolution, weights are initialized by Kaiming method and + biases are initialized to zero. + For batch normalization, scales and biases are set to 1 and 0, + respectively. + """ + if isinstance(module, nn.Conv2d): + nn.init.kaiming_normal_(module.weight.data) + if module.bias is not None: + module.bias.data.zero_() + elif isinstance(module, nn.Conv3d): + nn.init.kaiming_normal_(module.weight.data) + if module.bias is not None: + module.bias.data.zero_() + elif isinstance(module, nn.BatchNorm2d): + module.weight.data.fill_(1) + module.bias.data.zero_() + elif isinstance(module, nn.BatchNorm3d): + module.weight.data.fill_(1) + module.bias.data.zero_() diff --git a/simnet/lib/net/losses.py b/simnet/lib/net/losses.py new file mode 100644 index 0000000..be3b43c --- /dev/null +++ b/simnet/lib/net/losses.py @@ -0,0 +1,65 @@ +# Copyright 2019 Toyota Research Institute. All rights reserved. + +import torch +import torch.nn as nn + + +class MaskedL1Loss(nn.Module): + + def __init__(self, centroid_threshold=0.3, downscale_factor=8): + super().__init__() + self.loss = nn.L1Loss(reduction='none') + self.centroid_threshold = centroid_threshold + self.downscale_factor = downscale_factor + + def forward(self, output, target, valid_mask): + ''' + output: [N,16,H,W] + target: [N,16,H,W] + valid_mask: [N,H,W] + ''' + valid_count = torch.sum( + valid_mask[:, ::self.downscale_factor, ::self.downscale_factor] > self.centroid_threshold + ) + loss = self.loss(output, target) + if len(output.shape) == 4: + loss = torch.sum(loss, dim=1) + loss[valid_mask[:, ::self.downscale_factor, ::self.downscale_factor] < self.centroid_threshold + ] = 0.0 + if valid_count == 0: + return torch.sum(loss) + return torch.sum(loss) / valid_count + + +class MSELoss(nn.Module): + + def __init__(self): + super().__init__() + self.loss = nn.MSELoss(reduction='none') + + def forward(self, output, target): + ''' + output: [N,H,W] + target: [N,H,W] + ignore_mask: [N,H,W] + ''' + loss = self.loss(output, target) + return torch.mean(loss) + + +class MaskedMSELoss(nn.Module): + + def __init__(self): + super().__init__() + self.loss = nn.MSELoss(reduction='none') + + def forward(self, output, target, ignore_mask): + ''' + output: [N,H,W] + target: [N,H,W] + ignore_mask: [N,H,W] + ''' + valid_sum = torch.sum(torch.logical_not(ignore_mask)) + loss = self.loss(output, target) + loss[ignore_mask > 0] = 0.0 + return torch.sum(loss) / valid_sum diff --git a/simnet/lib/net/models/panoptic_net.py b/simnet/lib/net/models/panoptic_net.py new file mode 100644 index 0000000..c3a314a --- /dev/null +++ b/simnet/lib/net/models/panoptic_net.py @@ -0,0 +1,433 @@ +import collections + +import numpy as np +import torch +import torch.nn as nn + +from torch.nn import functional as F +from simnet.lib.net.models import simplenet +from simnet.lib.net.post_processing import segmentation_outputs, depth_outputs, pose_outputs, obb_outputs + +MODEL_SEM_SEG_HEAD_IN_FEATURES = ['p2', 'p3', 'p4'] +MODEL_POSE_HEAD_IN_FEATURES = ['p3', 'p4'] + +MODEL_SEM_SEG_HEAD_IGNORE_VALUE = 255 +MODEL_SEM_SEG_HEAD_COMMON_STRIDE = 4 +MODEL_POSE_HEAD_COMMON_STRIDE = 8 +MODEL_SEM_SEG_HEAD_LOSS_WEIGHT = 1.0 + + +def c2_msra_fill(module: nn.Module) -> None: + """ + Initialize `module.weight` using the "MSRAFill" implemented in Caffe2. + Also initializes `module.bias` to 0. + Args: + module (torch.nn.Module): module to initialize. + """ + nn.init.kaiming_normal_(module.weight, mode="fan_out", nonlinearity="relu") + if module.bias is not None: + # pyre-fixme[6]: Expected `Tensor` for 1st param but got `Union[nn.Module, + # torch.Tensor]`. + nn.init.constant_(module.bias, 0) + + +class Conv2d(torch.nn.Conv2d): + """ + A wrapper around :class:`torch.nn.Conv2d` to support empty inputs and more features. + """ + + def __init__(self, *args, **kwargs): + """ + Extra keyword arguments supported in addition to those in `torch.nn.Conv2d`: + + Args: + norm (nn.Module, optional): a normalization layer + activation (callable(Tensor) -> Tensor): a callable activation function + + It assumes that norm layer is used before activation. + """ + norm = kwargs.pop("norm", None) + activation = kwargs.pop("activation", None) + super().__init__(*args, **kwargs) + + self.norm = norm + self.activation = activation + + def forward(self, x): + if x.numel() == 0 and self.training: + # https://github.com/pytorch/pytorch/issues/12013 + assert not isinstance( + self.norm, torch.nn.SyncBatchNorm + ), "SyncBatchNorm does not support empty inputs!" + + if x.numel() == 0 and TORCH_VERSION <= (1, 4): + assert not isinstance( + self.norm, torch.nn.GroupNorm + ), "GroupNorm does not support empty inputs in PyTorch <=1.4!" + # When input is empty, we want to return a empty tensor with "correct" shape, + # So that the following operations will not panic + # if they check for the shape of the tensor. + # This computes the height and width of the output tensor + output_shape = [(i + 2 * p - (di * (k - 1) + 1)) // s + 1 for i, p, di, k, s in + zip(x.shape[-2:], self.padding, self.dilation, self.kernel_size, self.stride)] + output_shape = [x.shape[0], self.weight.shape[0]] + output_shape + empty = _NewEmptyTensorOp.apply(x, output_shape) + if self.training: + # This is to make DDP happy. + # DDP expects all workers to have gradient w.r.t the same set of parameters. + _dummy = sum(x.view(-1)[0] for x in self.parameters()) * 0.0 + return empty + _dummy + else: + return empty + + x = super().forward(x) + if self.norm is not None: + x = self.norm(x) + if self.activation is not None: + x = self.activation(x) + return x + + +def get_norm(norm, out_channels): + """ + Args: + norm (str or callable): either one of BN, SyncBN, FrozenBN, GN; + or a callable that takes a channel number and returns + the normalization layer as a nn.Module. + + Returns: + nn.Module or None: the normalization layer + """ + if out_channels == 32: + N = 16 + else: + N = 32 + if isinstance(norm, str): + if len(norm) == 0: + return None + norm = { + "BN": torch.nn.BatchNorm2d, + #"SyncBN": NaiveSyncBatchNorm, + #"FrozenBN": FrozenBatchNorm2d, + "GN": lambda channels: nn.GroupNorm(N, channels), + #"nnSyncBN": nn.SyncBatchNorm, # keep for debugging + }[norm] + return norm(out_channels) + + +class SemSegFPNHead(nn.Module): + """ + A semantic segmentation head described in detail in the Panoptic Feature Pyramid Networks paper + (https://arxiv.org/abs/1901.02446). It takes FPN features as input and merges information from + all levels of the FPN into single output. + """ + + def __init__(self, input_shape, num_classes, model_norm='BN', num_filters_scale=4): + super().__init__() + MODEL_SEM_SEG_HEAD_NORM = model_norm + MODEL_SEM_SEG_HEAD_CONVS_DIM = 128 // num_filters_scale + + self.in_features = MODEL_SEM_SEG_HEAD_IN_FEATURES + feature_strides = {k: v.stride for k, v in input_shape.items()} + feature_channels = {k: v.channels for k, v in input_shape.items()} + self_ignore_value = MODEL_SEM_SEG_HEAD_IGNORE_VALUE + conv_dims = MODEL_SEM_SEG_HEAD_CONVS_DIM + self.common_stride = MODEL_SEM_SEG_HEAD_COMMON_STRIDE + norm = MODEL_SEM_SEG_HEAD_NORM + self.bilinear_upsample = nn.Upsample( + scale_factor=self.common_stride, mode="bilinear", align_corners=False + ) + + self.scale_heads = [] + for in_feature in self.in_features: + head_ops = [] + head_length = max(1, int(np.log2(feature_strides[in_feature]) - np.log2(self.common_stride))) + for k in range(head_length): + norm_module = get_norm(norm, conv_dims) + conv = Conv2d( + feature_channels[in_feature] if k == 0 else conv_dims, + conv_dims, + kernel_size=3, + stride=1, + padding=1, + bias=not norm, + norm=norm_module, + activation=F.relu, + ) + c2_msra_fill(conv) + head_ops.append(conv) + if feature_strides[in_feature] != self.common_stride: + head_ops.append(nn.Upsample(scale_factor=2, mode="bilinear", align_corners=False)) + self.scale_heads.append(nn.Sequential(*head_ops)) + self.add_module(in_feature, self.scale_heads[-1]) + self.predictor = Conv2d(conv_dims, num_classes, kernel_size=1, stride=1, padding=0) + c2_msra_fill(self.predictor) + + def forward(self, features, targets=None): + """ + Returns: + In training, returns (None, dict of losses) + In inference, returns (predictions, {}) + """ + x = self.layers(features) + x = self.bilinear_upsample(x) + return x + + def layers(self, features): + for i, f in enumerate(self.in_features): + if i == 0: + x = self.scale_heads[i](F.relu(features[f])) + else: + x = x - -self.scale_heads[i](F.relu(features[f])) + x = self.predictor(x) + return x + + def losses(self, predictions, targets): + predictions = F.interpolate( + predictions, scale_factor=self.common_stride, mode="bilinear", align_corners=False + ) + loss = F.cross_entropy(predictions, targets, reduction="mean", ignore_index=self.ignore_value) + return loss + + +class PoseFPNHead(nn.Module): + """ + A semantic segmentation head described in detail in the Panoptic Feature Pyramid Networks paper + (https://arxiv.org/abs/1901.02446). It takes FPN features as input and merges information from + all levels of the FPN into single output. + """ + + def __init__(self, input_shape, num_classes, model_norm='BN', num_filters_scale=4): + super().__init__() + MODEL_SEM_SEG_HEAD_NORM = model_norm + MODEL_SEM_SEG_HEAD_CONVS_DIM = 128 // num_filters_scale + self.in_features = MODEL_POSE_HEAD_IN_FEATURES + feature_strides = {k: v.stride for k, v in input_shape.items()} + feature_channels = {k: v.channels for k, v in input_shape.items()} + self_ignore_value = MODEL_SEM_SEG_HEAD_IGNORE_VALUE + conv_dims = MODEL_SEM_SEG_HEAD_CONVS_DIM + self.common_stride = MODEL_POSE_HEAD_COMMON_STRIDE + norm = MODEL_SEM_SEG_HEAD_NORM + + self.scale_heads = [] + for in_feature in self.in_features: + head_ops = [] + head_length = max(1, int(np.log2(feature_strides[in_feature]) - np.log2(self.common_stride))) + for k in range(head_length): + norm_module = get_norm(norm, conv_dims) + conv = Conv2d( + feature_channels[in_feature] if k == 0 else conv_dims, + conv_dims, + kernel_size=3, + stride=1, + padding=1, + bias=not norm, + norm=norm_module, + activation=F.relu, + ) + c2_msra_fill(conv) + head_ops.append(conv) + if feature_strides[in_feature] != self.common_stride: + head_ops.append(nn.Upsample(scale_factor=2, mode="bilinear", align_corners=False)) + self.scale_heads.append(nn.Sequential(*head_ops)) + self.add_module(in_feature, self.scale_heads[-1]) + self.predictor = Conv2d(conv_dims, num_classes, kernel_size=1, stride=1, padding=0) + c2_msra_fill(self.predictor) + + def forward(self, features, targets=None): + """ + Returns: + In training, returns (None, dict of losses) + In inference, returns (predictions, {}) + """ + x = self.layers(features) + return x + + def layers(self, features): + for i, f in enumerate(self.in_features): + if i == 0: + x = self.scale_heads[i](F.relu(features[f])) + else: + x = x - -self.scale_heads[i](F.relu(features[f])) + x = self.predictor(x) + return x + + +class ShapeSpec(collections.namedtuple("_ShapeSpec", ["channels", "height", "width", "stride"])): + """ + A simple structure that contains basic shape specification about a tensor. + It is often used as the auxiliary inputs/outputs of models, + to obtain the shape inference ability among pytorch modules. + + Attributes: + channels: + height: + width: + stride: + """ + + def __new__(cls, *, channels=None, height=None, width=None, stride=None): + return super().__new__(cls, channels, height, width, stride) + + +def res_fpn(hparams): + return PanopticNet(hparams) + + +class DepthHead(nn.Module): + + def __init__(self, backbone_output_shape_4x, backbone_output_shape_8x, hparams): + super().__init__() + self.head = SemSegFPNHead( + backbone_output_shape_4x, + num_classes=1, + model_norm=hparams.model_norm, + num_filters_scale=hparams.num_filters_scale + ) + self.hparams = hparams + + def forward(self, features): + depth_pred = self.head.forward(features) + depth_pred = depth_pred.squeeze(dim=1) + return depth_outputs.DepthOutput(depth_pred, self.hparams.loss_depth_refine_mult) + + +class SegmentationHead(nn.Module): + + def __init__(self, backbone_output_shape_4x, backbone_output_shape_8x, num_classes, hparams): + super().__init__() + self.head = SemSegFPNHead( + backbone_output_shape_4x, + num_classes=num_classes, + model_norm=hparams.model_norm, + num_filters_scale=hparams.num_filters_scale + ) + self.hparams = hparams + + def forward(self, features): + pred = self.head.forward(features) + return segmentation_outputs.SegmentationOutput(pred, self.hparams) + + +class PoseHead(nn.Module): + + def __init__(self, backbone_output_shape_4x, backbone_output_shape_8x, hparams): + super().__init__() + self.hparams = hparams + self.heatmap_head = SemSegFPNHead( + backbone_output_shape_4x, + num_classes=1, + model_norm=hparams.model_norm, + num_filters_scale=hparams.num_filters_scale + ) + self.vertex_head = PoseFPNHead( + backbone_output_shape_8x, + num_classes=16, + model_norm=hparams.model_norm, + num_filters_scale=hparams.num_filters_scale + ) + self.z_centroid_head = PoseFPNHead( + backbone_output_shape_8x, + num_classes=1, + model_norm=hparams.model_norm, + num_filters_scale=hparams.num_filters_scale + ) + + def forward(self, features): + z_centroid_output = self.z_centroid_head.forward(features).squeeze(dim=1) + heatmap_output = self.heatmap_head.forward(features).squeeze(dim=1) + vertex_output = self.vertex_head.forward(features) + return pose_outputs.PoseOutput(heatmap_output, vertex_output, z_centroid_output, self.hparams) + + +class OBBHead(nn.Module): + + def __init__(self, backbone_output_shape_4x, backbone_output_shape_8x, hparams): + super().__init__() + self.hparams = hparams + self.heatmap_head = SemSegFPNHead( + backbone_output_shape_4x, + num_classes=1, + model_norm=hparams.model_norm, + num_filters_scale=hparams.num_filters_scale + ) + + self.vertex_head = PoseFPNHead( + backbone_output_shape_8x, + num_classes=16, + model_norm=hparams.model_norm, + num_filters_scale=hparams.num_filters_scale + ) + + self.z_centroid_head = PoseFPNHead( + backbone_output_shape_8x, + num_classes=1, + model_norm=hparams.model_norm, + num_filters_scale=hparams.num_filters_scale + ) + + self.rotation_head = PoseFPNHead( + backbone_output_shape_8x, + num_classes=6, + model_norm=hparams.model_norm, + num_filters_scale=hparams.num_filters_scale + ) + + def forward(self, features): + z_centroid_output = self.z_centroid_head.forward(features).squeeze(dim=1) + heatmap_output = self.heatmap_head.forward(features).squeeze(dim=1) + vertex_output = self.vertex_head.forward(features) + rotation_output = self.rotation_head.forward(features) + return obb_outputs.OBBOutput( + heatmap_output, vertex_output, z_centroid_output, rotation_output, self.hparams + ) + + +class PanopticNet(nn.Module): + + def __init__(self, hparams): + super().__init__() + self.hparams = hparams + self.backbone = simplenet.StereoBackbone(hparams) + # ResFPN used p2,p3,p4,p5 (64 channels) + # DRN uses only p2,p3,p4 (no need for p5 since dilation increases striding naturally) + backbone_output_shape_4x = { + #'p0': ShapeSpec(channels=64, height=None, width=None, stride=1), + #'p1': ShapeSpec(channels=64, height=None, width=None, stride=2), + 'p2': ShapeSpec(channels=64, height=None, width=None, stride=4), + 'p3': ShapeSpec(channels=64, height=None, width=None, stride=8), + 'p4': ShapeSpec(channels=64, height=None, width=None, stride=16), + #'p5': ShapeSpec(channels=64, height=None, width=None, stride=32), + } + + backbone_output_shape_8x = { + #'p0': ShapeSpec(channels=64, height=None, width=None, stride=1), + #'p1': ShapeSpec(channels=64, height=None, width=None, stride=2), + #'p2': ShapeSpec(channels=64, height=None, width=None, stride=4), + 'p3': ShapeSpec(channels=64, height=None, width=None, stride=8), + 'p4': ShapeSpec(channels=64, height=None, width=None, stride=16), + #'p5': ShapeSpec(channels=64, height=None, width=None, stride=32), + } + + # Add depth head. + self.depth_head = DepthHead(backbone_output_shape_4x, backbone_output_shape_8x, hparams) + # Add segmentation head. + self.seg_head = SegmentationHead(backbone_output_shape_4x, backbone_output_shape_8x, 5, hparams) + # Add pose heads. + self.pose_head = OBBHead(backbone_output_shape_4x, backbone_output_shape_8x, hparams) + + def forward(self, image, step): + features = self.backbone.forward(image, step) + small_disp_output = features['small_disp'] + small_disp_output = small_disp_output.squeeze(dim=1) + if self.hparams.frozen_stereo_checkpoint is not None: + small_disp_output = small_disp_output.detach() + assert False + small_depth_output = depth_outputs.DepthOutput(small_disp_output, self.hparams.loss_depth_mult) + seg_output = self.seg_head.forward(features) + depth_output = self.depth_head.forward(features) + pose_output = self.pose_head.forward(features) + # TODO(kevin): Remove unused output heads + box_output = None + keypoint_output = None + return seg_output, depth_output, small_depth_output, pose_output, box_output, keypoint_output diff --git a/simnet/lib/net/models/simplenet.py b/simnet/lib/net/models/simplenet.py new file mode 100644 index 0000000..226797d --- /dev/null +++ b/simnet/lib/net/models/simplenet.py @@ -0,0 +1,408 @@ +import dataclasses + +import torch +import torch.nn as nn +import torch.nn.functional as F + + +@dataclasses.dataclass +class Node: + inp: any + module: nn.Module + activated: bool + stride: int + dim: int + + def __hash__(self): + return hash(self.module) + + +class NetFactory(nn.Module): + + def __init__(self): + super().__init__() + self.nodes = [] + self.skips = {} + self.tags = {} + + def tag(self, node, name): + self.tags[node] = name + + def input(self, in_dim=3, stride=1, activated=True): + assert not self.nodes + n = Node(inp=None, module=None, activated=activated, stride=stride, dim=in_dim) + self.nodes.append(n) + return n + + def _add(self, node): + self.nodes.append(node) + return node + + def _activate(self, node): + if node.activated: + return node + return self._add( + dataclasses.replace( + node, + inp=node, + module=nn.Sequential(nn.BatchNorm2d(node.dim), nn.LeakyReLU()), + activated=True + ) + ) + + def _conv(self, node, out_dim=None, stride=1, rate=1, kernel=3): + node = self._activate(node) + if out_dim is None: + out_dim = node.dim + padding = (kernel - 1) // 2 * rate + return self._add( + dataclasses.replace( + node, + inp=node, + module=nn.Conv2d( + node.dim, out_dim, kernel, stride=stride, dilation=rate, padding=padding + ), + activated=False, + dim=out_dim, + stride=node.stride * stride + ) + ) + + def _interp(self, node): + return self._add( + dataclasses.replace( + node, + inp=node, + module=nn.Upsample(scale_factor=2, mode='bilinear', align_corners=True), + stride=node.stride // 2 + ) + ) + + def _lateral(self, node, out_dim=None): + if out_dim is None: + out_dim = node.dim + if out_dim == node.dim: + return node + return self._conv(node, out_dim=out_dim, kernel=1) + + def output(self, node, out_dim): + return self._conv(node, out_dim=out_dim, kernel=1) + + def downscale(self, node, out_dim): + return self._conv(node, out_dim, stride=2) + + def upsample(self, node, skip, out_dim): + skip = self._lateral(skip, out_dim=out_dim) + node = self._lateral(node, out_dim=out_dim) + node = self._interp(node) + self.skips[node] = skip + return node + + def layer(self, node, out_dim=None, rate=1): + if out_dim is None: + out_dim = node.dim + skip = self._lateral(node, out_dim=out_dim) + node = self._conv(node, rate=rate) + node = self._conv(node, rate=rate) + self.skips[node] = skip + return node + + def block(self, node, rates): + for r in [int(r) for r in rates]: + node = self.layer(node, rate=r) + return node + + def bake(self): + self.modules = nn.ModuleList(n.module for n in self.nodes if n.module is not None) + return self + + def forward(self, x): + outputs = {} + tag_outputs = {} + for node in self.nodes: + if node.module is None: # initial input + pass + else: + if node in self.skips: + x = outputs[self.skips[node]] + node.module(outputs[node.inp]) + else: + x = node.module(outputs[node.inp]) + outputs[node] = x + last = x + if node in self.tags: + tag_outputs[self.tags[node]] = x + if tag_outputs: + return tag_outputs + return last + + +def hdrn_alpha_base(num_channels): + net = NetFactory() + x = net.input() + x = net.downscale(x, num_channels) + x = net.downscale(x, num_channels) + x4 = x = net.block(x, '111') + x = net.downscale(x, num_channels * 2) + x8 = x = net.block(x, '1111') + x = net.downscale(x, num_channels * 4) + x = net.block(x, '12591259') + x = net.upsample(x, x8, num_channels // 2) + x = net.upsample(x, x4, num_channels // 2) + return net.bake() + + +def make_process_cost_volume(num_disparities): + net = NetFactory() + x = net.input(in_dim=num_disparities, stride=4, activated=True) + x = net.block(x, '1259') + x = net.output(x, out_dim=num_disparities) + return net.bake() + + +class HdrnAlphaStereo(nn.Module): + + def __init__(self, hparams): + super().__init__() + + self.num_disparities = hparams.max_disparity + self.internal_scale = hparams.cost_volume_downsample_factor + self.internal_num_disparities = self.num_disparities // self.internal_scale + assert self.internal_scale in [4, 8, 16] + + self.feature_extractor = hdrn_alpha_base(hparams.fe_internal_features) + self.cost_volume = DotProductCostVolume(self.internal_num_disparities) + self.process_cost_volume = make_process_cost_volume(self.internal_num_disparities) + + self.soft_argmin = SoftArgmin() + + def forward(self, left_image, right_image): + left_score = self.feature_extractor(left_image) + right_score = self.feature_extractor(right_image) + + cost_volume = self.cost_volume(left_score, right_score) + cost_volume = self.process_cost_volume(cost_volume) + + disparity_small = self.soft_argmin(cost_volume) + + return disparity_small + + +class StereoBackbone(nn.Module): + + def __init__(self, hparams, in_channels=3): + super().__init__() + + def make_rgb_stem(): + net = NetFactory() + x = net.input(in_dim=3, stride=1, activated=True) + x = net.downscale(x, 32) + x = net.downscale(x, 32) + return net.bake() + + def make_disp_features(): + net = NetFactory() + x = net.input(in_dim=1, stride=1, activated=False) + x = net.layer(x, 32, rate=5) + return net.bake() + + self.rgb_stem = make_rgb_stem() + self.stereo_stem = HdrnAlphaStereo(hparams) + self.disp_features = make_disp_features() + + def make_rgbd_backbone(num_channels=64, out_dim=64): + net = NetFactory() + x = net.input(in_dim=64, activated=True, stride=4) + x = net._lateral(x, out_dim=num_channels) + x4 = x = net.block(x, '111') + x = net.downscale(x, num_channels * 2) + x8 = x = net.block(x, '1111') + x = net.downscale(x, num_channels * 4) + x = net.block(x, '12591259') + net.tag(net.output(x, out_dim), 'p4') + x = net.upsample(x, x8, out_dim) + net.tag(x, 'p3') + x = net.upsample(x, x4, out_dim) + net.tag(x, 'p2') + return net.bake() + + self.rgbd_backbone = make_rgbd_backbone() + + def forward(self, stacked_img, step, robot_joint_angles=None): + small_disp = self.stereo_stem.forward(stacked_img[:, 0:3], stacked_img[:, 3:6]) + left_rgb_features = self.rgb_stem.forward(stacked_img[:, 0:3]) + disp_features = self.disp_features(small_disp) + rgbd_features = torch.cat((disp_features, left_rgb_features), axis=1) + outputs = self.rgbd_backbone.forward(rgbd_features) + outputs['small_disp'] = small_disp + return outputs + + @property + def out_channels(self): + return 32 + + @property + def stride(self): + return 4 # = stride 2 conv -> stride 2 max pool + + +@torch.jit.script +def cost_volume(left, right, num_disparities: int, is_right: bool): + batch_size, channels, height, width = left.shape + + output = torch.zeros((batch_size, channels, num_disparities, height, width), + dtype=left.dtype, + device=left.device) + + for i in range(num_disparities): + if not is_right: + output[:, :, i, :, i:] = left[:, :, :, i:] * right[:, :, :, :width - i] + else: + output[:, :, i, :, :width - i] = left[:, :, :, i:] * right[:, :, :, :width - i] + + return output + + +class CostVolume(nn.Module): + """Compute cost volume using cross correlation of left and right feature maps""" + + def __init__(self, num_disparities, is_right=False): + super().__init__() + self.num_disparities = num_disparities + self.is_right = is_right + + def forward(self, left, right): + if torch.jit.is_scripting(): + return cost_volume(left, right, self.num_disparities, self.is_right) + else: + return self.forward_with_amp(left, right) + + @torch.jit.unused + def forward_with_amp(self, left, right): + """This operation is unstable at float16, so compute at float32 even when using mixed precision""" + with torch.cuda.amp.autocast(enabled=False): + left = left.to(torch.float32) + right = right.to(torch.float32) + output = cost_volume(left, right, self.num_disparities, self.is_right) + output = torch.clamp(output, -1e3, 1e3) + return output + + +@torch.jit.script +def dot_product_cost_volume(left, right, num_disparities: int, is_right: bool): + batch_size, channels, height, width = left.shape + + output = torch.zeros((batch_size, num_disparities, height, width), + dtype=left.dtype, + device=left.device) + + for i in range(num_disparities): + if not is_right: + output[:, i, :, i:] = (left[:, :, :, i:] * right[:, :, :, :width - i]).mean(dim=1) + else: + output[:, i, :, width - i] = (left[:, :, :, i:] * right[:, :, :, :width - i]).mean(dim=1) + + return output + + +class DotProductCostVolume(nn.Module): + """Compute cost volume using dot product of left and right feature maps""" + + def __init__(self, num_disparities, is_right=False): + super().__init__() + self.num_disparities = num_disparities + self.is_right = is_right + + def forward(self, left, right): + return dot_product_cost_volume(left, right, self.num_disparities, self.is_right) + + @torch.jit.unused + def forward_with_amp(self, left, right): + """This operation is unstable at float16, so compute at float32 even when using mixed precision""" + with torch.cuda.amp.autocast(enabled=False): + left = left.to(torch.float32) + right = right.to(torch.float32) + output = dot_product_cost_volume(left, right, self.num_disparities, self.is_right) + output = torch.clamp(output, -1e3, 1e3) + return output + + +@torch.jit.script +def soft_argmin(input): + _, channels, _, _ = input.shape + + softmin = F.softmin(input, dim=1) + index_tensor = torch.arange(0, channels, dtype=softmin.dtype, + device=softmin.device).view(1, channels, 1, 1) + output = torch.sum(softmin * index_tensor, dim=1, keepdim=True) + return output + + +class SoftArgmin(nn.Module): + """Compute soft argmin operation for given cost volume""" + + def forward(self, input): + return soft_argmin(input) + + +@torch.jit.script +def matchability(input): + softmin = F.softmin(input, dim=1) + log_softmin = F.log_softmax(-input, dim=1) + output = torch.sum(softmin * log_softmin, dim=1, keepdim=True) + return output + + +class Matchability(nn.Module): + """Compute disparity matchability value from https://arxiv.org/abs/2008.04800""" + + def forward(self, input): + if torch.jit.is_scripting(): + # Torchscript generation can't handle mixed precision, so always compute at float32. + return matchability(input) + else: + return self.forward_with_amp(input) + + @torch.jit.unused + def forward_with_amp(self, input): + """This operation is unstable at float16, so compute at float32 even when using mixed precision""" + with torch.cuda.amp.autocast(enabled=False): + input = input.to(torch.float32) + return matchability(input) + + +def main(): + num_channels = 32 + net = NetFactory() + x = net.input() + x = net.downscale(x, num_channels) + x = net.downscale(x, num_channels) + x4 = x = net.block(x, '111') + x = net.downscale(x, num_channels * 2) + x8 = x = net.block(x, '1111') + x = net.downscale(x, num_channels * 4) + x = net.block(x, '12591259') + x = net.upsample(x, x8, num_channels // 2) + x = net.upsample(x, x4, num_channels // 2) + net.bake() + + x = torch.randn(5, 3, 512, 640) + y = net(x) + + import torch._C as _C + TrainingMode = _C._onnx.TrainingMode + torch.onnx.export( + net, + x, + "test_net.onnx", + do_constant_folding=False, + verbose=True, + training=TrainingMode.TRAINING, + opset_version=13 + ) + import onnx + from onnx import shape_inference + onnx.save(shape_inference.infer_shapes(onnx.load('test_net.onnx')), 'test_net_shapes.onnx') + + +if __name__ == '__main__': + main() diff --git a/simnet/lib/net/panoptic_trainer.py b/simnet/lib/net/panoptic_trainer.py new file mode 100644 index 0000000..9ee28cc --- /dev/null +++ b/simnet/lib/net/panoptic_trainer.py @@ -0,0 +1,168 @@ +import os +import copy + +os.environ['PYTHONHASHSEED'] = str(1) + +import random + +random.seed(123456) +import numpy as np + +np.random.seed(123456) +import torch + +torch.manual_seed(123456) + +import wandb + +import pytorch_lightning as pl + +from simnet.lib.net import common +from simnet.lib.net.dataset import extract_left_numpy_img +from simnet.lib.net.functions.learning_rate import lambda_learning_rate_poly, lambda_warmup + +_GPU_TO_USE = 0 + + +class PanopticModel(pl.LightningModule): + + def __init__( + self, hparams, epochs=None, train_dataset=None, eval_metric=None, preprocess_func=None + ): + super().__init__() + + self.hparams = hparams + self.epochs = epochs + self.train_dataset = train_dataset + + self.model = common.get_model(hparams) + self.eval_metrics = eval_metric + self.preprocess_func = preprocess_func + + def forward(self, image): + seg_output, depth_output, small_depth_output, pose_output, box_output, keypoint_output = self.model( + image, self.global_step + ) + return seg_output, depth_output, small_depth_output, pose_output, box_output, keypoint_output + + def optimizer_step(self, epoch_nb, batch_nb, optimizer, optimizer_i, second_order_closure=None): + super().optimizer_step(epoch_nb, batch_nb, optimizer, optimizer_i, second_order_closure) + + learning_rate = 0.0 + for param_group in optimizer.param_groups: + learning_rate = param_group['lr'] + break + self.logger.experiment.log({'learning_rate': learning_rate}) + + def training_step(self, batch, batch_idx): + image, seg_target, depth_target, pose_targets, box_targets, keypoint_targets, _, _ = batch + seg_output, depth_output, small_depth_output, pose_outputs, box_outputs, keypoint_outputs = self.forward( + image + ) + + log = {} + loss = depth_output.compute_loss(copy.deepcopy(depth_target), log, 'refined_disp') + if self.hparams.frozen_stereo_checkpoint is None: + loss = loss + small_depth_output.compute_loss(depth_target, log, 'cost_volume_disp') + else: + assert False + loss = loss + seg_output.compute_loss(seg_target, log) + if pose_targets[0] is not None: + loss = loss + pose_outputs.compute_loss(pose_targets, log) + if box_targets[0] is not None: + loss = loss + box_outputs.compute_loss(box_targets, log) + if keypoint_targets[0] is not None: + loss += keypoint_outputs.compute_loss(keypoint_targets, log) + log['train/loss/total'] = loss + + if (batch_idx % 500) == 0: + with torch.no_grad(): + llog = {} + prefix = 'train' + left_image_np = extract_left_numpy_img(image[0]) + logger = self.logger.experiment + seg_pred_vis = seg_output.get_visualization_img(np.copy(left_image_np)) + llog[f'{prefix}/seg'] = wandb.Image(seg_pred_vis, caption=prefix) + if pose_targets[0] is not None: + pose_vis = pose_outputs.get_visualization_img( + np.copy(left_image_np), camera_model=self.eval_metrics.camera_model + ) + llog[f'{prefix}/pose'] = wandb.Image(pose_vis, caption=prefix) + if box_targets[0] is not None: + box_vis = box_outputs.get_visualization_img(np.copy(left_image_np)) + llog[f'{prefix}/box'] = wandb.Image(box_vis, caption=prefix) + if keypoint_targets[0] is not None: + kp_vis = keypoint_outputs.get_visualization_img(np.copy(left_image_np)) + kp_pred_vis = keypoint_outputs.get_detections(np.copy(left_image_np)) + for idx, kp_vis_img in enumerate(kp_vis): + llog[f'{prefix}/keypoints_{idx}'] = wandb.Image(kp_vis_img, caption=prefix) + llog[f'{prefix}/keypoints_pred'] = wandb.Image(kp_pred_vis, caption=prefix) + depth_vis = depth_output.get_visualization_img(np.copy(left_image_np)) + llog[f'{prefix}/disparity'] = wandb.Image(depth_vis, caption=prefix) + small_depth_vis = small_depth_output.get_visualization_img(np.copy(left_image_np)) + llog[f'{prefix}/small_disparity'] = wandb.Image(small_depth_vis, caption=prefix) + logger.log(llog) + return {'loss': loss, 'log': log} + + def validation_step(self, batch, batch_idx): + #if corl.sim_on_sim_overfit: + # # If we are overfitting on sim data set batch size to 1 and enable batch norm for val to make + # # it match train. this doesn't make sense unless trying to get val and train to match + # # perfectly on a single sample for an overfit test + # self.model.train() + + image, seg_target, depth_target, pose_targets, box_targets, keypoint_targets, detections_gt, scene_name = batch + seg_output, depth_output, small_depth_output, pose_outputs, box_outputs, keypoint_outputs = self.forward( + image + ) + log = {} + with torch.no_grad(): + # Compute mAP score + if scene_name[0] != 'fmk': + self.eval_metrics.process_sample( + pose_outputs, box_outputs, seg_output, detections_gt[0], scene_name[0] + ) + logger = self.logger.experiment + if batch_idx < 5 or scene_name[0] == 'fmk': + llog = {} + left_image_np = extract_left_numpy_img(image[0]) + prefix = f'val/{batch_idx}' + logger = self.logger.experiment + depth_vis = depth_output.get_visualization_img(np.copy(left_image_np)) + llog[f'{prefix}/disparity'] = wandb.Image(depth_vis, caption=prefix) + small_depth_vis = small_depth_output.get_visualization_img(np.copy(left_image_np)) + llog[f'{prefix}/small_disparity'] = wandb.Image(small_depth_vis, caption=prefix) + self.eval_metrics.draw_detections( + pose_outputs, box_outputs, seg_output, keypoint_outputs, left_image_np, llog, prefix + ) + + logger.log(llog) + return log + + def validation_epoch_end(self, outputs): + self.trainer.checkpoint_callback.save_best_only = False + log = {} + self.eval_metrics.process_all_dataset(log) + self.eval_metrics.reset() + return {'log': log} + + @pl.data_loader + def train_dataloader(self): + return common.get_loader( + self.hparams, + "train", + preprocess_func=self.preprocess_func, + datapoint_dataset=self.train_dataset + ) + + @pl.data_loader + def val_dataloader(self): + return common.get_loader(self.hparams, "val", preprocess_func=self.preprocess_func) + + def configure_optimizers(self): + optimizer = torch.optim.Adam(self.parameters(), lr=self.hparams.optim_learning_rate) + lr_lambda = lambda_learning_rate_poly(self.epochs, self.hparams.optim_poly_exp) + if self.hparams.optim_warmup_epochs is not None and self.hparams.optim_warmup_epochs > 0: + lr_lambda = lambda_warmup(self.hparams.optim_warmup_epochs, 0.2, lr_lambda) + scheduler = torch.optim.lr_scheduler.LambdaLR(optimizer, lr_lambda=lr_lambda) + return [optimizer], [scheduler] diff --git a/simnet/lib/net/post_processing/depth_outputs.py b/simnet/lib/net/post_processing/depth_outputs.py new file mode 100644 index 0000000..190ab64 --- /dev/null +++ b/simnet/lib/net/post_processing/depth_outputs.py @@ -0,0 +1,97 @@ +import numpy as np +import torch +import torch.nn as nn +from matplotlib import cm + +from torch.nn import functional as F +from simnet.lib.net import losses + +_mse_loss = losses.MSELoss() +_MAX_DISP = 128 + + +class DepthOutput: + + def __init__(self, depth_pred, loss_multiplier): + self.depth_pred = depth_pred + self.is_numpy = False + self.loss = nn.SmoothL1Loss() + #self.loss = nn.MSELoss() + self.loss_multiplier = loss_multiplier + + # Converters for torch to numpy + def convert_to_numpy_from_torch(self): + self.depth_pred = np.ascontiguousarray(self.depth_pred.cpu().numpy()) + self.is_numpy = True + + def convert_to_torch_from_numpy(self): + self.depth_pred[self.depth_pred > _MAX_DISP] = _MAX_DISP - 1 + self.depth_pred = torch.from_numpy(np.ascontiguousarray(self.depth_pred)).float() + self.is_numpy = False + + def get_visualization_img(self, left_img_np, corner_scale=1, raw_disp=True): + if not self.is_numpy: + self.convert_to_numpy_from_torch() + disp = self.depth_pred[0] + + if raw_disp: + return disp_map_visualize(disp) + disp_scaled = disp[::corner_scale, ::corner_scale] + left_img_np[:disp_scaled.shape[0], -disp_scaled.shape[1]:] = disp_map_visualize(disp_scaled) + return left_img_np + + def compute_loss(self, depth_targets, log, name): + if self.is_numpy: + raise ValueError("Output is not in torch mode") + depth_target_stacked = [] + for depth_target in depth_targets: + depth_target_stacked.append(depth_target.depth_pred) + depth_target_batch = torch.stack(depth_target_stacked) + depth_target_batch = depth_target_batch.to(torch.device('cuda:0')) + scale_factor = self.depth_pred.shape[2] / depth_target_batch.shape[2] + if scale_factor != 1.0: + depth_target_batch = F.interpolate( + depth_target_batch[:, None, :, :], scale_factor=scale_factor + )[:, 0, :, :] + # scale down disparity by same factor as spatial resize + depth_target_batch = depth_target_batch * scale_factor + depth_loss = self.loss(self.depth_pred, depth_target_batch) / scale_factor + log[name] = depth_loss + return self.loss_multiplier * depth_loss + + +def turbo_vis(heatmap, normalize=False, uint8_output=False): + assert len(heatmap.shape) == 2 + if normalize: + heatmap = heatmap.astype(np.float32) + heatmap -= np.min(heatmap) + heatmap /= np.max(heatmap) + assert heatmap.dtype != np.uint8 + + x = heatmap + x = x.clip(0, 1) + a = (x * 255).astype(int) + b = (a + 1).clip(max=255) + f = x * 255.0 - a + turbo_map = np.array(cm.turbo.colors)[::-1] + pseudo_color = (turbo_map[a] + (turbo_map[b] - turbo_map[a]) * f[..., np.newaxis]) + pseudo_color[heatmap < 0.0] = 0.0 + pseudo_color[heatmap > 1.0] = 1.0 + if uint8_output: + pseudo_color = (pseudo_color * 255).astype(np.uint8) + return pseudo_color + + +def disp_map_visualize(x, max_disp=_MAX_DISP): + assert len(x.shape) == 2 + x = x.astype(np.float64) + valid = ((x < max_disp) & np.isfinite(x)) + if valid.sum() == 0: + return np.zeros_like(x).astype(np.uint8) + x -= np.min(x[valid]) + x /= np.max(x[valid]) + x = 1. - x + x[~valid] = 0. + x = turbo_vis(x) + x = (x * 255).astype(np.uint8) + return x[:, :, ::-1] diff --git a/simnet/lib/net/post_processing/epnp.py b/simnet/lib/net/post_processing/epnp.py new file mode 100644 index 0000000..d861884 --- /dev/null +++ b/simnet/lib/net/post_processing/epnp.py @@ -0,0 +1,263 @@ +import numpy as np + +from simnet.lib import camera +# Definition of unit cube centered at the orign +x_width = 1.0 +y_depth = 1.0 +z_height = 1.0 + +# Assigned based on ordering of vertices in mesh from unit cube primitive. +# Note this is the internal trimesh ordering not what is specified in primitives +_WORLD_T_POINTS = np.array([ + [0, 0, 0], #0 + [0, 0, z_height], #1 + [0, y_depth, 0], #2 + [0, y_depth, z_height], #3 + [x_width, 0, 0], #4 + [x_width, 0, z_height], #5 + [x_width, y_depth, 0], #6 + [x_width, y_depth, z_height], #7 +]) - 0.5 + + +def get_2d_bbox_of_9D_box(camera_T_object, scale_matrix, camera_model): + unit_box_homopoints = camera.convert_points_to_homopoints(_WORLD_T_POINTS.T) + morphed_homopoints = camera_T_object @ (scale_matrix @ unit_box_homopoints) + morphed_pixels = camera.convert_homopixels_to_pixels(camera_model.K_matrix @ morphed_homopoints).T + bbox = [ + np.array([np.min(morphed_pixels[:, 0]), + np.min(morphed_pixels[:, 1])]), + np.array([np.max(morphed_pixels[:, 0]), + np.max(morphed_pixels[:, 1])]) + ] + return bbox + + +def project_pose_onto_image(pose, camera_model): + unit_box_homopoints = camera.convert_points_to_homopoints(_WORLD_T_POINTS.T) + morphed_homopoints = pose.camera_T_object @ (pose.scale_matrix @ unit_box_homopoints) + morphed_pixels = camera.convert_homopixels_to_pixels(camera_model.project(morphed_homopoints)).T + morphed_pixels = morphed_pixels[:, ::-1] + return morphed_pixels + + +def get_2d_bbox_of_projection(bbox_ext): + bbox = [ + np.array([np.min(bbox_ext[:, 0]), np.min(bbox_ext[:, 1])]), + np.array([np.max(bbox_ext[:, 0]), np.max(bbox_ext[:, 1])]) + ] + return bbox + + +def define_control_points(): + return np.array([[1, 0, 0], [0, 1, 0], [0, 0, 1], [0, 0, 0]]) + + +def compute_alphas(Xw, Cw): + X = np.concatenate((Xw, np.array([np.ones((8))])), axis=0) + C = Cw.T + C = np.concatenate((C, np.array([np.ones((4))])), axis=0) + Alpha = np.matmul(np.linalg.inv(C), X) + return Alpha.T + + +def construct_M_matrix(bbox_pixels, alphas, K_matrix): + M = np.zeros([16, 12]) + f_x = K_matrix[0, 0] + f_y = K_matrix[1, 1] + c_x = K_matrix[0, 2] + c_y = K_matrix[1, 2] + for ii in range(8): + u = bbox_pixels[0, ii] + v = bbox_pixels[1, ii] + for jj in range(4): + alpha = alphas[ii, jj] + M[ii * 2, jj * 3] = f_x * alpha + M[ii * 2, jj * 3 + 2] = (c_x - u) * alpha + M[ii * 2 + 1, jj * 3 + 1] = f_y * alpha + M[ii * 2 + 1, jj * 3 + 2] = (c_y - v) * alpha + return M + + +def convert_control_to_box_vertices(control_points, alphas): + bbox_vertices = np.zeros([8, 3]) + for i in range(8): + for j in range(4): + alpha = alphas[i, j] + bbox_vertices[i] = bbox_vertices[i] + alpha * control_points[j] + + return bbox_vertices + + +def solve_for_control_points(M): + e_vals, e_vecs = np.linalg.eig(M.T @ M) + control_points = e_vecs[:, np.argmin(e_vals)] + control_points = control_points.reshape([4, 3]) + return control_points + + +def compute_homopoints_from_control_points(camera_control_points, alphas, K_matrix): + camera_points = convert_control_to_box_vertices(camera_control_points, alphas) + camera_homopoints = camera.convert_points_to_homopoints(camera_points.T) + return camera_homopoints + unit_box_homopoints = camera.convert_points_to_homopoints(_WORLD_T_POINTS.T) + + +def optimize_for_9D(bbox_pixels, camera_model, solve_for_transforms=False): + K_matrix = camera_model.K_matrix + Cw = define_control_points() + Xw = _WORLD_T_POINTS + alphas = compute_alphas(Xw.T, Cw) + M = construct_M_matrix(bbox_pixels, alphas, np.copy(K_matrix)) + camera_control_points = solve_for_control_points(M) + camera_points = convert_control_to_box_vertices(camera_control_points, alphas) + camera_homopoints = camera.convert_points_to_homopoints(camera_points.T) + if solve_for_transforms: + unit_box_homopoints = camera.convert_points_to_homopoints(_WORLD_T_POINTS.T) + # Test both the negative and positive solutions of the control points and pick the best one. Taken from the Google MediaPipe Code base. + error_one, camera_T_object_one, scale_matrix_one = estimateSimilarityUmeyama( + unit_box_homopoints, camera_homopoints + ) + camera_homopoints = compute_homopoints_from_control_points( + -1 * camera_control_points, alphas, K_matrix + ) + error_two, camera_T_object_two, scale_matrix_two = estimateSimilarityUmeyama( + unit_box_homopoints, camera_homopoints + ) + if error_one < error_two: + camera_T_object = camera_T_object_one + scale_matrix = scale_matrix_one + else: + camera_T_object = camera_T_object_two + scale_matrix = scale_matrix_two + + # Compute Fit to original pixles: + morphed_points = camera_T_object @ (scale_matrix @ unit_box_homopoints) + morphed_pixels = points_to_camera(morphed_points, K_matrix) + confidence = np.linalg.norm(bbox_pixels - morphed_pixels) + return confidence, camera_T_object, scale_matrix + camera_homopixels = K_matrix @ camera_homopoints + return camera.convert_homopixels_to_pixels(camera_homopixels).T + + +def estimateSimilarityUmeyama(source_hom, TargetHom): + # Copy of original paper is at: http://web.stanford.edu/class/cs273/refs/umeyama.pdf + assert source_hom.shape[0] == 4 + assert TargetHom.shape[0] == 4 + SourceCentroid = np.mean(source_hom[:3, :], axis=1) + TargetCentroid = np.mean(TargetHom[:3, :], axis=1) + nPoints = source_hom.shape[1] + + CenteredSource = source_hom[:3, :] - np.tile(SourceCentroid, (nPoints, 1)).transpose() + CenteredTarget = TargetHom[:3, :] - np.tile(TargetCentroid, (nPoints, 1)).transpose() + + CovMatrix = np.matmul(CenteredTarget, np.transpose(CenteredSource)) / nPoints + + if np.isnan(CovMatrix).any(): + print('nPoints:', nPoints) + print('source_hom', source_hom.shape) + print('TargetHom', TargetHom.shape) + raise RuntimeError('There are NANs in the input.') + + U, D, Vh = np.linalg.svd(CovMatrix, full_matrices=True) + d = (np.linalg.det(U) * np.linalg.det(Vh)) < 0.0 + if d: + D[-1] = -D[-1] + U[:, -1] = -U[:, -1] + + Rotation = np.matmul(U, Vh) + var_source = np.std(CenteredSource[:3, :], axis=1) + var_target_aligned = np.std(np.linalg.inv(Rotation) @ CenteredTarget[:3, :], axis=1) + ScaleMatrix = np.diag(var_target_aligned / var_source) + + Translation = TargetHom[:3, :].mean(axis=1) - source_hom[:3, :].mean(axis=1).dot( + ScaleMatrix @ Rotation.T + ) + + source_T_target = np.identity(4) + source_T_target[:3, :3] = Rotation + source_T_target[:3, 3] = Translation + scale_matrix = np.eye(4) + scale_matrix[0:3, 0:3] = ScaleMatrix + # Measure error fit + morphed_points = source_T_target @ (scale_matrix @ source_hom) + error = np.linalg.norm(morphed_points - TargetHom) + return error, source_T_target, scale_matrix + + +def points_to_camera(world_T_homopoints, K_matrix): + homopixels = K_matrix @ world_T_homopoints + return camera.convert_homopixels_to_pixels(homopixels) + + +def find_absolute_scale(new_z, camera_T_object, object_scale, debug=True): + old_z = camera_T_object[2, 3] + abs_camera_T_object = np.copy(camera_T_object) + abs_camera_T_object[0:3, 3] = (new_z / old_z) * abs_camera_T_object[0:3, 3] + abs_object_scale = np.eye(4) + abs_object_scale[0:3, 0:3] = (new_z / old_z) * object_scale[0:3, 0:3] + + return abs_camera_T_object, abs_object_scale + + +def test_pose_solver(): + world_t_points = np.copy(_WORLD_T_POINTS) + world_t_points = camera.convert_points_to_homopoints(world_t_points.T) + R_t = np.eye(4) + R_t[0:3, 0:3] = euler_to_rotation_matrix([1.7, 3.8, 5.2]) + R_t[2, 3] = -0.01 + R_t[1, 3] = -0.00001 + S = np.eye(4) + S[0, 0] = 0.5 + S[1, 1] = 0.05 + S[2, 2] = 0.5 + target_t_points = R_t @ (S @ world_t_points) + target_t_points = np.array([[ + 0.61674494, 0.61674494, 0.61674494, 0.61674494, 1.93547767, 1.93547767, 1.93547767, 1.93547767 + ], [ + 0.40753347, 0.40753347, 0.42753347, 0.42753347, 0.40753347, 0.40753347, 0.42753347, 0.42753347 + ], [ + 2.56231278, 3.84837313, 2.56231278, 3.84837313, 2.56231278, 3.84837313, 2.56231278, 3.84837313 + ], [1., 1., 1., 1., 1., 1., 1., 1.]]) + world_T_camera = np.array([[0.99376416, -0.05495078, 0.0970217, 1.43237753], + [0.00736171, 0.90056662, 0.43465568, 0.72350959], + [-0.11125918, -0.43123099, 0.89535536, 3.94788388], [0., 0., 0., 1.]]) + target_t_points = np.linalg.inv(world_T_camera) @ target_t_points + pixels_target = camera.convert_homopixels_to_pixels(camera.FMKCamera().project(target_t_points)) + pixels_target_gt = np.array([[198.60924037, 181.08880028], [-384.55689665, 452.51438988], + [197.90794419, 176.84519486], [-405.05431808, 439.75925094], + [451.6781963, 190.51153042], [1088.99607868, 718.53052576], + [452.57505678, 185.91876331], [1128.80169693, 709.80385466]]) + #target_t_points = camera.FMKCamera().RT_matrix @ target_t_points + #pixels_target = points_to_camera(target_t_points) + #print("Custom projection ",np.round(pixels_target,3)) + _, camera_T_object, scale_matrix = optimize_for_9D(pixels_target, solve_for_transforms=True) + + camera_T_object[0:3, 0:3] = np.eye(3) + #camera_T_object[0:2,3] = 0.0 + #camera_T_object[0,3] = 0.1 + print(camera_T_object) + scale_matrix = np.eye(4) + abs_camera_T_object = np.copy(camera_T_object) + abs_camera_T_object[2, 3] = 1.0 + find_absolute_scale(1.0, camera_T_object, scale_matrix) + assert False + #camera_T_object,scale_matrix = estimateSimilarityUmeyama(world_t_points,target_t_points) + print("Found matrices") + print(np.round(camera_T_object, 3)) + print(np.round(scale_matrix, 3)) + print("Gt matrices") + print(np.round(S, 3)) + print(np.round(R_t, 3)) + print("Pixel Projections") + pixels_found = optimize_for_9D(pixels_target) + print(np.round(pixels_target.T, 3)) + print(np.round(pixels_found, 3)) + print("Checking transform projections") + target_t_points = camera_T_object @ (scale_matrix @ world_t_points) + camera_homopixels = camera.FMKCamera().K_matrix @ target_t_points + print(np.round(camera.convert_homopixels_to_pixels(camera_homopixels).T, 3)) + + +if __name__ == "__main__": + test_pose_solver() diff --git a/simnet/lib/net/post_processing/eval3d.py b/simnet/lib/net/post_processing/eval3d.py new file mode 100644 index 0000000..f0463f0 --- /dev/null +++ b/simnet/lib/net/post_processing/eval3d.py @@ -0,0 +1,652 @@ +import copy +import dataclasses + +import numpy as np +import IPython + +from simnet.lib.net.post_processing import epnp, nms +from simnet.lib import occlusions + +EVAL_IOUS = [0.25] + +_SIZES = ['small', 'large'] + +################################ +# Precision/recall stuff + + +@dataclasses.dataclass +class Detection: + camera_T_object: np.ndarray + scale_matrix: np.ndarray + class_label: str = None + size_label: str = '' + scene_name: str = '' + ignore: bool = False + bbox: list = None + score: float = 1.0 + success: int = 0 + + +def extract_objects_from_detections(detections_gt, detections): + table_detection = detections_gt[0] + detections_gt = detections_gt[1:] + detections = prune_detections_2d_not_one_table(table_detection, detections) + return table_detection, detections_gt, detections + + +def is_point_in_detection_box(point, bbox): + if bbox[0][0] > point[0]: + return False + if bbox[0][1] > point[1]: + return False + if bbox[1][0] < point[0]: + return False + if bbox[1][1] < point[1]: + return False + return True + + +def prune_detections_2d_not_one_table(table_detection, detections): + pruned_detections = [] + for detection in detections: + if is_point_in_detection_box(detection.bbox[0], table_detection.bbox): + pruned_detections.append(detection) + elif is_point_in_detection_box(detection.bbox[1], table_detection.bbox): + pruned_detections.append(detection) + else: + continue + return pruned_detections + + +def get_size_predictions(pred_matches, true_matches, pred_scores, size_labels, size_name): + + pruned_true_matches = [] + pruned_pred_matches = [] + pruned_pred_scores = [] + + # Prune ground truth to only contain easy samples. + for ii in range(true_matches.shape[1]): + if size_labels[ii] != size_name: + continue + pruned_true_matches.append(true_matches[:, ii]) + # Prune any predictions that intersect with an ignore class. + for ii in range(pred_matches.shape[1]): + gt_match = pred_matches[0, ii] + # Check if there was a match at all + if gt_match != -1: + # Check if it fired on an unkown class. + if size_labels[int(gt_match)] != size_name: + continue + # Remove all non-object predictions + if gt_match == -1: + continue + pruned_pred_matches.append(pred_matches[:, ii]) + pruned_pred_scores.append(pred_scores[ii]) + + if len(pruned_true_matches) == 0: + pruned_true_matches = np.zeros([1, 0]) + else: + pruned_true_matches = np.array(pruned_true_matches).T + if len(pruned_pred_matches) == 0: + pruned_pred_matches = np.zeros([1, 0]) + else: + pruned_pred_matches = np.array(pruned_pred_matches).T + pred_scores = np.array(pruned_pred_scores).T + return pruned_true_matches, pruned_pred_matches, pruned_pred_scores + + +def remove_ignore_class(pred_matches, true_matches, pred_scores, ignore_labels): + + pruned_true_matches = [] + pruned_pred_matches = [] + pruned_pred_scores = [] + pruned_detections_indices = [] + + # Prune ground truth for ignore classes. + for ii in range(true_matches.shape[1]): + if ignore_labels[ii]: + continue + pruned_true_matches.append(true_matches[:, ii]) + # Prune any predictions that intersect with an ignore class. + for ii in range(pred_matches.shape[1]): + gt_match = pred_matches[0, ii] + # Check if there was a match at all + if gt_match != -1: + # Check if it fired on an unkown class. + if ignore_labels[int(gt_match)]: + continue + pruned_pred_matches.append(pred_matches[:, ii]) + pruned_pred_scores.append(pred_scores[ii]) + pruned_detections_indices.append(ii) + + if len(pruned_true_matches) == 0: + pruned_true_matches = np.zeros([1, 0]) + else: + pruned_true_matches = np.array(pruned_true_matches).T + if len(pruned_pred_matches) == 0: + pruned_pred_matches = np.zeros([1, 0]) + else: + pruned_pred_matches = np.array(pruned_pred_matches).T + pred_scores = np.array(pruned_pred_scores).T + return pruned_true_matches, pruned_pred_matches, pruned_pred_scores + + +def assign_known_depth(detections, gt_detections): + new_detections = [] + for detection in detections: + best_overlap_score = 0.0 + best_gt_match = None + for gt_detection in gt_detections: + overlap_score = nms.get_2d_one_way_iou(gt_detection, detection) + if overlap_score > best_overlap_score: + best_gt_match = gt_detection + best_overlap_score = overlap_score + if best_gt_match is not None: + new_z = best_gt_match.camera_T_object[2, 3] + camera_T_object, scale_matrix = epnp.find_absolute_scale( + new_z, detection.camera_T_object, detection.scale_matrix + ) + detection.camera_T_object = camera_T_object + detection.scale_matrix = scale_matrix + new_detections.append(detection) + + return new_detections + + +def assign_rotation_value(detection, gt_detection): + detection.camera_T_object[0:3, 0:3] = np.eye(3) + gt_scale_matrix = gt_detection.scale_matrix + scale_matrix = detection.scale_matrix + new_scale_matrix = np.eye(4) + indices = [0, 1, 2] + for ii in range(3): + scale_value = scale_matrix[ii, ii] + best_scale_index = 0 + best_match = np.inf + for jj in indices: + if np.abs(scale_value - gt_scale_matrix[jj, jj]) < best_match: + best_scale_index = jj + best_match = np.abs(scale_value - gt_scale_matrix[jj, jj]) + new_scale_matrix[best_scale_index, best_scale_index] = scale_value + indices.remove(best_scale_index) + detection.scale_matrix = new_scale_matrix + + +def assign_known_rotation(detections, gt_detections): + new_detections = [] + #Remove rotation from ground truth. + for ii in range(len(gt_detections)): + gt_detections[ii].camera_T_object[0:3, 0:3] = np.eye(3) + for detection in detections: + best_overlap_score = 0.0 + best_gt_match = None + for gt_detection in gt_detections: + overlap_score = nms.get_2d_one_way_iou(gt_detection, detection) + if overlap_score > best_overlap_score: + best_gt_match = gt_detection + best_overlap_score = overlap_score + if best_gt_match is not None: + new_z = best_gt_match.camera_T_object[2, 3] + assign_rotation_value(detection, best_gt_match) + new_detections.append(detection) + + return new_detections, gt_detections + + +def assign_size_labels(gt_detections, size_threshold=0.08): + for ii in range(len(gt_detections)): + scale_matrix = gt_detections[ii].scale_matrix + if np.prod(np.diag(scale_matrix[0:3, 0:3])) < size_threshold**3: + gt_detections[ii].size_label = 'small' + else: + gt_detections[ii].size_label = 'large' + + +def measure_3d_iou(detections, gt_detections, known_depth=False, known_rotation=False): + gt_RTs = [] + gt_scales = [] + pred_RTs = [] + pred_scales = [] + pred_scores = [] + size_labels = [] + ignore_labels = [] + if known_depth: + detections = assign_known_depth(detections, gt_detections) + if known_rotation: + detections, gt_detections = assign_known_rotation(detections, gt_detections) + for detection in detections: + pred_RTs.append(detection.camera_T_object) + pred_scales.append(np.diag(detection.scale_matrix[0:3, 0:3])) + pred_scores.append(detection.score) + + for detection in gt_detections: + gt_RTs.append(detection.camera_T_object) + gt_scales.append(np.diag(detection.scale_matrix[0:3, 0:3])) + size_labels.append(detection.size_label) + ignore_labels.append(detection.ignore) + + true_matches, pred_matches, _, indices = compute_3d_matches( + 'single_class', + np.array(gt_RTs), + np.array(gt_scales), + np.array(pred_scores), + np.array(pred_RTs), + np.array(pred_scales), + EVAL_IOUS, + known_depth=known_depth + ) + # Resort pred scores and class labels + sorted_pred_scores = [] + sorted_class_labels = [] + sorted_detections = [] + for ii in range(pred_matches.shape[1]): + detections[indices[ii]].success = int(pred_matches[0, ii] > -1) + sorted_detections.append(detections[ii]) + sorted_pred_scores.append(pred_scores[ii]) + for detection in gt_detections: + detection.success = -1 + if detection.ignore: + detection.success = -2 + #sorted_detections.append(detection) + # Apply ignore predictions. + true_matches, pred_matches, sorted_pred_scores = remove_ignore_class( + copy.deepcopy(pred_matches), copy.deepcopy(true_matches), copy.deepcopy(sorted_pred_scores), + ignore_labels + ) + return true_matches, pred_matches, sorted_pred_scores, size_labels, ignore_labels, sorted_detections + + +class Eval3d: + + def __init__(self): + self.n = 0 + self.metrics_by_size = {cn: EvalMetrics() for cn in _SIZES} + self.all_3d_metrics_by_scene = {} + self.all_3d_known_depth_metrics_by_scene = {} + self.all_3d_known_rotation_metrics_by_scene = {} + + def process_sample(self, detections, gt_detections, scene_name): + # Mark occlusions and size labels. + occlusions.mark_occlusions_in_detections(gt_detections) + assign_size_labels(gt_detections) + + if scene_name not in self.all_3d_metrics_by_scene: + self.all_3d_metrics_by_scene[scene_name] = EvalMetrics() + self.all_3d_known_depth_metrics_by_scene[scene_name] = EvalMetrics() + self.all_3d_known_rotation_metrics_by_scene[scene_name] = EvalMetrics() + + # Process True Positive Rate per object size + true_matches, pred_matches, pred_scores, size_labels, _, _ = measure_3d_iou( + copy.deepcopy(detections), copy.deepcopy(gt_detections), known_depth=True + ) + for size_name in _SIZES: + true_matches_per_class, pred_matches_per_class, pred_scores_per_class = get_size_predictions( + copy.deepcopy(pred_matches), copy.deepcopy(true_matches), copy.deepcopy(pred_scores), + copy.deepcopy(size_labels), size_name + ) + self.metrics_by_size[size_name].process_sample( + true_matches=true_matches_per_class, + pred_matches=pred_matches_per_class, + pred_scores=pred_scores_per_class + ) + + # Process 3D mAp for all classes with known depth. + true_matches, pred_matches, pred_scores, class_labels, ignore_labels, sorted_detections = measure_3d_iou( + copy.deepcopy(detections), copy.deepcopy(gt_detections), known_depth=True + ) + self.all_3d_known_depth_metrics_by_scene[scene_name].process_sample( + true_matches=true_matches, pred_matches=pred_matches, pred_scores=pred_scores + ) + + # Process 3D mAp for all classes. + true_matches, pred_matches, pred_scores, class_labels, _, _ = measure_3d_iou( + copy.deepcopy(detections), copy.deepcopy(gt_detections) + ) + self.all_3d_metrics_by_scene[scene_name].process_sample( + true_matches=true_matches, pred_matches=pred_matches, pred_scores=pred_scores + ) + + # Process 3D mAp for all classes with known depth and rotatoins. + true_matches, pred_matches, pred_scores, class_labels, ignore_labels, _ = measure_3d_iou( + copy.deepcopy(detections), + copy.deepcopy(gt_detections), + known_depth=True, + known_rotation=True + ) + self.all_3d_known_rotation_metrics_by_scene[scene_name].process_sample( + true_matches=true_matches, pred_matches=pred_matches, pred_scores=pred_scores + ) + + return sorted_detections + + def process_dataset(self, results_path): + + def _print(name, x, iou): + if final: + prefix = '[step {self.n: 6d}] (FINAL)' + else: + prefix = '(incomplete)' + if not final and name != 'MEAN': + return + out = f'{prefix} AP@{iou:.02f}[{name}] = {x}' + print(out) + if results_fh is not None: + results_fh.write(out + '\n') + + for idx, iou in enumerate(EVAL_IOUS): + # Plot 3d metrics + ap_values = [] + for size_name in _SIZES: + ap_values.append(self.metrics_by_size[size_name].process_dataset()[idx]) + # Draw the bar plot. + graph_name = f'3D_ATP@{iou:.02f}' + plotter.draw_standard_bar_plot(_SIZES, ap_values, results_path, y_label=graph_name) + + # Plot mAP per scene + ap_values = [] + scene_names = [] + for scene_name in self.all_3d_known_depth_metrics_by_scene: + ap_values.append( + self.all_3d_known_depth_metrics_by_scene[scene_name].process_dataset()[idx] + ) + scene_names.append(scene_name) + # Draw the bar plot. + graph_name = f'3D_mAP@{iou:.02f}' + plotter.draw_standard_bar_plot(scene_names, ap_values, results_path, y_label=graph_name) + + # Plot AP curve for known depth per scene + for scene_name in self.all_3d_known_depth_metrics_by_scene: + precisions, recalls = self.all_3d_known_depth_metrics_by_scene[scene_name].get_pr_curve() + plotter.draw_precision_recall_curve( + precisions, recalls, results_path, name=scene_name + '_pr_curve' + ) + + def process_all_3D_dataset(self): + ap_values = [] + for scene_name in self.all_3d_metrics_by_scene: + ap_values.append(self.all_3d_metrics_by_scene[scene_name].process_dataset()[0]) + return np.average(ap_values) + + +class EvalMetrics: + + def __init__(self): + self.true_matches = [] + self.pred_matches = [] + self.pred_scores = [] + + def process_sample(self, true_matches, pred_matches, pred_scores): + self.true_matches.append(true_matches) + self.pred_matches.append(pred_matches) + self.pred_scores.append(pred_scores) + + def process_dataset(self): + true_matches = np.copy(np.concatenate(self.true_matches, axis=1)) + pred_matches = np.copy(np.concatenate(self.pred_matches, axis=1)) + pred_scores = np.copy(np.concatenate(self.pred_scores, axis=0)) + assert true_matches.shape[0] == pred_matches.shape[0] + num_ious = true_matches.shape[0] + ap_per_iou = [] + for i in range(num_ious): + ap_per_iou.append( + compute_ap_from_matches_scores(pred_matches[i, :], pred_scores, true_matches[i, :]) + ) + return ap_per_iou + + def get_pr_curve(self): + true_matches = np.concatenate(self.true_matches, axis=1) + pred_matches = np.concatenate(self.pred_matches, axis=1) + pred_scores = np.concatenate(self.pred_scores, axis=0) + assert true_matches.shape[0] == pred_matches.shape[0] + num_ious = true_matches.shape[0] + ap_per_iou = [] + return compute_pr_curve_from_matches_scores(pred_matches[0, :], pred_scores, true_matches[0, :]) + + +def compute_3d_iou_new(RT_1, RT_2, scales_1, scales_2, debug=False, known_depth=True): + '''Computes IoU overlaps between two 3d bboxes. + bbox_3d_1, bbox_3d_1: [3, 8] + ''' + + # flatten masks + def asymmetric_3d_iou(RT_1, RT_2, scales_1, scales_2): + assert RT_1.shape == (4, 4) + assert RT_2.shape == (4, 4) + assert scales_1.shape == (3,) + assert scales_2.shape == (3,) + noc_cube_1 = get_3d_bbox(scales_1, 0) + bbox_3d_1 = transform_coordinates_3d(noc_cube_1, RT_1) + assert bbox_3d_1.shape == (3, 8) + + noc_cube_2 = get_3d_bbox(scales_2, 0) + bbox_3d_2 = transform_coordinates_3d(noc_cube_2, RT_2) + assert bbox_3d_2.shape == (3, 8) + + bbox_1_max = np.amax(bbox_3d_1, axis=1) + bbox_1_min = np.amin(bbox_3d_1, axis=1) + bbox_2_max = np.amax(bbox_3d_2, axis=1) + bbox_2_min = np.amin(bbox_3d_2, axis=1) + + assert bbox_1_min.shape == (3,) + assert bbox_1_max.shape == (3,) + assert bbox_2_min.shape == (3,) + assert bbox_2_max.shape == (3,) + + overlap_min = np.maximum(bbox_1_min, bbox_2_min) + overlap_max = np.minimum(bbox_1_max, bbox_2_max) + + # intersections and union + if np.amin(overlap_max - overlap_min) < 0: + intersections = 0 + else: + intersections = np.prod(overlap_max - overlap_min) + union = np.prod(bbox_1_max - bbox_1_min) + np.prod(bbox_2_max - bbox_2_min) - intersections + overlaps = intersections / union + + if False: + print('bbox_3d_1:', bbox_3d_1) + print('bbox_3d_2:', bbox_3d_2) + print('bbox_1_min:', bbox_1_min) + print('bbox_1_max:', bbox_1_max) + print('bbox_2_min:', bbox_2_min) + print('bbox_2_max:', bbox_2_max) + print('overlap_min', overlap_min) + print('overlap_max', overlap_max) + print('intersections:', intersections) + print('union:', union) + print('overlaps:', overlaps) + + assert not np.isnan(overlaps) + return overlaps + + if RT_1 is None or RT_2 is None: + return -1 + + max_iou = asymmetric_3d_iou(RT_1, RT_2, scales_1, scales_2) + + return max_iou + + +def get_3d_bbox(scale, shift=0): + """ + Input: + scale: [3] or scalar + shift: [3] or scalar + Return + bbox_3d: [3, N] + + """ + bbox_3d = np.array( + [[scale[0] / 2, +scale[1] / 2, scale[2] / 2], [scale[0] / 2, +scale[1] / 2, -scale[2] / 2], + [-scale[0] / 2, +scale[1] / 2, scale[2] / 2], [-scale[0] / 2, +scale[1] / 2, -scale[2] / 2], + [+scale[0] / 2, -scale[1] / 2, scale[2] / 2], [+scale[0] / 2, -scale[1] / 2, -scale[2] / 2], + [-scale[0] / 2, -scale[1] / 2, scale[2] / 2], [-scale[0] / 2, -scale[1] / 2, -scale[2] / 2]] + ) + shift + + bbox_3d = bbox_3d.transpose() + return bbox_3d + + +def transform_coordinates_3d(coordinates, RT): + """ + Input: + coordinates: [3, N] + RT: [4, 4] + Return + new_coordinates: [3, N] + + """ + assert RT.shape == (4, 4) + assert len(coordinates.shape) == 2 + assert coordinates.shape[0] == 3 + coordinates = np.vstack([coordinates, np.ones((1, coordinates.shape[1]), dtype=np.float32)]) + new_coordinates = RT @ coordinates + new_coordinates = new_coordinates[:3, :] / new_coordinates[3, :] + assert new_coordinates.shape[0] == 3 + return new_coordinates + + +def resolve_z_ambiguity(RT, scale, gt_RT): + new_z = gt_RT[2, 3] + object_scale = np.eye(4) + object_scale[0:3, 0:3] = np.diag(scale) + scaled_RT, scaled_object_scale = epnp.find_absolute_scale(new_z, RT, object_scale) + return scaled_RT, np.diag(scaled_object_scale[0:3, 0:3]) + + +def compute_3d_matches( + class_name, + gt_RTs, + gt_scales, + pred_scores, + pred_RTs, + pred_scales, + iou_3d_thresholds, + score_threshold=0, + known_depth=False, + debug=False +): + """Finds matches between prediction and ground truth instances. + Returns: + gt_matches: 2-D array. For each GT box it has the index of the matched + predicted box. + pred_matches: 2-D array. For each predicted box, it has the index of + the matched ground truth box. + overlaps: [pred_boxes, gt_boxes] IoU overlaps. + """ + #assert gt_scales.shape[1] == 3 + #assert pred_scales.shape[1] == 3 + + num_pred = pred_scales.shape[0] + num_gt = gt_scales.shape[0] + indices = np.zeros(0) + + if num_pred: + # Sort predictions by score from high to low + indices = np.argsort(pred_scores)[::-1] + + pred_scores = pred_scores[indices].copy() + pred_scales = pred_scales[indices, :].copy() + pred_RTs = pred_RTs[indices, :, :].copy() + + # Compute IoU overlaps [pred_bboxs gt_bboxs] + overlaps = np.zeros((num_pred, num_gt), dtype=np.float32) + for i in range(num_pred): + for j in range(num_gt): + overlaps[i, j] = compute_3d_iou_new( + pred_RTs[i, :, :], gt_RTs[j, :, :], pred_scales[i, :], gt_scales[j, :], class_name + ) + # Loop through predictions and find matching ground truth boxes + num_iou_3d_thres = len(iou_3d_thresholds) + pred_matches = -1 * np.ones([num_iou_3d_thres, num_pred]) + gt_matches = -1 * np.ones([num_iou_3d_thres, num_gt]) + + for s, iou_thres in enumerate(iou_3d_thresholds): + for i in range(num_pred): + # Find best matching ground truth box + # 1. Sort matches by score + sorted_ixs = np.argsort(overlaps[i])[::-1] + # 2. Remove low scores + low_score_idx = np.where(overlaps[i, sorted_ixs] < score_threshold)[0] + if low_score_idx.size > 0: + sorted_ixs = sorted_ixs[:low_score_idx[0]] + # 3. Find the match + for j in sorted_ixs: + # If ground truth box is already matched, go to next one + #print('gt_match: ', gt_match[j]) + if gt_matches[s, j] > -1: + continue + # If we reach IoU smaller than the threshold, end the loop + iou = overlaps[i, j] + #print('iou: ', iou) + if iou < iou_thres: + break + + if iou > iou_thres: + gt_matches[s, j] = i + pred_matches[s, i] = j + break + + if debug: + IPython.embed() + + return gt_matches, pred_matches, overlaps, indices + + +def compute_ap_from_matches_scores(pred_match, pred_scores, gt_match, debug=False): + # sort the scores from high to low + # print(pred_match.shape, pred_scores.shape) + assert len(pred_match.shape) == 1 + assert len(gt_match.shape) == 1 + assert pred_match.shape[0] == pred_scores.shape[0] + + if gt_match.shape[0] == 0: + return 0. + + score_indices = np.argsort(pred_scores)[::-1] + pred_scores = pred_scores[score_indices] + pred_match = pred_match[score_indices] + + precisions = np.cumsum(pred_match > -1) / (np.arange(len(pred_match)) + 1) + recalls = np.cumsum(pred_match > -1).astype(np.float32) / len(gt_match) + + # Pad with start and end values to simplify the math + precisions = np.concatenate([[0], precisions, [0]]) + recalls = np.concatenate([[0], recalls, [1]]) + + # Ensure precision values decrease but don't increase. This way, the + # precision value at each recall threshold is the maximum it can be + # for all following recall thresholds, as specified by the VOC paper. + #precisions2 = precisions + for i in range(len(precisions) - 2, -1, -1): + precisions[i] = np.maximum(precisions[i], precisions[i + 1]) + + # Compute mean AP over recall range + indices = np.where(recalls[:-1] != recalls[1:])[0] + 1 + ap = np.sum((recalls[indices] - recalls[indices - 1]) * precisions[indices]) + #assert 0 <= ap <= 1. + + if debug: + IPython.embed() + + return ap + + +def compute_pr_curve_from_matches_scores(pred_match, pred_scores, gt_match, debug=False): + # sort the scores from high to low + # print(pred_match.shape, pred_scores.shape) + assert len(pred_match.shape) == 1 + assert len(gt_match.shape) == 1 + assert pred_match.shape[0] == pred_scores.shape[0] + + if gt_match.shape[0] == 0: + return 0. + + score_indices = np.argsort(pred_scores)[::-1] + pred_scores = pred_scores[score_indices] + pred_match = pred_match[score_indices] + precisions = np.cumsum(pred_match > -1) / (np.arange(len(pred_match)) + 1) + recalls = np.cumsum(pred_match > -1).astype(np.float32) / len(gt_match) + + return precisions, recalls diff --git a/simnet/lib/net/post_processing/nms.py b/simnet/lib/net/post_processing/nms.py new file mode 100644 index 0000000..84d8b49 --- /dev/null +++ b/simnet/lib/net/post_processing/nms.py @@ -0,0 +1,87 @@ +import numpy as np + + +def run(detections, overlap_thresh=0.75, order_mode='confidence'): + # initialize the list of picked detections + pruned_detections = [] + + # sort the indexes + if order_mode == 'lower_y': + idxs = create_order_by_lower_y(detections) + elif order_mode == 'confidence': + idxs = create_order_by_score(detections) + + overlap_function = get_2d_one_way_iou + + # keep looping while some indexes still remain in the indexes list + while len(idxs) > 0: + # grab the last index in the indexes list and add the index value + # to the list of picked indexes + last = len(idxs) - 1 + ii = idxs[last] + indices_to_suppress = [] + for index, index_of_index in zip(idxs[:last], range(last)): + detection_proposal = detections[index] + overlap = overlap_function(detections[ii], detection_proposal) + if overlap > overlap_thresh: + indices_to_suppress.append(index_of_index) + # Add the the pruned_detections. + pruned_detections.append(detections[ii]) + indices_to_suppress.append(last) + idxs = np.delete(idxs, indices_to_suppress) + + # return only the bounding boxes that were picked + return prune_by_min_height(pruned_detections) + + +def prune_by_min_height(detections): + pruned_detections = [] + for detection in detections: + if detection.bbox[1][0] - detection.bbox[0][0] < 12: + continue + pruned_detections.append(detection) + return pruned_detections + + +def create_order_by_lower_y(detections): + idxs = [] + for detection in detections: + idxs.append(detection.bbox[1][1]) + idxs = np.argsort(idxs) + return idxs + + +def create_order_by_score(detections): + idxs = [] + for detection in detections: + idxs.append(detection.score) + idxs = np.argsort(idxs) + return idxs + + +def get_2d_one_way_iou(detection_one, detection_two): + box_one = np.array([ + detection_one.bbox[0][0], detection_one.bbox[0][1], detection_one.bbox[1][0], + detection_one.bbox[1][1] + ]) + box_two = np.array([ + detection_two.bbox[0][0], detection_two.bbox[0][1], detection_two.bbox[1][0], + detection_two.bbox[1][1] + ]) + # determine the (x, y)-coordinates of the intersection rectangle + xA = max(box_one[0], box_two[0]) + yA = max(box_one[1], box_two[1]) + xB = min(box_one[2], box_two[2]) + yB = min(box_one[3], box_two[3]) + # compute the area of intersection rectangle + inter_area = max(0, xB - xA + 1) * max(0, yB - yA + 1) + # compute the area of both the prediction and ground-truth + # rectangles + box_one_area = (box_one[2] - box_one[0] + 1) * (box_one[3] - box_one[1] + 1) + box_two_area = (box_two[2] - box_two[0] + 1) * (box_two[3] - box_two[1] + 1) + # compute the intersection over union by taking the intersection + # area and dividing it by the sum of prediction + ground-truth + # areas - the interesection area + if float(box_one_area) == 0.0: + return 0 + return inter_area / float(box_one_area + box_two_area - inter_area) diff --git a/simnet/lib/net/post_processing/obb_outputs.py b/simnet/lib/net/post_processing/obb_outputs.py new file mode 100644 index 0000000..b4375f0 --- /dev/null +++ b/simnet/lib/net/post_processing/obb_outputs.py @@ -0,0 +1,209 @@ +import numpy as np +import torch + +from simnet.lib import transform +from simnet.lib.net.post_processing.epnp import optimize_for_9D +from simnet.lib.net.post_processing import epnp +from simnet.lib.net.post_processing import nms +from simnet.lib.net.post_processing import pose_outputs +from simnet.lib.net.post_processing import eval3d +from simnet.lib.net import losses + +_mask_l1_loss = losses.MaskedL1Loss() +_mse_loss = losses.MSELoss() + + +class OBBOutput: + + def __init__(self, heatmap, vertex_field, z_centroid_field, cov_field, hparams): + self.heatmap = heatmap + self.vertex_field = vertex_field + self.z_centroid_field = z_centroid_field + self.cov_field = cov_field + self.is_numpy = False + self.hparams = hparams + + #def _debug(name, x): + # print(name, x.dtype, x.shape, x.min(), x.max()) + #_debug('OBBOutput.heatmap', self.heatmap) + #_debug('OBBOutput.z_centroid_field', self.z_centroid_field) + #_debug('OBBOutput.vertex_field', self.vertex_field) + #_debug('OBBOutput.cov_field', self.cov_field) + #print('----------------------------------------------------') + + # Converters for torch to numpy + def convert_to_numpy_from_torch(self): + self.heatmap = np.ascontiguousarray(self.heatmap.cpu().numpy()) + self.vertex_field = np.ascontiguousarray(self.vertex_field.cpu().numpy()) + self.vertex_field = self.vertex_field.transpose((0, 2, 3, 1)) + self.vertex_field = self.vertex_field / 100.0 + self.cov_field = np.ascontiguousarray(self.cov_field.cpu().numpy()) + self.cov_field = self.cov_field.transpose((0, 2, 3, 1)) + self.cov_field = self.cov_field / 1000.0 + self.z_centroid_field = np.ascontiguousarray(self.z_centroid_field.cpu().numpy()) + self.z_centroid_field = self.z_centroid_field / 100.0 + 1.0 + self.is_numpy = True + + def convert_to_torch_from_numpy(self): + self.vertex_field = self.vertex_field.transpose((2, 0, 1)) + self.vertex_field = 100.0 * self.vertex_field + self.vertex_field = torch.from_numpy(np.ascontiguousarray(self.vertex_field)).float() + self.cov_field = self.cov_field.transpose((2, 0, 1)) + self.cov_field = 1000.0 * self.cov_field + self.cov_field = torch.from_numpy(np.ascontiguousarray(self.cov_field)).float() + self.heatmap = torch.from_numpy(np.ascontiguousarray(self.heatmap)).float() + # Normalize z_centroid by 1. + self.z_centroid_field = 100.0 * (self.z_centroid_field - 1.0) + self.z_centroid_field = torch.from_numpy(np.ascontiguousarray(self.z_centroid_field)).float() + self.is_numpy = False + + def get_detections(self, camera_model): + if not self.is_numpy: + self.convert_to_numpy_from_torch() + + poses, scores = compute_oriented_bounding_boxes( + np.copy(self.heatmap[0]), + np.copy(self.vertex_field[0]), + np.copy(self.z_centroid_field[0]), + np.copy(self.cov_field[0]), + camera_model=camera_model + ) + detections = [] + for pose, score in zip(poses, scores): + bbox = epnp.get_2d_bbox_of_9D_box(pose.camera_T_object, pose.scale_matrix, camera_model) + detections.append( + eval3d.Detection( + camera_T_object=pose.camera_T_object, + bbox=bbox, + score=score, + scale_matrix=pose.scale_matrix + ) + ) + detections = nms.run(detections) + return detections + + def get_visualization_img(self, left_img, camera_model=None): + if not self.is_numpy: + self.convert_to_numpy_from_torch() + return draw_oriented_bounding_box_from_outputs( + self.heatmap[0], + self.vertex_field[0], + self.cov_field[0], + self.z_centroid_field[0], + left_img, + camera_model=camera_model + ) + + def compute_loss(self, obb_targets, log): + if self.is_numpy: + raise ValueError("Output is not in torch mode") + vertex_target = torch.stack([obb_target.vertex_field for obb_target in obb_targets]) + z_centroid_field_target = torch.stack([ + obb_target.z_centroid_field for obb_target in obb_targets + ]) + heatmap_target = torch.stack([obb_target.heatmap for obb_target in obb_targets]) + cov_target = torch.stack([obb_target.cov_field for obb_target in obb_targets]) + + # Move to GPU + heatmap_target = heatmap_target.to(torch.device('cuda:0')) + vertex_target = vertex_target.to(torch.device('cuda:0')) + z_centroid_field_target = z_centroid_field_target.to(torch.device('cuda:0')) + cov_target = cov_target.to(torch.device('cuda:0')) + + cov_loss = _mask_l1_loss(cov_target, self.cov_field, heatmap_target) + log['cov_loss'] = cov_loss + vertex_loss = _mask_l1_loss(vertex_target, self.vertex_field, heatmap_target) + log['vertex_loss'] = vertex_loss + z_centroid_loss = _mask_l1_loss(z_centroid_field_target, self.z_centroid_field, heatmap_target) + log['z_centroid'] = z_centroid_loss + + heatmap_loss = _mse_loss(heatmap_target, self.heatmap) + log['heatmap'] = heatmap_loss + return self.hparams.loss_vertex_mult * vertex_loss + self.hparams.loss_heatmap_mult * heatmap_loss + self.hparams.loss_z_centroid_mult * z_centroid_loss + self.hparams.loss_rotation_mult * cov_loss + + +def extract_cov_matrices_from_peaks(peaks, cov_matrices_output, scale_factor=8): + assert peaks.shape[1] == 2 + cov_matrices = [] + for ii in range(peaks.shape[0]): + index = np.zeros([2]) + index[0] = int(peaks[ii, 0] / scale_factor) + index[1] = int(peaks[ii, 1] / scale_factor) + index = index.astype(np.int) + cov_mat_values = cov_matrices_output[index[0], index[1], :] + cov_matrix = np.array([[cov_mat_values[0], cov_mat_values[3], cov_mat_values[4]], + [cov_mat_values[3], cov_mat_values[1], cov_mat_values[5]], + [cov_mat_values[4], cov_mat_values[5], cov_mat_values[2]]]) + cov_matrices.append(cov_matrix) + return cov_matrices + + +def draw_oriented_bounding_box_from_outputs( + heatmap_output, vertex_output, rotation_output, z_centroid_output, c_img, camera_model=None +): + poses, _ = compute_oriented_bounding_boxes( + np.copy(heatmap_output), + np.copy(vertex_output), + np.copy(z_centroid_output), + np.copy(rotation_output), + camera_model=camera_model, + max_detections=100, + ) + return pose_outputs.draw_9dof_cv2_boxes(c_img, poses, camera_model=camera_model) + + +def solve_for_rotation_from_cov_matrix(cov_matrix): + assert cov_matrix.shape[0] == 3 + assert cov_matrix.shape[1] == 3 + U, D, Vh = np.linalg.svd(cov_matrix, full_matrices=True) + d = (np.linalg.det(U) * np.linalg.det(Vh)) < 0.0 + if d: + D[-1] = -D[-1] + U[:, -1] = -U[:, -1] + # Rotation from world to points. + rotation = np.eye(4) + rotation[0:3, 0:3] = U + return rotation + + +def compute_oriented_bounding_boxes( + heatmap_output, + vertex_output, + z_centroid_output, + cov_matrices, + camera_model, + ground_truth_peaks=None, + max_detections=np.inf, +): + peaks = pose_outputs.extract_peaks_from_centroid( + np.copy(heatmap_output), max_peaks=max_detections + ) + bboxes_ext = pose_outputs.extract_vertices_from_peaks( + np.copy(peaks), np.copy(vertex_output), np.copy(heatmap_output) + ) + z_centroids = pose_outputs.extract_z_centroid_from_peaks( + np.copy(peaks), np.copy(z_centroid_output) + ) + cov_matrices = pose_outputs.extract_cov_matrices_from_peaks(np.copy(peaks), np.copy(cov_matrices)) + poses = [] + scores = [] + for bbox_ext, z_centroid, cov_matrix, peak in zip(bboxes_ext, z_centroids, cov_matrices, peaks): + bbox_ext_flipped = bbox_ext[:, ::-1] + # Solve for pose up to a scale factor + error, camera_T_object, scale_matrix = optimize_for_9D( + bbox_ext_flipped.T, camera_model, solve_for_transforms=True + ) + # Revert back to original pose. + camera_T_object = camera_T_object @ transform.Transform.from_aa( + axis=transform.X_AXIS, angle_deg=-45.0 + ).matrix + # Add rotation solution to pose. + camera_T_object = camera_T_object @ solve_for_rotation_from_cov_matrix(cov_matrix) + # Assign correct depth factor + abs_camera_T_object, abs_object_scale = epnp.find_absolute_scale( + -1.0 * z_centroid, camera_T_object, scale_matrix + ) + poses.append(transform.Pose(camera_T_object=abs_camera_T_object, scale_matrix=abs_object_scale)) + scores.append(heatmap_output[peak[0], peak[1]]) + + return poses, scores diff --git a/simnet/lib/net/post_processing/pose_outputs.py b/simnet/lib/net/post_processing/pose_outputs.py new file mode 100644 index 0000000..4ef0b72 --- /dev/null +++ b/simnet/lib/net/post_processing/pose_outputs.py @@ -0,0 +1,310 @@ +import numpy as np +import cv2 +import torch + +from skimage.feature import peak_local_max + +from simnet.lib import color_stuff +from simnet.lib import camera +from simnet.lib import transform +from simnet.lib.net.post_processing.epnp import optimize_for_9D +from simnet.lib.net.post_processing import epnp +from simnet.lib.net.post_processing import nms +from simnet.lib.net.post_processing import eval3d +from simnet.lib.net import losses + +_mask_l1_loss = losses.MaskedL1Loss() +_mse_loss = losses.MSELoss() + + +class PoseOutput: + + def __init__(self, heatmap, vertex_field, z_centroid_field, hparams): + self.heatmap = heatmap + self.vertex_field = vertex_field + self.z_centroid_field = z_centroid_field + self.is_numpy = False + self.hparams = hparams + + # Converters for torch to numpy + def convert_to_numpy_from_torch(self): + self.heatmap = np.ascontiguousarray(self.heatmap.cpu().numpy()) + self.vertex_field = np.ascontiguousarray(self.vertex_field.cpu().numpy()) + self.vertex_field = self.vertex_field.transpose((0, 2, 3, 1)) + self.vertex_field = self.vertex_field / 100.0 + self.z_centroid_field = np.ascontiguousarray(self.z_centroid_field.cpu().numpy()) + self.z_centroid_field = self.z_centroid_field / 100.0 + 1.0 + self.is_numpy = True + + def convert_to_torch_from_numpy(self): + self.vertex_field = self.vertex_field.transpose((2, 0, 1)) + self.vertex_field = 100.0 * self.vertex_field + self.vertex_field = torch.from_numpy(np.ascontiguousarray(self.vertex_field)).float() + self.heatmap = torch.from_numpy(np.ascontiguousarray(self.heatmap)).float() + # Normalize z_centroid by 1. + self.z_centroid_field = 100.0 * (self.z_centroid_field - 1.0) + self.z_centroid_field = torch.from_numpy(np.ascontiguousarray(self.z_centroid_field)).float() + self.is_numpy = False + + def get_detections(self): + if not self.is_numpy: + self.convert_to_numpy_from_torch() + + poses, scores = compute_9D_poses( + np.copy(self.heatmap[0]), np.copy(self.vertex_field[0]), np.copy(self.z_centroid_field[0]) + ) + + detections = [] + for pose, score in zip(poses, scores): + bbox = epnp.get_2d_bbox_of_9D_box(pose.camera_T_object, pose.scale_matrix) + detections.append( + eval3d.Detection( + camera_T_object=pose.camera_T_object, + bbox=bbox, + score=score, + scale_matrix=pose.scale_matrix + ) + ) + + detections = nms.run(detections) + + return detections + + def get_visualization_img(self, left_img): + if not self.is_numpy: + self.convert_to_numpy_from_torch() + return draw_pose_from_outputs( + self.heatmap[0], + self.vertex_field[0], + self.z_centroid_field[0], + left_img, + max_detections=100, + ) + + def compute_loss(self, pose_targets, log): + if self.is_numpy: + raise ValueError("Output is not in torch mode") + vertex_target = torch.stack([pose_target.vertex_field for pose_target in pose_targets]) + z_centroid_field_target = torch.stack([ + pose_target.z_centroid_field for pose_target in pose_targets + ]) + heatmap_target = torch.stack([pose_target.heatmap for pose_target in pose_targets]) + # Move to GPU + heatmap_target = heatmap_target.to(torch.device('cuda:0')) + vertex_target = vertex_target.to(torch.device('cuda:0')) + z_centroid_field_target = z_centroid_field_target.to(torch.device('cuda:0')) + + vertex_loss = _mask_l1_loss(vertex_target, self.vertex_field, heatmap_target) + log['vertex_loss'] = vertex_loss + z_centroid_loss = _mask_l1_loss(z_centroid_field_target, self.z_centroid_field, heatmap_target) + log['z_centroid'] = z_centroid_loss + + heatmap_loss = _mse_loss(heatmap_target, self.heatmap) + log['heatmap'] = heatmap_loss + return self.hparams.loss_vertex_mult * vertex_loss + self.hparams.loss_heatmap_mult * heatmap_loss + self.hparams.loss_z_centroid_mult * z_centroid_loss + + +def extract_peaks_from_centroid( + centroid_heatmap, min_distance=5, min_confidence=0.3, max_peaks=np.inf +): + peaks = peak_local_max( + centroid_heatmap, + min_distance=min_distance, + threshold_abs=min_confidence, + num_peaks=max_peaks + ) + peaks_old = peak_local_max( + centroid_heatmap, min_distance=min_distance, threshold_abs=min_confidence + ) + + return peaks + + +def extract_vertices_from_peaks(peaks, vertex_fields, c_img, scale_factor=8): + assert peaks.shape[1] == 2 + assert vertex_fields.shape[2] == 16 + height, width = c_img.shape[0:2] + vertex_fields = vertex_fields + vertex_fields[:, :, ::2] = (1.0 - vertex_fields[:, :, ::2]) * (2 * height) - height + vertex_fields[:, :, 1::2] = (1.0 - vertex_fields[:, :, 1::2]) * (2 * width) - width + bboxes = [] + for ii in range(peaks.shape[0]): + bbox = get_bbox_from_vertex(vertex_fields, peaks[ii, :], scale_factor=scale_factor) + bboxes.append(bbox) + return bboxes + + +def extract_z_centroid_from_peaks(peaks, z_centroid_output, scale_factor=8): + assert peaks.shape[1] == 2 + z_centroids = [] + for ii in range(peaks.shape[0]): + index = np.zeros([2]) + index[0] = int(peaks[ii, 0] / scale_factor) + index[1] = int(peaks[ii, 1] / scale_factor) + index = index.astype(np.int) + z_centroids.append(z_centroid_output[index[0], index[1]]) + return z_centroids + + +def extract_cov_matrices_from_peaks(peaks, cov_matrices_output, scale_factor=8): + assert peaks.shape[1] == 2 + cov_matrices = [] + for ii in range(peaks.shape[0]): + index = np.zeros([2]) + index[0] = int(peaks[ii, 0] / scale_factor) + index[1] = int(peaks[ii, 1] / scale_factor) + index = index.astype(np.int) + cov_mat_values = cov_matrices_output[index[0], index[1], :] + cov_matrix = np.array([[cov_mat_values[0], cov_mat_values[3], cov_mat_values[4]], + [cov_mat_values[3], cov_mat_values[1], cov_mat_values[5]], + [cov_mat_values[4], cov_mat_values[5], cov_mat_values[2]]]) + cov_matrices.append(cov_matrix) + return cov_matrices + + +def get_bbox_from_vertex(vertex_fields, index, scale_factor=8): + assert index.shape[0] == 2 + index[0] = int(index[0] / scale_factor) + index[1] = int(index[1] / scale_factor) + bbox = vertex_fields[index[0], index[1], :] + bbox = bbox.reshape([8, 2]) + bbox = scale_factor * (index) - bbox + return bbox + + +def draw_peaks(centroid_target, peaks): + centroid_target = np.clip(centroid_target, 0.0, 1.0) * 255.0 + color = (0, 0, 255) + height, width = centroid_target.shape + # Make a 3 Channel image. + c_img = np.zeros([centroid_target.shape[0], centroid_target.shape[1], 3]) + c_img[:, :, 1] = centroid_target + for ii in range(peaks.shape[0]): + point = (int(peaks[ii, 1]), int(peaks[ii, 0])) + c_img = cv2.circle(c_img, point, 8, color, -1) + return cv2.resize(c_img, (width, height)) + + +def draw_pose_from_outputs( + heatmap_output, vertex_output, z_centroid_output, c_img, max_detections=np.inf +): + poses, _ = compute_9D_poses( + np.copy(heatmap_output), + np.copy(vertex_output), + np.copy(z_centroid_output), + max_detections=max_detections, + ) + return draw_9dof_cv2_boxes(c_img, poses) + + +def draw_pose_9D_from_detections(detections, c_img): + successes = [] + poses = [] + for detection in detections: + poses.append( + transform.Pose( + camera_T_object=detection.camera_T_object, scale_matrix=detection.scale_matrix + ) + ) + successes.append(detection.success) + return draw_9dof_cv2_boxes(c_img, poses, successes=successes) + + +def solve_for_rotation_from_cov_matrix(cov_matrix): + assert cov_matrix.shape[0] == 3 + assert cov_matrix.shape[1] == 3 + U, D, Vh = np.linalg.svd(cov_matrix, full_matrices=True) + d = (np.linalg.det(U) * np.linalg.det(Vh)) < 0.0 + if d: + D[-1] = -D[-1] + U[:, -1] = -U[:, -1] + # Rotation from world to points. + rotation = np.eye(4) + rotation[0:3, 0:3] = U + return rotation + + +def compute_9D_poses(heatmap_output, vertex_output, z_centroid_output, max_detections=np.inf): + peaks = extract_peaks_from_centroid(np.copy(heatmap_output), max_peaks=max_detections) + bboxes_ext = extract_vertices_from_peaks( + np.copy(peaks), np.copy(vertex_output), np.copy(heatmap_output) + ) + z_centroids = extract_z_centroid_from_peaks(np.copy(peaks), np.copy(z_centroid_output)) + poses = [] + scores = [] + for bbox_ext, z_centroid, peak in zip(bboxes_ext, z_centroids, peaks): + bbox_ext_flipped = bbox_ext[:, ::-1] + # Solve for pose up to a scale factor + error, camera_T_object, scale_matrix = optimize_for_9D( + bbox_ext_flipped.T, solve_for_transforms=True + ) + # Assign correct depth factor + abs_camera_T_object, abs_scale_matrix = epnp.find_absolute_scale( + z_centroid, camera_T_object, scale_matrix + ) + poses.append(transform.Pose(camera_T_object=abs_camera_T_object, scale_matrix=abs_scale_matrix)) + scores.append(heatmap_output[peak[0], peak[1]]) + return poses, scores + + +def draw_9dof_cv2_boxes(c_img, poses, camera_model=None, successes=None): + boxes = [] + for pose in poses: + # Compute the bounds of the boxes current size and location + unit_box_homopoints = camera.convert_points_to_homopoints(epnp._WORLD_T_POINTS.T) + morphed_homopoints = pose.camera_T_object @ (pose.scale_matrix @ unit_box_homopoints) + if camera_model == None: + camera_model = camera.HSRCamera() + else: + camera_model = camera_model + morphed_pixels = camera.convert_homopixels_to_pixels( + camera_model.K_matrix @ morphed_homopoints + ).T + boxes.append(morphed_pixels[:, ::-1]) + return draw_9dof_box(c_img, boxes, successes=successes) + + +def draw_9dof_box(c_img, boxes, successes=None): + if len(boxes) == 0: + return c_img + if successes is None: + colors = color_stuff.get_colors(len(boxes)) + else: + colors = [] + for success in successes: + #TODO(michael.laskey): Move to Enum Structure + if success == 1: + colors.append(np.array([0, 255, 0]).astype(np.uint8)) + elif success == -1: + colors.append(np.array([255, 255, 0]).astype(np.uint8)) + elif success == -2: + colors.append(np.array([0, 0, 255]).astype(np.uint8)) + else: + colors.append(np.array([255, 0, 0]).astype(np.uint8)) + c_img = cv2.cvtColor(np.array(c_img), cv2.COLOR_BGR2RGB) + for vertices, color in zip(boxes, colors): + vertices = vertices.astype(np.int) + points = [] + vertex_colors = (255, 0, 0) + line_color = (int(color[0]), int(color[1]), int(color[2])) + circle_colors = color_stuff.get_colors(8) + for i, circle_color in zip(range(vertices.shape[0]), circle_colors): + color = vertex_colors + point = (int(vertices[i, 1]), int(vertices[i, 0])) + c_img = cv2.circle(c_img, point, 1, (0, 255, 0), -1) + points.append(point) + # Draw the lines + thickness = 1 + c_img = cv2.line(c_img, points[0], points[1], line_color, thickness) + c_img = cv2.line(c_img, points[0], points[2], line_color, thickness) + c_img = cv2.line(c_img, points[0], points[4], line_color, thickness) + c_img = cv2.line(c_img, points[3], points[1], line_color, thickness) + c_img = cv2.line(c_img, points[3], points[2], line_color, thickness) + c_img = cv2.line(c_img, points[3], points[7], line_color, thickness) #6 + c_img = cv2.line(c_img, points[5], points[1], line_color, thickness) + c_img = cv2.line(c_img, points[5], points[4], line_color, thickness) + c_img = cv2.line(c_img, points[5], points[7], line_color, thickness) #9 + c_img = cv2.line(c_img, points[6], points[7], line_color, thickness) + c_img = cv2.line(c_img, points[6], points[4], line_color, thickness) + c_img = cv2.line(c_img, points[6], points[2], line_color, thickness) #12 + return c_img diff --git a/simnet/lib/net/post_processing/segmentation_outputs.py b/simnet/lib/net/post_processing/segmentation_outputs.py new file mode 100644 index 0000000..f127a50 --- /dev/null +++ b/simnet/lib/net/post_processing/segmentation_outputs.py @@ -0,0 +1,78 @@ +import numpy as np +import cv2 +import torch +from torch.nn import functional as F + +from simnet.lib import color_stuff + +# Panoptic Segmentation Colors + + +class SegmentationOutput: + + def __init__(self, seg_pred, hparams): + self.seg_pred = seg_pred + self.is_numpy = False + self.hparams = hparams + + # Converters for torch to numpy + def convert_to_numpy_from_torch(self): + self.seg_pred = np.ascontiguousarray(self.seg_pred.cpu().numpy()) + self.is_numpy = True + + def convert_to_torch_from_numpy(self): + self.seg_pred = torch.from_numpy(np.ascontiguousarray(self.seg_pred)).long() + self.is_numpy = False + + def get_visualization_img(self, left_image): + if not self.is_numpy: + self.convert_to_numpy_from_torch() + return draw_segmentation_mask(left_image, self.seg_pred[0]) + + def get_prediction(self): + if not self.is_numpy: + self.convert_to_numpy_from_torch() + return self.seg_pred[0] + + def compute_loss(self, seg_targets, log): + if self.is_numpy: + raise ValueError("Output is not in torch mode") + seg_target_stacked = [] + for seg_target in seg_targets: + seg_target_stacked.append(seg_target.seg_pred) + seg_target_batch = torch.stack(seg_target_stacked) + seg_target_batch = seg_target_batch.to(torch.device('cuda:0')) + seg_loss = F.cross_entropy(self.seg_pred, seg_target_batch, reduction="mean", ignore_index=-100) + log['segmentation'] = seg_loss + return self.hparams.loss_seg_mult * seg_loss + + +def draw_segmentation_mask_gt(color_img, seg_mask, num_classes=5): + assert len(seg_mask.shape) == 2 + seg_mask = seg_mask.astype(np.uint8) + colors = color_stuff.get_panoptic_colors() + color_img = color_img_to_gray(color_img) + for ii, color in zip(range(num_classes), colors): + colored_mask = np.zeros([seg_mask.shape[0], seg_mask.shape[1], 3]) + colored_mask[seg_mask == ii, :] = color + color_img = cv2.addWeighted( + color_img.astype(np.uint8), 0.9, colored_mask.astype(np.uint8), 0.4, 0 + ) + return cv2.cvtColor(color_img, cv2.COLOR_BGR2RGB) + + +def color_img_to_gray(image): + gray_scale_img = np.zeros(image.shape) + img = cv2.cvtColor(image, cv2.COLOR_BGR2GRAY) + for i in range(3): + gray_scale_img[:, :, i] = img + gray_scale_img[:, :, i] = img + return gray_scale_img + + +def draw_segmentation_mask(color_img, seg_mask): + assert len(seg_mask.shape) == 3 + num_classes = seg_mask.shape[0] + # Convert to predictions + seg_mask_predictions = np.argmax(seg_mask, axis=0) + return draw_segmentation_mask_gt(color_img, seg_mask_predictions, num_classes=num_classes) diff --git a/simnet/lib/occlusions.py b/simnet/lib/occlusions.py new file mode 100644 index 0000000..9dceb04 --- /dev/null +++ b/simnet/lib/occlusions.py @@ -0,0 +1,50 @@ +import numpy as np + +from simnet.lib import camera +from simnet.lib.net.post_processing import epnp + + +### 3D Occlusions +def object_is_outside_image(detection, camera_model): + bbox = epnp.get_2d_bbox_of_9D_box(detection.camera_T_object, detection.scale_matrix, camera_model) + width = camera_model.width + height = camera_model.height + + if bbox[0][0] < 0 or bbox[0][0] < 0: + return True + if bbox[1][0] > width or bbox[1][1] > height: + return True + return False + + +def get_bbox_image(detection, camera_model): + bbox = epnp.get_2d_bbox_of_9D_box(detection.camera_T_object, detection.scale_matrix, camera_model) + width = camera_model.width + height = camera_model.height + img = np.zeros([height, width]) + img[int(bbox[0][1]):int(bbox[1][1]), int(bbox[0][0]):int(bbox[1][0])] = 1.0 + return img + + +def mark_occlusions_in_detections( + detections, occlusion_score=0.5, camera_model=None, allow_outside_of_image=False +): + if camera_model is None: + camera_model = camera.FMKCamera() + for ii in range(len(detections)): + if object_is_outside_image(detections[ii], camera_model): + detections[ii].ignore = True + continue + bbox_unocc = get_bbox_image(detections[ii], camera_model) + bbox_occ = np.copy(bbox_unocc) + bbox_prop = np.copy(bbox_occ) + for detection_proposal in detections: + # Check if the object is behind the target object. + if detection_proposal.camera_T_object[2, 3] >= detections[ii].camera_T_object[2, 3]: + continue + bbox_proposal = get_bbox_image(detection_proposal, camera_model) + bbox_occ = bbox_occ - bbox_proposal + bbox_prop = bbox_prop + bbox_proposal + occlusion_level = np.sum(bbox_occ > 0) / np.sum(bbox_unocc > 0) + if occlusion_level < occlusion_score: + detections[ii].ignore = True diff --git a/simnet/lib/transform.py b/simnet/lib/transform.py new file mode 100644 index 0000000..cb9c540 --- /dev/null +++ b/simnet/lib/transform.py @@ -0,0 +1,114 @@ +import dataclasses + +import numpy as np + +X_AXIS = np.array([1., 0., 0.]) +Y_AXIS = np.array([0., 1., 0.]) +Z_AXIS = np.array([0., 0., 1.]) + + +@dataclasses.dataclass +class Pose: + camera_T_object: np.ndarray + scale_matrix: np.ndarray = np.eye(4) + + +class Transform: + + def __init__(self, matrix=None): + if matrix is None: + self.matrix = np.eye(4) + else: + self.matrix = matrix + self.is_concrete = True + + def apply_transform(self, transform): + assert self.is_concrete + assert isinstance(transform, Transform) + self.matrix = self.matrix @ transform.matrix + + def inverse(self): + assert self.is_concrete + return Transform(matrix=np.linalg.inv(self.matrix)) + + def __repr__(self): + assert self.matrix.shape == (4, 4) + if self.is_SE3(): + return f'Transform(translate={self.translation})' + else: + return f'Transform(IS_NOT_SE3,matrix={self.matrix})' + + def is_SE3(self): + return matrixIsSE3(self.matrix) + + @property + def translation(self): + return self.matrix[:3, 3] + + @translation.setter + def translation(self, value): + assert value.shape == (3,) + self.matrix[:3, 3] = value + + @property + def rotation(self): + return self.matrix[:3, :3] + + @rotation.setter + def rotation(self, value): + assert value.shape == (3, 3) + self.matrix[:3, :3] = value + + @classmethod + def from_aa(cls, axis=X_AXIS, angle_deg=0., translation=None): + assert axis.shape == (3,) + matrix = np.eye(4) + if angle_deg != 0.: + matrix[:3, :3] = axis_angle_to_rotation_matrix(axis, np.deg2rad(angle_deg)) + if translation is not None: + translation = np.array(translation) + assert translation.shape == (3,) + matrix[:3, 3] = translation + return cls(matrix=matrix) + + +def matrixIsSE3(matrix): + if not np.allclose(matrix[3, :], np.array([0., 0., 0., 1.])): + return False + rot = matrix[:3, :3] + if not np.allclose(rot @ rot.T, np.eye(3)): + return False + if not np.isclose(np.linalg.det(rot), 1.): + return False + return True + + +def find_closest_SE3(matrix): + matrix = np.copy(matrix) + assert np.allclose(matrix[3, :], np.array([0., 0., 0., 1.])) + rotation = matrix[:3, :3] + u, s, vh = np.linalg.svd(rotation) + matrix[:3, :3] = u @ vh + assert matrixIsSE3(matrix) + return matrix + + +def axis_angle_to_rotation_matrix(axis, theta): + """Return the rotation matrix associated with counterclockwise rotation about + the given axis by theta radians. + + Args: + axis: a list which specifies a unit axis + theta: an angle in radians, for which to rotate around by + Returns: + A 3x3 rotation matrix + """ + axis = np.asarray(axis) + axis = axis / np.sqrt(np.dot(axis, axis)) + a = np.cos(theta / 2.0) + b, c, d = -axis * np.sin(theta / 2.0) + aa, bb, cc, dd = a * a, b * b, c * c, d * d + bc, ad, ac, ab, bd, cd = b * c, a * d, a * c, a * b, b * d, c * d + return np.array([[aa + bb - cc - dd, 2 * (bc + ad), 2 * (bd - ac)], + [2 * (bc - ad), aa + cc - bb - dd, 2 * (cd + ab)], + [2 * (bd + ac), 2 * (cd - ab), aa + dd - bb - cc]])