From 4fa2107895aefed437ca881bc0267afbb203e35d Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Wed, 23 Sep 2020 17:10:46 -0700 Subject: [PATCH 01/15] API for distortion parameters --- AirLib/include/api/RpcLibClientBase.hpp | 2 +- AirLib/include/api/WorldSimApiBase.hpp | 2 +- AirLib/src/api/RpcLibClientBase.cpp | 5 +++++ AirLib/src/api/RpcLibServerBase.cpp | 4 ++++ .../AirSim/Source/DIstortableSceneCapture.h | 15 +++++++++++++++ Unreal/Plugins/AirSim/Source/WorldSimApi.cpp | 15 +++++++++++++++ Unreal/Plugins/AirSim/Source/WorldSimApi.h | 1 + 7 files changed, 42 insertions(+), 2 deletions(-) create mode 100644 Unreal/Plugins/AirSim/Source/DIstortableSceneCapture.h diff --git a/AirLib/include/api/RpcLibClientBase.hpp b/AirLib/include/api/RpcLibClientBase.hpp index b14e18f5d1..632c3f0c19 100644 --- a/AirLib/include/api/RpcLibClientBase.hpp +++ b/AirLib/include/api/RpcLibClientBase.hpp @@ -110,7 +110,7 @@ class RpcLibClientBase { msr::airlib::Kinematics::State simGetGroundTruthKinematics(const std::string& vehicle_name = "") const; msr::airlib::Environment::State simGetGroundTruthEnvironment(const std::string& vehicle_name = "") const; - + void simSetDistortionParam(std::string& scenecap_actor_name, std::string& param_name, float value); std::vector simSwapTextures(const std::string& tags, int tex_id = 0, int component_id = 0, int material_id = 0); // Recording APIs diff --git a/AirLib/include/api/WorldSimApiBase.hpp b/AirLib/include/api/WorldSimApiBase.hpp index 286b98d99d..654d456a7f 100644 --- a/AirLib/include/api/WorldSimApiBase.hpp +++ b/AirLib/include/api/WorldSimApiBase.hpp @@ -63,7 +63,7 @@ class WorldSimApiBase { virtual bool setObjectPose(const std::string& object_name, const Pose& pose, bool teleport) = 0; virtual bool runConsoleCommand(const std::string& command) = 0; virtual bool setObjectScale(const std::string& object_name, const Vector3r& scale) = 0; - + virtual void setDistortionParam(std::string& scenecap_actor_name, std::string& param_name, float value) = 0; virtual std::unique_ptr> swapTextures(const std::string& tag, int tex_id = 0, int component_id = 0, int material_id = 0) = 0; virtual vector getMeshPositionVertexBuffers() const = 0; diff --git a/AirLib/src/api/RpcLibClientBase.cpp b/AirLib/src/api/RpcLibClientBase.cpp index 04b6e33ce1..16ba7e702a 100644 --- a/AirLib/src/api/RpcLibClientBase.cpp +++ b/AirLib/src/api/RpcLibClientBase.cpp @@ -417,6 +417,11 @@ bool RpcLibClientBase::simRunConsoleCommand(const std::string& command) return pimpl_->client.call("simRunConsoleCommand", command).as(); } +void RpcLibClientBase::simSetDistortionParam(std::string& scenecap_actor_name, std::string& param_name, float value) +{ + pimpl_->client.call("simSetDistortionParam", scenecap_actor_name, param_name, value); +} + //return value of last task. It should be true if task completed without //cancellation or timeout RpcLibClientBase* RpcLibClientBase::waitOnLastTask(bool* task_result, float timeout_sec) diff --git a/AirLib/src/api/RpcLibServerBase.cpp b/AirLib/src/api/RpcLibServerBase.cpp index 5035c92041..e772dcc3c0 100644 --- a/AirLib/src/api/RpcLibServerBase.cpp +++ b/AirLib/src/api/RpcLibServerBase.cpp @@ -292,6 +292,10 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& return getWorldSimApi()->setObjectScale(object_name, scale.to()); }); + pimpl_->server.bind("simSetDistortionParam", [&](std::string& scenecap_actor_name, std::string& param_name, float value) { + getWorldSimApi()->setDistortionParam(scenecap_actor_name, param_name, value); + }); + pimpl_->server.bind("simFlushPersistentMarkers", [&]() -> void { getWorldSimApi()->simFlushPersistentMarkers(); }); diff --git a/Unreal/Plugins/AirSim/Source/DIstortableSceneCapture.h b/Unreal/Plugins/AirSim/Source/DIstortableSceneCapture.h new file mode 100644 index 0000000000..b297d2cd4e --- /dev/null +++ b/Unreal/Plugins/AirSim/Source/DIstortableSceneCapture.h @@ -0,0 +1,15 @@ +#pragma once + +#include "CoreMinimal.h" +#include "Engine/SceneCapture2D.h" +#include "DistortableSceneCapture.generated.h" + +UCLASS() +class ADistortableSceneCapture : public ASceneCapture2D +{ + GENERATED_BODY() + +public: + UPROPERTY(EditDefaultsOnly, Category = "Distortion") + UMaterialParameterCollection *ParamCollection; +}; \ No newline at end of file diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp index 61fe335bfa..9e753f3b69 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp @@ -6,6 +6,7 @@ #include "Weather/WeatherLib.h" #include "DrawDebugHelpers.h" #include "Runtime/Engine/Classes/Engine/Engine.h" +#include "DistortableSceneCapture.h" #include #include @@ -344,6 +345,20 @@ std::unique_ptr> WorldSimApi::swapTextures(const std::s return swappedObjectNames; } +void WorldSimApi::setDistortionParam(std::string& scenecap_actor_name, std::string& param_name, float value) +{ + UAirBlueprintLib::RunCommandOnGameThread([this, &scenecap_actor_name, ¶m_name, value]() { + ADistortableSceneCapture* actor = UAirBlueprintLib::FindActor(simmode_, FString(scenecap_actor_name.c_str())); + if (!actor) + return; + auto *param_collection_asset = actor->ParamCollection; + if (!param_collection_asset) + return; + auto *param_collection = simmode_->GetWorld()->GetParameterCollectionInstance(param_collection_asset); + param_collection->SetScalarParameterValue(FName(param_name.c_str()), value); + }, true); +} + //----------- Plotting APIs ----------/ void WorldSimApi::simFlushPersistentMarkers() { diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.h b/Unreal/Plugins/AirSim/Source/WorldSimApi.h index f83353b5b2..6f904d1403 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.h +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.h @@ -47,6 +47,7 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase { virtual bool runConsoleCommand(const std::string& command) override; virtual Vector3r getObjectScale(const std::string& object_name) const override; virtual bool setObjectScale(const std::string& object_name, const Vector3r& scale) override; + virtual void setDistortionParam(std::string& scenecap_actor_name, std::string& param_name, float value) override; //----------- Plotting APIs ----------/ virtual void simFlushPersistentMarkers() override; From 08ee44c2a056746778ea81d66ceedc957de5bfb6 Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Thu, 24 Sep 2020 18:16:00 -0700 Subject: [PATCH 02/15] Initial version of camera distortion material and API --- AirLib/AirSim.props | 6 ++ AirLib/include/api/RpcLibClientBase.hpp | 2 +- AirLib/include/api/WorldSimApiBase.hpp | 2 +- AirLib/src/api/RpcLibClientBase.cpp | 4 +- AirLib/src/api/RpcLibServerBase.cpp | 8 +-- .../Content/HUDAssets/CameraDistortion.uasset | Bin 0 -> 89865 bytes .../Content/HUDAssets/DistortionParams.uasset | Bin 0 -> 2255 bytes Unreal/Plugins/AirSim/Source/PIPCamera.cpp | 58 +++++++++++------- Unreal/Plugins/AirSim/Source/PIPCamera.h | 3 + .../AirSim/Source/SimMode/SimModeBase.cpp | 2 + .../AirSim/Source/SimMode/SimModeBase.h | 6 +- Unreal/Plugins/AirSim/Source/WorldSimApi.cpp | 16 ++--- Unreal/Plugins/AirSim/Source/WorldSimApi.h | 2 +- 13 files changed, 67 insertions(+), 42 deletions(-) create mode 100644 AirLib/AirSim.props create mode 100644 Unreal/Plugins/AirSim/Content/HUDAssets/CameraDistortion.uasset create mode 100644 Unreal/Plugins/AirSim/Content/HUDAssets/DistortionParams.uasset diff --git a/AirLib/AirSim.props b/AirLib/AirSim.props new file mode 100644 index 0000000000..d4487d889c --- /dev/null +++ b/AirLib/AirSim.props @@ -0,0 +1,6 @@ + + + $([System.String]::Copy('$(WindowsSDKVersion)').Replace('\','')) + $(AirSimTargetPlatformVersion) + + \ No newline at end of file diff --git a/AirLib/include/api/RpcLibClientBase.hpp b/AirLib/include/api/RpcLibClientBase.hpp index 632c3f0c19..0fc52f8b19 100644 --- a/AirLib/include/api/RpcLibClientBase.hpp +++ b/AirLib/include/api/RpcLibClientBase.hpp @@ -103,6 +103,7 @@ class RpcLibClientBase { CollisionInfo simGetCollisionInfo(const std::string& vehicle_name = "") const; CameraInfo simGetCameraInfo(const std::string& camera_name, const std::string& vehicle_name = "") const; + void simSetDistortionParam(std::string& param_name, float value); void simSetCameraPose(const std::string& camera_name, const Pose& pose, const std::string& vehicle_name = ""); void simSetCameraFov(const std::string& camera_name, float fov_degrees, const std::string& vehicle_name = ""); // This is a backwards-compatibility wrapper over simSetCameraPose, and can be removed in future major releases @@ -110,7 +111,6 @@ class RpcLibClientBase { msr::airlib::Kinematics::State simGetGroundTruthKinematics(const std::string& vehicle_name = "") const; msr::airlib::Environment::State simGetGroundTruthEnvironment(const std::string& vehicle_name = "") const; - void simSetDistortionParam(std::string& scenecap_actor_name, std::string& param_name, float value); std::vector simSwapTextures(const std::string& tags, int tex_id = 0, int component_id = 0, int material_id = 0); // Recording APIs diff --git a/AirLib/include/api/WorldSimApiBase.hpp b/AirLib/include/api/WorldSimApiBase.hpp index 654d456a7f..181341ac58 100644 --- a/AirLib/include/api/WorldSimApiBase.hpp +++ b/AirLib/include/api/WorldSimApiBase.hpp @@ -63,7 +63,7 @@ class WorldSimApiBase { virtual bool setObjectPose(const std::string& object_name, const Pose& pose, bool teleport) = 0; virtual bool runConsoleCommand(const std::string& command) = 0; virtual bool setObjectScale(const std::string& object_name, const Vector3r& scale) = 0; - virtual void setDistortionParam(std::string& scenecap_actor_name, std::string& param_name, float value) = 0; + virtual void setDistortionParam(std::string& param_name, float value) = 0; virtual std::unique_ptr> swapTextures(const std::string& tag, int tex_id = 0, int component_id = 0, int material_id = 0) = 0; virtual vector getMeshPositionVertexBuffers() const = 0; diff --git a/AirLib/src/api/RpcLibClientBase.cpp b/AirLib/src/api/RpcLibClientBase.cpp index 16ba7e702a..9873110f7e 100644 --- a/AirLib/src/api/RpcLibClientBase.cpp +++ b/AirLib/src/api/RpcLibClientBase.cpp @@ -417,9 +417,9 @@ bool RpcLibClientBase::simRunConsoleCommand(const std::string& command) return pimpl_->client.call("simRunConsoleCommand", command).as(); } -void RpcLibClientBase::simSetDistortionParam(std::string& scenecap_actor_name, std::string& param_name, float value) +void RpcLibClientBase::simSetDistortionParam(std::string& param_name, float value) { - pimpl_->client.call("simSetDistortionParam", scenecap_actor_name, param_name, value); + pimpl_->client.call("simSetDistortionParam", param_name, value); } //return value of last task. It should be true if task completed without diff --git a/AirLib/src/api/RpcLibServerBase.cpp b/AirLib/src/api/RpcLibServerBase.cpp index e772dcc3c0..85266a4fd1 100644 --- a/AirLib/src/api/RpcLibServerBase.cpp +++ b/AirLib/src/api/RpcLibServerBase.cpp @@ -243,6 +243,10 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& return RpcLibAdapatorsBase::CameraInfo(camera_info); }); + pimpl_->server.bind("simSetDistortionParam", [&](std::string& param_name, float value) { + getWorldSimApi()->setDistortionParam(param_name, value); + }); + pimpl_->server.bind("simSetCameraPose", [&](const std::string& camera_name, const RpcLibAdapatorsBase::Pose& pose, const std::string& vehicle_name) -> void { getVehicleSimApi(vehicle_name)->setCameraPose(camera_name, pose.to()); @@ -292,10 +296,6 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& return getWorldSimApi()->setObjectScale(object_name, scale.to()); }); - pimpl_->server.bind("simSetDistortionParam", [&](std::string& scenecap_actor_name, std::string& param_name, float value) { - getWorldSimApi()->setDistortionParam(scenecap_actor_name, param_name, value); - }); - pimpl_->server.bind("simFlushPersistentMarkers", [&]() -> void { getWorldSimApi()->simFlushPersistentMarkers(); }); diff --git a/Unreal/Plugins/AirSim/Content/HUDAssets/CameraDistortion.uasset b/Unreal/Plugins/AirSim/Content/HUDAssets/CameraDistortion.uasset new file mode 100644 index 0000000000000000000000000000000000000000..775d478285e226f5818ff7a3eec9415fba94f124 GIT binary patch literal 89865 zcmcF}2Ut_tw{Ji|kPb?bCen21y@S$GnxYixgn*O~NPtiSQbeQ)h`>;yqM#zZx6nfm zBE9z}y$1;Jh%?TA?*Goa@4oN8x4$oE@3Yq0>$mr6XXhjhA-`oDou8juUjhI~2mwFa z<%=sa5=)1>=lOzS#6RnHt(*-11#QA};WnQ}=Cs#$n)Dyz0$j8gG=&CB=@YGalC4lc zDZ>3XUZM-yb0#+HP<^|vlYIGOWlxXk(bTX2aD`vpze1J@Iz zR-ig{H7)^mgN>2rg0}v&V17mA^&a`C==;0X8bZ7mw0F7$0OE^Y58?{C=m3Cw7oQ3O z0D$wNSCx>E5xXlQDj_CyS4>n&T|-<}RZU$*LtRo_?CxE0RlGdl4JiOXe$g+I0RR+# z-dj@PIRF45^&cNT9Rfg4;}q`QN8FuqRMZt3uRzy7B>wl;i#7bzi(e2CfcfHjH?9pp zf6?>vKUSCEe+Y5`*}y=85<+5<|7U@VX+Im<_Nh01@Ze%a#8!BWf3*u&o#XAnbwLuo z>j*V;1Pg0DR=W#>fjnTssy1K{)JDw_<^h3vI6_B3BZ@zh-%94~zF{7#rQJ_vqIdF%=W*|@0N z0R)JWNb%;q3x(SF7(gLzAgG5AK)Ybh@yZ2N<-#PY5Elp(Fw`>Kas7f~t7_w_YXfrz z*{Ogow&Do}+3CC4xO;*Czcs$Kp~TODKwSP(L_<{Y@+Z;91N0YhQBSb`+J&U54e%+* zPTkuL3WC8dY@lZ2VFU0W_AeFB zAP_mih>t#1h#d%!>GjAEA4nI=ceyYO-o!bD@?v<8|J;$TjRy$oXyc;o>gMSIV49W@ z{izNDf!aB`UhrT5&Gf`OKWUy9P6GcSr@LyIhlfxD!GM72wLEV8QvZ{K3OiS_@WxVC z{Wyz!z7g*(b+F@w$-Mq_j*pdb@=s|)AjlQ;2;}YI2?c4}0rnLRAwTJVnfQ-g+*toY zh~L@2Ob-Kiv!pcRcc$s-Xa`U=IDU$^^&jH?FJFY>qv7YB-bLU7o^(hD;cL%N3Jfr` znQ$4ePutbwFDHNOle%|NsQ~vy0has>89#?&fN)Bz=+B`zK!hgU2p<|cjt);f99
    u@Lv7T0>8XicQ88rUrCq(NLTB^8UIno&+Q*D0`l-R z_&-DZ-Lrsm!g(@$Mg1o+CISgBHN}!2e6&BIyp{dNlYH{fqW9V|2JnDH-ro1MRYL(fR~P}19)5g-TxOL*}TrxH~u0&^#t3x+Bja+GJA-zqsLPN zs3Z6y0K7ne*J^C(cvBgAT$Hqnd3GOb67dT*^nm_lclib=_fH59s3-7W2`mCg!{PVw z=;q9BN)K>@DBT*2a%u8>I*X9;Nqz#jvrjKf9LIA@bLMFZ~w%*{RitG zdB6P^JfZ)BC;Y$R?Om)z?N1&)tnf|bj}CBn!NZ3HzWrLK+#k0;ufLx2|HS)6`_=z_ z-Y=Yg;^A$IZ)X?Se~kXP;u8Yj@V(Zb3h<|j|4ze8;XfBD|AS8a+|$3&@G^MY<9mFt zaN!3RZN=cv!5_Cj`F{@oL-$MSzl($4|KD*a9{$qshuZ&m_b;el^#3jn-dumj5jOm# z;r}fT-gke;dHCr64-US7{vF5j@&6nL_iu54&ojJMJkAsR5#XXF8~x95PW}xCpR>Pk zZvLr$$NYbebNp{O`27Ec^8vq^i+0uWe~$C-F{to|>Yw%E?w{j|zv18!|0C+3LVxT2 zT_>J}|Hk)A1V0~Nv+zCMKlnn9Z%2Q_`GfM$*I)Smgo8id;dSCqb@=?m=MFxu@iB)F z1Nfi{Zc8pTuj51b_$wJx$6h*YQiI z)Yeja_-h6!e!=F@Pxb)74S=@V-ACR8Q4?f6d8S?ri<=aW2VlS(&nV7sJf!0dVRiws zkap<5xT;RZX28Ox7898C)ms|wtG5F=ZC*^|i%EuHggkuw2xn+nI1J%LM|Ny1hNHJ0p(zG-=yvFy61J2Nej ziSB1RAKxWW$8sp^rM^(wk7Oj_5|Nw;kIT%26z(Bjc)9Sr9~* zA9YBOoU}MADJbELL${!_t!&ig)zroatdIj~?5t`*jE%28QmH!*(Tpat+LUoVjFIe$ zpp-i0&p24!edWz0GfW{cxN_YuBAi3I^7v>c%S&UaMzGB2Z~|WEy*S7;v2Y6w1lwev z2CKaOE@`r`iEE=gTlHz=EiMgLcJUsot2*=+Kq2Lg*9vNlGLrL;AWLom-gD8?Jql6p zDn#eFvV8>8{Q|JJVv!VQ>E>=oe7_DaXPcztn?^qj{W`CX^emZx9^*L0W3MFbdo z)FO;p(L=r)lC-lYXAWk4)`;n)l{^@zCwJYMp2w@DxtnNbab;G`MGH`PAyM1E=f`re z*B!mNIDT{e_9-@es`N$6?o!h_HqSoR;^PF}k0WuYv%cU+%f^#nN&h05O0n4juV7<3 zURlJNim9??0}I9O(ahydj>_ovxmK1bUYda2p*C}J4E%3(ilOBNXE`c}>{zA@_+Vc^=DhD5uJ_eZ+Qh=|-z?byBOa`s8z z)o$)QrSM_J6E}vAmgj8Om8Fu}dDZ8clr*-?Dl4wmI7lgz=Ywv=H-Uf8k@IRd^}oWt z4d*?fEKF4y)CisGq_&!fvTksR>*qjV5qk95y=5{MAeO1bfXZFB*{s;{zHG>b+t-c8 z6E|D264zsX=~S%NiGIdjUP2tggk+uj@m5G+YUQJ2P`g?0i$w zWI*=T%6x0F05*ZUFEx^)`Y^Az@Geq;oq2rNuVb-99^z7z+eQo2?;`-;8LWe?#^qfj zWXOKXZmMhdUNT@t96+|Hj`5x+a(zjBc$dxvQ@%=*Hujn?N~luw>Jg=V&o_lMwEYc^ z=rG4us=4uL_fx)a*dXD0V_AmRppg!15A#S z9Xxa#Uvm;ZTjul1$r&Tr_4j|FG$z;DHm7+xHhMgxr^^amYI;H}`!+B}_39I*utS{8 zqrjIGhqsNE@Gs$^yKR7czh6AQojj*NrK&5Xswajofq zj!}wdD=AnEHnQ0!VDYqX{0b|v{J_4`TY2N7;_BB0>6^Y`c8!gC@%?9RoJkf?3O)nF zz!`Go!>z`|?!dO5z{)G#6HOkvrqUyx#x&(~L$A`u)+fE5cP@{u!2GW3uKXxlbe#X~ zlBE1;rJ`qEy&r2ePr$sn?6>4#uGG}DvFzyL>Qu8CNS=x~tzpb@p*$2$&o5p6Es@g- zF)Em6!mInaNM~+$xl?f=nbK&HA-qq2W6FzBM;K&x6JB`W1CAi+an@WEijq3ZNv{tASUNe>Mnq=BR^}^(C5R5FLjH<>tjw6Iyu&)dXHK(FNlc2XFgP^ULu!6qs+bu z=%^UV^z)ytv?l^uEojG5<)dbXgJX1W3ct56CQDh#8J83pT_`_W*VvhlFe{u(9wdq| zPiRP9I+vbGtB$KwDL3E#B80W=+qqH)49<7eM|!gakdm9uCWVOyYaYDJ=7-L}M-*cV z%{}=)KyVW|Fg~@~LIln`pL8XeBcRvr-7ylPzr=Qj4m>JYo>PnBZbrqfc(3M6Tw@F5 z%g>8UL}ZNhB)-+I^(ly?VP6&2&znqfso6PmM0fUCJYGDg(8=h^#I(<_RZFoi1X*r= zX{K77{K!@rlH$L3^06K`bXR}Fq+o+0uLZkk9h}CwNr=LIg!hq{u?p*nb6mb7v^G0A zOws@PLJIzmiJl-iP4 z$myt|j+c-bbvwVSHBI%6iA(KoOnugfs(|>siWN7m9wp+sw;(lc>u8@*J>6cYujkismbTH*37nic zT%3zls5xnY-*iu`>265-OY7-w8B53wq~9J}Ixnt&A6Q&H`V~6`bG)P!T_Vryw*YxNW2j+whHRr7kW`6eJTvT>Y%5xEs)2|j;gVP(dV|m zDLmT7Mn_oLzSmTc_Bo;zo2lD;qBVW($T6XPZsrB=n~;zxA(6D9OxL$t&xw;G-nH@= zzw>)mPVVAjkZ$cG&_)PMS|%HX!C@<=3R3XC)wB&Xn0~A9V8@Tvb%cgWk1_A?R-{A$ zFf~?x;wbJu#b6pjGtz5G-)c$T7#C4_vo&Zi)`PvP3n?G1qE{zhhvqGohOJuEGuC0l z9xE!}Rloq3c3Q-pr)?R(Mt8{g2iB9C0D`iAIThP zcHfHoOSuWS=RcD6@3y6%eVz{KK|1M$Aq71iXX z^A%_A4qM1nXmwk%l42T$#Ta2nCbF9Z&-6anNiolk*g%mJ##yXQe0;8 z=}DO=AK9yeNrklHhtZ|mvk!rWygzC~EK03s#iIkX%_~+?&bmA)bFw$RXj7%kuyrxa z3Xut2xoe})Q6~R+E{=)Tpa(K$z8_$WIByaz4}hhb&B0!cNyKNOc#81*^@LqQ-dav|=LHPI=uJXX8U_pAl|+4j?2NvAafQ9@d^fm~awgxc_|fN&i*7$fZPMtxXjoXa z0VXV!;-NL6wAwu0vBe;U2CxQCX ztwn!E>`{fR50}Z7SQ*Rw`&c2*$jJO+p8y}ZEd5MsisG@gz>W|81 z55tBBKF(4E!d-^VUR94>;Cgcq=Ur-reQ!~hXo?3IDqSrealou@(b;%-B7 zsNM~tjlDXB(C?zk@gFYNVQNk`df-^2rb?>^Qq~M?}!L#&TI#!#p_G6DzfAD(s}RH@(_Mp3d$*+shhM`5|8BikQsr^7VSQKB2Xp z;Oz%4RC8z2PiutxOCq1m(N?Y;Iw8|Yb&bF5BJ4a)qDHG}p%E=N+9DUk_zZ{J zuQ4h=&#K_UxuLWUX8f-XCq+KEDZd>tK`*hcaPL7@Pts>67R$A66Pd}hPOYsHBTqKz z@b-N22cODgQzAv@+l@G`RE{S`>4?~W>#Psl%|8HHx3vs|s6q;qj*80?t%(StnIW4k#&3?0az!QsIW617ibsaxs`K<(& z&ekc?$Qq5Q5G!qwYdLZ&&ET;EZ8dIJ8APl?3c|u_)G9kCz+<_6)PZOBnTiSa3~3g( zCv-Jjw7O%5Q7z#%AiJh5=s+~W|9WleN}*IwMa252?t|(wYK<>_dgjxVnkG(OhhbFj zZf7ealkJ{tLd&CXvNk)=yE7)69nT$#RP@X>zHDDt=Q(}g+3Hoh-_lfLC;9?2^SzP` z5_2+TVha@O@xjS$5$NsyitE|2u{B%tZP`UH*X$>_A*O5=Y=1yPht1m$wR4B=Z#dZ4Y zSlM0;!VI@n8t8E>=1%B3^Y^l`vKV)CA1tPtJ9TBz)*`+?JdKSOMi|c}YO}V_r~1T- z`V?0(@GfrCj2>z&b$WEpwq-=y94{IMO`OtfgsLBKhsqNMl}q=CS43FDt1sWVQ)MW% zuH?OWsk!+0bHl+7Bi*b1DYA7^BF zF$Uug$Ed0EWpnvi-bj|{Ij?Nt&PlG(equEdEo@ir=l_z6WhgFz!nS04M7!sGMmM3} zjhU{raa02B*RH*$%%kKt{+KO0r!SE6aX1eNN0*?;B*#&krh%3XeeB^>pfY)r49C?v z{;dsv=_cvrHY`*0Mp7MaAv_l0k*AcYdY)UZa4>AWS(jvuqdv_zcRHmWmC!`HD53n7 z-}@x$+tOLRmOfkE#VUodx<+tKeV0CsSc+RJSlZ?~AD32-&3NK|d24a&+T1~VCTJIQjfeU+ZCG#K8@^C z!SITEDIXNZg53LhvLuV7NFyh2is~6X8=5a&j&vAT(I3B@py+jR0|Rt@twvGRI4H8cU1u**y$5{6idg^c=QU!6B|DKcx-$qZ|~p3IFf6SavtZtHha zTU8O!u$6<43!c=S8K1*3d-g8ZH>5TgyD7#OGvpB7n>7bKGrq6nLn_Vg)yTk7YX%hN zHI91CZx8->!gNQQ)`=y>Q8@_kOg}Pp(43ZoO}rD z4?R6LYCXH5S^^i~Iz_5l_26&~qj%SKL>ik{lhP+lh}A^#D_-r_ym?-ez~*$Gz}ol% zS}wzUQgmzkXF7c`!@)_9E3I84<^HY6E+WLreXEW}PoA>jWeIzW3fBNZOJg_k@!7RR zOaGGngx2;%WXyYA^kO~91ouu`L`c*7?E7e01xcM!(JHAA$|qcbvZ-;R=5_8HSJ`*n zXZcC@6D)hAwdRhw{bg=?6(U=!L&2Fz74Zaavt*1ADMsLKlewZ|Y>vb*@xH&4F$SZ# zxVK>G-6kmHZ&+lqBCj;h;uQ{rMkvqFCw|Rbj)|_xmnmWnm>1eqU?**IpF0R3`nr{R z@xoWR2uaH7UAA$yYxCMcfbl+Kk?cx^$@tLau6E-&Ay+IeW%HCCcq!z8A@X||uMDv` z(VAQCGB5BkrQT5^?qLX<(zk|5ySk0pd2ha?k{$vM;=EZ~29Z|URC{Bl2)jvU7QGv)e^t%caLhN(nsgnZOcq|XokD}4qm zvQxbxn>PbB9NeVee$bouPaIR&=3)b6Rs8V8e0N8fZ;FI_c+j;v_9-mdmW%2s0xQ33 z0!%)r64`^(Ct)*kwXJ%azvmad+Il-QyMawV;;EYNj}l!ee4ZxzdA-@5gx*l`* z*o(?jE=xEG-^97Esjb6K3)BNU9M1cZC_%c&md3(iH+W3AOlVIVTn8-VLd0gg%H_Nr zI7^Rg8%P$AB{ytuOs-mLG3a|ou3BV*(>{Q0Y`mXyYfI!GV>m3Gnw5yTgb0w{zIZt^ z^c}MM?NIZqe)IZQGc9^C;q(?6n+)F50JP+o+M>!`#|{f)q_^%yav(AK(Im)JVpPzz zS5SpVtZ%Vzal?!15y=EJQhip`;#+`OpFGd5-&eKsgK%T2I@&fBr?ZwzPEEaNCO!x% zdAIhZA=hfK?InMuDN5557Pz^?J4~U{3-q?{lkHpATo*Za8tfi!;tto5M5;C*4)^CjF;-t_fh z+WQfw4K?i<$#JK7o98pjCbt-(!V>0{L?PpX2B#SVg4_|doV~CdNW;#3Wpnak@~Ld?@IX}LEtip#XNq ztAM!MQg2W>pA`%HFuW?~R|{d>fg2Os_c0yh9}x**rNsKlewL;t5Ivm`pFPmiK-1Wi zxraEKoW17!3Qw0PyHMlf&vj=-Z|~o#`zT5MHbappGNL-9ZC3sRVyiXqw|2-~lRNk5 zt-v!Ls;@{HUJ{2U5#PG|B^xX{ra;#eSLoK(^kcT{#mt@_p@Wo@G-^)y)TJ@ZCgDL- zHhFADOI|cJ8*~7?^M+cWN)Q_d7A3iyS60P@JfBo%6g{2VuY@qJrG-O8vz;N94wn>C z-R5~27{pzBl=jFa9rChzuw1dU(~FPtZjAt@i(vDXN(WRnQaR=m#u)!9LQM^HYz4XJ zJjS-xhB_wcn@suER5qEC2`aa|;q}mLV&oZVf}fP{5xI_d%trhq>&9XzHEZgljhj@5 zFJeci15}`o#3jIRgM1ewuEXUq)XHHvsQqS>>~w&uEw>3t)+=?1@_VK6apB?mfyYTo z{&u{$AodLge@3~WYf>xOm3Gf1YW9EuOi#OB9 zY8#%WQ}51?d`PMhYggBX{9jHstGl3x^gVZrQEa)<^SP6qxco?=ki7xZRS9-1pv*^J!u=RE5Snw|Y*E-LV0o#s=g`x@Joa5^{>~y5V_JdKB4|20u-&-7OBYpSXI*C3 zZ7!OXu4yE8oZTgSDYr@YA<5we0l`hb$UeXa2akh}`GtgToAe?Ugomr?gSI#BQQikT zmUnL}%0D2TZ0mY)&bQs(oZ``iaY#}&A&^xbe-kzo@!4R6vf5_5r2?=HyEg90TGBI+ zh%0H2t^q89EVR2SqGNQFy&MHHdfwf@+5NbG8PGs;r5RFH`LPVh^3KANFA zl+h4~ee%>p03m0$Qjj|so};dznTp7tWr!Kub7ddhxU-z3jNWUB(yf@k=09wgok}Zz zyxh-GG|5)Kh}2{-Z=0#7u9%;B+Qge5un>Gn$ZlmPT%e}Mf6Sq&#eyJRFIF_t>5F(A zQ+IoWAur}edSQZ_O-&wBL$ua#d42W^&&BTwUeBKQ?R{or2$$2A zVqy?fTynZNU*UuRd%yk*Fr+fD!P^@)rb}!L-KzQ~XdY<<7H{Zj9O8{lda`mtrZlT+ zG-jU}-6Onc_IfFt@>2Hk!>J#PR;(4DR;h)Mrw2VQ8I&=^)>I_7=+RlqibGae?o@v2 zmbv*p1}UT@t{^|m^s4ce?d;crkM(pRiYZ9#l!fx5g5s-}6J3O}Qh^IajKlKhFx2{6XJR>+Rai7|HQ0_u9F34r0o3f;OS6G1cVJ^EwAdWdqnEkBgVsZdw=? zt-_D1EGBIdq-j#_lzKAVG7s&b#I4I$IoFc-8a*(?g{cM$Tgj)M>)9}wC@APs`)#kq zy0hq@wfy76N~igI%DVJ4m^o4u^J4$iz$g`pJgY|?*BsCYEZ?~XL&%4uG?8Vq8~*6l z0RfbrSxptEgsgxZWjd_@d?T5gLMBH}0 zMPgieb-}KRs&$7T;oIFdVhSclMpN3A_LEsJ6<9{J)??8JLCvx5{HSe5^5{a@r4{XT zoldu57&B5NQzn#Q_ns*B0_|js}3fSn?p7GgEbTiXL*niC8d|T_4jlS z=R@OjYVM-#6}+Ceo{7Ce$&O5s%T#xhiqRPWV6M+J0s%V@g?x8`G|ESx^(mjL%Q`Fp z$@up2$eGGn#mlN$PS@!H(g;5ehh3w+^uinB;?Llx@D4 zyc8HjgA_$R#0nNqp3Pw$&Tv+GH}6}Led?KAy}6#KOQ`J>`CVp`s(m8t&QS0TVDI$1 zSRqqii(BaE$_4v5CFzqWy(C57EAn>Mp6~YG{2nkjU+TvPXtIB|70yOpFjuhkiPC@A zt=?TPLx|ZsT64XDZ|M^ldPUwJUC!i|mH;*%reOq5osDe1Oz#P3l};^kSyR&PAg?mj zx-5sC-_?T4Ej;N+n=265v&fs~k3;Sq-8GVD_8G0vSY0K91V8`k{vgr`0!~=$gW_+Ghl$KA!PTgrA7~nv%7ZX}gm--13b# zskC0noLqNBp0|T8F@H8EbF1!PkWPaK^Nh-G;>>wxFC+HyxgFuNhhIjT%U`*WT(M$( z8G4NmnrD6SZkxNDi6@%!4yQw7)vKz8`VO@W6QhkPk&!{9Ow2g%H&m_zOROu^5V00j zw(G4@N@`Rl`87?2>6P#y;!Z}ms1)Bvj{EVstbrZ0St@nOvq9N6mHZ3a^0%KE$3)8t z9UskNaSnBoEQi&*@B@oMIDt-H_j!9daO?@QO7C{ktIba3PP-*vnYPwjNF>Tt!71~y z_0Zk951OKStxJdglV9}`$4eKV$f4?3Kf;56cZ9$=cVXr2CHBV+)t+AM?;qT*?=_E<%!FLTGW7)AKGR+Ocz}CgRg7o)Nc0& zf9ig5+0mUmuMvsC=s57)+BQ8qo6P9cUUZ#<64iL%yd9A~x?6{u!}n!bYNCtTJK(MfJC$g_40;0vH(`-H-q!bb@}E4smw$tL zRF}MY@R+taXg9Z>U?ROG(Irsu;-_oeb}&ii-MNPd z0=u*#Lv_TDNyk0KJIhp@MRBQS2mY3hD(DSFpW7OBlI1=Z`C)K3U-|vGl!V-X^Lki6 z>w*Xv+Mu{Y=(6K)Y*Qy9LEmtu_CsFjP_bN{pMb}RJ|JwoBRzL83Du+0}rsfK!IY(${O) zTrM7P0byyV<9zC&W{>%ioV-zc^}1wZrHW}Cj;!x6&w#90@eC*5t+wfw1O4-+K-?A! zVj@tiOkrF#g1;wY{nSET;HX$*}iF8Xu%`B15Vke@WdswYzt zXAhIEknfYDpFu>}JTJPl9>{h1kv^P;6oMfqo43AULtg9*p7NLq%?9C&7)A=TE3Wy+ zsGbby;us9s#_J18fj?Hk2=K;D_K#a~xIETR)D*k{n%`piPjAMA8f|&;e<7_IGbdLS z`=a|QqN%$=-KjSsMfIT<1%u)aRb+JftVdkJYGM?txu>j_Z-B+qH50Al_QD6%1v4{_ zadY;xUNcO^ud0@plOVH-8r2U9^kb<~WeV=MYShE!T=<=e)-%T{p7NuYn>ZsmSe2&d zZ)r$JqIE4;3alF+HgDpKOxEV%Y5BSO4m65-(1o;ED?t(Jc)WN%{5HE*-JW|So-Z!t z*@9oZ14f!b{&1&FWw7;5fJF+68^fX2b3@Q=iLBmK*n!{}@gfa`Q*3V}hP}^|f#R(*?Q{-{fx2S~?M?wepDbm;ltE0{H@R9a=DtqIC z^Y;SpEZ-trs!;RJM{@=CDa%!dTmftkw906U)wXbBY^ps#^lK|qIW?1A$do5kUJe0i z^1y9K@F82^te@+%Qn#(#fQEJQN+BlgQFm`U?zbP-ua%Sccr!{Ww-pd%dMz_H&0kOI z7on@38QZp^2%(U-Fkql(-*e_uilqpM45yGUeL&&WHr-&Q5S6I8UjIpFt~dGhs%M&D z7zKr>payVIo(&pp3e?L&eS`PMB+r^6oiojsfSYX{44H=}1hgBebs z3d|vx*DyYT!G>Wa<-^$TYl|`^59y4JPZXnL7IOl>+0D(o-#;!t9VVS3WM{3*IO{x5 zw~CXIntVQJJoQ8&I9!gsJknNFW-jpF%Q5G5MdTLiU~Q>}25m)bH;k07G~wA%;ayX8 zsC2r!P+0EpScKV;_#^)!puz!jGFQ1gf0>A;l<}tORfyCz?FV(Xn^@bgr!xrL=^XN8 zgWG?fJ0Xm_f(~;{kM6hH?rU*rh%*zekqJ$=m;n6=tT*vY$mdry1RM)uI|-%pOM#DpCnYyZf@^7 za@Rtn&ka$vau5SEbb^_mLrV$;<;HC9jd-uwuZ?$Sm`@b8Mc#mzYv4heuDKm454P#<+E`_3U+zb#?0X9<+Da;lJcCPCl}YmowGv7xj9x_PT`1` z%xRMgJFFzue8G(JtXJ*pGOQ2r=^+Ik&X6a7ym|aF^}9`HFqrTMGf_|bllYd z_vVbOBtOB8I>h)+RvPlN(N7(8lW)nlGC&?8C#ToV2kj??yY)LmcmQGYFp_u!NRua9$t6? z;CA&(D>KSxM8i~7?KC6qF(DAlVZ2p(eL#a-6ARm$_T}QOX{*?oH*Z)HKpYjEcvG zKiNn!*hMFR6ka2}ti@YZK=577GO*w)EZw7A$R+sH`$PWv9tFDOXgg zZBDcZce7mbsa*JB|58pp4Vbk0&Ro5h9i#1|UVZx~u>EsTId}K;(SwP$EJ##WpjIzS zP>wh2J^hmrCcYP0UDg7a$~zY1anQl3YN~bf(?}n5(80*2_|)+TmWz{{mV+nf!)uQp z(-a(H@fLz{0;Ke6&jYGj3VoQu)w9Sg6@0^ZoN+IkjNF|fDTGRi=Y9)0tkXp^rR7lM z$uu=I*cQ?7CvdZ47<7-Wb6p~za^4w)&kbRFA-KJ|jl**epY(uLRw{A$_fy^K}qZWr1VcNm!nD%i<+-hw|1&S*%f8mT}>Hb=&-b`(xG4U^;lX zxO-X|mp$CwVfvoJ^qIj-w$kZ}&hcaRf;;@8P|Qg@RTh8I6HXSk)TXvZqXQtS*ts`_ z%iG~5v6%csT59ujj83JShw{NN*=Txi^OeDbqo)w$KF>3vf)~Fx(`f~Vww72(POr8a zn@y-CD7f_(Y^|+Vp!j2&^M#M2n+iWKZ>o$}OnF8pUS{za{#=VrQxZZ~Jt$P=$jU6M zBA9t=fwaEGU?|;)&JtVedr;m}*<|}62U$BRMN&O(Ylo=6p&z5{a(lrnYUdd&v9c^W zqSoZ|%rf^4%a*ddOk@~o=zKgr zAjNpw7+yhFRg@s#>IG_Y-VmsvaEal~PmtbSJok^#vRt~N1SbWa#*aC$Mb%6-G!PGc z6&-IqE@r0RHO@O07d|4E7d?uun=!6S?~&7-`C2zdrP5nC)~a{qT|V|>oj?Qq2Zmg| zDkb0anwkODkv(SlxkC87liI7`dx-gx5XJJ176}8FyEPrr-?mJ$H6?kJqP}sQufdgZ zv4N|blMK~raRo2cf^YY}?B*cvc>awjUZfT(Ju?kwHS+n+!$nrgldkO)93Rq};T|UF zwf){%=lu_0rtysJ^>CoMRYIDw|83OS==%F-kQ!9eZ6jx2L2Pk&Cb0%JpVtV)eAz{8 z!~U}c`~1pxn>wJez}$Y*#HA4^mqQf9gT>I(eLGArtK~D5Y?zDm@sHEp!0kXK+}!y- zQW1xq+H%(G&|lP6B9j7b+Ln5B+*O9d6fMT2FU=N$UM~f@8@d|1WsmXL%vynrJfzkl z1`cS==`c-ADnr{i zZ@xVt3oSp(JCn4qlYf09+*pp$9vOMyM6;GTBD^F}`dI6G%Gz6xcU zX#T{emj~5(ec+*0432{Lo%Gy>6{DU5iG}Izk=)zc1&NE+Fq!n-OU8`1c#1N6zVV-@ zojmJdjluDQrgJ4%3-%Z~^Fe`5o7XKLB#);t)jlMd;Cez<|}odA4zb_ z2CK-aESQXkKv(L7?t?b3yMWi6g_;w2*jM*bHSj~(q)@s@^VXWH;=FPFEx=fCOLFrg z{!zPjEiZ+V{bEYh_3;W_A|pmBizV#SgvVG-OMl;N*nS)p)$tSQv%Ni20}-A)(bJYv zntlF?dK)vOR4tn3(6YN4JJSmc$rW;fUa>g1dTgr_LwV}*ik1U)@q#ha_52zO9M}?; zYcYn2KHt(m+fSEgGn7(J^^v__H8bE&*2Z^vjLj|2+27iw;(EE<1+Tc1i@3!2|&K9C9zqLIs zr5fF$b_Nq|Zky}=b9>xc3HKVArFlO`n{ByqClX2I8AX|071`6aD`VY@*7k0H!fs)X zb|$Ct50JUFK$yzfC1kz6YAdo4v@SB4e>D5{YN{~qu~TRAC1ZuEJJZVvEFNtIO41n;-a68xGquFvp?8TX|2n&qyM?PrF4^+P{JPuFW@^$;YcVb zSC*9$doN?Z!?ZPDV;q#AfIO=auLsV5ufR!0UL45OQFa`Tay4L@vi?5h(J1FrGQ$XQ>TB5aD(p+0cu%+8C=7k&cV zikfRf07J4>X_eQZE&`E}bJsJNmJk{B}P;b({R1Q8Y0b+BidbIasc zz&xk)A8IP4m5L@~jFg~ur^?kIVF|Af`p+uf6}GS`R_!7+U$k5o%5Yew;4{Zng2@1# zmA2!}KOl~?DLChN34*p>c%IfRGA;I)i0`i7oBE6cB&pD=i~-vEdOM%ljt4grAv-@D zIyL%2LD}B9`Pw?=Qu$;UDvQX3jPEkceUR-DrY}R3BoKAwi$tGoEmQJ58KIRAz`jWM zof7P8H}Y88$c3r(-7q@Qb_FisDs`;_y%N8~xUp|)v9a({nXPmilj@H34^rO@JXtz# zZ88p6$WQ5FsWhdptlmeTx^+ID0K(k1Eb4sOk8sbZQ3u1-@4wddc8(!{TuJ-hgVuvc z_tO!XHdmcDhaGd9m{C4L|F-JqpGyVTzlLQv)J97O9#>CFDa?(Ck$AIxAgWndLToH8 z8UyQw`(&JKet!gwENmJ*BYyNsl-;E^FO5rCZL_Vq!m5j7vY-I60Pv;t`MrEJi4_+Y z!;Pj`d_cUowY9eR#@uo-WF5!j>&4 zjN?-Lq^Ho#*ekcwjGjPEsUXo0CvRGhE^#z*28i<}<$iXhVXo+i<+yEaB$(|YeBkjT zmQDCN|M{0j{@Be{lrqx}2KV3*qHQ&FNdC zu0uK%+KF$29cN2qIikp(@A5uMxTZm``H<{78}Vh6JTb~oObv#`d<7n?GOs>5h?a4n z5ZcQhx!5YOug&u9JlgrU1PBADz)brI)C1+DZTt(O zP}=4?qqqWA<^1KCZlih0H;1IyM9)d$E9CkC`zd+uJGlD$0&YQ??3O@PjLp}o1?|iF zUaS>`k69~b8>EoGo$F5Rcnzv6Ia8mx+9K8!svEL&7?e|8>=bps_LuXYlyK?4(2F^8 zmzmn=Sn{9xn109?0_V>*Rkj&(!?hRGc24@ws9r?lOrCr!#W50xnL49{7!#sFJe2`dEGgvmN;Q@a^R6n^zg$x9_Ck@$X~*_UUFu6ImvQ&s7)%3Xru#(;ZX4NLCYODTMTdh&C zmDY|K1VxD*qb;>k)zX$4ReOuQx7djlTVf_byx!}*-p|j6=gWD{bDeYF_b+#G3Z8h3 zrX9`)l52`jrOFHn6U?ASz_-`uY0|WyoW&CE?oYo8CF@V;Xq}sO%}a>ZOMc3aeV2%3 zkWJNDtRkQ)dD$r89cpoJCt!Q=f#qj(`8WMbmV!SVvmlhLMmxp#&z~uGik;=_Z8;rp z*SeiLzBu9jYpyNGgV$dRwX05k(lh+SYO`{gd8i&)^&Ur4w zyvJ>Gt$xc&&%T&T;&^J{h_K8=$p^Tjt#g~@4R9<(sB!BcC z+vifh(+Hbsn|y2_nD>3aK0)0|)YX;WF}zUjbUEjbknfw(c%kM^+DS#)U;>N*Zz9C*II&wwzd}2hb;ctM!;Qe-S#LZZIV0jX8dj7DnfkOOw6J z9)F+{EP?)yls)I9Or>|h8-oMZTJy1d{LK#jQwK=IW@dV?m&`R(W*ZQ(T<-z}tEI@l z)LQzK+_$}@7?{X+;X!@d1KST@`a-JZmA~U(YG3u@zUnVxt~#{Z)=7CcVNYmx-v6ia zb^q}Kn%0c&T}r!E`R~7!rtc$3UjbWFB1SIdU6B@F#EXNY#Y;bl!#Q~q9)%e;Ryi^G z%em0C+~wxs=t)Zl%8E+xf)JXIH#@JVu*PA+g9R+&^1NtBtGTit`!V;n&M< zoqX{E@O1DnLD4)mz$GSy~d-h7M{gY5u}L8Ow_W`;1YtV&l$V7I*g9W3H!LbVBk zmMT4*p5CokQy(=*KgA`xJ{K>dhq#6)?<%kfIoz8+B1+8D#{2e?-sI}cZ>AF5Sr6a8 z>8!SO-4tS+R96BUXeX$v9JUFk%Y#mG)y5Lydud72D(JJ-XEbaFLXX<-@AxDjru6o4 z$A5%`?r6uPTQr9Sz z3!eOqS!bffl_ObR#pP*{XVQHRj-p{XY6;ij+JBNk`s1wqz#tFFXRe<1T!-XbbUf9% zH>`DlN5$8pU2`a(rvoYJ5+K#iN52SAb|J;qRj|dobYNkC0@p*3cc%}%tXnCm*y~%L z%x-(nfd6UJ^Gy70_+N^uqwjh~X$8K8Gmsy^-#v&r6y)jX)oV;AYW|d^7wJas4QZ!ELTxkazZ(maq3!W4>pu z{QrSKWo#a9K^#{(YI*8$&sHl=?LyYv9XR%fUim#w+4|n1B+jg#mY(_HnXdIBfLWr+ zB5G0Z5PLf45(=aC>Sv<;dLaXKAlbT25EObgt5lSok?n%23L)Z=~-pNyK>e3q1TV=_pRHnSps zUwhu^UM5b6KdEoFRdR~r1S1k+&SFlO;crg)H^rM=VQzq?iXb*g6;o)`lIk}9oux`Irfq!}*n*ON#dG?ruwxCc&7Wds0Z{=nO z6JZwZ=7F&1an6euSfp8LgXfMf=iX4{!+z5sZ?`xD7}g1&+G2caZ^W(?6a!|Ww0~1y zwd79n^6hH=seWu>J+&o~i;Gi(2H9tpZPW$-qBKyv=6T3nZUo#Nt$EG%=Idtn6qTSv zMdP5Y#?zzV75qlXhROWO#r%fqd2Dv7dx}<lCry^PrPgZ5_Nf7BKsY3bO$dkPb*xK5A8IzMfCIP@P4`8Ufc*< zLfj|75BdVAbgBlutusfz>>L9WWqZ`f)+;3!PtPaxat7$PFK}PINS%B?*V=$pdAS%J z@9jIHw^#p@ZCKyYEPgCh?I!9}!N6V=fkYN0gX=^upNPA2|0j`}or@*HZUB2sITPZ( zd+m2SW&(+#=;6mPhMa-}ZXEkv63lr;`sELcOf2sun_JX+2M!AFurnC??(72T5ygVK)_1OLRN<{U3<#vc2uYE269O(Qa-M z7wSfVGnTMh&{d<8=Vo@Eioetp+n>2?DFl2Fw~ST~yqUZZN6n$d(0|wwmv6rZ*9H34j8j~J3HR#}f zb|vZ+8&*YchRJA&2-MV&DelCL1$d;%H5#;EoW~3|b z`Zb^eRez1~A`(;4*fSz)yd!4x$t`uxfY(u(|UZ#{? zn*Ca0b3M$4#gIuLLY=>4ter@$4LK81M{Jp#LN9GJBjdbsWK7zywf#tEW~Z@FeA#K_s(|N z7nmJgqvjN({>MDSb?pW3R0&5yLxPU_vQr0x(rxG3uBDmQf($OYf5bxGE7HsTyX84~ z^g@D@o^RvgnqOKTO{lOgF5yxo=E;aRbm49ZDPS z7*fgVXVC~sn4>h~YKJMOYJ18=wms#qBOpc=9T+#NN#lu%gH@cZ`XV^-?Y;=(Y;NCq2@JCL*|G%%Uj_qKrGOw{w0Ng*9A;aq)&uL1wflidST!1Q|} zGPj?g=S<5vN!ab9o74tE_7@?an6G+hx|N7Ml6Wp<6PLl2(&nF% zqxdDcugdGM{XJoMe+~lC z*%%DE=Hp&@fQgJXS6S>d2pU5*2G6XH$y8ul&21~utZFe0*IkjYDl)F=b1=_A^=pXqFMq8=nWQ1^;K)j%6#x|_8a!SHzC0~fYEptce_NqU8PXmkaO7n*1FFw z!rhvh{!yIUv1&hkkenRqJREQK_CGkv&LiV%`$UJug|U>VW%1`+b)<=T`!X!{SIE@q z$(KwR`OgODF(TZe|3LHRa9ezxBCq1w+sfju8Ple_0E7Kc8xO_q9$pvcRi%=RrM-Ju z0_`bnA-)F+!BcJ4ECwXp$XG{ye=O{8JJv2A_MyYQtqSGhoa!0@C|c_D3x?Sj94HJp zl_>-lcD)Ew^~BE!$1p+`c%FJ*)2Lb;89%V7O$zV3DV#qpDu|3dHa@n%{p zRoIsw{Wx(0X@bcoeU;A42BG^)l|h(^hIk$c*5Iy*;E8s2;Tq8j1&AZ!cHnausMk7c z${NG)#xCdk7Vi%fo%7p{pB>NRhcJ{5+U~sG1H7rJ+P`SYLAIJlH**KRCvH7_>9@dN zlAr@;Oo&c)vDcH+dkz8{q78Fy7#0bM~LZ1^a==Ra6Pd8+bDqd#AYL$-khC# z(dnM@ut|zozE%8Pvx>MO;R2q!$o4SS#!Qnu(${J5;)$JhpHPHLY34*o#mC*|P=Ey} z6I0Xvb7qyKS@_Ab05UM}XJ!oeM!ujTI!Z9xF1nYn2n? zyML{6Z|ga3qjB3gOf9Cm$LDxX%(sVDmT2QP|KH3~zn=?7;>fREo}mTx8pTj~h)V(~ zik!h{yPCTGA`dcE`+(p|R8D%h#?^mm^HW0`Lo6}fLcliR(vA8(yDkM4ZiK&-O4rqI zn|V0LFzbHPmFf>q6D$YtVFqQadx!l#_dM_DfaOqO5OVe}Q z$PWp*&ZMC{?M7&ioyHvF#SUc`ggNWn#KN@!Q-q8_l%+UuK(qWtf)%a3Pr(G z+ur|*%2FQo@%ypDsg`i}l0T0?uCDg1ibA`k+b zua%++XwzDHTyGL;=})~MXOe)W(}^e8wW07+xS@N~$)ESUy;VsPXOx|jE%zOzi&o&1 z%|=@4Ma`R)>`v$%!}ohC^-Tjk9}oZ)*S2DsvEouv+L`*3%j1{)_XoZ&o4^SM7{_A@ zxVd!MuC@C(izZ$Qu2phD+T)?z2{&}_g!=KA{1b~~b_rWWK6km-KB^zpeOZ)$sf$R@ zt68Z<2+7F1oE5$a3(|(NP=JsHqwX;`A2xHGeCG)SN?cRxK z{YMAs z7nfxQOI5 zIV=hgnPC2r`=>n@G0Kr6lc)zaU-E$UgI$80{!(#+KKGgLqn^yLwi9x?^p~jP1<3U1?pOpTpRr4MMwJdrZux! zp{8VoqV|*B!KkfS4>+1rl(iSn8Tv7)@zcA#l=$mX6XcUiHmZMwc??#!v-Z2Qq_vFx z*Tnb-%LBB52U0Gk$C*^W>*E7BJV9s2rW>-3nD5yj-tB{yw%9n;{1)cWJ`$IUL8z~*W z5-AO|R%^Q1*7ssLZB6zCYNU8w&T^=S%WjjrCBWscQSI`u{T~5OKtsVArbTnMjR38U z4V5A+_sXR0Uo*X46|B5qgt%urv!vJ$c3Ut}Q3Rd$CzHLl6Oxq;H!w)n=HRoy&h>zJ zF-vbQ)foRaqsA#vi;YkP%#Q2_J(+x#68;!q@|XH?g`f6mnICMw?&XuNeelK59#6Eh z=3ptf$SqI{wR2loS(x-=C{yg`i0Q@I^JX;^_6!}#Ss70>Um5;~pS}^sKAV(IJJo*F z>Y`ZZPNo+7PZuq>E+CSNmus98**Np#E;<_yPUr z2>pCtO5x9QD4vGbk0O^+nzZg;FLCY8O03FcBk-QmFp<=#%omjRpq7cduSTd z*=qAd#N^&(7yahmj&LJ2rO&C$>t0LW)ECK#1DX@C6BJOyu)?`le5gEdgx8;+zOaMl zT?&z4Wo)LX;EeRmwBGUbsxU9zBBQ!rWy=Y8=X!Z;`>~8@?qNF}#WwbbTu*X%^)F&lz6({LcXMrbj5-K)WeURT zFHxUfhu8s5rW|^B+?-g9&|Z)GBEg4UgUH*`0AGRYPN!c*EH_^s#l#kCq3NalA7?bi z=S=x8F4n;$ivJjH+T4cY>5R5O`3b)cVy^`)E@LXY@gZ$D7NLN%BzIauVG>r|*9@Y2 z)9zx;i3d7SAJ++l>G}X`CJdQ}>;0}PhQZuWES8I>AH4?9=H9v&Z)-L`$%6PnAG6x@ zg(!Vl8+Nc;_G60co&E8Z<-e_;TL!0?i0jA;>8xEMIb2;L9{naEjn*TKG9_2)56{P` z6uYEaS6AEQ2?rL%kn*)*PGCwwi3tKe<-K2qOkH{tp1|#Eaz=vbt^kY`)iLkx#cpoH@@m zvr);!H^Md-s0m|XG7CZR}O=p3a_l1AJ6@lRwqc?m;JIjC=gzBB94r! z3GgX0;D#K`1gQs|0}WCAJBMl=xzWN^6VZc;mr!ic66}+ zU74KvklRSAN!XAtDzOS#odDXoB>s_7Z8KW@rD!tc6l?}s=wX7MyDCa^tk4x;GJGU7 z6eV{r-Xf^d;~HUUY=5ok#p+8T2)4hxCtkgt`cm?qE$*8piWTY`ca0xt2gvLJS}t0% zMtYqBOcT%)^qEeuRnv4(jmnd`Kh?hW+S$R^{iHw3J7O*t)n4?ho;5KHp?$;-<)n6m z56Q2fJ{#vBa)cLCyR8l?zLsxV3V%6Vf9y{KUjD+j)*lAq6$|0l*xFPYDXRrK{Mi~8xMA$Cti3Og_Kijw6%n5cLl*G4@U*Y(X{mG7!1=-p+6}E1HH{mGvEzn> zO(L3&d{D1iK1u#kP#{IH&AC4(i%)b0;hNu1s3eMzC)GW^Y8zNc2EQE{D-!VS8jlPn z-Pi-thR$}0=7iKpPiF{-i~NhglvOdJ4C#DXbUOa0p`m0z4ALF0qlN zu3sqs^ht$2W2Wa#iuAwF(_vDTLs{mucNpUFMbwFxh|zxyTc;Ux$A_cXO)KUw+>}0} z&V>zA&evZV8kp^Gb|&UeEd3Pddit5ohdUzrI^2(bUtiFS4EU=rjRojf)0tZjhw3!$ z*8j#mEM_#p*2{mjGV|;=AK7wX$Y3K4wsZTHN8}k>A1NATu=dMNMouy;BNZW&HW_un zrJ={FA@>#@XG53q8xlLWDqbU;ki}F!`oH^FBOI|THnvcXI<^5-Fpfuh!PncFDi+q+ z!VBRz&FhL82d{*V$qLd-6rEH-P?Za=%hJxEk!f?o;-a9(WVl#lpIpP53Dt3{ zlCJkb;OF48r`z3@Zbyz;{wQq;nm%jG8*l97C%IPUTgS$8MWslKH?i*xA7%q~pPG02 zG$ga9%c-ICZ}xSjr1kSs8-&OtY@x-H=z|S|pQNdU%vsZC3@;K>F_yfHmL4{@mbwO& zo{tTQYnwcr99mP|`Gj;!xtiS?N*^8sJwN?-fUz#CMGSQ5UOo&UylAwJvN_Eed3cH2 zhx7N$IjxLMCPMPe`faL+3W#flE9k$0*qjP1=~pAU`FBFvevC=O5`Tg7!UDd|E1wPB zKyMY`^2v|z)TIwdDUflA)*-Nno57u^%CYfu8R{B#C)NeNJ*mYXA| z)QGFYYf!$40dWo2swv`~Ye7isZu+Fu>o92vPd|$I@l^FkW>?z%Xg%W` z6e>9QW5Hc^$P|*(jlA$u0NdW#(mJ3L^n>|7q#KLb$*P~cZ7oeHa><#+9rhlT>Q&Rf zaaSWkszHIa$>R)~^z+V1Mrw87XX=Q#zPN>!)bXu{O|bh>&s~C+aC{@z<#`bH=Fc&*k+q5j`?U$a;G z2(s9C&>|Rwz7B<;A9dpICb6Bz$fZ32A2Jd-{-x-f;MR-{<`25_TsiPpK2$`1ov_~# zExnBs7fR4s{hp*$aj{k=s({rcZC@W8Sfv9$)K}!~`e|HK{dNR4h_~A+jTbSet|mIu zEiQp3rfgCYN~NzTUs16uAr3~iDwxsu_}{hCuhagmsX_qg z+Cq`gXH$H>xQMvMgg9Z4@O822lT^c~HeorIo>$eQoMJ>P=`yL@Maa6_$E(!9`MF6E zI_*!G_@&MNBRooYoAT?A=S|>IZQ~hIuz_?$n+VL9cRnu6J)Qj$1mZ=7XE>k5Rf`-6 zoNZOE9=--lH)d56CZT$BBnG9RIHU{qYe^CN-yt+Rv-#1(ocpaGk~k*HrzIe`klX zpjs$X1!95&$W6Z*RI!V#e{8F20N|xw=?8foMyZa)ne!=!y@HMMZ)u8h}R_~{)n3Uyp zHrrp0n$h>8y4>RYfTPHPw-SCEBgEL*FHsL#4d(QH>C(74ygCy9HLN~z&&=}*d?$yU z3La{<(!s-1w5%DM9y)tmoiNtBuBV{Kf?2{XWM(R|au%*mDBc$TZYK_?2oI{#m;Rd^ z7AHF5PFIdsFvE{@WUy{h!*n@Em4p7CywRPm5_Rr#pkT(W=CL1ixQ*@TfCJ)U!SGeT zk`dduhHq}u{&r2-RV^JzDY+smTa1aReX%R7-7Ke|DaX0L6|Jx8^fycQE<s0cJTE~gs3x@}e4?9$D`{)+H9^C*%Y= z);9pWV@dd$ET@o?Wdn(%oRPi}I3W~(z{V_z6>tgp0(Z%=N$F^!%_8i;1VW+CkYkZ;y5m(5-9@i| zHBN0N|G-GpO}1@Ktw;#1s$v~XAl2>2otV-I;JtVWw=2_#Hcs(#_uQrr=Yly4WWBQS zdTW9YVcTEtJK3?p(#$Tr*tD`#Bfr+o&$8A{#G8`zN%iaTuUT>%-D35rau_JKltN)? zc;LY*Gw6T&8bypj7vEa3(nw ztVbcc%De1EUZzfe+g`@Tg3DU~DxiH8>s4+?Li=>2ut8N~_?Sw~x{qedJ5PS3mWh;L z+l>Js*fZjU!?b3F+|UlLSkAR>3RUKn=CP_+QFS-V8QQt{6b+H3e8~Og3n=qq%&4QS zV?5m4MmImBD{SM~2qkf9=NA)Py6d~0Vy|VK8gKR*?-yc1XFL_deOI?dDiqbO)9#-< z?Ryei!S2W4wA>YPsMdhr^6^eC);%mLJG;=#DB9lfK=2v^%-;P;i!Gb%w;Ml>Q6by4 zoUEbO^;EM=n_n%MyR~BI z7!iAJhZpjQyA9`AygNzN{+!tY4Di^$rX`g#sg$>x>l`}D6m-SPDMSCzx}Z(B83|pa zpZHcexaN&73%z?xob>FMR*8^C{3Qke=<|4Ri#PHI{S2<>7xc3+EdRe300Pk)WRKqfcXzR%gy~o>Mk=TBsai?0b zWy96`1jAX+r9ND)es)sl3Lg2Gb~fyDCe!F=X3;Sag!W>3_a**EoGs)?H}PZKoAo&P zU#BYUwvpX(j0Hj;R*_M3Ip{Fjho~zp>3U)}!@`1}U+#IAnUqeVO$8L5`ddz97rdK2 z0tfCKESFn4Z=KQ*;0d21FTesLdIGt3FGqMs|6+Izv%!p6h^!nz2CUwi6uNj-fj&DY z#{+xQvG_LMZ!=r2BDuN8tyhuXq7hh}%7a5SlxZrvG}<%TF{P(>PD?~kh{;|`yBaFZ zk&W<(P9wjv;?4yv%auhpYeM~(#`3{@k@522_0~^~@Uk4BM}P<3L`@Bk0p#kw4I(V? z3;9GPaXWsy9tegn$cU>U>WE|Rv`BZZUAfIR&Oj3R@L4Q|B>}n;zy~2SFqx8)Aic*f z)^9@HyE{1`E zF2Fj7QA*~ta%2CQAw>56z#h0d?mVQlZFTk`gny86PPcBn%$GPKDfHM_Fzz3Ys~ zHolZ;=`lu$S8)F}zg36SwE=u*`T90Dd|0v}a^+oEc)kR_sVGUh0&@e< z^q8X~AKFF`xvm6`gma^X;-pm@5E`<|yUh~w@R*HVAGqvqNYO4%)RD(qBhz-1RGE;U zZarE1z3M(x+H@c9M$|%sk`OJ9tLYzV-*<*^0?Pa#vx02=qzu#Vhi)Uo9@QIaghBx&SkqtZm}! zK)p>|X(TZD(qvby)7pNE>6M%9d68^>eG%ek zg$cl`Hz_!2V;QVlLRIMoTL>85{)4G6;^uBs^3isd;75AFvkVcCRvfK4NgI0Nkvrj6 z23JJr$U_1S1x0C_>()j{zfI+J`e09fM4O+u$3i$~Nbve5p!wU5#dTl>JO&evR!|2k zv)AF+DHM+2rIi)__|1j3C^1ik)@Zzu)!41d%&G+wHmC3Mos==VbzUNFIGfPist=%b zcz;~zpO^gzaVF(gOh6Pvq~KlIE800%YLVQrwA&<(>|%()u9)m5nIZ*&nC>5PpY>nw zvI>otc8fQGR^OksOu2unJ~GBnQ{g2&CE24Fps6Ph3bxe=l(!VPM_U6uHQgnppaql~ zEM(JUL7AX&GD%8809>+aJ@P{dv$UAgibj3$euw#>iR1(?EVfyJgih@i%`MAIG56+! ze$T_l-5nYEFU>ogSpTXG*by|_8&hjINQX4{ta4^i+e%_ZY*+g{`A^2eIB6x(0mK{2 zw%ou0TyFNl+R~DU`$5^FLtbiSK-=iZHY_M9RY)DYeK~voU~#3R-$c-MMK|~$wvo0j zKY!+Ugj}PlqAm2*1f2(#-e=A~%*5^;oUVnsZ=)eZzqVel>c(>Ax|JP<%n9a3F;m62oyB_dXcqJX%GHM~s!HKlz%qrF$d(+O0E~zX|5drT;_gKY~lEUMQg;4qxBF%EH23O9N;tHe*9L z#AiLXOxC*nal8jxDVcO_XU67yBkx=4;@K2tr5@tjqHS4jIzjI{LyB+(@*5oKBkCyL zNCfY;nHqXDpL-8op6`|{i5jPo1P8v&$gFW`5qEnS@%u$Ql_ zv^Vv#^ejdBN7LSa^1)gUuHLN8wxya~WIQZw@w>5A-`!c)fJ#H3tW}zSU*Ke7GzzzP z&zEZkcw~pQ*&Vw9b~#M9+iv2*NYuk`TE?mK0m_gqHCmBctKA#c3(V*_%w=Q<_ds^% zSo&(5Y-e8TSU1uDQR?|RRm%;2kXQEJ zL@MAztn$fb8@uxOzEgyiRohE`XrM2Nin%o6kLz;#tQHE)(2wJl3AV*|6+npH`tw0o zB`$rQ*|+Tm8Ue|?F3VveKns7^UINMw)-NnXUKiURW9bkCWbdZi;M@Bh#5c!X&TuBQ zu3mz!z(9Jb6(CM1P5@Z&TVPn(!FRnU|&_SYcTJcMDi*Ue;r@adSlJ*yUG0smG^?}(!qU0w_xc`TQ5eR z#;?7=h!U;g*7plp7T$wwxfwq5fR%aSGgyULNeC3I^u_VU`=#Xknt)(}^%$8I$8 zf(<;D`>YT%YeX4KOXqL-yDi~b^UHk(#nMk{(jGK7u)12nzNdXQPe1(pYZN3=RZmJwN3%A82XkR5T!Zu)E`O zEKQv@GjSXQP3={3lS1p&gBHi|$JQh4{xHSW?D?-jf0YM5hiIqNI(sav4y2+F3BJ87 zE%cn*wB~PJ{yiILa;Z$+a^0^E%E>tT)PF39N6|rtN^0e|u_IW6!8>r%lJl_SX@t~+ zJ*V%o&J2N$gVw6ZbhOX8oJ`B_-0KfVYUPeRf~^3WbEfy?do(@RjYihU94ZvQl9MF^ z>{N!0Pm|}2{{pMIG`$r!Jy=qeX)_{*t;5N-vOPK~$#7t)v{8mVL_@YGx_0PIM4v-@ z-+M#c>yc_QvFw$Q5R_tyX@+QID@Wf&eL+!2U4he*{qH9xX2wre1K*G0BG{#+cYmie zC8s7diEWnjdRUuI6t7z^YFhzF_!42L2JhRCAV z5aB|h-< zmiaf8k-0GMKFZ(bGQU+kzTK)!Ag_u%G(x&&mB|x)i68QC04>AnX*IYo8i%A(S}w<0 z#(Qh%ovd2CP&`PlMc7i(EM$HD_DH2FE7DJ7cm+TYzRn!(?xmuda*dFdt18iV`3-DY zt0~G_z$)%<{r~BaWUcu~6WoEpwxbrBEYetTM$ZfQE7KwM6aC6=;Nn-^bX0 zMP*aSgHh))9$P}=sZJB;&$Mcf6upu(2j38(_b7n@AO-fYXdT zI0pMryb$w`u=t*<&oDd+^Ge++*yC@h$p>}5wUQ`Z?fd+ZD}K*g{hqJ3P4VN2?6Ij& z(kID1HYf=p*gm-j{|xq~Od61&+Rg2!zGiJ4uI#^Q!$Dp)LW3>|QudZbKKG|W1MZ}r z92kSK43Wz9uaLnV@m9dFY~mZtnAQ#L%vGCiBglE=-i@?*5QkO{C?#%E7G7Evo+f;# z*)IWQiS?JT@({_Bn5#gvpyH{03))X$Ka-FJL=KOqJ^Q-MT8D=op#+WW-$^W;?^Cou55 zM&%7W#tMOKfhyaykEw<`Rfrg+X$%*^)6_4iwI`Z|^`Kz3sUVZ|q0M1jzFvgNkjp*h z*_5AJ8_+gxROQkNbr0YnlRA#Y3>&;x$h$v`kmX-SbrC(c(ZZi+^94=e>0=&{&Vxay zrLRULJ!XbKCa@FL7>WWR)??*2PVl&nRP^2;Q$XgrU3qh8G{k0y6+a`x0MBINL{|f8 z8I;vO+zV@c$0xU&2}+lO2@-*ZQgv&G19ar6U^L;PI)ul&iIMD{k{M;;{*~wZ69cam z=ib{Zj={9libTF1?QpJqEMLxBMSWk>^lxSgNCWz)ye1Lb`v&3njonniN18--dLeNL zlcbC}l8#fx*EZ5*9>JU8=@2fhrUi6JF&1-z{65`>Io+G2MI!INlJx+ zktYRNjqKV%8(@D~m~^{fHWbl1cC1hC-J<%Esq)VqS-@D?%I z{i3~RDd#JA-rexWqwIcZRwoB%#C4{Iv*Ui?OrQG>yYIkiqN!jlx?E{{&;0#f95rNt ztubg`f?;5T-wJ4oxDPy|$$xv_@1=3fJcHimM>C6`-uYE!m?s?Q4WtwJ`s7ueSxTav z_J>(0r*jR+X7HVT*-DkS$NfZf`@6Jy%=?Y2WS$es+rMx*zzu$YrRXZY>8r>gTi-_r$y9uN1CL8aA(SI0Sh&FBRV~TpabG&yvQZ$H1u`$92I~|j0!fXJ zN70&^S%hxpzmDb`ZDTS42S{p@J(heeJzCfGGbham-LI=98hI3i+z3Y`V>_i9&GZ7BgV-pvh7&_ci_{eSICAB;nMO0d$iMU@zG* z@_-{S9T8cL>Mn!~l2Hc&f;*WF$!;1!2Vn;`nklge@h3C76s!s=!0Jh&hM^p&pR=`Q zdhfvY>TwA~@tCf}QlgH2s4o2*Jic;b#>M;my;(cct^r?{)yUdTMvFVk>c#ssFZ<#4 zWpO^2PXttL!o?bSQWM#Hxo5zjQe`e@ne&-lMU?5Kw7;5O9XSfdzI;m>1Y2uu8Rtx0 zY)6R*YMAbB{y2y4esi>GHM3YQK;oB#LX`0Zx(T+#=I2r_er}4U=k;ZQ4=UsFUr*(s zNh1OXFK6*TMKsQwHj7#n&iYj~T#mjYWERInD^&MbcD7yB8z)Z_4W;0(!lC5p4L`z7 ziQD->rysT=*!sIYj1<8GXM7WKS%j)=^#*q(@dm@)sKsMy@d=rG?vCy9SMa!e-<%(r zv&538?l@&Hl_T3e1wSTp^2ch9j*F=*(ueteQO`?G1)b9LZx0@;$sT5Sw_!Y!uxzO% zE4vd90$Nhz=U7uicCL8twY{QTrH zIV5*?S?ZU-29OqoEDZB=tVk{vLr_u*Fe`W?x8ZMWxaMe7aXn)9<#dp-XH>Xj-#m*Y z;c{#d_lFakc6qSudRxz4TSs+N>54>A_Fif}-{_>)rPMS^l){3G#UElJK55(u$z%dJ zZOH}y>cMpYILEU__@r53+2H}XRtw8FWK@Qik9R`$Als=I3j+5MA?j%@8HbCo%ohYs zD*k;eIqQfLgy{D5O{V;5j(9T{b8b}C+Fn2^Ekzzcx_)F zxVnk?9(Wc+-4kzZXk>(x`3&bTwWY{pn5vISg#_W9`v8VCxbN-BwqZ^M zzqL)0=#mN)8jBH$!p~kX(xc2HY@|OwBzE~ShWOuJXIm2vYO|Tzd&_50 zbbj6m4owzxtJu5gfw;g(P6=7uGNQjac1!<$qRChKaaP~9;lL`Jw`n(P?w2^{O}@Wv zEMoKSCY0&L-ro!b7IB2XbDl!|$)Dv|&J56{By&LZXn28-Zy@$bu&syp8vc_uo3y0C zB~aN6sSKDAqCO_doiRl*K_dx)yc`w8mKg zZ^dit$PAg@b*_R0ry`~O6A$Dc!Kx23dZ#z3&w=Y2R>6lMM>}WT@GQ0Za($_liz;R1 zTPG7`f!Wg$At#=eTyvXByW)wgOLG10^kk~$i%=GC$>Y1TxQ&J2|E~U_w9Z_7q-qgg zb`G>E1z^%Gb9)u8d=3gPUU}=n9SIabFlqJ*JY%|fy$Cuk@J|DL_yN^}&+)!>NQC)B zFR;$fxisOJ_$6Sn^*@`9!gX;sHj+TH0Y7m+!)I$h!cSUF2bSl;%drZL67v%H0Wy%A~&n$#wE{N=I4R5rNXUgkH+6=|1(TmFIr!}??R|OBdD-T7Q zg@V23t~u0xWq)-eIp$^`VCG`U-OJI^F%ECNnU<{YKeVg81$ZI6z?_lEmr)F_0_f$O ztkrO(>#b6FEkIThn0ET2I@!*xd_~`?4`_rF9?7kzz%^iKpuU`w+9L_L6iVNC&OH#z zlVPe&hh9AoAA{Of15elK@E~xAPgKOk*tCsYg#<)vo0&jK?LP+!uB*?u-j=fW94O>0 z6Qw*8Ol(W>jE1%Edk~{zGnI$SVw-1Qqc)ds&Z6NlW$mG8Jm_`L^klaLlR#a7A7RL@ z(K&a{Y02cQclqPdoB2sfj~Gz!q!0EvBVkti_%tP$(W2C^5wviD#l+j`aA$U*(1lu z7dm_TtEVYMgfLy~nbJF7NE^0XH|#L%PhX=OcD@trc~w11qiF1!3<;2A2~ham2kKY( zxp%c%(sPJcwy$*xqhF(5Uoz=;d#RNrVa8_Y+JM7ABrxY(V=$AsJXh7O?^=cR)7&~} zqL0-*Y2A2(?emO{U>UHSdlcN@;-Cl~_xzQFYvTUA*P_YVzdKb%V9{a?4rp#~EE_ab zEd%X4Xt|L{i6etrifJxY-JvMBda^Br14PDRnz*wkzbX+rDg&0HInQnA_k=(dm2o1Q zhkHH#w4>^B4H>|O8hE3&5j@?WLc1_oNp0EI!F^$L-o6#ePVbXaq~x$ zm}2v|fCJ;?-3o{FHK!W!cYmvyWHUe|7U|M|9R70ZbBxe;Yg>8>Z42z&Bf_qF@(Es7 z-Ppw!W-FWR$zkjWu`Gqs90mxista_r*W2O_Ftf+NP-2|5jA`O^V+L%L-e*5?aiN8S z9FU2V`P?7Jt*+2HU}dp;5cYvdU9o{oVz)xKVr=CL&{5a4JA{<{aaS`pUIpDNE3l9( zHO{REMNah~kW6-Rm$YFq*6I2Iggn+B%c&^DLsK=CQsTIx`8Ov@8=Fs0JqM-A^bHG~kcIb|e@7lYJ zLukCHNDR`JF&jJG3zaom+71M64Kj}Wc<`W6doxT_eBmQ*G6Q`72?^UrMO^PhaX+$P zfCxBHWcwLK(Noe@_k9?f{4k#LRoQF!gT3+xmY3|s2OgCY^<$t+Wx<$R0#rCxXzp9{ zvM#c{N&E<;47Sf^tXGWWDD6m@TNI;?HQ~@dvCg!!tu38$q6fv4x=j}rdfW!0gf9I6 zQY=t4R4+E)U7Mvz`R4|$Jty6D;z&m6VSs~gV)kKk(A{)@_5Py41}2HQ@3bTU5RrDT z;Q%GTXQq9j57sdXR&>fBVEH|L#^o40S^w$#vPjo-U&95N^z=B&cLnf^Mf+*B42uEoX%A2in8voNxLKRTwS7AZm379TfdX>udo{h??MW^tx%`KEUUTpTkr}bE6aB zGHYdrBzE5zvlNr5YWe%t!U(C9~$&mIvP#VX1!kNikOm#OaYArlH9ij?d?)+0G| zC?D%H=i^L^1`cGRpg@D!wgAIR(Bg_gbUaM+DJPsZDtA&>A$55Lp(1F>{y+f1uv~UNV>;Wub6&Y`*gQPR< zcarE~ZT+@qJvC9AhYxr*2+MqObCBfSnW+zVigs_zk~ir&Qtv}zzk7-m+gZiU9(q)G zzJzLVLm5n&@=&gFqiU||W#)?$vWjKH9U(fbK5W7pfI&&HZxm63=Jy^^AJP3sdfK71( z`C8#=QOkdIy5s71D3~KQODv`GlJ36>6&wR2K#c~rmxj)(0bjClwS}9*OwSI^OQJl% zt+`NcSq$7JEI6g_0|jHB;m7jyX1+&_$WLq8R`go&zvZMd@3l&a0}LlMyq4YP*=$MF zdLnsv+t7De`!r^(DJav|HXouip<~T9Bpmdn2t(1MQ4rzN#l2$_*gdwo)8i7*?{LWn z7FJ2}H@ym9Tsc~Jp3q>CWUNhj)uR=PWRDmsX8%76AWOE+i#hBi;nH*77wch^R#P3I z-H!NmMz#|RK4FD$+h)7^JbNIAO!bZ#4{w$LdY70{6NneEVq>;&&DuE#P+G&E;1(F?$@#S6Z^o1%g2ZL~xz7CX!t=Y^%@XL}o4d%=oI8a|trH5-@03<=S$+ z&b|V{w0L|CkOnuS@(6>IjF<0N^uwa>!$0n8Z%0de(IN z;+`78T=g!wXWnvY4Y7V&$@81HepvN;T{;l`RF2+#(uVf(life@OsGDv@qA6IvV#XLqZ^%6{$EZw9QT1>Jme2&p+r$FS@fR25# z(my3+`ILsQi#`p8Xw!am;I}YDd9R9R#gNlRQ8!`Q#ATMO6tW;--a+$Ku+CB9Xkr_7 z%=F5kq@3rasPZ2P!xHS-|%~!(n?{}<|Acea%ANs90j;z2p zz5M0M@E?QwGuDoQJJl}9g=z)*o&3B0>pOB>?83|F4p!~Ko@;f9 z`!ua?zB1&9L;8unbmY51%>n#h?seMZyDh6Nzs@SV{MT&PGn-GR>hlqM7<`u!O&9>r z4e6+;q zz~@bub_2YCCq_vZ&H)Pg9u&wH2M^`m&np+Q$|Elk`AS0qjIXoqs!V3};)QKno~W1t zO3XCbdAgHhA&&KWuylAWaC>93cB!*^^DJjs*cp~qu;0H548&gLpk%&<^^-2*M${J-HR_N_we`W#~NP;?XfT-KxEOO zO0s{WPifR3xE@ysk$~v-N=uDG5UGlxy};|N#IWi0*NLXZ(@@174o73QEeffkh0(Jg zmsTmTFPw?bn)dXb>g*_VBB+C)({!>^ZQfF5{3N05-Iojqpyt78yRez8NIC$PR-=2w zqeRn9I3&__X<-$)qIyBmjP&+=LVV6{m8n|3-OffI2)AlcSAg4<30d9Bs^NzH{x@xC zX-e>7XR3BOt99QB3J~S3_)bgNf z!jUnz%kLb`JsV8DMy>TKTQl(_Wf(*GrWY{6q@V4|R|xgp^I1=&MhP%5kQ3aUCW+RO zNGxwr>zJ(1lIl6$W(UukthWH8JuiBb8@_^JidKk?FX);REI?J|lMc=d?*K|)7wlV< zH|qfTefcJdssWKr^q^bFX!q^{CEguwy$XmdR1)-3(PU#!c%}!_Gye&$Xi|HhD$BD@ zkEZTdW!!gClS)AAH3E@V`Xx7H0{E;q=<+e&bNg_@IOU#!(R*D}`1!19=(zo28!FK3YTwSCIALT`BPK4baCjxg;q&?jCns zIrsQ-6qSKo^x-!tB$i`+Xl7tjY^W=d{LaR4nW^5%6w-xH66G{ zT#)1PK`m{9jJgA;&Cc%@h?O>E;M00S9s&{#CQ(vCG2$X1k&`>tYx`Ur# zF6Rc;6eUXG%jdX>{}nMpTA9QCPdg&vKA~kV|xG-m%^;z=)T-F;jI#~ zy+?aOcJ$8{@&icHsO8Y?t~QE2;oyy^(y2$VvDAFE)c)O^lH@AOmr(E^TX|P2d)K+$ zvhsGao;qvV`LpLptIkXbOBo+l@ok`!at9F!Ve_epnkvvrpS!%9qYb>gOrD{?~jw*$FZxSLuUj2vO0+ zjX59SUdmId2ck&yKXrQnV}5dg<47Cfx5z|1;WYV=j{-3=tk`1;T3Fs|EWoI_ME1O6 zIs=IXggqqKcP0Kt*t*p8T-LOLL2%5Uz6+cN(bQ=-d1Fx7re+`d$?(2R?LPN{{qNu!)@`?ss}zZ_gfIp%A{&z)q=bbdLl0Y##d!b z>cxX1;dmjpk)~y1Ls=d_3dNWFk=8HX@cSzmu+>)|c6B}+{Dy)3o0|Yc^7`{Y5_pFz zTgePj{!D~8I_$G1hyE>X;(;T6RqTmi?l77=H>L6!i)E&EW~7ITTvEYd3Tb+;%Z|)5 z>hfdfkWQ@*k}#mKcD)M8TN}647{dNw;4OxmHcvk3T4U@ll9r%z#s#nt2|sVPVQc#sU`-t7PP>J;RGlk3!deF&t2BVG+p2IdJ5LL#XNECfrpdz z?5?W2LU05a>mt9sx~5#G7-Rl4cKI*i2JKgg^NJK+$*lro!4`{BBh$Xi%SE!SW7#P&IK3giND!f|U`i{~O; zb~I?(W5l$cUQ=o?$h5aBb87lq3Hdc5*Aw>4z9#r?njlp`RW!>{jHsHHK?;gPcBeFK zvh57Ey1|sc39L$2-PWM6h8-VDW6rwMOrgBQ54gliHv=eLy*^r9)gHMsn)Z0`rO(&c zdiirNOGscY#MSzXeX}C1;6${NELrB~QPxxH;OT#0lrhz3dT8He4@I=Dqs+r9m7XOV z&Kc;A@@Xflr@xwFbX6R%s$!6$&@R4W{C)7uf?za6@Y@)h((lJxbaCqeZfx{UevCXR zi!yQk20(ctm*fAPj*oojl&IZnMGT$#$)$n`vbwX;M}_Zu^JLmB6m~XXF|`;M zF1O`PuQ~>?T%o%hNByfTVG@YQm_~|cue5z{@pMWL5hqKSYy=|P)8R55qz5~(FW1I z&|KlU@WfT_h*LFf!V?b6QW&87oJjqB{L2ltgsF6eq(j0XfG9Lj5-EGtyMd}GPC^;y z^;F$DjY0&EHEK*XK9h_j2MgkAhJzacHk5u2i{_Cq7+1k1$>vSRi zCI9)qG|MO3e3eU2j@GI{ArjJpSktUqq<5$`q|6&M5+P`%o4Yp{NE>6%YD z#(#wMOm>y?OHl@~NY-zP+)ju+F5Z79N-v_{jdDey`1#FqsP@uYV4+(dR(D5POEbe% z8apYksYwZN<^M`B3-M*DfDlfTj?PARIrr0yweA{Znz(YcSB?jto1qhO`=e}^AgeG? zCgxgRsQgR@%^+t^bJ2y_)@0=~1~6NMbouaO|4r(A;U4C;AoTs5wmIQEjUK?-@?TkG$Ry_CD`a;aR2k}43f6>9~!m# zEhu0JRG*!$H`w`nXvIJbzdC1$Hf0Q7ghe!a_<=q)_MJH9nUd14mxSIMx8U>JcxJhK zQpEO=(hw#IlMJ$BO0en$CV&ob8plk1e0S>*J+ii#Bzp((P-5ZLvmqq%t`MsKJCVOXRrt&PT zd|k(PS4o{wgzEJ7c~EpFbmwFk9p+eso4B`O8@p&i+u1<$<{5f9NK#@5UCDmozD)a4%#i3m^YC{H+rrZY|(5C_{*iW27b+budhW4f)2eRK+q@UE`( z>Z5gN)H)rWBN?bN_*{4`c=1a`bvqMXEq~Ey`MEIhj~9%FGR{Sk%?J14Ck_ z6qKLz$>yvORC7FN)({<^)oObi9G0148i0``6uxU#LxCM)Qz-wq6grtWPpG3PmrSfG z_`^8A5{2@y*wA}RM(XSJ_hj~H>J)9RPUP)Fi&Ys3TJu2xtS>`OS{)v1UK>APWB|jY zR?DqK2~Tm4AVqG?qj;LNTls~1rx=n9!cHV`3LqoVW?b|0UYIsRX|*((EOov&zQKEk zxB`kh^8SeAl9XpH#q7E5-k!fIdd` zVnGdGw$I3+SXCLqnr3MA(~s~XI;gBRV%?|6+Ykqb{e$e~;<6Y|na<{^qxWg^tnV@6 zNr_#v(RYnX;#GlI*2f^54G~eX({Y&*LIrsevxi0xb4!vft(WhvNZta@J=Uj`%dKIV zw14iKX*uW{>EeydGW*@ir!X`I6O^2440PZeXtFiM+%Q3}xwg%XM|wVua_Lv`cfYYS z<16PK>qd>h}eJW&k?6AeoxSK*F%pxJNlosd_KuW{8&6t z7Y!xI9*BuKafin5)k1PVO>0uBwfkIb2W#TT$9(8x;&3M+*bQwPc*WIG3uCzGPz08K zF?!kA?mlQ25b4F8d(AqOD6(y$adC$3K~BMy6GZ}&*_pX{mm9zeok8bZ1x@{}Y|Rd! zY@5>z_f?Z~tDWlD3Sqz=Bz3D`Lyd%}M~|!(EsZwYHq^TlsARNhJ;@t9Gyf^{mlJZm zqcZ3Tg-;9oTt1Xbb%2>nOo8n5!{pQrGPRxWsE1Aa4rusrFO z8@QDzJVj!1Draj=GipjD3^!T}3LhWO=3-xvkJc#tqkW#_!0mtTX6AH}z77*pCEdFIiE9la06kD`)Lb zBT{P_cP8Au>vCf_ysI@n?ZIzAFf3&*r!1N5{dBC^+&iYl4GzDdP6_Z>I=Z4jb2~$} z2Qs^I!)wz6yj-0FpZN5h=f}FtM!L zA*)pr4mF*0FI>{*RL(z`*0iXJE!&{WnM}SWz#Mc<(dDlB^T*SMGY>yKj5$N<_CErE z@ZTyVraA`(V%Zs$J)CUHY1+In=;zklW>}~P?Ll*=fzTccbcXQlRvhtri2G-%U0)=O z=L*!`XJ`n6(}^?t3l2BmQ|V6yb`DQ2ehAQZv@+Do9%FhqC-m$IO^E!;{W#^BnL>&r zHd5(Vx6`tNgCP&~#ndUTE($^)=Cqt7q;Hqz6Ybt+w-~irdoKdoCVh}C6EZHP&wx>)SeH*Ab+{^&Bw?Wh3xgvt4Q?=Cp2xomjLSMD)OsD0P;BhbONKLz zad-~+O3DDk|7ao{>=T0mjvCyD?{gI#bL|bc3mICCFCaK(Zg`%F0fy?amZay!*%+V# z$dGRbhY4rGQXhH8d;(rVUIe0FRQ5)StKvg-`U=sji2ExE1|}xXE7U?zjK}2PFy`sn zFz~M`_}~M4Btshft?vcA&4V{Bz81PySVPuLM_Kv6Zbk$B;R{mbsAK0oqS6VB&fQm@ zI|E5dz^IGI=Bcil&2}jfui!t$brgz=Ts-c{{1|vxEV!qltX?+N`l%Sp2btOa9JP31 zf{hRV^jOsjYD@nz(k(NJ_NjUqfq9v= zrlyqTI*ovS?n^VUydAkgE+o`v=+|Z2Z&x8)--kU?A!{xwnQNEuOy)PFgWzE2XK$~5 zzXnT_HVh323W_8O`<}$KJn22n`%PQp;-&$Mf|05oXz=EPt&XTAY2T$qpqMGLe{*Bh zTfrw2%}KMt=)DUnOIVqFCglUGHdjk%aQqQ-`gz8YLKnR^s=EW}QB+{^=kF{k35d6j z+HI+xe<&+13WWj{r>~V4wIrdekQ~#4E-g#DoR{g@!)vn2iHM6qQl?tI!DCtm4v3=s zB}8B(Q#O)pVlJq9U%nCt&@!BD4IM9uMnBD~8`ICB9Hpm75LMflA;Hu2HlI93O+ zF{~6N^e0L|1-v)j!~E7PC&T&s!29~4B77&uAa=tgZHQJEUc}lh4y^XMF3uPed}r;e zsygQ6W%|sL01v04Ww(CZAvyTn9q-Tp;Rn~WT|z(e>;45wQBwIWr;+b0LX!zQ-R(F8 zTU^M0eLiFJZ+LdtmMKH9;LYHx;5EVle+~FTnF~(VCacJsY;VmmGC z5-CR>1nicZG%JfESOq5ZX=7v}JbzAS^Oc+2oH+{qn?(~pty2D1HL zQyl(b_FMwmWWv{u-+FloDE^h-8#cNx_un_0T7}kO#L?hUG=Ae2eqv$BlVV3Vj16ht z2ENn$}2m?BU<-X?@Up zFlB5-*E^i3QKScsxPeQ^9a?3j`no0M5L6Pyd%PTC%aO8Et&MhIWWSeh%xQqJBgrmd zIhA!F6u0K)E2PQZ>JajyvT}qOQZ*O&RX&{Y`LnI+iWbG~^cht$%$SW`-HRmq6+gY& zehKx9+6f_U95H9`yAD&XPAe$eTmnNx)QPXe&fHUd-&arrrO6T!p)TTT+eQnq7Tk~B z*XGr69%U4{ani|_KjJVcIt&y6I@oVS;?odj(%j9Ql`%lAV1>NN3M(?rZ72*KBjQA> zMDJ`@ax|wqRzgL40+Hu&Kgw$7y?5$~YR{r-#p_6Wm)Z@)P(x8GzW+LJ9b1`lB_~SiMR`XcCEN(40*y1ZPxL@)KqPyz4>%?i~ zDBr$mD3e@a83!=ow|n(nA_8&CynT9B4(kzw^05xi zkaK;EWPDNBA_31?eT!@KlK5+|myELJuEaUn%x|3u8)(jr2?`5u@onP5AQe0qGf3?D?17R}^&9#@c)wK0qMI=T~xk zl%6jfm{hk-$nJS2OKZ{! z>mu+p%Qi=1*tsFnMusEvdvDQ{<{epo?3zQPM&^ua=+?NV=t?ydmOe$Zv+cdoCX_iE zL#$kt^9D=b^qz1rXuXX@7EOF}((#*<5ylMi1E39{CRl;L-rsqJ7Z~rQg4>ogF=ngh z8FQ}=+oW@%Crw<2eJ=h#3&3AH|C`FRa2`f*U#UP5bH0nbRER_(drf`K@Dd%m`9e1s&q*%aOsM4cKaMxw$I%DFcxcvD>YrS45>oXC6|U2yuh3({?WMLjEt7j_g?tlTvEN| zJvhg0t?XO>4i#$73ifE%IJ|3lwUM$TGZw;d5A#}KR4u(oB5rJp$)Wh;fN+rt+}gSo zzLFr0-}R_zSH;m=qrxLyf)-6W1JrT(>#XcG-Q?kh$CMhgKIdpI_vD2atm~@gmkIeg z&!@b968fmzfk*A%AhhUG2P>s>iXPUB5 zifb$;&-b4sBYMlfjTYqR26lK1F2+|@+*O8{MQWb&Z9PDbj=e@A#-ZjJbH7Eeh9nItsUkBQ(EO$W5wB8t#R2(diu^G zID?%*KF53QYb|enDZ^U~W4E4QS}0vtt-ovKR>X9n0;C=n>a$O9;5^4}yK^OSp9AgS zH>D5FP9rYQuMUI{(*6mKI!FK0blaEx(4UC3Qo_aw8#AClgapbglTW{pZnDa65HB!= zG*F+O7cS&_s!oyqeqiigjrFC z&81y_9bf3s&tB#5S*;zSi^Je*&#)8_s;@LRM}0p%KRkElJ~H?lK))7-3=8$&=9$6Z z`l~UOtmIl8l|`^H{p&gf3JtvbQ7LqOZK?{uyIMWW#<;{-6hc1ezwX?MxbIYLOk}tF zQL95GZfV){Pjz4l;6q>tbOLD#slIWcP22tOq5205?6cB4Pix$|fHthR;Nv&;vD`(&$276nQN40G0W2!2hF`7E@Np`BPK1W64 z_^~vUmZuIT#|He%nn1F&9g{jOt@n2&8U(;HV_N_cvdhPU=j8EXO%+`<_4d9;jF6Rl zeVwt%ha{1=5%wLJt(V64ppltcilb*1UuW5B#|D>ge1R7+dqGAB^N{#;*VeMkqSjpV zZS7oJnf{JFfUwgBFBavr%(P$~wi!IJz-d4v+&H87?B-$@ve2T6yx1gKhimA360rGj zbG&An@T{XLtF#@yj*`^C?bLP69KRFLA~%zD!RdyZjJ|QoUs7#j9V_<{QW&SSciA(4 zH&&FunPaH>-tGJ2vnaxGMfgQP=kAsVa6E9o76u_OJVD+yG3PVn+(QjM>C^iUB%S}R zmHGq@qI^tcevczb0rZF2GI|5RZR`t9+p6|lF~7X72nIwR!wL?R_cf4#4n~8)a`WXA zW@u9%e$gw;b%*o?*7y}g#9aMk*SFGD79+To1fZ?0PT+xyTe zUCx|NMostD^{NXTziCP10=H`EP{B%B;{~KqIkp#KyRo<)GJlV+wzMOdmRvf(t3B<7JtNtZnv!OgVPqc}}p& zZ14O_{ulY=;E;SeGs++=?3v3M3qU(Cu|~~25$42uCsWbBOiL>K)4+W1hTu5&q|HAF zle6&o5u;)dy1mSbO&WUHGh7ir9-ox%wYI!`yhDM2d6;Yo+3q<1!o;=V&v<{$SrylY zW&b;CMf1cOR*&k}Lcd>qA%pkF9f?oS`rC+Mpk9W9OUoJA%u;3kylz&KxNLV>KR-7T zWu?Odf5z-U-%`v=&sb5kbnPDN^x7W0?0G-Mf83n2I30#%Ai@sF2=!CUi6TG zWLOU;h=Scde*f6Zz8A8$F2s6#|G;v0&%Gd|dlZN*czzp%rA6dlC6#D&*|&-VphqE@ z!)y+XMYFM4m|ic>pXI9e^Op(U-uZBe*`qN{PnzijRfrdMdC9MiY1unyR9n<=Um<hf$)TPc9^-V_a&*^qEdxy9$cDwi$ULJD0He7av)=LRe7^ z+d121vS{W!$`U%%AuNCBz8B!0EuH!!&V5XMf&JL@LuY@ikZbyIXufzme#$4^&wFafrae8s2MV%!Lhwkgy&F33)HbFlD?RMs z7UIk?7=UlFL?h(uwbiRbv|>%aN$)chB}_X1yL~+Ami46s!T9Io4l}e7$af9FdIIm4 z67$keapO8JjycZ*Y}g1^Qf+nrF>G-IO#={q0j{XQLR-77Iq?UdzcM~)zCdU84g~~G zQe~bDvjuiQm=8w2)Gabcf9tw<4N@0yS(ik}*p+MoS|HhXrBGLE(=uUFk=E}~4)f;%cf%C4$6_!aMd)&mFtdZQ%G``tH z;kD-$;ugR^CnO@8Ph7u9ue$qOH%O=I&Hf6YjG+#@zXo6NmHAFCrLssaIG zq%PVdyr0SNYJUQ6gan1^#F!4lZnqQ3snQNJ6GYFD)mTv%TSN-4S%kRJovP&xd_Ab@ z9e(l{9qjX*rZk`mgzY-(Ot2vOn=XsB5-6$MvSerwk~7O|m&=BLQVWAq+$!<}Zwo;| z!iIW%+Jt!SXs%RHwdo1A$M-@_kAm%G`d5GLrlB_U0z(UQe|TuJSd(`F_f#JFF>F09 z5oHoarB;q|XwgK&nsR>0Z1f;{Bbscwbq}U#z_=vzm?o8X@t1f(on(nsYcaGgA8^4j zYo%#Y7aA*_C=A4co}>z=(^CS4gffcLWg=H zi)JSb9F)MANdlp1OH52ECV0EXhxq^=!_bE^LfkQZ+Q+b)mg#vOxj6`Jgb%Gf1L^_Ri;@EjzvJeA(F@)e4e zN%8V1^X^Clnjl$s<8v+ihWQx=(m#a_1Dcf`+76}9MaKS6h#>MjWXdpqL9o>t^@p<2TX6#=h8JZbi420%Uq(E4OGDHi40CpHkpbLV1^~_BGd!WM9|4s62Sw=dL3% zN^qk2_|qf%t$;}*BBuPgF8Cj7MZ0bhk@q=B$!VX54@OrNk8rJ&Tl1QG-;_V>d(QZa zuyT(d^%dyn)1OXY@E7o^aF(TD*!OxcNR6w_RCaxW^qE-5faBJLL;Gx&TYI8)22`pW z#;(pRut>z(l^;aQ=@0JOobhZ4_!TzqJh&Tm*KIra-v`sc$f7Ds2~#JJ*R4n!{+oFC z4PB84=>^PPw^mJam{Jlb)X&}u`-UYWr) zQ$H6*p|G^dU}6cQ9%Z{!nMuGMO!Hr^SIczuw3>nfw))Gwr`CC$(De+vo)CFHC)+SD za4tm^*MWN9iiGVte)sB_CX|CUkaiwbc1K$I#&qGovR?92kU zWO4UFO_YgQhwIR)#fyzWUPOj015-a>gim2}p5Lx5y$iqQC9_>~RXF30e*_ht^axu* zai=d|Fr5}4pSJwR$5FR^nIYc>TF|`7>>AOpfEBJkuJZ=I-ZFm=m(-{@y@i6J#r}Ek zdd~8qr>@J=q3Y6$u@`3=>=_t9?WLyA?_{G!Qt^djYr@yCm@vQz0Bibsg8_&A!6SI1 zysjw$nb?0RJv<)Vw^$!rM(WY}nT6_i&99MbrUBh`R<*}ZTj_R4COA*U&i%4NUo~%#_ETb zAVQe-DAg8Oz&wCJlN;{IiC23Pm9b7)D2BpK2VX79n8O!XF?wwKTbk+m8?fN zJxS4?&}EMwOHM4rtTFby^zvB)2x3aunGcj0+UD@YLLJ*IqF9eKlsnCWE;*vM{$W0= z-rR7|LZ1R(2W^_v$r`)v|8_UQ?53X)G`t;q$kL-=?B&hD*D7hHv_lW{ogb%|6zQ2b z1p638EiVTJyT0~e4;k;N@GT+1t4gt{)?=cjM7{rFawN$p7pblufs+(Kt8IXwsq zEMw7~13ngRt`o&`=dr7 zXr0N2x8RFI?9i^7qS#z>u=DI~hd!yo;6N_B{M+W#aZN{I{YjV?4g-*)h_rB1q!YUD zl!2AQ3{M^D@ud+XPC%J@8LklFI0I70CtSd`LGo~r?9VV)g1_k0PA8r1&u=A(2e-kI z?VU{?(d`zY4EBRBcTxMjyxHrLQ*;*wX{slpHsY@CA=Q`QGQ--pQsF9 z`^gOoG2Z1VMlOgy3P88}NiJt45ty1J1UJUC2BC)l6J8KZSqx^YxwEksY1f?!pQA-g zm45B9XGx_)SqkMFd!-1$>r9q-JR})`^LYUSs@Qv5B$lqsMeE*28HstbafNT#%=sygPza-5Ljpl0A2`uv@^o<2ZMM>~0QLk>+|)3V$tj?dAK7XHC+3KYJed&e&d*5I>(k!9fEhal;YSs0-9>WO1S&VNdaw7X;bD=;PORqpr9r)9Q_89(s zO^~#aU+1cZMKREtfZhO*Kn}68V_(-`&awO64zFuqv^sF$};gU4k^oAx35p|s4yE!fkKmo7R zd^e~p9~*QY;dQ+Q!n8uS`SAwh32DK&j5P4vcR0nUweaU$SGM*fQ~VZu{-oA+@Nb2R z@nemnVJxYn{9xZT{_4f+CQx_act`h8ocv!1Ma>+~{fb{j%n+5OjVkyI>|Db3J;pYc zUZ=kjBGCA!+TeZp!F4KNI_V^Nr8;wSmD+nvpMh*mTG#P6F---Xv!O^Mh$SP(#f`ky znI{^y_n7my&95b>)vN@5+3&k6^@H;V`_;Am`VHzWZf7zBuB5&OR%_=~-PP8s zZtbETYz1Y$Yd?PQbcd5Jr-5d6fgOh}TF6(R@RMBoj^|j`+jQoLlw7nFs@^WlWjqS4 z7fbLT_%IMvXyklv<%X1&5=@e%{&|?sYyyG6(jn|w9#t7uGg#z%07&SiLBJKgr~2aw z_6hvkmb`|O5K-n3TsF{jqV+RGFrFa(#Bb~f;EA@N2^lK2FKL4&vun$=qi(Q z3|8$IaN7lV?&gmS;zl-^@b})0hdjud+7bHVkVa?71;o;~)C+PFe=gh~cnJ6tIh++F z=Q`QD57|zy+*35u{yeBc^_h59?z^JjLGK!uCy;)~aDxDL8@hX=xF+H`&fwvCPV@Ki+fE{niU%eogDLjJ_f8>Jq%7>sOPhjm~o! zXtEA|@KR28zJ6i;kgFV#cS}bjo-D0;w&;}bUl6exnOe=E-<8*`Wj?P7{*`}6jo7&~ z`(jLpYPbLQ^!IW&%;6wt-p`{AsAP*<%fYP*wuJ-sL6#E-yY_;!xbr3;XRpIOvhqv= zyl@_f=QlCzYovD#Oc!~SoDe%zq@U{CHT&hvkqwP2u4#ytSLOOU8!g$dj+_0w+A~(t zB!QawE)PT={vkZ)`{>W+QEI1cApdKZo{QJabQw0BtpYonz zE75M>yB^G@Ubw|NIo9o-tB-G)9dC*E9aOwmLAT?!i)T#jO#s(24Vql))qrKg9J{Pm z_n)N!2k$oe4PzgjW_R8GvED8&j;utcHBS9jvf*PdPNSeLb3Ml+?>yl);7~7^T!loW zDJAQ%3+>rujp604>gVDz63R8MOt@pp!|f`@cIiqb{$^iv8pOCUw2ZR#sOPNqzYS}h zw<5@4Q$NQrVP_?;+221qikTmlRYoau&eT`DWq!Hb*8Td}^{}hI;qS!GgOrSF3X&sk zrfT~|eDZYZdbQ^VoAvfOmB#*dvGy9lAsVc#8t8bn>!8tw2Y+HY5`t>xw$%UR@bgcd zdFXfM=J$0m@_$C!vvnt%g0Xl0nh3Q&TN0#Io|Fmz@v3L+c|5Qv`yH_I;ULHa<9e3t z!z#HP<2^F@GMZ8SPHNm^dsK&+O4@IQC`ir^U%pgJ@6_Cmx6aCb>0%4^5$wN}IT&$S z!$=vtG4boa;*tOA&wYM?9Mm9-9{-2wKzN$0>GGrYkcy);VEL+`6`+&S)Gwcw@B4G` zRnpXJ_@?%D-^7De_o#q^)sl8c?#L%vBP6LTS$NVGH>Fw2P4Ds}tW|`@<$@n*x{RJO z;kb|8aX*nMB`m>jXEf0@Phj|aJwEJ7bXTL(EKXnDIBtEwQtaN<%h|Sy1-OlguD3p~ zAB!DN2YT5#Gd;QYcJT$xi#4$X8O%e@P``Ugw3O{hfLHZn6`QjyS#gIoybv2KkA(Z@ z9=;uWnEhNr{O8_A0N=G4k7)UE!{xVHCnThzxWc)F5uq1zRaVg+<6%h1dHt^e)@Y+$ zDs8{AijTmYn3tTOFBs7`RIzB42s@+^a(Cpz{5Vyb46bI+fgS`uDllWYy?S zTijwAe$g=F!Vk~nV*I1dsnJeJ#MPlP==hVi-V|fW;txApuZYyE6hfaad*hj-#-gC2lfd;kd*~iV$ zYJ`I2rb}h-xkH*gV(%FZASo3#W3q*HKPq5+=pSM9S6iEwrR5XmVS8ifzbtSoSJPw) zzYe(*o$ju#9zuRUS$OXOj(YBn;NS41mcW%=W%bDW+CSR&sw(XlMM|7Q&1?jGe^)yh zfemR=PYXM{5perBez0fS|E&p%^=0D}l>ZG_oBLB|vn5qM@I?!aZqW)f+MgaO`}{&C z@6h*J{?gXpztEQ@#yO=12A^5)zemRPCw3Q_2!_132mK$EZSFDM_s@wXphO!e8u#Ue zgJxXrPU~0HmI7*n1Hi8?SWDPnWxoIA5}&9pE%hO~5U%$8=f|#-C$0UAw3*jlUV8QR z`tqaK_gq`*|2cEz!CS5BMt1hQhvze(qblWiKX!JNtDqj=0}& zS)1ElEaZGbIIp||tCaF5?Z{Bh53io^Po409w_1!LOF*s3qqL>}3t+RwAdnh|&sZ`1?`&h;{WEuX2gc-&bWfn0r#&|q0 zp6A{5^7>q#bAH!3-!-g%R?kNytptz{1{wM~P)I$DRR~(*xz4!5q1A;{{=j|ey@kntgjPc)`VrdD z^M7tQAu8pX&=MsXyKx*#vZrM4I{q{GeDZN$!N02)6kaOcyZH*hFBKoKb=GM)P;wZ% zrq^-P!(rr#f@9-FeZ@Yfnkgcm6#P1ZO~_6%6N18cr9&xIu6MKwH674`7_)4MnkKV; zuu8t>c%9RCRuSKyJq)$BoP z8~Y&rMI;rB;h;eMHL(m7ePz&biar3u1Q4@{!0z=|HrFt(0-{A4m1V@wlx;}D2zWgR zjPNiEI4%bnA!{vfuF#T#m_zfGeqXD--_{9j|EU2>9PV|Rt}g4xz|Z%NRHTH(Nd94o zH!RNjPVA|(0}2ag3RBNOAe>=A`I8?S{Hr$qEnb*n1n25W9+#I6@D*^CtX&}ko}F&# zZGMtcA9FhB)9X(c95{)$3vdZm4|+)AP4V1yBukfbB5}D%!CDeEtcomk-6Wf4ChUdE za{6nVmF9@R1aBW#*$UZ7j`D5oCoa0U|Tz@j3RX zR_xK9u0DCJqC1b2YpRwMX6#`y4`Ut3T~=fq8-jiQ+Rj@cK+uc!mhr4O5UH!TX0?6k z=5W-N`Ygd}x)-_d1i-~kXoSH%p|VQIGwKG+^&*dkmwFF88`0{9ZZYi(my3nquS^Ze zxV|@XJe#`U7=-TT+}sd`*%=qLFc1ARr8J39nfh>w_RWfC_dmLzIT`?uLy>0&3d%q9 zmU%35L~B7rF~z7G@W$IEb?YA>Klso$itGn_uIxofwcgfuK4qXHW~m7%KYiWcf=7ec z^kdn+X*)+x#n}NuU!sO=eU3%7eGaYWOuR<68jH1+TInFtVRJ!3GSCCl0F`2@@pr)L z&1%hViOLwns=bHds!}G^i`7NSqg>d?auU&3?%8ZukiyGZ z>T)Z>LEuQg3H=HDLMBz=-}Tt4u_+??6^9 zhW=Hiq;uGEF*m>i^mmz^?zJ#Bv~==j0faR^jrj>Hg@BvKI4J!?40lMkyCy&{TX(-O zJ-p-h*wawov84yrE9S$Z2_>AidFaCrz=cV!<||u#Hv+sWt?C;t6BJ*#eIuQ{=H8f~ zmv_mDLXqbe1iyc5T=W0500wl})lJwFTD4{NCEWG%zMC&ilPxFSTphBxfXP8?uB`F= zD16#fNT@c=a?_=kYQRUTspf*Ekm!h-Xh7T?>opM03^}3lf1F-Bmj#PS^0U@JH&Zi) z9oaOqCHm`Q&DC5D9`YVeSJb63x`oNIe4fFYX&mE;+-|bW%<`VivH+mnuZifYcCq4z zA*>L?InrxEaW=l9jw)%_V6r798mDCxvZ*kc374!PF+RVn8U|QL&L?Cq!&xm*hTQ>g z52IMP*SuB8B2W{$`}vIf#3y2RIJ$3eSdx-_B-I;JDny9YHn0uJ+`~K<^X(sHU!H1C zH*nr3iv{IYIapPKRr&0D29=zyaabiZT%H0noDw;wqNN}#XngM8Uxf@oqYI0d6P$Ab zPigP{UG!+D_Bl?Kj7AWOp1H)5JhNx~YLq8f)745srR=Q%A1-j5e=42OdYiB)YGZ(V z6qxo>z)*8;ttu2#IVK_%qmJI$NCe1qG9yI3Owm8D#f87mikuWF)%@FOFUyC0esAzj z7MfL!&AVxfOi$x5c2k3Hr6%!1{sqxD8L^WZ)-IH) z-iR3%jNsRlV)j_igsku@v@|>T)Bg_QW_zb1?I#xY_hsSF;(x5r3}ja7#LBj7753Y* z{q&ENAjdioHoR4D=vXcO3rozRHOyN+3c#Mzb^?STVJJ{s6cNAl~P8O1voJ_kSR}gaA zl3O54U4q5ZtAPEB|2y;TBWuA@>L>iEsjkeYofU^haX~|VO4Vx~#9mx{;)JeDTq>oQ z8q)twPbutOd9i5h;Kw>;Uy6!%yh)E~3crga7`m2^9`YqI!Mac~8FmFZgZBg4p^;y{ za`AV$wCz;k69e4R?CNY(Y~lMOq-uSyE54gk0zB@}z{OuQxt=`{WN*IG=LY>ErP$3L zI^S{TXE4j5O8*$$?r~vAj+XNw^z4=VKe_1RE!5wb=Z=prcAr?e<2e)KL_K%j_Ukt* z4N`d?ava43ES)r4VvlJ`z~7|SP=)H0fBc0r)GrCoKc0Kzξf?zMe7;As7#Kkp4b z-nD;k*OGt6yc&zKyacQT8~Zo{*g4np_}J5Oxu}(XQ*7O|J=uZplwCX@+731yrN`N6 z78QmP%!n9ST75TZ%O;=GHG-|IwzT2Lj8q$4BJ}5dv&!1fcV^rHppjt*d1~4_jgDxr zBY*oFIqEF;zd5RUZ&pyp! z3<;lum1EyQi_5eO+ICWSCM%vJCsiQyI)#~db6d>U;!3m{Na54T=5%$mLnH<9Tyu{3 z(CBPSz{kryLZ~@whvb;#awS1G_llanpNA_zNzYW>L3CXm_aqrGgpxj3HD%%_RHoJQ z2U9t-u?=Ngp+eCtboDVD-AVa?Y@Q7~25$jlkX?V!l$6(*iOkK3g{K?W-ga>acrBk7 zOGGOFG{EO48H#O|1fMNxZlW}Eb;dh6oso0m_$c*Hi6>d@w54d*8HH%jx#9d69XCC(`P-{JVx9!3?Su5xF=GPgM0}Vi&Hm_dM{HTe6;>c@&=fy#+R;+<&rzySqM!snvX!w(md->L zCrMwUu4%}i<}ac-57kBOT+^8(dS(42w{eny599tw6Z8`dZv!rLp{BAFtKM?u?ye=d zwLekATjb8Jypz*gGh^q(-(z{zuLUIuLOk15E*6(GHS`Q>MXl3^_J6gjKtz2Hr@aVI zdcd*UlYRBcSX^3KH1p*84?V z#nTNoS#T%sr=`pDt7&31Jg01UF!qb58oZ5|tMk1vzHTiI{E4+DY6S2RD)Foy&hp(N z;`{uv1Sq4@GRrOAq{PthOW(`PMikuVLgxCEpl_=u)y3O1=f8_uwaeS1QRItZyhba} z95J30X&crMFC?A#VQ7q7={va1GOrAxIu3B!P3(zKQyaiQLf^Q$RK)&xl^c!&C}NO^(`a}&)An=9u_#Ur+KjuF zACi_2g=;-XXPD%xoiPs;Rgo}=C6Bg)V==joRWqx4sFqC!M(^aiJom6BEdc|4)WjIr zbk6tD+V3UA*eXJMw&c^-kzoFsw6IZ@OmCJkB%j`N77_9^%ocq$;%vz!c|WwMs(y0j zX|@zs&7mEe?3yNsy%lPE^R(&>v&JG#HD{3U!=FQM{iwSsDMR`7r>o5qMQy@}E7x&R z&bf6#u*8bVVC|5(nz|N~=FJcXT~+mlmA(4t1IWZN1Ky5#0;K}jB(_ozuTstrSf#QfVhw08b;12P7m7Zo|k zYc*zp>3ez-_4T9#>XqB_Xll2^yGp3Xz?w(;5yg+Er^`Y|gBM06PyOpdp_rr%*&$xr zA{wK8M^vb|D6PgC1r5k?U(Ye097=Eo#~#gM=AEAxu-o6kd37z7S@^U2`Eq|VE={51 zFs&k7@Dig;pN?-m`vEx9K~~IJ3l#GNLm{J%XCU*wa~D%RGsFEjirtEz zj{D9%QxaD$y)fggd5($Gf9tA`>wPvTV^9!%LE6Sj$UUs3KF4JH7YEk2f|4S0G>+e+ zSi51I|A}zJ(Qi)bAG>s&s2ZMO19Yxa22I|%^?B#>$1&?2m_sY$-0q-={axg*Tm>J~ z-miilNOIE&e=zvde9(`pj)hmVfNh_Q_1!RW_2m(KFs=Ve{uWI{Fh-2Eq2mrFTzB*z z@@_wTFXSqltFf2v5V`p_Ye;neBxv>;#z`e)R8ImmT2VkuS@j@fzjXxmbd@*#g&qwp zN1Q8@ZZkSM&ne{`SDJO_Fw|$B2kDo^EUfQD9919w`1 zb`ySRTB52`+h=F(^wCOFQ-gJS`RRKJ@|HJryGbt}_s{2D`?hYGhq<3~np+PMfyj-Y zy>+K!6r!z21II9ikda$C4qJT#N;S#~5)i28cG}pZ`|$KHD_(-u(Y!sIFM~NoKXc}z zNv^kD_8Em=7wy2)xponZ=erL%jX_^XB0V+IM)Q~aJ}C~%9FO?ZjDS;~X$Ghfa-v`{ zYlO!jhpTbjni#+%SXvfJvH&o>|GH?Nm8y@^a zsrtp(oysvI$sOzml908&@7`9PaO1dA&)lWl-IF0-&DMAXt45C_yFV3inFtz+!V#$9 zn!i}o6k{#*-u`TXt!x6bCg?SDQ~nQWS;UUcs3JJPh)J>suo zsYq8b7vxo&OU98OaRD_e_pSBaBE5*M^>YqWxc}&cst>;8IqgTT0d8ni#MG!=BcR1B zZ*qrX!v68bcWP5*6PEK>N3yEv4Byco*K3CLBe}2bFz@#mN|B@q&y#<{!bz+5+ebtGWV^WikEVnV5cb0A(-p~^ zIzMYbN(hR@Kf}q{(h|nW!xHFL0fgm?^T&mrv1eWcX{Rf=1gOfU=B1x*mR05FIbHUo zu}Gfds&9X$V!XfN7f#3fUR8dHQm_um<>no+WD9f4cZ1etpLd*8y)Seo*gnr%8F!3k z$%+c-N*FjwwyB+tfb(57_(JH-m(v%#h=^olFS2;i{3W~wB7m>nIdVyM^Me}}$@yS# zar9aN;+oS5mKj*){l@j7id5U+!-*~O`Pyj03yX*L@m1uizc+^qq$J!Bb0K)olq^)e zNbDc;IXSMxbU^oiw>^MaFiQUjugtf&|Ur9K*rPR98T7M9!j~C8A0)!@v$$VM~s~pZ%;ORkU9VFT36Td23D#!xoR*mAF7EL0TY*x zdzDM3Ij6nTP+!ZGL$cpXi;-yAs_68=O0!iR zYhCar&m;*{E*g4E#3Q(ht9%diU?JnuxVDN!~i#XLz}LOr&Et!BOTr~S9KfJfoK zz7#0jdwnt9GKB9{=4A%JFLyXElrOCWSx|2+A4j6UdEgQa_i?p?NV@RcMD`B)q1D*F zHEo2cP7VEi96o?T$CAE4%)q&{aQaqY#Q|aRM!uaSxJ)J-yw0urAC8< z?o#blc$8JuTzy*rA-XLqs*&1v+KF{H&EM9njBym*T$bjF0Y(1N%2r!~O>MuNN?s6C zk1>O?=AW6_2F>42{?zr-eo!$Ib2Thmp#7Z{SlXw6nETjzsN<_rXsVAMb>#O?n{DS) z5)1opS1yT7f0*fY15a=MJ5o`z|Bm`4UWKUz*Ns4^A?3Qh*jrGa3}2Gx$;QSf zhC79fRmeKop1oTsUu(JkKK0RsKO&_bAg0Z;TX!<=Y@Ch=ItbKFxutP_<>{*OB#*Fz z_a-$NByL7^(4FsB0xE*|xB-$b`oVei#1X7?P11c9 zOu)*U0^H5)_ZZ)}#$W@<6_Y%TuqIQUvV`DIIU2#RO5%)}-h)&Jxc9j}FEWBZ9FEBP*{$Vi3$N%5(IT<`tNS>lJ!y3QBo-cTnBWMY!K;ZuHf zgXwnpf^m0{G#-s(>sqlnB_Y1dJmYJIVIl(3YHrcW%OhshHKW3Dyza=E4Oa$VB80ai zVM1LB+~ISZ=Mn9;E!0(gUOUKxQ2!xkygG#Nk<@%*v1e{k#<&Ug?205y3(Mti5Q#$g z%Y1m(f~j0`u=)=-e-i9pF*5EE-|sS>MjYjv7@+%mCfGwwJUQBjxpVz{qgU;GkZ}bO z_ts!<5WN_X*oy4zwe^@Bf)t~M{T;6d3$M`OR3w-iW;}B%x z<_(2@WsSDwi*qPwi0GE{dnrVK4F8=Mo@c5yCPi2=w))VmGNtA%$cuW8Jvu(X{Nnkp-5FNR0=z z18$^cp-IG*rX-7r0!YN*UDzhvN6sKNq;lZ~>)%1FXxq+3AczH@a-^sGc{K{a|Hnl00_`MgwB0{rQt)^amE0WGc1i%61=o_GcH)u7fFZqMjn<$H(9|!>Bl?C-cq2zmUnu|N=w1 zqBbpVY0x0op~CD$2s0$tD>Nr?`t%=wz;k)4rSozRSvn~l7*mh)*cg=V25>H?zl-uL`K-yvo{Zs?oY z$of&4WS6Jz*1@_KRMo3w_dpg4jb@$zM!>0#q(319D{#~5C1pQGPGA@>#H%Qu+NUR? zf!NR0@nb!U9|Ay|-S4di8lSa?dljc! z-1(go+$H$jdq4xMJ#W~YE;O0B5 zVtOq#dNF7w04pLVg_#mgZo`i>zCFpbcYEDcFz{lwi&`isVbHD)Hq^v5+N)3D$UJBn znK;&^Nxg#2A=2m>$UrJjzEn(r9a`1U*o?)}elY)tM-WP=bajQ_UCSy_UT2n>G?fYi3@N2Ip3AYe9_t;%r>ys)Ezq385bS+PpBTA-qdp-NC2JhDixF) zuzU!lyO*!hBxa}QTe+k!32(BDR#hNlfdw>)XuyF55WYt)&B7dz@xzd4`lt~a0^e8- zKlzU)1STl_tNrKtVUCix3yY~}Q)$RAe_jxCP6x+?O?`gtKL;;2HAky=B%RWeFpiGi z+^Hl=CQE+C4GGJ+N2ZI!0&F{m;FpSf{3BB5FW=iNm!#QO*h{(pM;}G+NRE}dJr)7? zUOiaxwu^V3*i_#0RCbAxH-%Q%oggN}Yz5J*o}rNDuvb0A$Mes!1J%;QEGz<%gjDC( zd`Wi1wAl{-Ch^>F{r}rAT5vJ=Zc+EJ?&b+QIw}nH8Vdwh)znKVGEZDi`Q*mBql})v z&`-;Zp8ZEp2Ev%MPrr+XP21S&$GXY+b%Fv5(3+CY!zvy0X;#C=`q8(Ir4EBz`bzEL zm&M(B4^5tl15~Lo0Ky-FJfX=B5=WnC1xM2-4j@SSk`Ne4-^(??ZOmGAFVUw#0fi4+ z%};;iy~EjZa1KU!`8e0!cj59&g6>HPvit|d)J$(}Lgm&>{6o$G9u>?PpPZ5<5vp?G z9~o*Ps(vm>Sa)7gbiG(|T&xtM3}BP9)n%3meMzYG6;)6(-IvbA<(|#ATHm3aJ-!iw ze+BDX0UqOCS;R7ugT876hD8*KM)-Wb$u0DmzNNBOx=eET;%2b*VO)fvxt5OF>!{pr zx+gf|V$UnFP`^p6Xb^FiNym{}@56@1KY;m>C$x~L2(&H&iOiQmVn z15t{2IXVM;Nvf2m6%e#KR~e8v{(I+OgGUa`WMdB?rOD1sTTttpti;N=D6QYBg@eq# zR>+TWr%Jw?(+buEwE^AdZ&s`tf62Ev+i;`sd#-fF-nss#)ps=EPP$246`Ut4O?Ku@ z-@1y2BqzW+?Ufo8CfQoPSL`1-9b6fu&0~t+5CW3q4hJ>z_D-^gfdjV%jTzpnk`U6J z^Qf5hx=|0^dC@AdR45v?3fpAyJxMb%cy+@ zHflphk@HF+XP)L4h4Fzq4{#58N~Jo^;ftiiQo#tzq`=CmVh|J1c5}$LU(OY;VPbOv zSBt#PxP!W;MfQFnbrtioj9&YC}zEV{deTWH=?xAt09kP_F9dLa&0!+Rq z%K@|*Iaw@4^l#RyH1b~@*?CRK)g_#3p&;ljJomg3*gz5_8BHCBoQVWeYyOL`C7(Cu zkA(~O^h249&l*rtj_j~d5|C-iYkfVZbrgJ>z44^nJ}FkhS~b4TOQqqncu zQja*pdp`NKy0bs`{!Pw8aWi1+i)a=oMykG8xl53lCv7nuK|Bl zIMn!a70wUAW;e=kPb%fDZSXGAeIF(z^qm{;zvawlrfRTu=jQk%3iJC8H)n38*0d%tdveL7)V?z z&f{OW6WaS#3GSo4HxB&dOHb!c%hIIVL(?>b_He7Mfbn=x^SgB1%Or)K`A4mc8^Sfy zhHsQKyjBI$dz#!oEz&Kw1z42&>r7H|G_!=JB=7pel+4FR6!4HD6Q5# zv~%qqaayUS_c}2uj@a9JHhqRzr|;QPPEgsI#=Xl^=Z~fP*Gsf|jr4tUv1U2qM^wBY z>4*n1e}pg;75Vav4MRo+AOna=9)mqix?{$Kc~Y$la&NEW|d{8EYf{;wwhwbXf7`uND3`EW96bF z<2&`-@?}-QNJ3-$yEns;VSCh*eiT~8na@JlfFP~8XzvS>B~(A_Je!X3ijtRAHE+js z3*#{JcSXS2YCWv)$&)g!WWr1PHS@TvWPt$lOexO69BF;;jZ z-C-ds4Hkj1hg&-s*^)rxidZ9L*0ZfD!%H5SKZ7uj-(dZI+`3zcf$QHw8A1C`{YBf;a4qW_-@a4~d7;{gci06Y8TVtcP& zn#`fMuaH0w{1^6W{^p=SnvIw*{qfhy=pXC%(CUyWI(DWw6PSSwPb&3A zut#tGAO|_D=LIA0?v?t5PY3?v7^but9@RJZH}bn8(nF)$IEAsdntZTaI?$z`WPsrf1QWVwK8WOj5k=s4VoxSv!GzIgR z+X)!_+%JN@?~yTh+YUdep$43LuV670U-gox0@|m)1{bAH3W5P$P7%5H;VZ?LWKO9zK?`;_)Hky}Kfx?G;H`I#` zh4v z(R#N!fe?5UC+d1It-EBF84M{rwegD`7PRV4+>r6y%f#nvOk57Vv}1qF5Pj}fUH7S# z%P%BH&t$iO#4)T-eMAIxq>$j%O_+h!O@-I#zB5|qhf)U>KIq;#_mUN1&1pPHat0|1 zq1B~VS!0h3S$9VoEi-Eu9Qe#+xp>_9;nsP<|MwHW?gm_Rheuvy!jryTHdRWTy=jpv z)MADMz7~jJlGW}a+E~MhKGr9^b_9(_z)p%hU!9y~o5zo2YzP}NI(Lav4rGyN7EZmL zb<@5vxw^g@TGry*5ip%^rB9su6L7=LwP;s~lL{O!ZlIZF1Ao@7YFWZkK;rHxgcoqOl?s2n9n<+%oe!iWWIG{}$UqweBV8*uFdWPHBFK*Wg;C zVit7hi6M#5OxUxzWW)vc-2lfXWdL-@=A%$d>tHehl3LEF>_EvtKnigOx&q|Im+ zHs(E%FZplzFaJ+xNCoIuJ0Uxy6um`t1-f5lOMeB1&fSV2kMxg;ewh}qcSWP-t1Q69 ze-~J=oO@d@W@u-=fS~oV3r~G%@d9Q6Tvs%Uc6C)^+I&AAbaGO+vcI)Hp9=KW+8Rq1 z^CSikd*5JX4A|2%Y`q>vs~=C>c72q7r!6KZdkDq6qdjER>a~G#JeDo#z8&<|uIqpe zu5m3fefXy>!QW1NLNwJLn0PjkV@ULnVw?)MI@i&#? z9cys)PuWjCSkse<8H9hg?B1VHSfFx6mXxu*2`Dv2eJ>wDQQijiT@ol)I#r^r~ z53KKAixBpL-Mb#6IQWKGv#BWfJoKDjjaiKl_6=UIeNTCh!gwVp9=)@jj5aRteru7O z-p?%#H+28(nXPlu1t=c7GGLVq<2kRYAJQUtHEeGyyXn%HWQneZ%a^I$Nc!hdQB^vx zBx#Pw13QBTNuakL6R8~C66oD^<7GncQ!{hmv5hgMMK*WRuHd8C*f}>t_?NS|KS zQz@+q=$wUSBt?mr&0YZG4k*~xW0I@Ta+%V5G#unO#$bVky1J{oSg;_62LKPE{+$e^~8er01gR$rVBip3Si^AfkB>_r89LWCr~?e?e)PP}!850hg;Hq~K*`lUYAn8AI>1r_$<7XOs5lh9Cje zYH1#pbt;GR|Nfgf;qh#-Wpb|UXBY+GS6=qj@jo=`*k~C=-;AS41|ODTk^^-6R91z4IVf);T9KAsR6lbfHBV<9$IDAp9OEEz|C6EmQX7ev21%oq)bq#kiff0=kuuT$W|N&~lQ-NsBC$t%mWKCn2gPlLH~f6n&!fW5T5h#346v=m@B zx!+o~UbjygO6-_@czW`x$zOn*GC z=&b$;4_#g02A(mQ1>v2&kPZ006&6X zTTj+<)+UZ|@PBq{GE;X`^T6cuh((jVu6S*(rU>YYBgDKdswS1LB`4*94Pw4e+s~;^ zhER?VQ1pXYZp`w=@`jIx`s9*PPse{P>Yq%jHoUtI!5+-%XNN5DCC%q_jpldJuJPH4pc6vuBBfm+N0s4oAww26SC0di3KDX zXtA#s;c-(24@4Y^pHYrhdv`d5<>LXM|HrBx76qAs2_zwdwEM*3gjw!YArQqOXBArP z{BzH9dyH?9n#7$5f=Y$KXjx_YIDnq(R&tsn+wd#HJTo1Pp1XO%c$_{gQv&x^RZ|6e zegfnS5CL3@ps+iXa-3FdfajT72*Z0MIJ{TUTFrRr$Javu8vLV$c;IcwN%}t2WvoAO z_msgyDoE6(8Ht)%NZ6Z~X<4-2S2V(pl<|=h(tnaxzVYcvZvf8q{brSC5=wl-YkGLF zW%}VQi=Bz*O5}XjO8uIqHp1DY&ELuJ+N@*48y@2{uH&bh49}P28(&Z!R{MAHm)m5d zn0L=x^sv`x9*>1HzYpu%v?VESU6}WNViK^0zb9XJ&b+GbT^bM9J6yw!i#}aDy%k(Q z>Ab;ob8bZ!AHLgxD@`^4fYj%tQ78gb01(CSViVp3S4eJeD6v?I!x-MIPZ%>vZetMT zLp`~MQE7ut=QXWuzVl_I@BU~opLABHev_H)rxT%v*Wh_zwZ*Qm&U4HQj9vt$gRA~YXsMHv@%ji3f)P0|M#S*TM$)Y0K{3TYb}v&#T?qsJfn z1g|{8#+6RIut9-mAYy_E9ARrH=KlhU+W-E=L7=Cok0H65+O}U1;#xq}FrNAzKK(F{ z?Yaz0RfE3RQ;ZWQdF`W(#pfCrqh(52J}124sl3B<@kN{?-sM!z;z0A=7T&THUET8l zVFdjSAIAeFOiHH4qYlMWnP&fO^z~b8Bx3SDeK9jdtATxabPLJ!r*^tP!;7k)#*bS< z=I?EOj1bX<(BktzfYBPS01)f~o?5NSIr8>$ z%(f4U*xO~KW+kg@P#hW4qAKFsJkJYoeQU0|)VDv&w{t79pfUvP6-VETVPvndPA&cp zU-smy7~Zex|#c7<8Hjyzq`Nh2bf7~4-D0W>-NYIW}XGzBcn62mWxfx&wO9W@#Xs%nhQ%P z@=rSlm8~m!1-NMVQ&C^CzUY=Pj7sq3Qy2g8NBBbRpp~6Ma&7&LVxrKjLxvr|mD1Ht z-V_DKF#~@^*L(F7M1cztEJ6DqYOx(4GzLFywg1P+qoMy{zLZN$eDZUpeL*miV>nIN8FKQdDi|!mbkyn>Iym-@EevkCZx*BK* z0sd0{(acFxlVkc~3J-oN{w+MR#5L;>g;d3V0?Y4;vnj_2JyIdp>Zy6Udtyo@pge~PNVTCaL$!eM2a#`l) zI}uyuSgU*puOY@pjyrO1>d45#TFvf>U#>%SLvVWmRok9^@K6&lA_m8k-0S-~Vlo$U=7PIJ>`?a+E+DZ3?Nej#s`aM$8^5x5xTSDBh$)lY~ou_`2Rz>-jJFh~}W*`oxe%Kdk8;K4E9;*b0>z zD>yR`N?tlF^sbg>oQ{HLBa(^N*u2{gH;06*Ck6BU2 zhrranj#dWwd+QhkaX9)s;?gTVAG-3wzI^&OwDC%XM*%&EaiqVCvDr)rkhb2oLT+&K z2MGQ>iRHK6%Q)yE!|x-ODkXar#iz| zO{F91Oyl0swhBn4K$Q2Cq>_zdqC$C zb)O$J^wHiC8(#J4*s6C%dQvUUL17UiWFCMt9K3RsJThgG+r;#x0kbe&)06K2rN)sX z0c+>&pv4*9mDv5=xtLa>f^zrcMc@EA}u2d<1K-9 zrVQjOY*WGIdR4KF88+2bbrtTAJ|1VlvN$I1R;cg(v*Huh#*L^g#vSQET!Zv+Sh8U0&+_iSG!(n0soH?x^df8 zKr0Yq)MM;_b8-Fg89w_O!$EwFKW^!`qX%KCTd6M>)b!$dfN%L=0=&Xg#gE_oiezzvM zsp50a--qS&AA7iK$e;S6YD>Id(eBHlLchV^Tb-4MDEPldsyJ36qhQxX1|({=OhnDd zv@g2O{D?w-wc5!-X&yclWwt=i+Ek1^UlDDO?D}C^uR-4EY0+98Ctml9p#IIY`ChSJ z>*MjnNWks)2JiLa$;57-KTk`u_BxdH6_f}Jf6eyrg)oEWD6VkM$wUY@eYcSBOw3Ae@g$5V3(N=DVH~RiN8+Ga6ZcxK*YLV-|W3l%t<8PS#lWQ z-m;Cyj4B?FNH*~Z3nCC0s#(&k$cR{$pwyr~CK`tgk|X3QV9~nT^Dydp-9mVB#mg$L zti_dY{SO${WkF#s(Y5<4svekL`2`1w2U^5r6FVq=s4D9uak^L3NW9^S%iL?$PI>i- zxsX>n%(rM)FR-DadBX4$dSgYtfGf|rMZp^`@@Xz5Rx$=ySPQ??B+C&xI8 zkx;|0YV2PV1GRoWQx(%2T+MK@b?@&9+likXFqi$1`joDt|D?@@caYVd@K{}-T-ogd zFH#d_b<34j4?|X;GMDVVC7}XvOmpZ}yLqJO7EtM$t{Z>O!J1pO8SwnsZ~3Czn6C-( zQRq`l#>G;8_sG5ZH&(W5HK`UogBuDw#>mtpRdIx*ICuAE#C*A&lCS4hRjWa&b8)cu z1fYaU92!o{#x#t}qe-bLpyPpGWS!?Wj%KqtAEq2evWI6yv--0O=e{pHaoN6-q=`Q z(`kcS9$gVg`I^VoxHwq0*>}E6>$x zci|iH4l?P>-vI!Te97vDV3#y5LBqrPx#r#m`xT8t!AZus)(kC8s3?f}4ufd`_4w9uLW+@tvuMyS1(|n+=5;toXD)A3toWXnK(? zD@^luVOIy=nyD!5RpRlEH0ViY=^^FsZaX1SY~J>{wD!D8@J@m2-tp?e@diS_)pi2d zwMwag9j9_Au;=T(_kqGa!=EIje=Pa#R6^C}+23omN0+#_D(C;%7hUPscY=FZ|IR}F z?w)jyaSt@!3ooY3BY8XlD^udMbix^pZ&wdLSA~ABV|R=%j~f<8qHjz*k5Z~Xsed;K zc_q87N?P1Qe|=_&f7Zld;5lKHYH)i!B!s756sR39ID$gqD~1Es7;P8lWPLoOIDk zNaJ|GN>uHbqz+_M=j8Lejh^STN2lk9Y7Xu^EQ=gilW8 zZMR=!EV8cbI}|`*8#T*&M!KP6lk-YgG2rB2_{GStnP*By~V z(xh@#Yn(+1w&xSe>Im^(-(Vr?PB>ox8Ku`7useLo@lQ zeYMa|i5-8@r^2711G$KvUs&nn7x}z7a%Z(`fAao7-VZ6$vi1XmH4A2xH`FT@B-=Jh zpB`mnkCYn|pOqM$1L_(^UCAN;)#y1S<3az^i-$RRDlSxN>BcB7dYcS8k{5o`hbWsB zkJow=@Fxfl$Z1QVr+n#!vPHZBgi6s)8MR1c|24zYa>|P$Rw99s$*jVD)wu z@gMA-f4a}cU+idM+_&CZi)%Oa8-{N-aafEAO0phf$Wx@l+2fN6p4qCyZ}iC@U57sq ztpPj(9Wh4+aY>MIob`^oC(Ld2F~fiL|FCtIL2-0Zn8qE3gamgINN@`-A%g@@La^ZO z?lNeA;K7|i0(^wv?hFKXCb-KmI0Fne46tl%?bdG9c2!q(-@bkO{^{;p=e+N8mL@!1 z83AFjLHXwZuYtspAfC>wdJdC^-W2$qjMPTCGsNi##5JLqQ(JJa`X0^+5}{-`cb>fd zxe#tDGVgeB|81+Kao0x88<1tUx(1jsz6W;+;SY+*o2l^w-9UWx-hADMFLJ9lwm9D#&&zmQ$j5dTS$o;4{rnE$L@MU(jq#KipjTN`wf@kSXSF)kfkvzN?qvE2Q@RnH4IhjshKJ5lupgK(QslaUPP z=Qp(hSeu*{=6-iMbQj6q7T+RXl}cl%PBn78xN54DHD$Q~VTlPsL6(LRhlroxKr6D4 zcdl=JR{h{^WI{krUiI-~`KfoT2A!{k~0~e?pDRySSsQA8syW zIBhPPhfP7vnV-?DAbhFVkuK<`)v!~`0`I}*lNcTc9JSkTS;f#I6?lh(Uz{#E#5v>8O z#KX3XXnvjB9<|KDQ_TZB)T2L3YowGEx*G06hq^(G`sGZqiYez$4Q@)SU)#$nuQn@MU-M%wSEjUF@tXzZi!()BsG}b9ivAJGY`tE|nu2Hln+w39lnC~b+$vP< zQgHdqu#v?>#kJV-o7*8{@j|wTK>{*yaq9Tv}<ITcQLRSvWEMf$>anMQzc?&&<_(yqD_`w7Y7TX{GGua zkNtd7vML%g9^?ypBG>Hj6u%7tQ#$e-W~%*HQMnZzK;A4fD(>vioQO)OIeskW%akn;0bradRa*lf~{8+1wVb&iywlW!m^Hec{YN(%8k+PrMx zVo|K!y_en5*RmJJB5|4aA9m z9O%BF3$~ccl)5H&u4*y9?o{AG(aPp6)IZihp!yNqV7*(=$9~1`MSTq0xqoxlHob{Y2K@`pc-=x^*%xf}v@KT&s z%scsTJYzjLOz$O|ubh@BnP_||3snHTYFCX;aR`I&dzLRAARoe`)^=Y2+P_6~wbRv^ z+3r`|4pAW~+cVG3!yR$iZykSX-xO~7h!wOK^_?(pRMhq|9v$^YnEiPYg;QvntSwkY zbp$=YmBhZamdvxrHTB8oy8pEn2Kn#&J{tAOnO<;`6<06-Csh6d)faFqM@G~bFjD3b zLm4+?eH#sU*RB>@2lx}lSUU$=M-xfJPYEo;VV8E|pKQ>@CVub>k9OH=x2o!`s`}y< z&1>mOu!41p|4$z*cdR_E3!IaNyy3j&6PY{9=STdRsPe?y1S*qE%{!3bJzs~U=5IJ8 ze^|yv(im(zdS=JKO9oh%M>>YOz?*vv-*V}a!t6d3R#$Pkk4VA zQL;Bzx8ng6OIS`bJf^YBMO!IdH{8#qKontB$!@qaN*vf+D~{i-1d?kJQm$IuYQ!pX z92SL(AvIH}ckBgyin`}7GiA{QK+!*Fc^A3E*w3TJIU{;3x>9CViR(NamX7>SI0bC( zAlle0X+5880dB#Xzj_^ueY(TR;lSOhvM2PApzBVD`T{!~YQ%2nRQvS9j|#j(ZlZUq zAI=w?0sCXSIkC?SBp>IZUv)jO6&HJ0?)mG~fG;`ZC%W=v+d)b_!HSc+`pX$z$fvYS zQ02nME*%=8p0_rnG>6`}nsHk8e{#V&=Ag0h10ntd)yQ-c-C#HI?X*i232 zw@fE?bl}V`wtgl$q@*Tltyi(WXVC#@yE#=k!(u~X0?u8~?phTU7N-vUx-5TG{}kHT z=3cl6<=J)}P8t>w_kNKH2eg zX5#qCml|F1^#vD$x=t@U2+ik9yL=}GWTbrNMQ&Ni)uYb0Po#YMPRFxpdh)Q3j@z-V zO&TBYT&N|DlT^tTY9Ub`)G5LL7{ps?dS`a|CC5Nw@L?3SJ4eka-WV}PjPv;Yix#e0 zt^Qf6)qx9CJ{!ujlSJ&%+|`EwKU~X2{mWJOvpWbly6rpRf8XPwY;7Xadv*B24imfscz6J2cEA*S;$%loz#2m;@b|7)DfvyWLLDRPyO0dAX zh#hNQZ5Uof|DSbp)qELAB59DjlfMs%Eu{h7b3B8cjg9TXiyY_JdAwI;yBr2cv)_B> z@(vdBy-m?GjnNYShHRp8f46+$a!gj51YGSwQVbMK7;oa?qmo;SQPnY(E47Jy-mld_ zVhr>r7(=~kRD9r#^HKDFJK0o76#q-_DSPQ7E$gd!-3QLYInVgv(?l;rsl%(!1Ezaa zc5@dyRu9XE58u-t4#y|wZUnl{?>834bjv*!B_6n!%<~AC}Qe_lwq03Lan}_k+?p{a!i7;pag=FYQV?70f?9`;6p#Ieq~vCD zC!E;36D{J@KzyJ#k0Y*PBdNOP>*5m4$ZACYeDhM=MN&5r1A0ribaD`d+#xVB$={&M zAa;_G=Sn{kOWhFRc(T?SgI+VnwO2b@ccYU!q3g)z%!clZ!{F^rzQ?U@u4o4vs##>) zr;`CB7TI8M+#vnek&g1%iGf@3z$B35uc}Bv9=( zf&F)z8nBW8=A+3Y?PlW79=~-ATIpk7n@0)BfU#X)i_z&8-D4#I(0j{!@Zw&0&tkB@ z2Pc!VLLX043hy2AcqE3o316jujlWQ0uXdd^AWyKR;>SVLOfq|Y`+lZ zFij0*b76tLv!gTvK2Q;Q-A=CpP1(eyo91=W4rfAYI%vhW3=ju7GT=qaVqU>@|<;3EST*Lh|XEN-iZ zajDp(8jxOtXHF~`5GCz*oDoW9^H4>RSS(#2wXr?=`>;2*kI20S>$z zy$}ys3>1mQ_hH;x9IN^hz>-nmci#=bNnBz-G+gAs0UYm+bWQ?FrRj3$`snC$d?o7Z z;4vb)(vM$$jt?m}AHs(_0gt)!ry_`!cgW>-tei~00827f&sj*lOi$3?a}u*7jbmaJ zXijjTEm_92(b3tyQWx@QQ<4cB&+;m|{{5?wwAOz6%{P0LCAelRO|4Sof9o?%H%ekl zm)=nN2)c5w>|CDh*}arN9U1&0a=gkJqvX-YC1a$Qq6;UDPzMF2Kty%U7K)g3+Kw*r z=o#u_+}s?r7kt`Lu;^1q+u>}m2$O-M!)UXBf#vkq3m}-@QE)Y>;3eIY82qRvV6p^A zs&OITG`{ZCcJm^jSH-(FptCTN|7bv@5P+hO@2kJkHFuq&vM?9FJ8BH_ZrI$9y*KPraD9EKJF@H&M~uT!))0@NSpRxmx&6n#q8 zDlV?zF@h8yoU!vUR=xgXx7hy^KZ%u=0=jdpLdPCs(6(NDF(-??om7pw+ zc1Mo8_%fib`j~=TyS|zy>5&*4eESs7^8qBRe57K|BZP5L;WZ9H>;Kg zLzGU$lFCSEQhw=nyZzz+(s(u#7+0( zusMQ+1wBn^x1q4+u0AMUIvDX6Yks$XvW$$q?RE)b%joYH0SH%bQR(s`NQp>t={^VF z&n`M%{23fwy>$s1v!_b8j_p4e6Z@5xb7RUh2WIh<_o+xa0^VJdTd{f*WbJuy@N*yo6+`*l>t&>^EzL8dDF=flOpRH^a=CbWFxxr5iaO=n2w0nant7pKP`C$dRr$?XRLeMRIM66HXlul0D2gR!Ge$&`I#9hYheEHdmCi zofGsRKcCzOX9ML#$o}ry`pFC(pi(+V)>oX8e;L}XSlFQ9TB_;|3^{gv0m#{DBx@w2 z;0g3ZIeH@s`g|4&`#Pw6ZGBP59I9GKWCXhpEYYOq@xbIZk?~3(C3+tFdU`mo9cXyY(H+7MH5JhK)S}J-<)^|6K|ukuI*crF_al! z@@9#w(PLR9qxL-8S+?Wr9vI&@l9@0%`ddXWJ3o7W(G(8{qa?^Cv9tZeYXDROEH0$^ z^AGq#%OPd{AK@Z~VK&&4mg5_Sp=CZI=YGd+%Jq=W5>elK?uGn@V#)UbMVDP&?U5j5 z(R;%Hl` z%T*(oxK!PorJV9x4#Zq^KiTE8az}q1a^b#Y+>C%?ABj2M-Ccy_k1uZhHak)$ulC z-adSe2&T?nMVYM>4mKGJ@1YBmG})`zXt1S(@Xg13nKt?#XVs65-GUD08i90{jy-FQ zR^n$uQSMIrKj0H&e&FAUCm7ryzK?wit}}i5S>cj>N`c-wlxLil89|j7nw|8zymINz zQ-dOT(w2;QhH1sXZ7+Q$o4rq;dIRk1m);OK6B{zf=8bQNqTCM*)8LI;Q?Dn1fctyP z^%WvFG&;6>UP-~`ndF-*mJP9evL1tw=hheHr|97L)%~hJ`tFn)Mm92DzYjdUmOoJT z4h2(xCo#nQK)_NnW@|Pa^0)Fv=N3QR*2gQad}8RXqn1_3r;(@jY63k+4vl&F%;BbM zED*)YUzkyki6v^1pFY8wp2ZUIh`vo_QG(s%i+E!Ecl7U3wd-w*T!~Pde$d2=U2(h# z2DaKS1b-^3d8)C#kR_!K=cfTtzy#SF8Fwq~^Mh?})kYzW$kzh)k;4UZHPpras5Y-J zR*Hk4M43ZU=KQER*)F#{9rj$szcYtWNjV*4tk1Pp6&G-9wqM#7lrWtq%h;OOghxG0 zeB5Z@8QYzP#L^!i`?Mb$lAM;$rWJ$GA~zx7i5WPIB(#>y97c}q1-}`1JP}A%HhR|$ zTue_RQH-AHs3(iTqupMAteC5Jd@S8 zr15@^bj+@5?D~9j_84eIc$Uh?trCotCc)FRmSPB`^Yc=obkY&asp4KI=P5D#5&lHMWISPuxseZPi&7rZf2l$r24Su!NW| zG9p1lFia_6G%UVOBywVJGsFWI9wS4oOf!K;DAl;l)!hI|&Y(XSCc)!2=3?_b&OsO} z%|_w{ZKN5ciMsxT&&drFGL7|?hewGTC4*oXT%nMhT-z{UhU4DHo4%AO?9-UFC$7Ycqvc^!>5Z-zt(`=vCp9Alz*xaSbHKBqNAHn4y=EK1oz?xR+t?A3{MB zV8bGH_HcC===iRJ1aA^C_i3JdKg1jths-kMpMZ>2EG1hGb)#UZ8 z+@lQ|$+g3{gW*QRyL=>FoXFFn+JS<0=6E(Px>`aQvDDL4FDhf3to4XgXVByGx+%c) z@hVK{pfh#0!ik+YAa*+cz5EMMq11A|^B$`GrP<=wpNC-dZE)t9dMky-5xERtij0Df z4B5i9T)`HKT@SY)5J>wvw`L{EvWUGG`q7K!B1o1Xt-~%oI76&BbO754wfMwG`49n`_?^k4+ zI``#T362)bLd(tS81)JSvWQe=vUSb|0Dw@#g5a~_(uVpcK_P=%wHmtu)#X6Z&6IW< zK=;m1#OH7Z)kBPjrY?9f&45-Bxg9(0IeJ6Y&=Rx$r}n0Q)+;4M;6=w=^UT6H=Gm%Qhqf zQ9hn4Gn13y@7d$bkawhF>$fMn#6|ohwmf~j)Ra5~0MJ>1@mrDbu}H+c;+>)Fr+q`F zOZ`VJW*f_P^%y1ezUocxr)M<|#zu$X{1q{U+p7fCyoQ}kCYlK{E`A~=$S;4?TseOn zmJ-aNwB}}j6X|J!Zry=rNIvmM4m9^<-ow1vhoQLT*Q(d^*3c~2A+vwpmEwPf;%ioq zdCXz8X?-itUzF6T#X-x#x<$+SpIaRGM}1jYa`u?S>U}$8!rMk~NNBU_!uH+ogpjD&a_40F;mVo&LB#W90uHzFhg-6C%965?Hb!m>+@bO-O@jq-h(M;hIQ*oEg zvL|iplzQc+fj!E@`3fUAXwsX}c!GYyC7sD&GQ(!@PEW?lUbUKQI@PzOY4*XZ6q1UH zSy)psu*yjZkSF_?__%ulzCV+-H}*?*dv`Uc|7}=ANZD z>tB=19BUkgLfdhvDG8b=I}A>&UG^Efdu;Jz!D)N-fnnaG_=QgV*n#J@R>)EF8{2T7 z)(;v+FrLD1539OQ$^EWjK0mABbXYsYKRwC^OP?Gcl>0p__ezqAf18+uHTuR|oZ2&% z2U~nO;^^`G*#=Q+8bk;$7e8cW@|2VL<|Rpnw}@(2F53!hP-!#VgI|~WKE`4RN-St? z)l4<~F(HYSh~n4zjPW451!`M7#QP<9)T6Y`*-#XC@Cu1^b{lI-Y2fSsR;29ZdZxAp!NDP3U0M z*ey_p57NHD9(=c%3oOYnpceVa7{od*HnQ`QRuCKPcs~0qtL*K&!6d4OC$uc;{v0-% zC8bK#s~l=abbpY1|7+{#Q}H)rUaI9GF(>~UzykvCa9)9wl*uY%4#1KPu3w%@v+`7j1oPh8f?@Zs^+k_f`PX#LH8l~CXXK_FTQno; z4mY21Oy!pk{RiOs(7#Tzy@C7Z8(kx2n`14x^6Ml-#h;9^yS>ci!pt0&Y1F~=0JbE&ll$~iDfVWMsRYLTW^sRAOVyMr6O?SWqt6t+jBgS=@(g3aH z&OEy;nVE1k)9A~U231R}@TQE0ww?^K;poYOf17Kv_Z*Kkf|Q|V?29u3xh-d%heJKQ zWsG?ra5aOPF^!HDC_yP5?UHk94s+w*TDnTwg!x)1KH{04+on644r>hp%z{ z2c!;XI8QOyeW=V*eG4nxSCaYH3vl05x&CLz^=Jg!GudFg@03Lqw=}mQej+tF)pUl~i;~Apal!tx7e=Z8G+l z#Km)7I~}5DA$=vhUw4&(w^MijtUB2dG(S78fAYbUGy@CRya+!~2VM4j@!3cXDBbMn zSya&B4vPDQgW63m##h@N3kg*j$!&9wNN0YA)oGM9&<^nX=chwW9}rd?bVZfoet++h zt0MU~2XlJh2TgUw-*S@wL~ipy;_s-jJB98f5=H8n@Sz$^OFflBeXIKE*rA=3eFm#D z#>QOu{(H&8+U*h=F&x>FDaEhdKAuC@&$aLXK31MaY{vcw-0U=cnl(IJ;WXVS+aXEv z`}*L=>UiH#yfk(D!xp7+9gq>t+>5)prX?km4#k^%fx*R>ox{y5+yU7t5?Q&|DTh`% zG(GyR&`E-%mtFJht)WccD)}U*Qg&`;@2>SpZH`_!K_j>-b$&gp<^3?AAv5MxPqWZf z2n|54Uazl%?qW?=IzcJ;qB4OUcjJJ^>k}hqP-oEP_G)|Jk6nwPu*2=aA9qu7I=1pe z&7+L@%ls!-U*2zi6M;8AR;+yURZVoOdo9x03+wnZf>l`JLDyPu<46@W_xRKXG5OaNvfbXUnikkSZ!JywOp^i0 zsx1J+4BOJ!$U_p;X1$KQHvgHNCmnwfPScqHIcs!&S2V+e|HES!RQk&!OPl%TG3V%= z`Sv_f~+;p(!Fk8Bs}uwAqp6mTtKgL(R#V6E%~bk+T`Q|M?6O+P$yXmK?ULSN(H zcW-AHd3_i9xFc}4E7Sh^T~y2qQY@N|L_!g5`4@U{K*w@~%&x=kaScvBmY8|4)_c(p ze}OW|F0ax9AHY%pPc!War}mdkrtcT#mr4LGT)fs_Z7HEv6wq152eS+bN>oHmDkXtd z#64dro_%7?EXJjzILy*GIdx7;Z=ec?wO?O@K;*xs15 z9Y?h=ZSX8iEL35CD!L=Xv(8d~lJH-Ne*Tkc8lyvZVEdnThTRc<;*>HSTFqiOu|o$s ztM9qhCi4|@2$;@}5Y%F~h|T2a{`9>Z9lBCGlaG&l)A&aF0V-B`%6=!Ix|Gq4wravX z^!KdCz@T?kmY4hLQYYc-aeZ*HxMKf&jG_8T z%1!|~i-v+;W;<}FGIK_y%jzyCNbloUci_=Nh`QH*{w)-D3qBS@x6Q{)Ai@pGL{olE z#1wQAp`p1EW7m{HEqB^oI50@~kr@R#C~uPPBc2&HX81Y`At7S(6aFJt52NOotM>L&*@v~& zC*rus^xf<#p!>lK>qF4l>-wwqT!z50@=m4XW9=tD`jHk^e+t~M=2v(w$nNTR)x<`B zoCP;5|JlD9!NXgSCj$YCkj(`>pARE<@pPa~&Ow*~aOhABV^uF%bBsY_xs*lRM zV$GiDqUSX@FA|oSL}BPf#TINi-e#`G;&|grHUdlL0|Lllx!fhC{*0ork7y5dN6<;n z6$e+Gz*h9G&WrBHA<9>HnL!T-H*3j+FaXfN2L7Ht<{5Qt-sjl>w{HoSabgt``~fhv zJ1T5RO*l?55ui|DM-vR`fufObncMeyv>}Kyc2dg@5B2rFU6$hSGkEFL9*uxIJ zJjFv})aG$Czunu?wHAjpy=j_zm&M;LW72W0ocB>imEYIzdex_Uhz3&8?&EgeT)no| zIkCC9>_{3kLb+M7^5y2ux5$LMJFtUmv^C=kBB8shzCRqdO{Da;cmjc5QmXh?d`wIG z&t)%HV{N8n@{Yr-0y1vXX|=6Q#e64UU{Ngr*e)^>v6LChq%ncuLv&I}c<#e>J^ouQ zX7RgcyJAOC$g?xHdQ%eibKxJjy>-DP<1`<2^%NV`&q5!@V-VRCTSVH-(3M?ei79MZ>G+uQJ3E2p3S9$FBNig0*AO;o&Hmef%^G&0^ z4V{RF4jU8z)eop(B@*+Vox+;G7={KHquAkkMJF`@JjvqIe$YggpOHp*9oZV@2># zC|nn+Y#%(S?Pn%>`fWMdNJAFmvb!Ql)#S_g?f#9Or<7gpW4iTWUpsziTK!C7F4do5 z+w%B9_L7x+AKRDM5@qP){DelK%yDkLy$)$IH1rg_3c5SL<82J|M;KXW&R2WbQuhVl zS;)Li7Ye_Awqh*#eW_k1hiUs-dy~E(;YHb2W+K>HL@cH;QIvRcEF0gbE=F%*57Wr8+_Slv)7{R*TiL6CP;I2^Of#O*mP^b=LQri}00vbgt?7Th;;4 zc1teu55Hh>FwyGVp(>IM<3LT9!Y#9OZ-fcorMt)K?t*0*GpZ;~|2_J-Kgo9Iq&fj5 zp|R%-lh*hF4AwV>B9ib`w|;y-zWysC7`> zYtvs87%JXj0OyJB5_7t}IGCZPX`~WW5WZ#+znmAAIutJd#pZvV-8O3$qomUkYt`@b zWEMAbf8G10UU&JG1bP0U>1+2~P#WzJmK`v(XwG-%?NZ(2;{5sw==#3eU*dt6%=tA! zM5t`>c0048A=83$caWFj}0Rp7VJ-q0@13jbtQXWq+{5yQSn!h z>1xoA{~*jxovST!%*XTwzg|auZ|0M7d-+oa?yNXT8g{XxAA~|dE2<<|KQhIj`qoD^ z723DW3RveeaGD=ez;Yrz^zm#Sym%aLg8qveLC z-v4?cn(cH6eYc7$LF&QNuD)fA`Bck?20}Ec57hyrvm-X#*nooV8FpBGvuxXU6V&*7 z8p*r@e#FwW8yEF(sN1-2vbw{7`oZ^N!?nt`YwNV+1P0pLuo)QyRhG-A4;}oO4cpN9 zB~35pPc@f9(e(dRWsw}uDW#nb;!6Pdt6v%aIHVDQ4znV|9_aO7=4j*zSW`*Ii26ds zs7|@mBtN|h_q+O=WIp%>Phd-C#PR;$^;tJkE*X5%b+_Bz-khbq-U;%$X1Bq0S?_EM z$e}P@j`Y!A3cfjN@M*K>dcP2rNKNs?Ti!yDJ#f!^c`%BMoPXiimcLpEBaBKUfOw4Z z8vI<5gcV$!M{EaXIXTftVVlmfjMuHzt=yw-8NW}8|GG#u*$u}bFo?RvcmYC&YZ6j- z9sH@27r_VF5@XCeMdI5Mpvl0%g8V!mc-TD+S{qi zJ)Sg4^jcQXeT-JN1)u45M@~aCE+D#$& zO_k1ae=z;#9|7f$k*9c=Ab1-j~`hjirL`(Exw zjm32Re8sWiQilToUuSKCob*r(^fp9p@=?iG7hWgGj+VR4Y7f0TZdvkd?G=yXNt@DB z{CY74BlzTRE3jGhbdv~h^HeOziR-@3F;6?+STLVl6g)TTKn3U%0Sx7 zEfN{9d9~EzYDtf0F%2<# z&dW#6587_Oxz;1D(mr}{L7VFDRqY4a7yjg`juCB`S>Z~9u!Xu$Y20*n|DC~=WbT4l z+&B5NI9oY)To1hYVH^oFlXziQLd+yP(IC)spnoRCm73>0*0T=zcg@enUs!W<;WX2& zciak8>n_H^UEj)Wg6MaE6VE(HR0XLaryzEIhb zAr%%Uhn|=GplofR^^O<@{PH_n*~MPH1K=__Dt4}KEY+i|XAVO;Jc;I2U1qD+f4}!! zWIm<(DKifr5IDivPYCoDH&$PyGU`QwO=m-9R+SqJy4=u?JdRc^mRj^hQp4G4A7v@C zMV9LZlg=ve2{iJ-n&YSvV`(1u#=O=y|2jIbdu+;5(-Ys}X-xtK@apxWu zClO`Sm@~8x-tbS^;@8u6NG?Qiekn1O*YI-(&)CLkP@ta!(~9A*0?&@~{;I~o8D%f4 zJpJ|#heYT?nyIC=sJc9NUZM7&8n!>knGL6u5C5Y9%(nE^r{9(^E+2Ka`AwL6$aD*0 z35^MS0#lBck@BTQ?d{oG($bz}Hc~LxlpXF?*S+zni?yJ7Q)f(Xyv&K2pL$-*TUd4@ zc{(qb#U9S5J{Y-Ca*@Oa%qI{FC^?jiTiX8) zmt(EnOw{ai1XV9`8%3W_+P@-OeIO9FK-_g;<&9%&Ce>4vl~`Ecl3W2zveJ8mnvIy& zI(?HDrI<{--;A7fKcJS8TsHW8UE@SOqN4B+;k&!R#kCHNjm|ht%hj`gvTd|%|0eJ3 z4o>Ia3Jl^!i#bB$yV4p(^Tw7kE2v5xOg4DWe|ayl;IU>*Jfx)*R5}}xU~PSMOPzZ8 z3zO!~F8V}}Y${Ny87E~PKHMiRh5c7?zA1FIH0ki)S27o%y?xZ-P7+)R72w%Gx>G?$ zmhPM+>1BQB+>bndW%#4rZuGcXMdje#q9Gi@mi0XU<$Fx$HAVf3hKl#nHF{(bOml6K zD9*GQc`n7d20?nW6S@Q?Eg>LWv&R=xv_9*8;^_W@T)v5*iS&g3>7DVRea?)w-P0r_ zI$dw&`pL%_eI_~V!}SHDXC$1_NJTP*-^04xuXXj~(ixV+F zDMT-@R{3ggaR#Xy6*gZYr7zx)b>U%~(@No5I!WRhH)2D8^OH;)Z{#k*ZYj1_E9+gv=?u>aMq(wY?5Sp3SB~>ma6R_N+s{LY8+Ey1fm_J$`Ze;}u{er4R#hwaQw7vV7g!dldYQTTt z@6rz%qwr%CPaoUyoPMokv*Y)@>GJRJ%$j?b0j5FN*scYC)^PpzYlZ)=y3z#deDEgi zAx9dFszC!Vi|L(bQ@i+I!Y#=Amd7rbpLGd(Mqal*ig|~@Go%cy2v4JQ^8Vd@o>c;v zAU~bBbyba3YBj$GTPk1Ul z2F;I{i_(7kB`d?6r0vKx0Y3h1JPH<-zM~BESXkeww>7t6#h}@+7LCVi5Jk3fC4L2U zc0KODCD5S|FIdK2TyRO*@uVXYN)XZNHZ!E!MKg_q=IPRej^7`uNPkZr{^CO(cfa>dU9= z&8))6-PyuRH$2aSz$Vo4X;=JNt5d1^5~Kw@*hl5MRtkH(XruM%q7R*Z*H*L^JYhBa z)8*=24#y)enLYRzK8_R8#oC@0{(eiRh~`%{ciLvxBvLNnUk5CjbV~s>96;SdlHu$*(*kEtHsZ1_osM4tT;0f^tWGyWb|{ z(X#=_Z@YVNgl^N@8d}k3r>{L1#|;a$(_a6kaZ+Q~ z^D=}_88}S#7#b_A1Je1PpMlvclm2le=iS-fsn&L0?Zc|@&t~_m?-Jq+5`}?L8hImT?ub5JXN)V{H`Qt zfG1`L{jg0hLjuek zf3*jm6`_4lCU&K$4}?Fna`z%8Z<}-n2X!0&7Lvo8+rayU+8<*IxBhqUC@1D7|5Vhu z-7tz7F}Pf(B~7z{vj%My}rhHOwTcLrlNR{+K#XK+^&g%9x=(&#-@z;r4va7!HHB^iN?brk$tIPH|KLjXVSrTKct&EC`UzO68w7ok+xUJ>9)moEML7=HxAzUcA!Rmg75U zON5H>CslA2?Z7P`HeNn5o7l>8cm*XSsmLb}Me-H0uP-&F0ofyx96qylkon@ee2N;d z5|QV9@we(&iTcMu(UVF!DGTlPm^mKe9IakGwagPU-}!jyFp`&vh<4t|dP%v^UNt;!XRUnfnp zU&+yxdwmpLkYA}ltiNVLUd4Z%aJ{n)W@&c#fjPNc722cqaO*2KH0#f8{$0Z6#mxN7uvYMmUEU?HyvG#t|0WZmYE+%eG%Y~|eTpdL`uGEZ5|v&Ld0EYFmYmK6 z36}ilx{NwWTD;{KO&tj4$zNQWToqDvU+0>yI(|xbM@tR-zER?cnnDVAQTf&xN&Z8Z z@O<CP=w=L)?F-v$(m0V-9yZ@XB># zO0iiw4Zspf4^QRiD`%b<@63?bi4C_9jzLK5ip3jD&i_LAo7Zt7UOM?Z_&z>9H%v@# z>Vp@SKn#h>`dSThdHmKn_!C?U$`$YTNB1Wb9@voUZ@!+LH!Y%y}So-GqvGDKGt5S#TPB3k&$B454n4{l-g#+iXF{ zS&{1mV5svP&F=72^?@K7%snessvW~Wi~4`}tkLM-6XMc@_0`|^F)K4FHodR&yOeba zxsx4Pfe?Sn{-^#gl?gZA9Okw2fKT7km;1e8r;Ve3d6}-J39!>~x{6g|;BVQTu9TnT z_TTC*zV|`d&;?vyyH`WDkntgjb!=Ee}mVE0j;0T1+vr! zp4Y5e=V?wb^?=chX{~g=bt@^aJ`V#x9%bT(=Jl!BvcPX6+r3I2OVz1y!?_A_PHjmp z6)~y3c=k9;&Hs$5hhf2`5?IWh7=S?{?{-Zl2%h(Kv7~E2@H({J)XAHp^xomeIPdtwJ&Pw8dVx!SMR8e`=R0rDa~)=R?S?Oh>Znx-_dY!%Dql{r zHAwlN6u$M;=oqVv5hu=1cBIlUn&2%AnpLN~k>aO{2tWF+Z3JKHLig_K+P)`$mG&3` zCU*X;t|*%ur}==(nA(+Lf!GysP&w8taqcb+dVU zeU~^hvLV`u109;q1!cS&>IP*lmWu-17cZILJ1~uc|K#I~Sw>P9xsshZIWXa~o^rjb z*~e}PVw>tASJuX;ccJwM{=Q~}N?}tbd53XMVgt*`7&*~`Vrmf5lxKqc-{}_YT3%jp z61q8)!O{ney>_gFW0Z8+MUQh7C@SAoQ9|cSkyJD{f2$3LkumsEcu=`H(cut$w#Sj# z&Op;VZYtJ{xo~G~7EJ@s+?A1bo&=fnljp{U4S9a_3GkSep*I{f_$?)b9fV`U`&tI| zFD0)F2oFBFBY|r|qc{qA!WOB41mk|gm;;(3cDhg@$1~ZORH7@>L&9!!VzY37>X#GfyjbJ2OX&Czmn?(9Fro z-Avxj!_&px)6T^i0}p_K@jrY1e=q(&x8pzcB753Dnt5nhSUFn(T^wE9G4P&R6wMqx ztT3Ji`ajQ-cX2YabN*jV@+O~LJUl1yWYWracce-C11VdnVde>8V>u~Ae}cv?}+YJ-+EidH*Sl-+G9>~veVAuX)?LrYuS zSnLBS)=k-N*KBv{>}=ds6BiW!o^%s5h6IRdLN&COG;N7QBgBL!qag-;G9(b?0sl!f z1YPf$d(JX+oMmS;rYBj>opa8d@7(X+nR})$#L^RTiltuzp5Wud8tisi8D~B@6CX=K zR>(6j7Tujl#UXE!BMq#!bmVvxs>4h@#)F|qlB)6>Vk z?Jw;6scG`<&)(|9M8s=ph5lfRKzo7xCkC2O?JM!R#4C``CP4As=r<(2jX54dC(ZGO z)Ss+-=iSFvy%=0Pk~wi{UA}`*Fpu^S!`OfZQ`mx0Ueu+MA3(!q)D@TGnSZb9n+w&w z$JVwLx-P7Fxd{^(wsGWYu}IIf!TIxF#o~Ia(4Q-by282I-VgVmtv>$r-1&zwfnnxV z%%P_VUb-NLz_JuQ$ZrxXQ?&2uuIGH=ZQJI){_guf&wcrZJ&F#qfQfq{h8{$tETNy6k#j0+$r+e-9>Zti?vgedjm($PB(rr^@2@`;Jv!sDeACG z(N_yU{;?g*qoB+79$?^ zk3K1la}W}N5a-hTJUsCmo2yVl6VSVRLgCN8ZJxz?3wogf9#34a+kTrJ*gPz`7?^b9@d zxF0oTq*LHtLn<^-qpUxZm&TIM6rDO2%joog5yDbrxF(+|IyD29(Q!#i2)59PVaw>$ z&(i#Cq0>jOEg!DuyDr~3bo)^EN8W|( zt|Puc*)Dc9On?cU7AyHB|K5wHubUhEaRQ{`$C8qjBPhUg8s0_spk46ez?4Dwz%gYI zoR%5fa{A)yrv^UhSvWPgxU)-&mSs>sInx@;eyil|e5?FEzv8L)U)kV)^Wv)~CTD*u zR9vIJUZ9pWC&DHeFll7JfY_pw;@&q(EdT+ikaH8x6AE?bfywH*DZZh?ngJMyB1(%x$EA zMynO%ttk2+g#@ZpLkYD4N(~7KKSCccjX#YK#GeMk11h8sD6RE;vpc(Wv!>L3*}3Q3 zbI(2Jn{&_1&iOZ%9r|-(V&cVFL|K_+A%n+T+fI($tbTVi`v=z%??7P161MptAmSgb zjkHM1@d+MRvv(0oPr&1LSC&_~YgU%JO9N$rn#!t5zo)#)S5fWt`@Gf$gR>yX&n#!N z#QakzjI%6pUFGZGmEqg9c|*SU2miQI^6iZ*xh^ArpfTUS=aq{;Exo<+>DZ3s2*!vD zLbIuWM{nm>w1B0_}4Z*HmYkP^~Jp{P#avd$+75=rIyj2oVzYdEvM4lt__9k&?uOSCiDcY zBwxzD+_n2b_(&!ELJ1mq?X!2lc&%ub2@36Z=GKFP)qA6}F6JOZ&_!>b+1_udWfbh} zD8wlRMR>c|D#@(fyYR{6d`*NaqwN$Z5<;6%5tfvv+V+aGdHe3H#FfYLG0$@c@~!Nno}6%%_?ZHr)JfQQ%8i1tl- zitJeNrL-b7W?HAX5%H$#wX{8dj!y!c(=JXG5y|ns0q`IK=qCVOofgq&Ke^o7cfE0c z$M25r_bzlk7Wayu1`Ws0&JJk3b!{ixcr@27A)2GofwsEH?P+#Bw{f%G8fBbsi%xK^} z1WdacMVpSFcxvc{h68sBhcese_0Eh&UW~=`Y4jJK$?NHE_Z|PPx9D2W?itd+A1W~I tYJ7A0w_8rnuID~@T~j9xXY|{)-lH;xeyAYh_5L>FwXO*%s=jvbBzE1 literal 0 HcmV?d00001 diff --git a/Unreal/Plugins/AirSim/Source/PIPCamera.cpp b/Unreal/Plugins/AirSim/Source/PIPCamera.cpp index b87ad3749a..4e6f3b41d3 100644 --- a/Unreal/Plugins/AirSim/Source/PIPCamera.cpp +++ b/Unreal/Plugins/AirSim/Source/PIPCamera.cpp @@ -23,6 +23,15 @@ APIPCamera::APIPCamera() UAirBlueprintLib::LogMessageString("Cannot create noise material for the PIPCamera", "", LogDebugLevel::Failure); + static ConstructorHelpers::FObjectFinder dist_mat_finder(TEXT("Material'/AirSim/HUDAssets/CameraDistortion.CameraDistortion'")); + if (dist_mat_finder.Succeeded()) + { + distortion_material_static_ = dist_mat_finder.Object; + } + else + UAirBlueprintLib::LogMessageString("Cannot create distortion material for the PIPCamera", + "", LogDebugLevel::Failure); + PrimaryActorTick.bCanEverTick = true; image_type_to_pixel_format_map_.Add(0, EPixelFormat::PF_B8G8R8A8); @@ -66,6 +75,7 @@ void APIPCamera::BeginPlay() Super::BeginPlay(); noise_materials_.AddZeroed(imageTypeCount() + 1); + distortion_materials_.AddZeroed(imageTypeCount() + 1); //by default all image types are disabled camera_type_enabled_.assign(imageTypeCount(), false); @@ -312,12 +322,12 @@ void APIPCamera::setupCameraFromSettings(const APIPCamera::CameraSetting& camera false); break; } - + setDistortionMaterial(image_type, captures_[image_type], captures_[image_type]->PostProcessSettings); setNoiseMaterial(image_type, captures_[image_type], captures_[image_type]->PostProcessSettings, noise_setting); } else { //camera component updateCameraSetting(camera_, capture_setting, ned_transform); - + setDistortionMaterial(image_type, camera_, camera_->PostProcessSettings); setNoiseMaterial(image_type, camera_, camera_->PostProcessSettings, noise_setting); } } @@ -423,30 +433,36 @@ void APIPCamera::updateCameraPostProcessingSetting(FPostProcessSettings& obj, co } } +void APIPCamera::setDistortionMaterial(int image_type, UObject* outer, FPostProcessSettings& obj) +{ + UMaterialInstanceDynamic* distortion_material = UMaterialInstanceDynamic::Create(distortion_material_static_, outer); + distortion_materials_[image_type + 1] = distortion_material; + obj.AddBlendable(distortion_material, 1.0f); +} + void APIPCamera::setNoiseMaterial(int image_type, UObject* outer, FPostProcessSettings& obj, const NoiseSetting& settings) { if (!settings.Enabled) return; - UMaterialInstanceDynamic* noise_material_ = UMaterialInstanceDynamic::Create(noise_material_static_, outer); - noise_materials_[image_type + 1] = noise_material_; - - - noise_material_->SetScalarParameterValue("HorzWaveStrength", settings.HorzWaveStrength); - noise_material_->SetScalarParameterValue("RandSpeed", settings.RandSpeed); - noise_material_->SetScalarParameterValue("RandSize", settings.RandSize); - noise_material_->SetScalarParameterValue("RandDensity", settings.RandDensity); - noise_material_->SetScalarParameterValue("RandContrib", settings.RandContrib); - noise_material_->SetScalarParameterValue("HorzWaveContrib", settings.HorzWaveContrib); - noise_material_->SetScalarParameterValue("HorzWaveVertSize", settings.HorzWaveVertSize); - noise_material_->SetScalarParameterValue("HorzWaveScreenSize", settings.HorzWaveScreenSize); - noise_material_->SetScalarParameterValue("HorzNoiseLinesContrib", settings.HorzNoiseLinesContrib); - noise_material_->SetScalarParameterValue("HorzNoiseLinesDensityY", settings.HorzNoiseLinesDensityY); - noise_material_->SetScalarParameterValue("HorzNoiseLinesDensityXY", settings.HorzNoiseLinesDensityXY); - noise_material_->SetScalarParameterValue("HorzDistortionStrength", settings.HorzDistortionStrength); - noise_material_->SetScalarParameterValue("HorzDistortionContrib", settings.HorzDistortionContrib); - - obj.AddBlendable(noise_material_, 1.0f); + UMaterialInstanceDynamic* noise_material = UMaterialInstanceDynamic::Create(noise_material_static_, outer); + noise_materials_[image_type + 1] = noise_material; + + noise_material->SetScalarParameterValue("HorzWaveStrength", settings.HorzWaveStrength); + noise_material->SetScalarParameterValue("RandSpeed", settings.RandSpeed); + noise_material->SetScalarParameterValue("RandSize", settings.RandSize); + noise_material->SetScalarParameterValue("RandDensity", settings.RandDensity); + noise_material->SetScalarParameterValue("RandContrib", settings.RandContrib); + noise_material->SetScalarParameterValue("HorzWaveContrib", settings.HorzWaveContrib); + noise_material->SetScalarParameterValue("HorzWaveVertSize", settings.HorzWaveVertSize); + noise_material->SetScalarParameterValue("HorzWaveScreenSize", settings.HorzWaveScreenSize); + noise_material->SetScalarParameterValue("HorzNoiseLinesContrib", settings.HorzNoiseLinesContrib); + noise_material->SetScalarParameterValue("HorzNoiseLinesDensityY", settings.HorzNoiseLinesDensityY); + noise_material->SetScalarParameterValue("HorzNoiseLinesDensityXY", settings.HorzNoiseLinesDensityXY); + noise_material->SetScalarParameterValue("HorzDistortionStrength", settings.HorzDistortionStrength); + noise_material->SetScalarParameterValue("HorzDistortionContrib", settings.HorzDistortionContrib); + + obj.AddBlendable(noise_material, 1.0f); } void APIPCamera::enableCaptureComponent(const APIPCamera::ImageType type, bool is_enabled) diff --git a/Unreal/Plugins/AirSim/Source/PIPCamera.h b/Unreal/Plugins/AirSim/Source/PIPCamera.h index a1465163b1..e5d7e2c7a4 100644 --- a/Unreal/Plugins/AirSim/Source/PIPCamera.h +++ b/Unreal/Plugins/AirSim/Source/PIPCamera.h @@ -60,7 +60,9 @@ class AIRSIM_API APIPCamera : public ACameraActor //TMap noise_materials_; //below is needed because TMap doesn't work with UPROPERTY, but we do have -ve index UPROPERTY() TArray noise_materials_; + UPROPERTY() TArray distortion_materials_; UPROPERTY() UMaterial* noise_material_static_; + UPROPERTY() UMaterial* distortion_material_static_; std::vector camera_type_enabled_; FRotator gimbald_rotator_; @@ -79,6 +81,7 @@ class AIRSIM_API APIPCamera : public ACameraActor bool auto_format, const EPixelFormat& pixel_format, const CaptureSetting& setting, const NedTransform& ned_transform, bool force_linear_gamma); void setNoiseMaterial(int image_type, UObject* outer, FPostProcessSettings& obj, const NoiseSetting& settings); + void setDistortionMaterial(int image_type, UObject* outer, FPostProcessSettings& obj); static void updateCameraPostProcessingSetting(FPostProcessSettings& obj, const CaptureSetting& setting); static void updateCameraSetting(UCameraComponent* camera, const CaptureSetting& setting, const NedTransform& ned_transform); }; diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp index a96c27e05a..9a53bc310d 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp @@ -67,6 +67,8 @@ ASimModeBase::ASimModeBase() else loading_screen_widget_ = nullptr; + distortion_param_collection_ = Cast(StaticLoadObject(UMaterialParameterCollection::StaticClass(), NULL, TEXT("Material'/AirSim/HUDAssets/DistortionParams.DistortionParams'"))); + } void ASimModeBase::toggleLoadingScreen(bool is_visible) diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h index fcae63cc14..58d1ee2fc3 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h @@ -16,6 +16,9 @@ #include "common/StateReporterWrapper.hpp" #include "LoadingScreenWidget.h" +#include "Materials/MaterialParameterCollectionInstance.h" +#include "Materials/MaterialParameterCollection.h" + #include "SimModeBase.generated.h" DECLARE_DYNAMIC_MULTICAST_DELEGATE(FLevelLoaded); @@ -48,6 +51,8 @@ class AIRSIM_API ASimModeBase : public AActor UFUNCTION(BlueprintCallable, Category = "Airsim | get stuff") virtual void reset(); + UPROPERTY() UMaterialParameterCollection* distortion_param_collection_; + // Sets default values for this actor's properties ASimModeBase(); virtual void BeginPlay() override; @@ -124,7 +129,6 @@ class AIRSIM_API ASimModeBase : public AActor protected: int record_tick_count; - UPROPERTY() UClass* pip_camera_class; UPROPERTY() UParticleSystem* collision_display_template; diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp index 9e753f3b69..cf33ab68ec 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp @@ -345,17 +345,11 @@ std::unique_ptr> WorldSimApi::swapTextures(const std::s return swappedObjectNames; } -void WorldSimApi::setDistortionParam(std::string& scenecap_actor_name, std::string& param_name, float value) -{ - UAirBlueprintLib::RunCommandOnGameThread([this, &scenecap_actor_name, ¶m_name, value]() { - ADistortableSceneCapture* actor = UAirBlueprintLib::FindActor(simmode_, FString(scenecap_actor_name.c_str())); - if (!actor) - return; - auto *param_collection_asset = actor->ParamCollection; - if (!param_collection_asset) - return; - auto *param_collection = simmode_->GetWorld()->GetParameterCollectionInstance(param_collection_asset); - param_collection->SetScalarParameterValue(FName(param_name.c_str()), value); +void WorldSimApi::setDistortionParam(std::string& param_name, float value) +{ + UAirBlueprintLib::RunCommandOnGameThread([this, ¶m_name, value]() { + UMaterialParameterCollectionInstance* distortion_param_instance = simmode_->GetWorld()->GetParameterCollectionInstance(simmode_->distortion_param_collection_); + distortion_param_instance->SetScalarParameterValue(FName(param_name.c_str()), value); }, true); } diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.h b/Unreal/Plugins/AirSim/Source/WorldSimApi.h index 6f904d1403..4f1c5e9bc9 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.h +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.h @@ -47,7 +47,7 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase { virtual bool runConsoleCommand(const std::string& command) override; virtual Vector3r getObjectScale(const std::string& object_name) const override; virtual bool setObjectScale(const std::string& object_name, const Vector3r& scale) override; - virtual void setDistortionParam(std::string& scenecap_actor_name, std::string& param_name, float value) override; + virtual void setDistortionParam(std::string& param_name, float value) override; //----------- Plotting APIs ----------/ virtual void simFlushPersistentMarkers() override; From cf8d7fbcf7ffe5970e2496547a4ecdda306329c7 Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Thu, 24 Sep 2020 18:21:08 -0700 Subject: [PATCH 03/15] Update PythonClient, remove distortion postprocess at EndPlay() --- PythonClient/airsim/client.py | 14 ++++++++++++++ Unreal/Plugins/AirSim/Source/PIPCamera.cpp | 12 ++++++++++++ 2 files changed, 26 insertions(+) diff --git a/PythonClient/airsim/client.py b/PythonClient/airsim/client.py index 6d619df68f..2ab9d9c9dc 100644 --- a/PythonClient/airsim/client.py +++ b/PythonClient/airsim/client.py @@ -482,6 +482,20 @@ def simGetCameraInfo(self, camera_name, vehicle_name = ''): # TODO: below str() conversion is only needed for legacy reason and should be removed in future return CameraInfo.from_msgpack(self.client.call('simGetCameraInfo', str(camera_name), vehicle_name)) + def simSetDistortionParams(self, camera_name, distortion_params, vehicle_name = ''): + """ + Set camera distortion parameters + + Args: + camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used + distortion_params (dict): Dictionary of distortion param names and corresponding values + {"K1": 0.0, "K2": 0.0, "K3": 0.0, "P1": 0.0, "P2": 0.0} + vehicle_name (str, optional): Vehicle which the camera is associated with + """ + + for param_name, value in distortion_params.items(): + self.client.call('simSetDistortionParam', param_name, value, vehicle_name) + def simSetCameraPose(self, camera_name, pose, vehicle_name = ''): """ - Control the pose of a selected camera diff --git a/Unreal/Plugins/AirSim/Source/PIPCamera.cpp b/Unreal/Plugins/AirSim/Source/PIPCamera.cpp index 4e6f3b41d3..a24b3b98b7 100644 --- a/Unreal/Plugins/AirSim/Source/PIPCamera.cpp +++ b/Unreal/Plugins/AirSim/Source/PIPCamera.cpp @@ -218,6 +218,18 @@ void APIPCamera::EndPlay(const EEndPlayReason::Type EndPlayReason) noise_material_static_ = nullptr; noise_materials_.Empty(); + if (distortion_materials_.Num()) { + for (unsigned int image_type = 0; image_type < imageTypeCount(); ++image_type) { + if (distortion_materials_[image_type + 1]) + captures_[image_type]->PostProcessSettings.RemoveBlendable(distortion_materials_[image_type + 1]); + } + if (distortion_materials_[0]) + camera_->PostProcessSettings.RemoveBlendable(distortion_materials_[0]); + } + + distortion_material_static_ = nullptr; + distortion_materials_.Empty(); + for (unsigned int image_type = 0; image_type < imageTypeCount(); ++image_type) { //use final color for all calculations captures_[image_type] = nullptr; From 42f5aecab92f88d9eb8ffaa45e968ac67166f33f Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Thu, 24 Sep 2020 18:22:27 -0700 Subject: [PATCH 04/15] Remove irrelevant files --- AirLib/AirSim.props | 6 ------ .../AirSim/Source/DIstortableSceneCapture.h | 15 --------------- 2 files changed, 21 deletions(-) delete mode 100644 AirLib/AirSim.props delete mode 100644 Unreal/Plugins/AirSim/Source/DIstortableSceneCapture.h diff --git a/AirLib/AirSim.props b/AirLib/AirSim.props deleted file mode 100644 index d4487d889c..0000000000 --- a/AirLib/AirSim.props +++ /dev/null @@ -1,6 +0,0 @@ - - - $([System.String]::Copy('$(WindowsSDKVersion)').Replace('\','')) - $(AirSimTargetPlatformVersion) - - \ No newline at end of file diff --git a/Unreal/Plugins/AirSim/Source/DIstortableSceneCapture.h b/Unreal/Plugins/AirSim/Source/DIstortableSceneCapture.h deleted file mode 100644 index b297d2cd4e..0000000000 --- a/Unreal/Plugins/AirSim/Source/DIstortableSceneCapture.h +++ /dev/null @@ -1,15 +0,0 @@ -#pragma once - -#include "CoreMinimal.h" -#include "Engine/SceneCapture2D.h" -#include "DistortableSceneCapture.generated.h" - -UCLASS() -class ADistortableSceneCapture : public ASceneCapture2D -{ - GENERATED_BODY() - -public: - UPROPERTY(EditDefaultsOnly, Category = "Distortion") - UMaterialParameterCollection *ParamCollection; -}; \ No newline at end of file From d7362078ca3b679a507b813891aa194ace03723c Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Thu, 24 Sep 2020 19:21:59 -0700 Subject: [PATCH 05/15] Refactor - move distortion params to PIPCamera --- AirLib/include/api/RpcLibClientBase.hpp | 2 +- AirLib/include/api/VehicleSimApiBase.hpp | 1 + AirLib/include/api/WorldSimApiBase.hpp | 1 - AirLib/src/api/RpcLibClientBase.cpp | 11 ++++++----- AirLib/src/api/RpcLibServerBase.cpp | 4 ++-- PythonClient/airsim/client.py | 12 ++++++++++++ Unreal/Plugins/AirSim/Source/PIPCamera.h | 3 +++ Unreal/Plugins/AirSim/Source/PawnSimApi.cpp | 9 +++++++++ Unreal/Plugins/AirSim/Source/PawnSimApi.h | 1 + Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp | 7 ++----- Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h | 6 ------ Unreal/Plugins/AirSim/Source/WorldSimApi.cpp | 8 -------- Unreal/Plugins/AirSim/Source/WorldSimApi.h | 1 - 13 files changed, 37 insertions(+), 29 deletions(-) diff --git a/AirLib/include/api/RpcLibClientBase.hpp b/AirLib/include/api/RpcLibClientBase.hpp index 0fc52f8b19..f71961af50 100644 --- a/AirLib/include/api/RpcLibClientBase.hpp +++ b/AirLib/include/api/RpcLibClientBase.hpp @@ -103,7 +103,7 @@ class RpcLibClientBase { CollisionInfo simGetCollisionInfo(const std::string& vehicle_name = "") const; CameraInfo simGetCameraInfo(const std::string& camera_name, const std::string& vehicle_name = "") const; - void simSetDistortionParam(std::string& param_name, float value); + void simSetDistortionParam(const std::string& camera_name, const std::string& param_name, float value, const std::string& vehicle_name = ""); void simSetCameraPose(const std::string& camera_name, const Pose& pose, const std::string& vehicle_name = ""); void simSetCameraFov(const std::string& camera_name, float fov_degrees, const std::string& vehicle_name = ""); // This is a backwards-compatibility wrapper over simSetCameraPose, and can be removed in future major releases diff --git a/AirLib/include/api/VehicleSimApiBase.hpp b/AirLib/include/api/VehicleSimApiBase.hpp index 471a2cfd85..3c60e5231d 100644 --- a/AirLib/include/api/VehicleSimApiBase.hpp +++ b/AirLib/include/api/VehicleSimApiBase.hpp @@ -56,6 +56,7 @@ class VehicleSimApiBase : public msr::airlib::UpdatableObject { virtual CameraInfo getCameraInfo(const std::string& camera_name) const = 0; virtual void setCameraPose(const std::string& camera_name, const Pose& pose) = 0; virtual void setCameraFoV(const std::string& camera_name, float fov_degrees) = 0; + virtual void setDistortionParam(const std::string& camera_name, const std::string& param_name, float value) = 0; virtual CollisionInfo getCollisionInfo() const = 0; virtual int getRemoteControlID() const = 0; //which RC to use, 0 is first one, -1 means disable RC (use keyborad) diff --git a/AirLib/include/api/WorldSimApiBase.hpp b/AirLib/include/api/WorldSimApiBase.hpp index 181341ac58..507df792fc 100644 --- a/AirLib/include/api/WorldSimApiBase.hpp +++ b/AirLib/include/api/WorldSimApiBase.hpp @@ -63,7 +63,6 @@ class WorldSimApiBase { virtual bool setObjectPose(const std::string& object_name, const Pose& pose, bool teleport) = 0; virtual bool runConsoleCommand(const std::string& command) = 0; virtual bool setObjectScale(const std::string& object_name, const Vector3r& scale) = 0; - virtual void setDistortionParam(std::string& param_name, float value) = 0; virtual std::unique_ptr> swapTextures(const std::string& tag, int tex_id = 0, int component_id = 0, int material_id = 0) = 0; virtual vector getMeshPositionVertexBuffers() const = 0; diff --git a/AirLib/src/api/RpcLibClientBase.cpp b/AirLib/src/api/RpcLibClientBase.cpp index 9873110f7e..f70aea22c6 100644 --- a/AirLib/src/api/RpcLibClientBase.cpp +++ b/AirLib/src/api/RpcLibClientBase.cpp @@ -398,6 +398,12 @@ void RpcLibClientBase::simSetCameraFov(const std::string& camera_name, float fov pimpl_->client.call("simSetCameraFov", camera_name, fov_degrees, vehicle_name); } +void RpcLibClientBase::simSetDistortionParam(const std::string& camera_name, const std::string& param_name, float value, const std::string& vehicle_name) +{ + pimpl_->client.call("simSetDistortionParam", camera_name, param_name, value, vehicle_name); +} + + msr::airlib::Kinematics::State RpcLibClientBase::simGetGroundTruthKinematics(const std::string& vehicle_name) const { return pimpl_->client.call("simGetGroundTruthKinematics", vehicle_name).as().to(); @@ -417,11 +423,6 @@ bool RpcLibClientBase::simRunConsoleCommand(const std::string& command) return pimpl_->client.call("simRunConsoleCommand", command).as(); } -void RpcLibClientBase::simSetDistortionParam(std::string& param_name, float value) -{ - pimpl_->client.call("simSetDistortionParam", param_name, value); -} - //return value of last task. It should be true if task completed without //cancellation or timeout RpcLibClientBase* RpcLibClientBase::waitOnLastTask(bool* task_result, float timeout_sec) diff --git a/AirLib/src/api/RpcLibServerBase.cpp b/AirLib/src/api/RpcLibServerBase.cpp index 85266a4fd1..10a21339f9 100644 --- a/AirLib/src/api/RpcLibServerBase.cpp +++ b/AirLib/src/api/RpcLibServerBase.cpp @@ -243,8 +243,8 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& return RpcLibAdapatorsBase::CameraInfo(camera_info); }); - pimpl_->server.bind("simSetDistortionParam", [&](std::string& param_name, float value) { - getWorldSimApi()->setDistortionParam(param_name, value); + pimpl_->server.bind("simSetDistortionParam", [&](const std::string& camera_name, const std::string& param_name, float value, const std::string& vehicle_name) -> void { + getVehicleSimApi(vehicle_name)->setDistortionParam(camera_name, param_name, value); }); pimpl_->server.bind("simSetCameraPose", [&](const std::string& camera_name, const RpcLibAdapatorsBase::Pose& pose, diff --git a/PythonClient/airsim/client.py b/PythonClient/airsim/client.py index 2ab9d9c9dc..06b3dfdb59 100644 --- a/PythonClient/airsim/client.py +++ b/PythonClient/airsim/client.py @@ -496,6 +496,18 @@ def simSetDistortionParams(self, camera_name, distortion_params, vehicle_name = for param_name, value in distortion_params.items(): self.client.call('simSetDistortionParam', param_name, value, vehicle_name) + def simSetDistortionParam(self, camera_name, param_name, value, vehicle_name = ''): + """ + Set single camera distortion parameter + + Args: + camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used + param_name (str): Name of distortion parameter + value (float): Value of distortion parameter + vehicle_name (str, optional): Vehicle which the camera is associated with + """ + self.client.call('simSetDistortionParam', str(camera_name), param_name, value, vehicle_name) + def simSetCameraPose(self, camera_name, pose, vehicle_name = ''): """ - Control the pose of a selected camera diff --git a/Unreal/Plugins/AirSim/Source/PIPCamera.h b/Unreal/Plugins/AirSim/Source/PIPCamera.h index e5d7e2c7a4..153614e91f 100644 --- a/Unreal/Plugins/AirSim/Source/PIPCamera.h +++ b/Unreal/Plugins/AirSim/Source/PIPCamera.h @@ -51,6 +51,9 @@ class AIRSIM_API APIPCamera : public ACameraActor UTextureRenderTarget2D* getRenderTarget(const ImageType type, bool if_active); msr::airlib::Pose getPose() const; + + UPROPERTY() UMaterialParameterCollection* distortion_param_collection_; + UPROPERTY() UMaterialParameterCollectionInstance* distortion_param_instance_; private: //members UPROPERTY() TArray captures_; diff --git a/Unreal/Plugins/AirSim/Source/PawnSimApi.cpp b/Unreal/Plugins/AirSim/Source/PawnSimApi.cpp index 9da9d1d61d..2478af8f8b 100644 --- a/Unreal/Plugins/AirSim/Source/PawnSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/PawnSimApi.cpp @@ -10,6 +10,7 @@ #include "NedTransform.h" #include "common/EarthUtils.hpp" +#include "Materials/MaterialParameterCollectionInstance.h" #include "DrawDebugHelpers.h" PawnSimApi::PawnSimApi(const Params& params) @@ -426,6 +427,14 @@ void PawnSimApi::setCameraFoV(const std::string& camera_name, float fov_degrees) }, true); } +void PawnSimApi::setDistortionParam(const std::string& camera_name, const std::string& param_name, float value) +{ + UAirBlueprintLib::RunCommandOnGameThread([this, camera_name, param_name, value]() { + APIPCamera* camera = getCamera(camera_name); + camera->distortion_param_instance_->SetScalarParameterValue(FName(param_name.c_str()), value); + }, true); +} + //parameters in NED frame PawnSimApi::Pose PawnSimApi::getPose() const { diff --git a/Unreal/Plugins/AirSim/Source/PawnSimApi.h b/Unreal/Plugins/AirSim/Source/PawnSimApi.h index 2148ae16cb..0cea10087e 100644 --- a/Unreal/Plugins/AirSim/Source/PawnSimApi.h +++ b/Unreal/Plugins/AirSim/Source/PawnSimApi.h @@ -79,6 +79,7 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase { virtual msr::airlib::CameraInfo getCameraInfo(const std::string& camera_name) const override; virtual void setCameraPose(const std::string& camera_name, const Pose& pose) override; virtual void setCameraFoV(const std::string& camera_name, float fov_degrees) override; + virtual void setDistortionParam(const std::string& camera_name, const std::string& param_name, float value) override; virtual CollisionInfo getCollisionInfo() const override; virtual int getRemoteControlID() const override; virtual msr::airlib::RCData getRCData() const override; diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp index 9a53bc310d..50b8eb1f02 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp @@ -65,10 +65,7 @@ ASimModeBase::ASimModeBase() } else - loading_screen_widget_ = nullptr; - - distortion_param_collection_ = Cast(StaticLoadObject(UMaterialParameterCollection::StaticClass(), NULL, TEXT("Material'/AirSim/HUDAssets/DistortionParams.DistortionParams'"))); - + loading_screen_widget_ = nullptr; } void ASimModeBase::toggleLoadingScreen(bool is_visible) @@ -203,7 +200,7 @@ void ASimModeBase::initializeTimeOfDay() sky_sphere_ = sky_spheres[0]; static const FName sun_prop_name(TEXT("Directional light actor")); auto* p = sky_sphere_class_->FindPropertyByName(sun_prop_name); - UObjectProperty* sun_prop = Cast(p); + FObjectProperty* sun_prop = Cast(p); UObject* sun_obj = sun_prop->GetObjectPropertyValue_InContainer(sky_sphere_); sun_ = Cast(sun_obj); if (sun_) diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h index 58d1ee2fc3..90305e1e0e 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.h @@ -15,10 +15,6 @@ #include "PawnSimApi.h" #include "common/StateReporterWrapper.hpp" #include "LoadingScreenWidget.h" - -#include "Materials/MaterialParameterCollectionInstance.h" -#include "Materials/MaterialParameterCollection.h" - #include "SimModeBase.generated.h" DECLARE_DYNAMIC_MULTICAST_DELEGATE(FLevelLoaded); @@ -51,8 +47,6 @@ class AIRSIM_API ASimModeBase : public AActor UFUNCTION(BlueprintCallable, Category = "Airsim | get stuff") virtual void reset(); - UPROPERTY() UMaterialParameterCollection* distortion_param_collection_; - // Sets default values for this actor's properties ASimModeBase(); virtual void BeginPlay() override; diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp index cf33ab68ec..50438533e7 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp @@ -345,14 +345,6 @@ std::unique_ptr> WorldSimApi::swapTextures(const std::s return swappedObjectNames; } -void WorldSimApi::setDistortionParam(std::string& param_name, float value) -{ - UAirBlueprintLib::RunCommandOnGameThread([this, ¶m_name, value]() { - UMaterialParameterCollectionInstance* distortion_param_instance = simmode_->GetWorld()->GetParameterCollectionInstance(simmode_->distortion_param_collection_); - distortion_param_instance->SetScalarParameterValue(FName(param_name.c_str()), value); - }, true); -} - //----------- Plotting APIs ----------/ void WorldSimApi::simFlushPersistentMarkers() { diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.h b/Unreal/Plugins/AirSim/Source/WorldSimApi.h index 4f1c5e9bc9..f83353b5b2 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.h +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.h @@ -47,7 +47,6 @@ class WorldSimApi : public msr::airlib::WorldSimApiBase { virtual bool runConsoleCommand(const std::string& command) override; virtual Vector3r getObjectScale(const std::string& object_name) const override; virtual bool setObjectScale(const std::string& object_name, const Vector3r& scale) override; - virtual void setDistortionParam(std::string& param_name, float value) override; //----------- Plotting APIs ----------/ virtual void simFlushPersistentMarkers() override; From 4aaa6e31465fd433d96cc8d62f2a11cb099f342f Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Thu, 24 Sep 2020 19:23:34 -0700 Subject: [PATCH 06/15] Remove unneeded includes --- Unreal/Plugins/AirSim/Source/WorldSimApi.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp index 50438533e7..61fe335bfa 100644 --- a/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/WorldSimApi.cpp @@ -6,7 +6,6 @@ #include "Weather/WeatherLib.h" #include "DrawDebugHelpers.h" #include "Runtime/Engine/Classes/Engine/Engine.h" -#include "DistortableSceneCapture.h" #include #include From eab194ed5e42d7cc45bc4bfa5587ab72241f584d Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Thu, 24 Sep 2020 19:56:27 -0700 Subject: [PATCH 07/15] Fix includes --- Unreal/Plugins/AirSim/Source/PIPCamera.cpp | 1 - Unreal/Plugins/AirSim/Source/PIPCamera.h | 2 ++ 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/Unreal/Plugins/AirSim/Source/PIPCamera.cpp b/Unreal/Plugins/AirSim/Source/PIPCamera.cpp index a24b3b98b7..1b659b4548 100644 --- a/Unreal/Plugins/AirSim/Source/PIPCamera.cpp +++ b/Unreal/Plugins/AirSim/Source/PIPCamera.cpp @@ -4,7 +4,6 @@ #include "Camera/CameraComponent.h" #include "Engine/TextureRenderTarget2D.h" #include "Engine/World.h" -#include "Materials/MaterialInstanceDynamic.h" #include "ImageUtils.h" #include diff --git a/Unreal/Plugins/AirSim/Source/PIPCamera.h b/Unreal/Plugins/AirSim/Source/PIPCamera.h index 153614e91f..4b0dc13228 100644 --- a/Unreal/Plugins/AirSim/Source/PIPCamera.h +++ b/Unreal/Plugins/AirSim/Source/PIPCamera.h @@ -10,6 +10,8 @@ #include "common/AirSimSettings.hpp" #include "NedTransform.h" +#include "Materials/MaterialParameterCollectionInstance.h" +#include "Materials/MaterialInstanceDynamic.h" #include "PIPCamera.generated.h" From db5e99ee346f84e54dae3e655dbd846ab3c7db27 Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Fri, 2 Oct 2020 17:05:59 -0700 Subject: [PATCH 08/15] Add missing material instancing, API to retrieve distortion params --- AirLib/include/api/RpcLibClientBase.hpp | 1 + AirLib/include/api/VehicleSimApiBase.hpp | 1 + AirLib/src/api/RpcLibClientBase.cpp | 4 ++++ AirLib/src/api/RpcLibServerBase.cpp | 4 ++++ PythonClient/airsim/client.py | 15 ++++++++++++++- Unreal/Plugins/AirSim/Source/PIPCamera.cpp | 5 +++++ Unreal/Plugins/AirSim/Source/PIPCamera.h | 1 + Unreal/Plugins/AirSim/Source/PawnSimApi.cpp | 15 +++++++++++++++ Unreal/Plugins/AirSim/Source/PawnSimApi.h | 2 ++ 9 files changed, 47 insertions(+), 1 deletion(-) diff --git a/AirLib/include/api/RpcLibClientBase.hpp b/AirLib/include/api/RpcLibClientBase.hpp index f71961af50..aff70791ee 100644 --- a/AirLib/include/api/RpcLibClientBase.hpp +++ b/AirLib/include/api/RpcLibClientBase.hpp @@ -104,6 +104,7 @@ class RpcLibClientBase { CameraInfo simGetCameraInfo(const std::string& camera_name, const std::string& vehicle_name = "") const; void simSetDistortionParam(const std::string& camera_name, const std::string& param_name, float value, const std::string& vehicle_name = ""); + std::vector simGetDistortionParams(const std::string& camera_name, const std::string& vehicle_name = ""); void simSetCameraPose(const std::string& camera_name, const Pose& pose, const std::string& vehicle_name = ""); void simSetCameraFov(const std::string& camera_name, float fov_degrees, const std::string& vehicle_name = ""); // This is a backwards-compatibility wrapper over simSetCameraPose, and can be removed in future major releases diff --git a/AirLib/include/api/VehicleSimApiBase.hpp b/AirLib/include/api/VehicleSimApiBase.hpp index 3c60e5231d..c147b09dd8 100644 --- a/AirLib/include/api/VehicleSimApiBase.hpp +++ b/AirLib/include/api/VehicleSimApiBase.hpp @@ -57,6 +57,7 @@ class VehicleSimApiBase : public msr::airlib::UpdatableObject { virtual void setCameraPose(const std::string& camera_name, const Pose& pose) = 0; virtual void setCameraFoV(const std::string& camera_name, float fov_degrees) = 0; virtual void setDistortionParam(const std::string& camera_name, const std::string& param_name, float value) = 0; + virtual std::vector getDistortionParams(const std::string& camera_name) = 0; virtual CollisionInfo getCollisionInfo() const = 0; virtual int getRemoteControlID() const = 0; //which RC to use, 0 is first one, -1 means disable RC (use keyborad) diff --git a/AirLib/src/api/RpcLibClientBase.cpp b/AirLib/src/api/RpcLibClientBase.cpp index f70aea22c6..76994801ab 100644 --- a/AirLib/src/api/RpcLibClientBase.cpp +++ b/AirLib/src/api/RpcLibClientBase.cpp @@ -403,6 +403,10 @@ void RpcLibClientBase::simSetDistortionParam(const std::string& camera_name, con pimpl_->client.call("simSetDistortionParam", camera_name, param_name, value, vehicle_name); } +std::vector RpcLibClientBase::simGetDistortionParams(const std::string& camera_name, const std::string& vehicle_name) +{ + return pimpl_->client.call("simGetDistortionParams", camera_name, vehicle_name).as>(); +} msr::airlib::Kinematics::State RpcLibClientBase::simGetGroundTruthKinematics(const std::string& vehicle_name) const { diff --git a/AirLib/src/api/RpcLibServerBase.cpp b/AirLib/src/api/RpcLibServerBase.cpp index 10a21339f9..84ea34e073 100644 --- a/AirLib/src/api/RpcLibServerBase.cpp +++ b/AirLib/src/api/RpcLibServerBase.cpp @@ -247,6 +247,10 @@ RpcLibServerBase::RpcLibServerBase(ApiProvider* api_provider, const std::string& getVehicleSimApi(vehicle_name)->setDistortionParam(camera_name, param_name, value); }); + pimpl_->server.bind("simGetDistortionParams", [&](const std::string& camera_name, const std::string& vehicle_name) -> std::vector { + return getVehicleSimApi(vehicle_name)->getDistortionParams(camera_name); + }); + pimpl_->server.bind("simSetCameraPose", [&](const std::string& camera_name, const RpcLibAdapatorsBase::Pose& pose, const std::string& vehicle_name) -> void { getVehicleSimApi(vehicle_name)->setCameraPose(camera_name, pose.to()); diff --git a/PythonClient/airsim/client.py b/PythonClient/airsim/client.py index 06b3dfdb59..58ea197da1 100644 --- a/PythonClient/airsim/client.py +++ b/PythonClient/airsim/client.py @@ -482,6 +482,19 @@ def simGetCameraInfo(self, camera_name, vehicle_name = ''): # TODO: below str() conversion is only needed for legacy reason and should be removed in future return CameraInfo.from_msgpack(self.client.call('simGetCameraInfo', str(camera_name), vehicle_name)) + def simGetDistortionParams(self, camera_name, vehicle_name = ''): + """ + Set camera distortion parameters + + Args: + camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used + distortion_params (dict): Dictionary of distortion param names and corresponding values + {"K1": 0.0, "K2": 0.0, "K3": 0.0, "P1": 0.0, "P2": 0.0} + vehicle_name (str, optional): Vehicle which the camera is associated with + """ + + return self.client.call('simGetDistortionParams', str(camera_name), vehicle_name) + def simSetDistortionParams(self, camera_name, distortion_params, vehicle_name = ''): """ Set camera distortion parameters @@ -494,7 +507,7 @@ def simSetDistortionParams(self, camera_name, distortion_params, vehicle_name = """ for param_name, value in distortion_params.items(): - self.client.call('simSetDistortionParam', param_name, value, vehicle_name) + self.client.call('simSetDistortionParam', str(camera_name), param_name, value, vehicle_name) def simSetDistortionParam(self, camera_name, param_name, value, vehicle_name = ''): """ diff --git a/Unreal/Plugins/AirSim/Source/PIPCamera.cpp b/Unreal/Plugins/AirSim/Source/PIPCamera.cpp index 1b659b4548..ecca794040 100644 --- a/Unreal/Plugins/AirSim/Source/PIPCamera.cpp +++ b/Unreal/Plugins/AirSim/Source/PIPCamera.cpp @@ -26,6 +26,7 @@ APIPCamera::APIPCamera() if (dist_mat_finder.Succeeded()) { distortion_material_static_ = dist_mat_finder.Object; + distortion_param_collection_ = Cast(StaticLoadObject(UMaterialParameterCollection::StaticClass(), NULL, TEXT("'/AirSim/HUDAssets/DistortionParams.DistortionParams'"))); } else UAirBlueprintLib::LogMessageString("Cannot create distortion material for the PIPCamera", @@ -41,6 +42,7 @@ APIPCamera::APIPCamera() image_type_to_pixel_format_map_.Add(5, EPixelFormat::PF_B8G8R8A8); image_type_to_pixel_format_map_.Add(6, EPixelFormat::PF_B8G8R8A8); image_type_to_pixel_format_map_.Add(7, EPixelFormat::PF_B8G8R8A8); + } void APIPCamera::PostInitializeComponents() @@ -91,6 +93,9 @@ void APIPCamera::BeginPlay() gimbal_stabilization_ = 0; gimbald_rotator_ = this->GetActorRotation(); this->SetActorTickEnabled(false); + + if (distortion_param_collection_) + distortion_param_instance_ = this->GetWorld()->GetParameterCollectionInstance(distortion_param_collection_); } msr::airlib::ProjectionMatrix APIPCamera::getProjectionMatrix(const APIPCamera::ImageType image_type) const diff --git a/Unreal/Plugins/AirSim/Source/PIPCamera.h b/Unreal/Plugins/AirSim/Source/PIPCamera.h index 4b0dc13228..0745001eaa 100644 --- a/Unreal/Plugins/AirSim/Source/PIPCamera.h +++ b/Unreal/Plugins/AirSim/Source/PIPCamera.h @@ -10,6 +10,7 @@ #include "common/AirSimSettings.hpp" #include "NedTransform.h" +#include "Materials/MaterialParameterCollection.h" #include "Materials/MaterialParameterCollectionInstance.h" #include "Materials/MaterialInstanceDynamic.h" #include "PIPCamera.generated.h" diff --git a/Unreal/Plugins/AirSim/Source/PawnSimApi.cpp b/Unreal/Plugins/AirSim/Source/PawnSimApi.cpp index 2478af8f8b..99a8d84726 100644 --- a/Unreal/Plugins/AirSim/Source/PawnSimApi.cpp +++ b/Unreal/Plugins/AirSim/Source/PawnSimApi.cpp @@ -435,6 +435,21 @@ void PawnSimApi::setDistortionParam(const std::string& camera_name, const std::s }, true); } +std::vector PawnSimApi::getDistortionParams(const std::string& camera_name) +{ + std::vector param_values(5, 0.0); + UAirBlueprintLib::RunCommandOnGameThread([this, camera_name, ¶m_values]() { + APIPCamera* camera = getCamera(camera_name); + camera->distortion_param_instance_->GetScalarParameterValue(FName(TEXT("K1")), param_values[0]); + camera->distortion_param_instance_->GetScalarParameterValue(FName(TEXT("K2")), param_values[1]); + camera->distortion_param_instance_->GetScalarParameterValue(FName(TEXT("K3")), param_values[2]); + camera->distortion_param_instance_->GetScalarParameterValue(FName(TEXT("P1")), param_values[3]); + camera->distortion_param_instance_->GetScalarParameterValue(FName(TEXT("P2")), param_values[4]); + }, true); + + return param_values; +} + //parameters in NED frame PawnSimApi::Pose PawnSimApi::getPose() const { diff --git a/Unreal/Plugins/AirSim/Source/PawnSimApi.h b/Unreal/Plugins/AirSim/Source/PawnSimApi.h index 0cea10087e..ff94310446 100644 --- a/Unreal/Plugins/AirSim/Source/PawnSimApi.h +++ b/Unreal/Plugins/AirSim/Source/PawnSimApi.h @@ -80,6 +80,8 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase { virtual void setCameraPose(const std::string& camera_name, const Pose& pose) override; virtual void setCameraFoV(const std::string& camera_name, float fov_degrees) override; virtual void setDistortionParam(const std::string& camera_name, const std::string& param_name, float value) override; + virtual std::vector getDistortionParams(const std::string& camera_name) override; + virtual CollisionInfo getCollisionInfo() const override; virtual int getRemoteControlID() const override; virtual msr::airlib::RCData getRCData() const override; From ed312867ec305e1562628ee62913e23dd2d772ff Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Sat, 3 Oct 2020 00:12:41 -0700 Subject: [PATCH 09/15] Fix docstring --- PythonClient/airsim/client.py | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/PythonClient/airsim/client.py b/PythonClient/airsim/client.py index 58ea197da1..b215d8f587 100644 --- a/PythonClient/airsim/client.py +++ b/PythonClient/airsim/client.py @@ -484,13 +484,14 @@ def simGetCameraInfo(self, camera_name, vehicle_name = ''): def simGetDistortionParams(self, camera_name, vehicle_name = ''): """ - Set camera distortion parameters + Get camera distortion parameters Args: camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used - distortion_params (dict): Dictionary of distortion param names and corresponding values - {"K1": 0.0, "K2": 0.0, "K3": 0.0, "P1": 0.0, "P2": 0.0} vehicle_name (str, optional): Vehicle which the camera is associated with + + Returns: + List (float): List of distortion parameter values corresponding to K1, K2, K3, P1, P2 respectively. """ return self.client.call('simGetDistortionParams', str(camera_name), vehicle_name) From e41becf38739cace8c7df5680f2781727eb52f2e Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Tue, 6 Oct 2020 20:35:31 -0700 Subject: [PATCH 10/15] Revert change for compatibility --- Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp index 50b8eb1f02..2365e72495 100644 --- a/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp +++ b/Unreal/Plugins/AirSim/Source/SimMode/SimModeBase.cpp @@ -200,7 +200,7 @@ void ASimModeBase::initializeTimeOfDay() sky_sphere_ = sky_spheres[0]; static const FName sun_prop_name(TEXT("Directional light actor")); auto* p = sky_sphere_class_->FindPropertyByName(sun_prop_name); - FObjectProperty* sun_prop = Cast(p); + UObjectProperty* sun_prop = Cast(p); UObject* sun_obj = sun_prop->GetObjectPropertyValue_InContainer(sky_sphere_); sun_ = Cast(sun_obj); if (sun_) From e5967a0c8d7a980761776b6a08d40c6014ef11c1 Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Wed, 9 Dec 2020 01:26:04 -0800 Subject: [PATCH 11/15] Add placeholders for Unity compilation --- .../AirsimWrapper/Source/AirSimStructs.hpp | 72 ++++++++++--------- .../AirsimWrapper/Source/PInvokeWrapper.cpp | 6 ++ .../AirsimWrapper/Source/PInvokeWrapper.h | 4 ++ .../AirsimWrapper/Source/PawnSimApi.cpp | 11 +++ .../AirsimWrapper/Source/PawnSimApi.h | 2 + .../Scripts/Vehicles/VehicleCompanion.cs | 5 ++ 6 files changed, 65 insertions(+), 35 deletions(-) diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/AirSimStructs.hpp b/Unity/AirLibWrapper/AirsimWrapper/Source/AirSimStructs.hpp index 710cc3f01e..1d8340ed94 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/AirSimStructs.hpp +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/AirSimStructs.hpp @@ -34,12 +34,12 @@ namespace AirSimUnity z = vec.z(); } - AirSimVector operator+(const AirSimVector& V) const + AirSimVector operator+(const AirSimVector &V) const { return AirSimVector(x + V.x, y + V.y, z + V.z); } - AirSimVector operator-(const AirSimVector& V) const + AirSimVector operator-(const AirSimVector &V) const { return AirSimVector(x - V.x, y - V.y, z - V.z); } @@ -101,33 +101,34 @@ namespace AirSimUnity struct AirSimRCData { - #ifdef _WIN32 - _int64 timestamp = 0; - #elif defined(__linux__) || defined(__APPLE__) - int64_t timestamp = 0; - #endif +#ifdef _WIN32 + _int64 timestamp = 0; +#elif defined(__linux__) || defined(__APPLE__) + int64_t timestamp = 0; +#endif float pitch = 0, roll = 0, throttle = 0, yaw = 0; float left_z = 0, right_z = 0; - unsigned int switch1 = 0, switch2 = 0, switch3 = 0, switch4 = 0, - switch5 = 0, switch6 = 0, switch7 = 0, switch8 = 0; + unsigned int switch1 = 0, switch2 = 0, switch3 = 0, switch4 = 0, + switch5 = 0, switch6 = 0, switch7 = 0, switch8 = 0; bool is_initialized = false; //is RC connected? - bool is_valid = false; //must be true for data to be valid + bool is_valid = false; //must be true for data to be valid }; struct AirSimCollisionInfo { - bool has_collided = false;; + bool has_collided = false; + ; AirSimVector normal; AirSimVector impact_point; AirSimVector position; float penetration_depth = 0.0f; - #ifdef _WIN32 - _int64 time_stamp = 0; - #elif defined(__linux__) || defined(__APPLE__) - int64_t time_stamp = 0; - #endif +#ifdef _WIN32 + _int64 time_stamp = 0; +#elif defined(__linux__) || defined(__APPLE__) + int64_t time_stamp = 0; +#endif int collision_count = 0; - char* object_name; + char *object_name; int object_id = -1; }; @@ -138,18 +139,20 @@ namespace AirSimUnity AirSimAccelerations accelerations; }; - struct AirSimImageRequest { - char* camera_name; + struct AirSimImageRequest + { + char *camera_name; msr::airlib::ImageCaptureBase::ImageType image_type = static_cast(0); bool pixels_as_float = false; bool compress = false; }; - struct AirSimImageResponse { + struct AirSimImageResponse + { int image_uint_len = 0; - unsigned char* image_data_uint; + unsigned char *image_data_uint; int image_float_len = 0; - float* image_data_float; + float *image_data_float; AirSimVector camera_position; AirSimQuaternion camera_orientation; bool pixels_as_float = false; @@ -171,12 +174,12 @@ namespace AirSimUnity { int gear = 0; float speed = 0.0f; - #ifdef _WIN32 - __int64 time_stamp = 0; - #elif defined(__linux__) || defined(__APPLE__) - int64_t timestamp = 0; - #endif - +#ifdef _WIN32 + __int64 time_stamp = 0; +#elif defined(__linux__) || defined(__APPLE__) + int64_t timestamp = 0; +#endif + float engineMaxRotationSpeed = 0; float engineRotationSpeed = 0; AirSimPose pose; @@ -199,7 +202,6 @@ namespace AirSimUnity AirSimVector Scale3D; public: - UnityTransform() { Rotation = AirSimQuaternion(0, 0, 0, 1); @@ -207,11 +209,11 @@ namespace AirSimUnity Scale3D = AirSimVector(1, 1, 1); } - UnityTransform(const UnityTransform& obj) : - Rotation(obj.Rotation), - Position(obj.Position), - Scale3D(obj.Scale3D) - {} + UnityTransform(const UnityTransform &obj) : Rotation(obj.Rotation), + Position(obj.Position), + Scale3D(obj.Scale3D) + { + } }; struct RayCastHitResult @@ -219,4 +221,4 @@ namespace AirSimUnity bool isHit = false; float distance = 0.0f; }; -} \ No newline at end of file +} // namespace AirSimUnity \ No newline at end of file diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.cpp b/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.cpp index 9c45287d57..5b75e55921 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.cpp +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.cpp @@ -13,6 +13,8 @@ AirSimCarState(*GetCarState)(const char* vehicleName); AirSimCameraInfo(*GetCameraInfo)(const char* cameraName, const char* vehicleName); bool(*SetCameraPose)(const char* cameraName, AirSimPose pose, const char* vehicleName); bool(*SetCameraFoV)(const char* cameraName, const float fov_degrees, const char* vehicleName); +bool(*SetCameraDistortionParam)(const char* cameraName, const char* paramName, const float value, const char* vehicleName); +bool(*GetCameraDistortionParam)(const char* cameraName, const char* vehicleName); bool(*SetSegmentationObjectId)(const char* meshName, int objectId, bool isNameRegex); int(*GetSegmentationObjectId)(const char* meshName); bool(*PrintLogMessage) (const char* message, const char* messageParam, const char* vehicleName, int severity); @@ -35,6 +37,8 @@ void InitVehicleManager( AirSimCameraInfo(*getCameraInfo)(const char* cameraName, const char* vehicleName), bool(*setCameraPose)(const char* cameraName, AirSimPose pose, const char* vehicleName), bool(*setCameraFoV)(const char* cameraName, const float fov_degrees, const char* vehicleName), + bool(*setDistortionParam)(const char* cameraName, const char* paramName, const float value, const char* vehicleName), + bool(*getDistortionParams)(const char* cameraName, const char* vehicleName), bool(*setSegmentationObjectId)(const char* meshName, int objectId, bool isNameRegex), int(*getSegmentationObjectId)(const char* meshName), bool(*printLogMessage) (const char* message, const char* messageParam, const char* vehicleName, int severity), @@ -57,6 +61,8 @@ void InitVehicleManager( GetCameraInfo = getCameraInfo; SetCameraPose = setCameraPose; SetCameraFoV = setCameraFoV; + SetCameraDistortionParam = setDistortionParam; + GetCameraDistortionParams = getDistortionParams; SetSegmentationObjectId = setSegmentationObjectId; GetSegmentationObjectId = getSegmentationObjectId; PrintLogMessage = printLogMessage; diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.h b/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.h index 36c22c2e1e..2fb702ca0b 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.h +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.h @@ -27,6 +27,8 @@ extern AirSimCarState(*GetCarState)(const char* vehicleName); extern AirSimCameraInfo(*GetCameraInfo)(const char* cameraName, const char* vehicleName); extern bool(*SetCameraPose)(const char* cameraName, AirSimPose pose, const char* vehicleName); extern bool(*SetCameraFoV)(const char* cameraName, const float fov_degrees, const char* vehicleName); +extern bool(*SetCameraDistortionParam)(const char* cameraName, const char* paramName, const float value, const char* vehicleName); +extern bool(*GetCameraDistortionParam)(const char* cameraName, const char* vehicleName); extern bool(*SetSegmentationObjectId)(const char* meshName, int objectId, bool isNameRegex); extern int(*GetSegmentationObjectId)(const char* meshName); extern bool(*PrintLogMessage) (const char* message, const char* messageParam, const char* vehicleName, int severity); @@ -51,6 +53,8 @@ extern "C" EXPORT void InitVehicleManager( AirSimCameraInfo(*getCameraInfo)(const char* cameraName, const char* vehicleName), bool(*setCameraPose)(const char* cameraName, AirSimPose pose, const char* vehicleName), bool(*setCameraFoV)(const char* cameraName, const float fov_degrees, const char* vehicleName), + bool(*setDistortionParam)(const char* cameraName, const char* paramName, const float value, const char* vehicleName), + bool(*getDistortionParams)(const char* cameraName, const char* vehicleName), bool(*setSegmentationObjectId)(const char* meshName, int objectId, bool isNameRegex), int(*getSegmentationObjectId)(const char* meshName), bool(*printLogMessage) (const char* message, const char* messageParam, const char* vehicleName, int severity), diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.cpp b/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.cpp index e4b5966142..4cfbfe47a3 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.cpp +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.cpp @@ -220,6 +220,17 @@ void PawnSimApi::setCameraFoV(const std::string& camera_name, float fov_degrees) SetCameraFoV(camera_name.c_str(), fov_degrees, params_.vehicle_name.c_str()); } +void PawnSimApi::setDistortionParam(const std::string& camera_name, const std::string& param_name, float value) +{ + // not implemented +} + +std::vector PawnSimApi::getDistortionParams(const std::string& camera_name) +{ + // not implemented +} + + //parameters in NED frame PawnSimApi::Pose PawnSimApi::getPose() const { diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.h b/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.h index 6525666e88..3404afcbef 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.h +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.h @@ -74,6 +74,8 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase virtual msr::airlib::CameraInfo getCameraInfo(const std::string& camera_name) const override; virtual void setCameraPose(const std::string& camera_name, const Pose& pose) override; virtual void setCameraFoV(const std::string& camera_name, float fov_degrees) override; + virtual void setDistortionParam(const std::string& camera_name, const std::string& param_name, float value) override; + virtual void getDistortionParams(const std::string& camera_name) override; virtual CollisionInfo getCollisionInfo() const override; virtual int getRemoteControlID() const override; virtual msr::airlib::RCData getRCData() const override; diff --git a/Unity/UnityDemo/Assets/AirSimAssets/Scripts/Vehicles/VehicleCompanion.cs b/Unity/UnityDemo/Assets/AirSimAssets/Scripts/Vehicles/VehicleCompanion.cs index ce674191e7..d7b788ca48 100644 --- a/Unity/UnityDemo/Assets/AirSimAssets/Scripts/Vehicles/VehicleCompanion.cs +++ b/Unity/UnityDemo/Assets/AirSimAssets/Scripts/Vehicles/VehicleCompanion.cs @@ -194,6 +194,11 @@ private static bool SetCameraFoV(string cameraName, float fov_degrees, string ve return vehicle.VehicleInterface.SetCameraFoV(cameraName, fov_degrees); } + private static bool SetDistortionParam(string cameraName, string paramName, float value, string vehicleName) { + var vehicle = Vehicles.Find(element => element.vehicleName == vehicleName); + return vehicle.VehicleInterface.SetDistortionParam(cameraName, fov_degrees); + } + private static bool PrintLogMessage(string message, string messageParams, string vehicleName, int severity) { var vehicle = Vehicles.Find(element => element.vehicleName == vehicleName); return vehicle.VehicleInterface.PrintLogMessage(message, messageParams, vehicleName, severity); From 57f458ecb003d974f5e0ad3609b354f6af68811c Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Wed, 9 Dec 2020 01:27:19 -0800 Subject: [PATCH 12/15] Revert irrelevant changes --- .../AirsimWrapper/Source/AirSimStructs.hpp | 72 +++++++++---------- 1 file changed, 35 insertions(+), 37 deletions(-) diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/AirSimStructs.hpp b/Unity/AirLibWrapper/AirsimWrapper/Source/AirSimStructs.hpp index 1d8340ed94..710cc3f01e 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/AirSimStructs.hpp +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/AirSimStructs.hpp @@ -34,12 +34,12 @@ namespace AirSimUnity z = vec.z(); } - AirSimVector operator+(const AirSimVector &V) const + AirSimVector operator+(const AirSimVector& V) const { return AirSimVector(x + V.x, y + V.y, z + V.z); } - AirSimVector operator-(const AirSimVector &V) const + AirSimVector operator-(const AirSimVector& V) const { return AirSimVector(x - V.x, y - V.y, z - V.z); } @@ -101,34 +101,33 @@ namespace AirSimUnity struct AirSimRCData { -#ifdef _WIN32 - _int64 timestamp = 0; -#elif defined(__linux__) || defined(__APPLE__) - int64_t timestamp = 0; -#endif + #ifdef _WIN32 + _int64 timestamp = 0; + #elif defined(__linux__) || defined(__APPLE__) + int64_t timestamp = 0; + #endif float pitch = 0, roll = 0, throttle = 0, yaw = 0; float left_z = 0, right_z = 0; - unsigned int switch1 = 0, switch2 = 0, switch3 = 0, switch4 = 0, - switch5 = 0, switch6 = 0, switch7 = 0, switch8 = 0; + unsigned int switch1 = 0, switch2 = 0, switch3 = 0, switch4 = 0, + switch5 = 0, switch6 = 0, switch7 = 0, switch8 = 0; bool is_initialized = false; //is RC connected? - bool is_valid = false; //must be true for data to be valid + bool is_valid = false; //must be true for data to be valid }; struct AirSimCollisionInfo { - bool has_collided = false; - ; + bool has_collided = false;; AirSimVector normal; AirSimVector impact_point; AirSimVector position; float penetration_depth = 0.0f; -#ifdef _WIN32 - _int64 time_stamp = 0; -#elif defined(__linux__) || defined(__APPLE__) - int64_t time_stamp = 0; -#endif + #ifdef _WIN32 + _int64 time_stamp = 0; + #elif defined(__linux__) || defined(__APPLE__) + int64_t time_stamp = 0; + #endif int collision_count = 0; - char *object_name; + char* object_name; int object_id = -1; }; @@ -139,20 +138,18 @@ namespace AirSimUnity AirSimAccelerations accelerations; }; - struct AirSimImageRequest - { - char *camera_name; + struct AirSimImageRequest { + char* camera_name; msr::airlib::ImageCaptureBase::ImageType image_type = static_cast(0); bool pixels_as_float = false; bool compress = false; }; - struct AirSimImageResponse - { + struct AirSimImageResponse { int image_uint_len = 0; - unsigned char *image_data_uint; + unsigned char* image_data_uint; int image_float_len = 0; - float *image_data_float; + float* image_data_float; AirSimVector camera_position; AirSimQuaternion camera_orientation; bool pixels_as_float = false; @@ -174,12 +171,12 @@ namespace AirSimUnity { int gear = 0; float speed = 0.0f; -#ifdef _WIN32 - __int64 time_stamp = 0; -#elif defined(__linux__) || defined(__APPLE__) - int64_t timestamp = 0; -#endif - + #ifdef _WIN32 + __int64 time_stamp = 0; + #elif defined(__linux__) || defined(__APPLE__) + int64_t timestamp = 0; + #endif + float engineMaxRotationSpeed = 0; float engineRotationSpeed = 0; AirSimPose pose; @@ -202,6 +199,7 @@ namespace AirSimUnity AirSimVector Scale3D; public: + UnityTransform() { Rotation = AirSimQuaternion(0, 0, 0, 1); @@ -209,11 +207,11 @@ namespace AirSimUnity Scale3D = AirSimVector(1, 1, 1); } - UnityTransform(const UnityTransform &obj) : Rotation(obj.Rotation), - Position(obj.Position), - Scale3D(obj.Scale3D) - { - } + UnityTransform(const UnityTransform& obj) : + Rotation(obj.Rotation), + Position(obj.Position), + Scale3D(obj.Scale3D) + {} }; struct RayCastHitResult @@ -221,4 +219,4 @@ namespace AirSimUnity bool isHit = false; float distance = 0.0f; }; -} // namespace AirSimUnity \ No newline at end of file +} \ No newline at end of file From 5b3e1cd56326ec3d3ce7f9d26f8f82090533e8f5 Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Wed, 9 Dec 2020 18:29:03 -0800 Subject: [PATCH 13/15] Fix typo --- Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.cpp | 2 +- Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.cpp b/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.cpp index 5b75e55921..dbff2108d3 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.cpp +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.cpp @@ -14,7 +14,7 @@ AirSimCameraInfo(*GetCameraInfo)(const char* cameraName, const char* vehicleName bool(*SetCameraPose)(const char* cameraName, AirSimPose pose, const char* vehicleName); bool(*SetCameraFoV)(const char* cameraName, const float fov_degrees, const char* vehicleName); bool(*SetCameraDistortionParam)(const char* cameraName, const char* paramName, const float value, const char* vehicleName); -bool(*GetCameraDistortionParam)(const char* cameraName, const char* vehicleName); +bool(*GetCameraDistortionParams)(const char* cameraName, const char* vehicleName); bool(*SetSegmentationObjectId)(const char* meshName, int objectId, bool isNameRegex); int(*GetSegmentationObjectId)(const char* meshName); bool(*PrintLogMessage) (const char* message, const char* messageParam, const char* vehicleName, int severity); diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.h b/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.h index 2fb702ca0b..b013c0b1ff 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.h +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/PInvokeWrapper.h @@ -28,7 +28,7 @@ extern AirSimCameraInfo(*GetCameraInfo)(const char* cameraName, const char* vehi extern bool(*SetCameraPose)(const char* cameraName, AirSimPose pose, const char* vehicleName); extern bool(*SetCameraFoV)(const char* cameraName, const float fov_degrees, const char* vehicleName); extern bool(*SetCameraDistortionParam)(const char* cameraName, const char* paramName, const float value, const char* vehicleName); -extern bool(*GetCameraDistortionParam)(const char* cameraName, const char* vehicleName); +extern bool(*GetCameraDistortionParams)(const char* cameraName, const char* vehicleName); extern bool(*SetSegmentationObjectId)(const char* meshName, int objectId, bool isNameRegex); extern int(*GetSegmentationObjectId)(const char* meshName); extern bool(*PrintLogMessage) (const char* message, const char* messageParam, const char* vehicleName, int severity); From ded679fcdadd2c5e6bda0422eb284cedac2383eb Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Thu, 10 Dec 2020 17:03:37 -0800 Subject: [PATCH 14/15] Fix returntype Unity --- Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.h b/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.h index 3404afcbef..e49b5c52db 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.h +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.h @@ -75,7 +75,7 @@ class PawnSimApi : public msr::airlib::VehicleSimApiBase virtual void setCameraPose(const std::string& camera_name, const Pose& pose) override; virtual void setCameraFoV(const std::string& camera_name, float fov_degrees) override; virtual void setDistortionParam(const std::string& camera_name, const std::string& param_name, float value) override; - virtual void getDistortionParams(const std::string& camera_name) override; + virtual std::vector getDistortionParams(const std::string& camera_name) override; virtual CollisionInfo getCollisionInfo() const override; virtual int getRemoteControlID() const override; virtual msr::airlib::RCData getRCData() const override; From 2667c3a04519314b791737d4b86e22321da59914 Mon Sep 17 00:00:00 2001 From: Sai Vemprala Date: Tue, 15 Dec 2020 14:50:42 -0800 Subject: [PATCH 15/15] Fix unimpl Unity methods --- Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.cpp b/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.cpp index 4cfbfe47a3..a5df914e53 100644 --- a/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.cpp +++ b/Unity/AirLibWrapper/AirsimWrapper/Source/PawnSimApi.cpp @@ -228,6 +228,8 @@ void PawnSimApi::setDistortionParam(const std::string& camera_name, const std::s std::vector PawnSimApi::getDistortionParams(const std::string& camera_name) { // not implemented + std::vector params(5, 0.0); + return params; }