From 41bee43e31ad2b7b3711db27cb8d4eb560abdbe6 Mon Sep 17 00:00:00 2001 From: Tomas Nagy <99697918+atomyks@users.noreply.github.com> Date: Wed, 24 Apr 2024 15:59:04 +0200 Subject: [PATCH] feat(learned_model): create package (#6395) Signed-off-by: Maxime CLEMENT Co-authored-by: Tomas Nagy --- .../CMakeLists.txt | 23 ++ .../learning_based_vehicle_model/README.md | 208 ++++++++++++++++++ .../image/python_model_interface.png | Bin 0 -> 94435 bytes .../interconnected_model.hpp | 130 +++++++++++ .../model_connections_helpers.hpp | 27 +++ .../simple_pymodel.hpp | 102 +++++++++ .../submodel_interface.hpp | 60 +++++ .../learning_based_vehicle_model/package.xml | 26 +++ .../src/interconnected_model.cpp | 138 ++++++++++++ .../src/model_connections_helpers.cpp | 47 ++++ .../src/simple_pymodel.cpp | 111 ++++++++++ .../src/submodel_interface.cpp | 15 ++ .../simple_planning_simulator/CMakeLists.txt | 8 +- simulator/simple_planning_simulator/README.md | 59 +++-- .../simple_planning_simulator_core.hpp | 3 +- .../vehicle_model/sim_model.hpp | 1 + .../sim_model_learned_steer_vel.hpp | 144 ++++++++++++ .../simple_planning_simulator/package.xml | 1 + .../simple_planning_simulator_core.cpp | 20 +- .../sim_model_learned_steer_vel.cpp | 88 ++++++++ 20 files changed, 1188 insertions(+), 23 deletions(-) create mode 100644 simulator/learning_based_vehicle_model/CMakeLists.txt create mode 100644 simulator/learning_based_vehicle_model/README.md create mode 100644 simulator/learning_based_vehicle_model/image/python_model_interface.png create mode 100644 simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/interconnected_model.hpp create mode 100644 simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/model_connections_helpers.hpp create mode 100644 simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/simple_pymodel.hpp create mode 100644 simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/submodel_interface.hpp create mode 100644 simulator/learning_based_vehicle_model/package.xml create mode 100644 simulator/learning_based_vehicle_model/src/interconnected_model.cpp create mode 100644 simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp create mode 100644 simulator/learning_based_vehicle_model/src/simple_pymodel.cpp create mode 100644 simulator/learning_based_vehicle_model/src/submodel_interface.cpp create mode 100644 simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp create mode 100644 simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp diff --git a/simulator/learning_based_vehicle_model/CMakeLists.txt b/simulator/learning_based_vehicle_model/CMakeLists.txt new file mode 100644 index 0000000000000..58a3ad57e6f9e --- /dev/null +++ b/simulator/learning_based_vehicle_model/CMakeLists.txt @@ -0,0 +1,23 @@ +cmake_minimum_required(VERSION 3.14.4) +project(learning_based_vehicle_model) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(Python3 COMPONENTS Interpreter Development) +find_package(pybind11 CONFIG) + +ament_auto_add_library(${PROJECT_NAME} SHARED + DIRECTORY src +) +target_link_libraries(${PROJECT_NAME} pybind11::embed ${Python3_LIBRARIES}) +target_include_directories(${PROJECT_NAME} PRIVATE ${Python3_INCLUDE_DIRS}) + +target_compile_options(${PROJECT_NAME} PRIVATE -fvisibility=hidden) + +install( + DIRECTORY include/ + DESTINATION include/${PROJECT_NAME} +) + +ament_auto_package() diff --git a/simulator/learning_based_vehicle_model/README.md b/simulator/learning_based_vehicle_model/README.md new file mode 100644 index 0000000000000..b6df96b2d576c --- /dev/null +++ b/simulator/learning_based_vehicle_model/README.md @@ -0,0 +1,208 @@ +# Learned Model + +This is the design document for the Python learned model used in the `simple_planning_simulator` package. + +## Purpose / Use cases + + + + +This library creates an interface between models in Python and PSIM (C++). It is used to quickly deploy learned Python models in PSIM without a need for complex C++ implementation. + +## Design + + + + +The idea behind this package is that the model we want to use for simulation consists of multiple sub-models (e.g., steering model, drive model, vehicle kinematics, etc.). These sub-models are implemented in Python and can be trainable. Each sub-model has string names for all of its inputs/outputs, which are used to create model interconnections automatically (see image below). This allows us to easily switch sub-models for better customization of the simulator. + +![py_model_interface](./image/python_model_interface.png "PyModel interface") + +## Assumptions / Known limits + + + +To use this package `python3` and `pybind11` need to be installed. The only assumption on Python sub-models is their interface. + +```python +class PythonSubmodelInterface: + + def forward(self, action, state): # Required + """ + Calculate forward pass through the model and returns next_state. + """ + return list() + + def get_state_names(self): # Required + """ + Return list of string names of the model states (outputs). + """ + return list() + + def get_action_names(self): # Required + """ + Return list of string names of the model actions (inputs). + """ + return list() + + def reset(self): # Required + """ + Reset model. This function is called after load_params(). + """ + pass + + def load_params(self, path): # Required + """ + Load parameters of the model. + Inputs: + - path: Path to a parameter file to load by the model. + """ + pass + + def dtSet(self, dt): # Required + """ + Set dt of the model. + Inputs: + - dt: time step + """ + pass +``` + +## API + + + + +To successfully create a vehicle model an InterconnectedModel class needs to be set up correctly. + +### InterconnectedModel class + +#### `Constructor` + +The constructor takes no arguments. + +#### `void addSubmodel(std::tuple model_descriptor)` + +Add a new sub-model to the model. + +Inputs: + +- model_descriptor: Describes what model should be used. The model descriptor contains three strings: + - The first string is a path to a python module where the model is implemented. + - The second string is a path to the file where model parameters are stored. + - The third string is the name of the class that implements the model. + +Outputs: + +- None + +#### `void generateConnections(std::vector in_names, std::vector out_names)` + +Generate connections between sub-models and inputs/outputs of the model. + +Inputs: + +- in_names: String names for all of the model inputs in order. +- out_names: String names for all of the model outputs in order. + +Outputs: + +- None + +#### `void initState(std::vector new_state)` + +Set the initial state of the model. + +Inputs: + +- new_state: New state of the model. + +Outputs: + +- None + +#### `std::vector updatePyModel(std::vector psim_input)` + +Calculate the next state of the model by calculating the next state of all of the sub-models. + +Inputs: + +- psim_input: Input to the model. + +Outputs: + +- next_state: Next state of the model. + +#### `dtSet(double dt)` + +Set the time step of the model. + +Inputs: + +- dt: time step + +Outputs: + +- None + +### Example + +Firstly we need to set up the model. + +```C++ +InterconnectedModel vehicle; + +// Example of model descriptors +std::tuple model_descriptor_1 = { + (char*)"path_to_python_module_with_model_class_1", + (char*)nullptr, // If no param file is needed you can pass 'nullptr' + (char*)"ModelClass1" + }; + +std::tuple model_descriptor_2 = { + (char*)"path_to_python_module_with_model_class_2", + (char*)"/path_to/param_file", + (char*)"ModelClass2" // Name of the python class. Needs to use the interface from 'Assumptions' + }; + +// Create sub-models based on descriptors +vehicle.addSubmodel(model_descriptor_1); +vehicle.addSubmodel(model_descriptor_2); + +// Define STATE and INPUT names of the system +std::vector state_names = {(char*)"STATE_NAME_1", (char*)"STATE_NAME_2"}; +std::vector input_names = {(char*)"INPUT_NAME_1", (char*)"INPUT_NAME_2"}; + +// Automatically connect sub-systems with model input +vehicle.generateConnections(input_names, state_names); + +// Set the time step of the model +vehicle.dtSet(dt); +``` + +After the model is correctly set up, we can use it the following way. + +```C++ +// Example of an model input +std::vector vehicle_input = {0.0, 1.0}; // INPUT_NAME_1, INPUT_NAME_2 + +// Example of an model state +std::vector current_state = {0.2, 0.5}; // STATE_NAME_1, STATE_NAME_2 + +// Set model state +vehicle.initState(current_state); + +// Calculate the next state of the model +std::vector next_state = vehicle.updatePyModel(vehicle_input); +``` + +## References / External links + + + +## Related issues + + diff --git a/simulator/learning_based_vehicle_model/image/python_model_interface.png b/simulator/learning_based_vehicle_model/image/python_model_interface.png new file mode 100644 index 0000000000000000000000000000000000000000..d81caf7a94000c60b8d3594613bb481cea839c65 GIT binary patch literal 94435 zcmeEu2|SeR+kZ(J5`#op$6m4wvV>ynQ51=6&DgVM9ZJYxicl1ltzA(lp;ET7bW~_T zlqHIit%yYZuV*D3> zCn~QkDkq2c_Lg>V#XI}pJ$$7-9sS@EeDC4q;OgY+=rGepPF7AqN>)xvc8wWUSyWyV zi-rHlDoV>@mA22c$2&WE&fajNSFo$QJ6=>yca5|x+)Ba%X^w-xwi5h3{rqSCHgfg! zC&D$NvZ9@$!pt?F0Oa0sa?-LZ;Tt_idp9q*i<~T07XHP;C0$n^M<*}%nJ%@}%%dIs z@Xj;c46rcUu4m}06^L^RHgr%3QV!5onQ0T?=;Q0^=9g(Z@I-;_g@E!86yw>dCzz0vf$81{@cwed6JGjmclAB3@tAz)V=&5b#Xun0u zewT|9+~n)K(eCL%)bqi6yKMAwaCCF4F;?&s?L^+kIxPftht*(sa7Bi_fyEAZ=PPG0V_ zuQ%Jq8{Yh@yCWA&?eQ>jRCAisY@4ftpUccuLQK&jD-t&wu;nHGRI= z{eN>i6#^C~>*lv%gMpEjshOSU2CT9y&AtNg?*6lbJ2O(genGU+_VM!fbfB(MuvA>2 zi>sfbsW;vpX&wj$2G?BtJlx?EvI4;gxNCX2d-=d;PcKhs1d9?eHdq~gjx-aTx#W%i z`NgR3`s<_n^BC(ndU-hd`2@jjXYZ&qJ20~rErpd;n7tDCvw>i-$Ssi0xXiJRH8kVE z&swGPm%AfPf6vT8o7su~^*2C#<2UwUvPRxqNp^$wwjfP&r9giV#Q-xCDLJLtG5gbJ z<+~~P!9@M~JN??Md|7utPYZ1Z=1z+&ZT99)i-O|pT>XWnW!6jn`HSVxofdi7*%zTr zi;D91i$zi82Wv&)FSu5Id#Qkvr^a6=cSoWo5`MrbIeI$G{;6&6j`#I-wg1|WeeLvq z!C%SAIy!t6ss0B`WzIsN#jm-`fOgHt(H-yS8t`=h{L#|*Jze;D&6;?*0;KxlM&;Ig zV;Rb_YowJFXI`K7G+!@&AA85yU;aK9IrG3@eC&4y`J>1B;eDJP{r(4!mDi&B=PyCy z*GFi!HPuc3R?FY#%@zK&P`SA=_18!BH%vuEf$0|>@BxCV&IDLNy6($Wi8Pj7!eUvMQ7CZ+}(A-9@o2}^HIW7^fPFYWS2kTuTK zOh;#nowklCw3@v{YyThI#oXe@w;=ey&8R*8rJEwIY!2)Nw2Jg<4z~66^YLmjw-i1qs{*Vhm42ifd@VYw#8rgj$pmDM75 zu>7y?V7$dZXOo$xnSt@9@9*=k@&AlHeqj9Hd-T7x^~?P(^EdS;00Bp(h71rV<%Fd4 zum}JxLCTK%MGyYpyUAHz;P2)m*U&PeFKH7kZ~ZL?N#i1D2zo9WLJae_xgjco{R1(n zobq>|)YsL++uhO5+a2%e>FVih2cP{R=Kv<>XU{m-I{yE)0~&uyvjgCbzt5lLXp=rS zo1^{muVV=EFpbDe&Iy&Kem*e&a1EiNk+|qYwE+ay!G|w65AW#!AHDqjW^o^odGHw^ zkgF$SuyWsEEhWSU zAd@iHkI+nIuK6g*e!*maAq)CZn(&Qt_|MoDz|1~D7J!~*r4=C8LdY7pU`f58qNG5( zpp9_9h+$B_)<#z2mro{+KCVC!BhZ_AaV|=qYdc><`nlFNGb2AB;%4X%xG%K$A$v<( zQZsqquQZ$;xPKUjB&AFXi!}eJBnx)?znP*-DbrTemoBXN)h_&PQ*`<7q24dJZ|@*K z7bs3rtFBbg_q!drchJlasrbMH78?+e)I0s_&0z$TX>tCGsnKlj@9E9I2Zq$_z!Q&D zHED5twy+CkfZ&6f$dC8;^Md*+LUOnxl{p8*{d&xT0RrBa3JR!pGm9&}i4niWx6F0U zzvRyUZcspx1{`U|qo^n^t*9vb<)7IS@LW@(dDpqX;Qy3?QSiq3Y<95pS9aT}ztPZA zcgsesgVgUJy`6#P^8UpzJ8NQi0<8=^i;@07(o6o^rKHL~*#d{z%dryKd@;_+u8=qxO{Tu;JQ8R+s_5a;ZsGR5TA!&c(S>N7RR$?Y> z{a!NSYvS}bqzd1g-mhBnxB7+uIoV2s_H$OX9Iejx*ETVl(&<-p3I7??|Ig;&pMsQU zy}i7GwDOvt3s)+$st=k+`7`RQGvodHp8vN6#WZ(4htrsO?>WT7zh(*$?FauN<)Lpy z0W@{U9J85YwJNhI$e(DovA7n}ML~YX1E{Lh`?Dl*U`l{%EWG*+_rMuK%^jxtdtHZ`|hJ(IkJkcxh_& zul(dUbN|;%E|q9ubdC%7VP>iLt?QWa9DgB~@FT|mJC~sCgUA)Xa7N#zc3+~^uScf8 zKmz#1-2Tk~O{B2j6VCrT*qSyA|G*qjZVpmVo(;FO)&9Sd1pZnF{=R7XcWk2gQ?kH+ znx)Qev5}+2uQ^%RuNlstV7cD_8iYUjwI2L^P51Xwxzs%FOS<=mCW61Dqy3iU{RVga zRu$(jl?BpP>K|BB_@<=rgIeIgQB@}jMoLNf zo7MRjia69`z<%M#PuhWEKcB8TcP|L_TiSW9GhfX90HO$-_=B7vsy6=++q`*#^9-~# z&4{*d(iRqrRE-t&8#iQ@tJ7OqN8GHVi%|{lysZ(|Ie1%{e&5ZT9D@4ZOD;1?$5^4> z)K~>g?!8)h_vx|gYkbe2?|7#cRNMaQ^5x*{8#gAKds8P%(G__apU)d;(6J|k(TfPq zXVm}s&w_-qJbY!vXAEUHRAKHHU)qE>p(jc|e_T(`9huV9dClxcjfOunN>G$nd~EJG7@Zh{0DLbOVk*x@8zH*8b-=p#22it6+Z^&gg{3 z?&Uw~V9LsMwDKp(Y)=V;DO zJ`ClIyNR6KGLi2mPos;`p~7GlnhASBe|y}w<_5!Uqo;v6*MH;Dq8}I}JYgwe?KS6| zNg$<5u?G@%BnKr*f;y>B#u?pOjWpNWz@9Ha+yJI=leSC9u`0+Nost%Q* zSo!i(|4) z#q@ZGz=TKm!eyu${@v~=yQ-I;aN70a$hP;}|OpVkSS7fH+KD{q0jnv_?QJ8wYt@L8=@bQ{Q!W6aP zvIY2zkoSz%MYbP5eH^NkI2|kZvJrt)pNDkE_Umt6-s(k8O&!_z9V)kVw9*=^} z#P?5}Pq$oYz%7nkEK?%8`r4x{U3D_0%vSFCIuiq4p*(TxKTX)7u%#cL4OPIXa<>Qf zU*eapj9RkTbmN+>#Lv^?mC&B|qwA})$t*?B0<5@$dJah{F3fi=3!9IBymi~b=G35< z$12UOJUDgI+4Oj^sW1m!Z?4v}$dnA@G|+C>ESURLpW?W>c%x%xJ9 z#_qxE_}3TCvpn3WWMi>=;9BJ|=k(>eD_qZ547Tqc;;WP5Bn;jfZs#l^~Hw`bSHSZ*j^HLveo z3F(Gqq{YRZ1M-#3@}vbU%7Sl-I`($ieV*Jl`l!5;9^)9V{=V-zf4b4l!5eNRd}|fnFR_&vold}L zRqP(R#RY5QdP^^P*;!pHv11O0^In}h@qYL|DdkOZtdu>=(6KFE*}WN|>r#o&_s^Gp z!H+FSyD|03IP^ffBKLq(>bkeJ!t={xKdHV|?ek`*+C38!} zf>h-~%j~W3PIaSdvj#7P#CX=(4{@mB=Ld(qn{5KCxOPxjY|YtF8zNIeKY#4lyrZmp zUOZjNVj}*Tcjc1Z+H@ptZFYJd+nylTmysc7kC?w^BYgVU@j1%%e3~M^mIO+u!cgYc zQmw5Qm*bfES;^woTtf%fG+WD;Ouo+E%v*~~M5$`d!zq;QCS1P$^1w-%M~s+-r;#Adf(<1kJG)5Hhnb}*b$<%y0~-S{9XIqOr!}K zQkX?u3uIU+m+y$3SiQP*>TUiKVq_8%_EGT}!2qfb2x z?6{>z4g&K!RaRjkUDSX1rgT&MryBH0bO1U#SiZzTvCaMJf#|K1m(10JZyqf*oWV}V zF#vm**VNDAvQdut6i#~Pw>auMT@)9A!os{6|I^Czu^%+hm{rSbI!DT|_OV!9 zHHRZx%^90GG&Y5D!r zcU{jN6B8sh6dluJ4ypY>CclW%&?@F4urCT#7IYbNf+x7~vL4BK;C1bFW81YUo0(YN zz&t-P#VIRj78PY?pc337xOUKU9?pK=g>zXblMd5Q%oH?1oA2`uOJ0Du93A6hMliBF z&K+|)P&)EpFAOaudBBLQsjpE`W_b1y+6m=x!GVlINuw4V8vr*q;wa#C0)CPhoxrE2 zL(~*wlx&wdhSoZ9rQb)Y!W~U$vamnc$G5L5P0LD>5qso*%~kr%(XyB~FHd-}L<{UC z=AJazW*6eG{G2TO+<%x@-fe$ib*bgacmi?ONEXi~3{Q_qI36{O*Wn8;77m44D}&=9$k^GNty(aGs*9xqY^ z>pJB^2G(;MaLmt{=mbu2@asL|#FKX&VZ>TH=j2x(z<9k-u|=&v9Y>DiwpAuROxjK9 zd_oFjDRpkjLYrpu-^w2job@U402z;;e5o>%+=TBH3R9w!=|wFiv-MvpvK_rGn4u?+ zW8O!1QjxoBHTY5sSl5e#N!&OslrbirIjV@>R+2PscJ;1s6xXP`62>-@4ZjyW(l`o> zVnzvpG3*)@DtDv9i*OLowzcv5jxb@*?$eXPoO|%0U_mZt>p`}Q`xs25;@71V?hyFI2OVy}XfcLnJr5bS0gPctud3?}JjeDlSKrvkGXO^6`400v_Es+nNyqBOt6ZdkW#VS2JLE^v4iX1xK7oXnt7JJEjh zGNx;wQBQ!c(n~I$yJ9QacsLa!Lgup4rayeg{OW2wW|?}T|5I?B*z2p?g;2|3Xay>ZM!cZFhBvvZ7H2~obj8C`?kzJqmJ#U9(B7f1Tm;NmzZ zGg4J}wYE5EU)zaeo{mytbrek4f!sU)o>GTeu<0SMMcB9o@e)t{bnAPxk~fZ zWdqb2;;zm^VG@;fSd|?+8L_;2Pl%5?Rl>`(9&|piNknr=BqzI&ShSf+yoQTikD#>% zIVx_T_z2O$6am`_Hp`vMZS{!hf;ho5CW|U?r*X_G*28bZ7Sk;X*^f5iKTeU}N(>cD z63puii7?U4;%LYA*lCvFYEMa_I7JE^n?+j2#3*?S6>K+H?#*n+C3@a?buLAg8+*_u zr?_de9v`QA;6+C4u(kvoM9i;o7VJ!mggNPZ{g8cBPZ`OTnieuq8Yn!GG4a281-SmeA45JX|T&CQ42?zDZu2_3%3(p*$3B zSkOqk?!^PwF^{bw!$&o(akZ~xwCF3cv(!GDmU&x=$MuwFg6%CYc{98nf%#`-IUHzO)q1ve^*komjQZD#tnImDxR!4=Yt=*gVhpOV9TyPAD!iPqED28L!8Zt}ilq$q^;m zBewI%W2<;`n+_l9?=w@tKOJ~7RJi@SgibJgFR}nx8*ZKXLAqNdl8H9GySM1^4_KSg z1rSO0h7F3&c5!YK2{HJN@c!ndqu&!QnF7eGE%1|B`GdqA3mneUs~sNKe$bg|4H$oc z%-sevPWP)je>*pGJJZJi@NatFGs6v;i6~h{m$~273Wwt>qh92YHQ$xN$r^lSHrjT?!NMfuO+ zm$H(>`dfkxf~?Q8>8l5D64qXdz7$U%j7bP)M;Fh1yH?FIe|J@h-3QIl)P~y|4Ueu2 zU&gMl&RCFlahcSdQ3~g$yKK+L93+|${ALxU$6v%^r~+xXblI6D$v=14MRI;~zDLzS z6+3(hk7f^u(=o{8L*8p3>uU2?1XRC8jfO4b8UCA0*dRW}rki<4tH_0}m2+mbbp!O! zYS-?368)BVo5&PWn*C;W7l!ahi5jY}->jKSO?9qq!X|8kQM!yXvenx+CcPSIh1YEL z{&~{E3)#K-+RUHYuEvBvvfqXg!}nSw(YI;}j)^qHt=&DFrOv!gahyMM&k>E+`Pt~i z=0iJfEjEN!CKd^b)<0Wv<|TUTnnKPZE<=66v6ii5gBF!#qTvBBnv4af@7rqq+)@J> zz6F2N;S*dQ9{TBB1|AZZB?!C0?Us{YfyAgy>pt|zwiCM_msCS4#P%{H^i$pwrxT*t zhS&D3`#kkd79d#^{37e+wY~37bdZ!f_Q=Pozi+AJD|&ZdwI);mlHE1+9lrJIm6QFs z0#0fEO;N3*2t?Yt&1Owb$=jd060}%c`>a`!)ttZugZS=&Y17qI>a=uoCu-bBok^$n zY1)%5IiJywJ3M3Wk1qo@`e zC&}0otMS@E(D`1`4fr~mjRaGfe)=_NP5#ima!&T+O zCUGCKA&J4&S89d24jW4E7pjLL<0@?3nLP|CSM>Y^izsgQReDoLwv%}fE{1y-g{`v5 z%8PH|sk_3|e5qaP?gbbDCn~P}oLeL8bm>|X6G9^?_on(*0C3?_x0Dz{NFqJ{Acqw1 z3dYKXT-NB9kTi#h-@Ddq%OeKaSRPOiq=SmB5^8`;@aNM4m=;SFm=q)2%dQ$euAu4R zN>==EXZZ+sD=C`Izr*w9Km`n|KpW-y)cdz}GSNZ3X-ZQsWJ32(eFkzsFC8c^VoJ#S zCzUWJ{74qh!Xss_N5?L)795F=!2Ay$q0|-Fk-y{K;tj|OG>KJ&ps24OCd*6DtW7!# zV_Te;&cIL1Jcst39&3( zOwJi00T#rr$V!C!3V=ij;RAFVol2+QFU~D_yP@+20-%c_pR7nS-LxFZ8-^(y#@d*d zkSVi5PPwr}8lx|HsbCAYf{V%04X-%~>A|lr3^!=8>NGNLj&c(gITB2H10%Ot5T}64 z+wRw>bNYNk*6FwvI^2+J9y_GFVkMLAQ0eEr%8)Xjc4iCZk#o=|!cz&mM~*HJe7dU= zC_@3uoV*GqJg`qOr5!*G;L8_s#d>slP3;C&E?#JB5P55bXORTr>c0>5?dHs_}J{C^wD~S8E@yZeE0zf9ChFN|E4}dn+J^fnaWuRH)(g z)s_+5E8tPk_}mL+p0vOA3__&$Ed|%0dR9C~@AOQd(A{0uE!t3zy!-T1UKtti4$J4` zl28~SUdH;RYML9g5R_=j ze{>D%Ic1_dUZ5)K=Fsh%(L(7$C%kS4ErmQ^5j@~T8(ihl3P2Okn)-1kBDaiubV%H| ztdjJ4jI8Nr8TicK{t2-i-EIbmdm3lKw$Io#otGjQCwfxGAWmMAlYla)I30Q8xrZOH zj?oMPdt{k(w%Pb^Ee1L#nr991eZwGR-A=`&0>OPJH@7@MCex1z)=1g|j;7O_XD0l# zdglmxpEKPB@$kK#amf&ueKvKLyt}_R*=}!8F_?Fh8)J|)LJz0Za(OLN+mZ)vL@7AO z0mp1BNnXwU!5F;?Z2(NuFjB?H)tj3JIwVW0sB{Rp72@sDCai4NW(%1uK}9k z%L*8&VO^8q@V)yoNLb%%VByQCpUHs|+<|5xjW4|84_S+ekT$)V>g}nwb;W6G40f|^ zJ8I>5J!P9H2cgz^Ukw9cAsr(Dwcn|qjZnw4f9{WFRFP2uZs+BR#)iaX9M5QVga2RI*w=X7!t`-(Ilrxfh zz8%M$zV6YkJEF<4{Ib?DXi@s*6i&4`)V+#_WRV(?1=Vc~GAl~Lhu@ssL*l`uQVUFJ zH~=^2M@eHYNz{1u(1n#)LO*#7!b)bwiS8Gog5lDFVd9GnobT9x$q<;XTk1bmb#KX& zh)al$%sXoo22@f7nB1_L<*q8u$_wYyS5&1!ZcpK-XA029^=Y2z+!G*Kp}({4zCH=H znZc*A(?cr_+NXX1A7+2p>VBow*<2j+oq+3uoZGC~5+{V>o(8meU^^D4Yr4NX*lP@L z%a^QtRQo3J#vb5q8?Q#GVaWz4HDWWmDN^sQSLnyKmc2d=Wf8KH?9)O$RDcVRw7+H3 z>m~gUP*jk0j%|`(GMq&a;AdZ$nB~GbaEuP^&1V(1Y4CyAIRpmUtTk~rA4gy%Ky)jy zpW$bN0b&SSyeyJ+XTtBnhH(oD28L~hQrHwksFEldoqyrF=jVmDXP?V1gl3lKc9Hq*dd^JnaqIS-z`EHm+D!G5Y4 zCbKL(@tEpXpBesi6x@%FcwVC}Pb83pDue4rfsu?18Goi^4U2x4BgaG%jo3YJjWr=qD-zs}D!?1wjU26D%+H%zG#);Dw_} zkR7jibEE(AM$=%xFck<3B7O7Cm2-8&)Dn*l2F6iB{aMI>5rX({c*VAyk`_lM+s9fF z(isWC@RM56Q2>S3fGbkX9|JFIJONms5_tLGv%3baHAf-ko>*|Rr4R3}(4uJplnWnt z0sUdh4Ir@+;qP^qJ0{uIjn6|SQAZ4(T6-&FsPH^uIUo30n{J08-hQFBOCqvx#KRcw z0@uxpR6<%FEKzI`WRizUoL;V!o!g~rbm?+E2`h_smTrE3y*Hf)K{>zw&KjQFK4qza z?Lqlx0lhg-0Cl*xi%l!*0TQ$joWL)14~5Onxw4@Jsp>FE<}|!;@JL7I`!>vXo6_F& zXQ4A;>QldA?&|P!$c!JqND`-pvK@2?g3J76da&*QKTmt~^Px_^d ztZye>Pc-I@3t&$v4{`iPkyoO|u`@q}0!;XzNWvta5$2p~&HhWT2}ppH)^&UcBSOcq z!|Ii0#G)$n88%(+lcFNGf#b~sxJ_}J$<`ZGA;{j6e@nhELQQ@BoYn(zYzBESI~t)1 z!aYSbeA*4f(-dAtxkiRezB=F7|1z-jqmAT&A|u37ZS=s)H~YKdS0o{+^HQh2mIhBG z7w=mpT{tI0%)AOOIPm6Ee!%0Iq&QCTs}$o)lC2`zxmNK!pYt^>1Q~Z{9{wr`qPfBZ zQ$R$%t-H*vFx6PW@KYSa^UX)uc6|JjTx+aDG8*Sn%YKlC2qtJWGEU5soJ8eKe<3LZ zGr;e?yxNg-jjA|_6z^P+GpwaC@8<@|NP{bFIimoy;%$5>$~htl^2q3>uIYFU?u*v4 zCkdQ#YC!5^bMh``{mef4Jz<<7^eub8xZ?z4B(;0u)wDgHyC#gD$+(QcqANOV-j@Vl zLmKI=W0B>n3}keo#8m!$)V~9m@UK~XyRIU=A-h@@!VQaS>Ao@u+g9X&R()#7oExae z$ggf=2{AW-Nih(NFW!N;yq^5mO_p@*S&3z!?pOv|C-dG${uv({BnUo-^_Bylຖ?|Aj|*f=MyS0%?tfInp1!1>r~5@Cvg+SzlwDUxe!xlKUBI4DCWD%oXG$I^ zOweFMDK~STO!hcUFJhuVcYi>qe`L_r3tX9=(Rl0#iKT1r zJvj2#1$hJL#nbd?+beOwGqN;w!m8N$0?*sI+57fFvu7POg(d(v_~-Y&e?AseRG>W8 z@>uwsm2T941T)fE{_;D5@wc4PL>sv05521<1{ELz z&rG1V&f&V!<^hcwUeKqu-7JZ?SsVlikRNNKX5qd)5CN(^hYmBpZE=HfJIFS?&MP)q z52-KLE`TnmjUM)YBn-}XK4Tx-X}#FMaC#<#vZ`Rr&1bsM$YxX7^;>nS#W5$6gWtSn zdsr1wb9P$RTEeg?d#40?{?*dY234-Z% z-(L^#yb?&Y74IRB$$PZLu&VSk&`|i6JiPh~cc_|m0VROafv5$YB7m7L9CEUc|YAe2{EAY|0R@!V<` zU@@7wY>D_3&{btGy9o?uB%+x^lyDae?SMk-0=3wZdi8N@URBU$?NOfSjM$w5QWm*g zY6wH2{-P8iQ=^tUp%5hruN!xFA3T6rI8K=`H4ea&!xj=**>ZXglJWX!g*@)+zGn6D zr}FL~h3W$8?qK&Q=sT8Q9yB$=>hNYGAiH?HeRsDPLRWSx-}@;Dba9oy9WD!iSs3m+ z9Uqlny+ZOX@EKh_iN-A52bF9qS6k;O#opzhax`k-3F3x?BrPJ59A7V1Ya^YCFrdF$ z%XjwvZRMHPWX;hOU}h^8u&SYTP&w8!N;cpt(V^W{#2BeU6vrlI{GRYjqLin=v8q4w z2Hai6HT|Fz(~|1U>9VXHg!Gz8W;n6=KOt+P-A-OBC zL}!>^v!O2r9WjBuuiQ;K9l!2I^u&u~JN|Vb&&->C-&T~vHGCHcevVUtT2A%rKkrcn z0o>_c3g~z^`onq|YJ^TP^Q$TE0p;9gBTXZ2goZ`faZ4Le+Tow?7iWRo*Kp5B4N}mc zC!GUnjUqyZZ&pV1f(zO?iPM6UPl4thStxMSaCN@+=#8@O9vC22&>(tGKv|)ZfA^cl z?yX6W{egl%z;8&lN3oD~5mn`=_i===Ml#a6DpiLQ9)*m+A#BTGCDbD2kr+*fiifY@ zm6#AF-(9%3o6Ypnt$V?gPJdFvdsr7$!ADjQYF4=Ausu1ulyJq(VGkSHEr{}nod712 z7S?+gdr#p`CUX`RYMojNWRv+&g;xNekh>8u!o3uK5Y+-I@+*)HbH%*m%A$b z93zsTUe;fq-omoz1&-P76YJW(%n5cQ{rlP+8_i6~8cZZ}eT=7)!cbFiX@Zt-fgx}2Qk7#X~n@hS4YzVcltVd5aV zwE(nz3+Z{))QOgQXUYxt<#CeYx0+juM&*_r`0NO!d2Lih<#Q+uF+yUzdjeE({FX>n zsSCLE19WJAt(-d*H$iZswqX#4(i^y4ogqv`7Fr%PfJtI#TsXAk4R|zGM54Jmx)8Gh zV}fSa<$D#1BMoorD%v^VVNNdZW(*$y>hFV2(c3nJ8uPsU;pG_|bGsbMAvRk)ohbCw z@8QOci?L?GP~Tmz1iN1cCJk8-%LC?=}3t9+EE ze9Kq6Y!Jfck5;aA#C=GL0NGT=Mj&OdBFq?u%Iqj>an|)y-cxqh-m_OX8O3qG%@xEQ z;>dd17x+3da4S=Mip=c^p(rLccHI-TzNCg`tGJZy{MbhyAhADi7u{K#s{n%3>XCiD zTTVB{eJp8Q8&pE&5JnG%`R?wR2nzT-gEuF0Wo})eKQ080)8!)j^qwuM+-4jEVxx$q zw9H$gc#>GZ)IB!SxU5{9k!uj^x``bvh~&-0B;D-V5u1pKa6ME7JzfE19YIFJJIhVa zJQ~*4d{p*Pr0!DX5b?apvQxE)(3hi@08LIRqgc7y*N_&m#ZmH6lE+4_gaR47Z7D&S zVSepb5bDjT)~H-pZ)35%GO~I+G)m0NE@tN`t#Cg$;+grQuK;u<@cOC82<8^FD{% zV{F^Clu_xN$F^>0GTdT@Gq1gKc=-pTmKRZ}{Fmf#0ZzwV&$Tq&9cC)mT8Mdx=xmLz z*j5C)EWW9YNAZZbR4rb#E2={*&F{ekPw#UT5(5)RZ49p1_``zIUW$v%Ga^H1b|$b} zkPg4$Rr5j{t_q@zic!4zo3)4W(L&7i2?k=vM4*5Y=x~QTGN?%uPF~Wk@VK?j-G!a7 zkkM~sa^*9dn6-y^oIxrchu?}+hL}HBs7lIPbYCLrZFCwF>6a2vebYoycARpK3gjYi zo?2=oCu!VN*W#FZbg{u3{%VVRZ|NSZ+P3Y=Xtv^tpIK`P0MQ?M7bLw0eiL}e){bb~ z&2%A%#q^mvPQL1aK@&v=EtruDqn5>wi6Y%B;ZAfWB@X~TP)jg6`Yal~SS}k>j+-?I z7KdBk3K>0b87OR%9;~Ir_+~T53*a)dID%}@+w>n9-sXMV)5%t8Ud5_DYQk(a34v0; zu9Iqu%i4~B?# z5_gFv@m0S><4S$*&l=z`Xs(8zxI z{=Vn6YyFF6CRiz!sm(+JNwhbSY6jIvH}kYMzkFe`sK5apnoG1xo6+h%UmHe*2mtrENU*hc%{WAj9O7-Dl|6 z?n6p0G6#i%`e3S?lZ7s(8_I2CuW*VItc>B^Z+horW1pdo;VRdYaF05aY%?EdCZtwo z1d(`^k2&sRzUgv^Y&Em6o6vn{{N3HQyIgn%0sy3@({zY%^Ttu?12VmbdP6VC2E?u8 zBcJR`JH zO7mv!fdWyWY-Gw*+(I{76Y987YRzkrQp%3=Cym0M06KfVN!mhcQM0x0Mx-FI;O2__ z$MRM>!hL!75yT8q)XOF`9qKRyd<6?z;w)O|tv??w|(06SH-+>it0xl3fzD6o8J`P2h zX8z|>LALRRYxlthQQY2a=60*z?o3oDH?y zz4>mPn`r+)Ac>o_!gfMVczu<%?>){Ut8Px!qXs$`UChh- zszb3JE0suRw-1QXcRw(cIVdw^tUhKYxHO0FJ*Zb|+|oe%ve72)*6qEg2Tc!9Qn6f=6C0Y^hOCEvlFW_8iB*T> zKR+N@?eX-2+lO1t+v*RS-}C2j&(kc1@^mGrUb5yrWL)rUEqIkkp@xgsZ<(My+)HO< zc#~&&Ze`IQM`~y;x5X~0B+?(>BYos)kc_ zb?*^8Ux^-0FK-p4cwa(_L3h`Go%LYKC?T>=x$j`#QM)4>Ni`cf{3aT*)Amw z$Wr2E=W<`D715Vubq2$Z1D*I~B_U|KmZspcu=)A9Y`N%q*fu1XWT<|{CK;)%w8#)Q zb%j6bi0U+N*F$zNxhtuDc8IdL-gDUSJ#oXxcmN7(-P>Xxe^50Qv*T#TZt|XxeDk~h z#1xFkrQ4IQJ$T-Q;5)A)9OI3H8j>&Hd)hnfUYj_Bua8Z;UlK6^(H?M`S#DS&l&mX@ zyW@D;!3S~g4V$Q_TYIXyvpnK7gZ|ls6nGNpu-d1IZanO-VM4;v)9YuCZe=H+Q-;Hc zA6_K8F=3OevY!!KOsWwH5OrsZ#kJNb7QPkzBz+Qw()mJ5c?n_pbM7$>Kg^k!;QZ4| zy0(F8Y}eAuKdBSa0VtIPH07o3oqToLTeEN3i#IR=SjwAIG13Rpw-SXLol26>^23KK zuJ$0iZz}i@X@<^xG&ZmF(iQ;^P$F$63I#G%a6DaQsY>DwP!eYLgmP(Ih}o<5{>56o zH*Pn)vql0_ngMW$@*k_Vk8PUqkZITT^fOOWYuOif`J12Hyr`t%`N~}&kE(ep0aaM9 z(S3q%B(Cnn8J*>oCD{uKn$@u-PN%;hFZX}6x!VyH35ZwVd0nViyDYDr0XYab1_*Vdp;+{7mVw(406?u@UuqJ;zdmL?=F6=bgsK?rqR=(;5dF3=;V{awv z`q-{LkGg@iiJuNnc+BKBy3R|7Z?!445cPoF+tax2;e*!M+NWJdkSL=F5@GeXTu|hC zz_o}ZamYF;d7GNZm68<$Z^>ORmgg>h`>>O5OWi6)Y)@=?-DyA|53XciyP0OA=gD1R zvEv|yf|f1-lvo`qj6w%!zcnLWfyJ%NBuS;@x+1xrVfGkS#mOC7I27ZqcVhdUV0p}y zE)W`Gu3&DyEK2F@Dp$tby}*HNgC(nYqDGFpoZ5dXQ`?5Idllz2gy z$AezGSs^L_*r^`{>8)Gw_MQDRrQSXU@KNoFeSrq*1D>YIW7dl{$4ccGoQg$9I5T{%UJTQFAIPu1L;Kj? z?i**$kyiyZ;sTk^$W{Sv5G0Q7(Nrtn5V>4!XCds5tvyC5CA!}Q$`qRm>YzpS$H1q{ zyzG6YEv$t85IP72r^%5>a5{*LVd znqj%ylgkbliq`~ZoWF7T1(NtCX!L_27sXu?Edq20#qEc!pRV{ZiXf3t-?m(FsYHaL zhG(NFx}+;# zq68#3QO`n#ci^K1159>CvmGWS-vc3FM_gUdL0gnxWr(LZbx&d0Fl3;7Y~N|Td)Uq( zC8E!z_euGJa)&xd4!2AJadJ$mD6GHl(^xQY$~J4&{2^b4XrweX zh$I{#A={IdokdhGI?GiGueu>#{Vhs&QP7(;{j0;PQN#?T>bld&d-jBbS@8$oS!)hy zFAxXHpjntL$FDcv_G>?Yws6ivxE*?U{yB8F2PRwy?R{AiC)1`2Dmxc=ub8IpXAj#! zGasKaxSXf(j38pGK@_oHEB%cj#eNOCV2T;{f_0QzSdoTls1V*PjrTYSwLdjjFe zJY9EDYkx(t%x#;wskOg-zpwT;N*<9;(7-SjTgW&RwLyU}vyM@@C@_d2aMwFfBd8N@ z5c66JK=}b=yRhi;p8V#VtMn^`J44#JW#XxNat7!^P@iajmLBy)jRs-ecuj)$${QnN;1@9Vhlsf#{NyzZf-gJyGoS*MK^Qbo(5X~!EMgYC$Ki8 zQ8};&`g)eLxk2xHYyadUQZw|Ba>*~wa`u$V#3k5{86ru!3ZkeuF>i?7k+AK=-;Yo7 z-o~J8-^=r?o*ZS}t8qGLL?{77{g%Z!at~TV8N9_pBj^EQuN8m$-VGA@h}j zYH4kENP5lMUi@l{nx+}9WqXISttOoTLJ}V~zq~Q>PUgnUTe0+$hr-5#Iy&oey{6Qx zpm>{5^HD9{|9+)KUfeHu^F&SR@g<|eP@cVAo@@sUU?G%}1>?tq`1@0%^LOxB8P5op zLNbCDGKwH79R2Or6*6?IDHb!b z>C^ZLZ2sS#0+qB1pm@=_2R9D_uxT;9PphGMBU*bXTFI8cc4Yk9JL0S$++v2^-4>9k zu^p#Nr_Q$LMPIcG{WGFX8zpUblOjZZ*mEfPtE&074~=j8dDhnt3eZ8lMbEs8- z8ad1@9ghqndP;z-GM_%4jOJ&0XuLjTDFKl`f*4+jvO$OhBS|14#g53(uhwk4!`TC=%IMe?a~i zhO!z8XCueSn${7)!rXk2>TjH1PqlcZ$13TM{AW0h%REAgS#5~HzpY)oXmugzc{6u2 zBI|P``$`k<{0z=}yWZt|5-yuwx1%h~8}#ucsEURbA9w?D#I7gK83*}A0T(i)L-!i5 z(&r1GMQc5Q-Q}gHEZ)Ky4w10MBFh!?5)uU_@l4+Nj2LPD`I{MUOG z!=tV$T~709-dVMsZnp@?=Hx-?MKK|Oe4$C9g1J*FgNAJXH$Zk+dyn9-Ym zKjgKD@!*OXvu|cz!n0*5;wevgUrj@R-2v?~XPraAH&t6Fi%O@Z++hy8pwc|46H!~V z?|dC1puc?M^~IDrQ4VbF7_OG}q%Km0&4}ctWFjKermoV@(_TxB(V@uB09#**1845i z;}ox{X(V0jGWq;zywrYzGhNN{(+S<(a#W}B)TNZT2T^Ju(p2BnmW$G2;4}INW{NO6 z2^x6Di5v;{=H9|Ck-RjI!Y72mBp=w{8-dmzHd#4NUg_oiy5Y=&x4R9S+D@QNw=c6@ z2hx1+;@npO!qiwX?dlO`FXvtgDM`j zr~&Foo5vbpIj#-ft`0@7Tb#}BRPUVff};BInnb1j4eQyR&dcFOi<_Yedxut|F6d2< zeufh9)?l|6^jsE*lJ`>| zkYZYIa+GRQVop)Xtw%8lr$AP4z4ttLC6VAl^o=A-(fAakl#7Rb2~6-itNLAVYDfrD zpE`w(P%=J!bjAamu|pH~j^FI4>S>IPaNj2FBiQwUq8tSIwJMIRS+IJegw2ICR<&V` z7AULJ@w=^LE_b;0*u3B1@IkcJ+W{!ysd}&P9MP2)^TFkxu((9u`~qjB{*=w_sBQ2o zWj%!zD^d`!bB25KQB1fZk{J}_zqZ{#&G}jplY^LY>gC;{&@=c^1kOOD0>~cN@2WnjHZGi2}?1P7uQ%L1|?tSiz zV6A{`X4%4{iJR75fGtOm$<CTTY>Uq5M%jq5#`kh-&-_-SO-9K9!0cz6qsWF(bJDdi=3A1MoZ{qm9Bbx~mZ;_J^8zb`FWWGm>i7D(w^GAaD!A4r?KNtY-D_;LRcaNN$p{ zHjA2kit{n!k!6~1c1Tw*hzvTW;tlaArtP9I1vx@x^V0IGOc+PxTqs1e!W?*U>2Xp^ zMAk0k5SWH_mvx9NR^`c1!rxdC60O9PZXatJfPtDgUNx|!saQH4k7(BKzS5pR?_=@k z-a7%ilX$5-l-yCC^qoodEUqw55rOxS4SL9S!@lzBcjwIa^>4r#c|Bz-;|Ic}@5O?| z-)*lXhKQ_xwi2t{OF?4tQ+4^P8Zp8Y3@;nGb1{Hmy%tmJ&7>J^I?exT~ zyu>Buh`?moo!` z2&R)!_Ha50kylPe_*BADE-yWtZ*BaRRTRNJ!U6A;C}|LdhPiNe!x{Lw`_)0f!WvDF zkLq1$5HJM%iYzP_U1J%wpbbm#4E6k!BX?Itif!$-N$?S=`v zfFT|?Aa@yJgOnzO4#cdL9xBl5_oUMqvbRm)xdvmPTjy0Z0vKAD7b?dkA5r=Cwju_r zuWy&bL>NHtIUO~;C2nPXh;|>RZ6X{kGXDSQdh4htyYFpWdXSnShaN&gK)SmTX{41d>5%Ra zhE4&M7LiWr5O7ElP$?xO1*JPgeb3=;oRrm_dfgVeeG*sCkQB) zv|!I5IbU_KFgte?Tk z+vY9oHgk`l!3yz)4BgEu(=}kA<1fnuh$Hy(hsGN!tzg0t z$rVky>=PkMsBn)B1uc#8g9NBUUp&(m&!>CnpPx#e9n2ZMlNz>l_V#bcRT3Sq{{SC5 zDMNfLK_C8d5!fI=qr_PJY~I^O8jaZd{{h}jxA6#-W@H|4%REY80L0oH+j9WFB2TRD zs6d#j;s=<+ryGb=Vh%I!C6 zHY&s%w3q&<7JmHIN!GevKbGVHMkvKdma#~n*aX}_sRkR;##%4Lq{!+vkb!N5sZE3; zMR`c6sTqcXN#B0ku1>N8cO`7nmq*=0V;WPwnth7VXU1OrXt5`&B;jdfhffl~JUwY2 zDHK92b8LVT5kj6^0b*etcgwn)veRbBOmQ~{#1;PU5xr)(x-oR3Z=STLm1O(f?{sd( zUD0ZD1?k2?d$h4t*AuoWb&rRd$RA0PJJF1LlS#(tJWU@jL?Qv>EdcyaTz>aIYW3s4 zK`pmKZtbC|sH|L~=8A%^*sGkL1y&pU>UB^c6qOj^JcxOgmi8hp{4S<46;95Jx1U5F zoiwxX4!#0a$S1e0f1(yA=+jqM6S*9}#%7t;4OmI4?%6IgC1B_Bl5FGl%`A-$QHPsJ z4l@W=zVRmN@Y|2Yrt5+*yi87AzgQ8+|6k z=r8c3+slRF+ zAS3NhaGoH0ZxQdo8SG7R#fo*?nw(_MHINb1m@{A!jgePV67bLP75x>EMLSa4`}ts$ zPxt5M)D=TIK<9Yzo$p-tF{U6wmsOjm($FS%6-Nxnt&^T}@j&mO$Ly_JDOXkJP z_)Bo1qB%zE83qLtns}FwA^dA!Kx*h2b>91RKOBn~*%5MJkt_+I*cHzzo8h++I(^UK z7SzsVW*(oU)Awr9S9T0WR-9=-U8x!$t8s{JAPNmViT$!jqai9nE4=E#}w6&5pf zqBC?h0c)@IZyKnwB?tn3$4E+Oh)1z=0Z^=inunNc@i&;J@6VAioXvp|-_8e6E;qd@#FgqhP!wL`213j1y9%3k@~=x-&PxWN<%qx&MXm z98iU1%%I7zCG*5Rh@N(<#DpY}4_f}r{WOt@4k45d;iJ|(Dt zDGO`Wn@{TR*3)|Rac5LBkHAhjS}{+7zKg>4GfK4WYqdSxU)wT#bVX0X!p4*?437R* z!%taWOfh%@n3y~E&V2JC=ziWZvdK&K99YU_e)3t4g7u(DVXBVU5wb{++pWwZ>#97t z#`Qf@aDe=Ua^_3=sqU;Pvu7Z-bRNk~J?bmt+=D(jPh`9FF?gw<@eA>ho z@t+}Zp9!#LhQQ#5J+x7=Y$nA4h^#;q0%*>pTx-mM`d}#*SqmUr)?9L>fvs?V`T3eSXUIoYWG@yLEc}l$!g?om18+dw z-$}>4Q_T3YwaJ{n)vfuwCfn~6eeJM4Qm?P~kG|VWf4R+6s#m~*S_)B;f%i?~Yj3!3 zm&6Sc7F|~LzfTgvSSz=D_}<^TIt5QsV~8axHEPgD`V4o*GEcihFnNcj0Q6>eD)ilF ze$+~2*9-=nt%TkR)&m~+4+@nS0_F+!TuQ(@7?Wz%=>{EPpFBLuxOO!f6#+grJM;E0 ze+a1b6_Dqb5jPZfDMBlo8KoG=LtxgBv=uH~5?_YrQmp~u#h4i`NwH9p0EW^@7LdRh zA>VzM>MrHGdqD97KLJNEpwp%DG>R7pWr#AflO#|vuWH;ANTa1AXbDB0KQ6=jjPE!HK1zebpr{qOp=`wpjVHJlHe1Zj;k_*XeuCj z)x8IR2uA*U2oGxk4=7>f)vV}^y65ovG=9VijBF^y7 z6j;TgVNZ#3{1!`rBo)m`;1$lOz^}8Lynt2 zZhQotab^?n*P(us`Q4`^0*q*jXk)0IxaZH!>1KL8nFDXD?y=PInC?fDpa+;_{%!Ri z#&`s{Cz}cawEMMRBdQb6s-nw6ETrmyN1pL+-6Du(_pIxpb4)BUp%X` zmpO#d5E4)m&_>0a(jKs?f1;R30AhbGZk4|~==`@dWOzi6CjCK*1` z^k`j@>BcIm$^h@ri&`-2S>a5QfM6wV?VBTbdJ6iGy}_ecUxyCvkA~An{$vNbZ?c%4 zGie+sXj{}z54_}@Q!a0MIk8hoyKMGII$0<7jBL-F^H5AguV8Y}P@VYUvF&s@_3O|Y zfGqA75p$9pY=SmH(r~nyYhE3r6#hs5*#^E%p-Q0xebqjc8us9tc5!PU4-hEY^O4rN z1|JU<3-cY6U+siDyRP3WBPbeyW8RQdvM-|b-#=XW0}9qZ%(+oMn7n;t8hr8}z8%!v za=2^gXP$^2&w}qpw5Yz~?fyN*0_azP&|a5E9%OT(VKzA>j;zx z)j_3sIq}UO>GAMuU(-ePb5YTg9dagI2LBtnVV$W58n3k>6znsER%%FI;vBMQprgTY5~Eo)+Us-?eo%k?XJ7ohCPI*b9DbfrES-5 zfa}EK@;1VY$Ktta;4L3YYj$RdThq+Hw|y8Sm*N#rtm{#XTx;>a)#y#KqH=LM1xCL5m&s; z$hTfvsiRW1lGo2g{kZ%zD<(ysnhU*8c^8CVk6lXwBeddt(xK7FhFi&XN-8u5Mk`%v@tiwnWL5bXG>qW(by#3 zWixy}mG=#~ck3fLU<~JBJF!N*AA24A^PT1hvF4Yi3MP4Y&%-o%#d$&grEStWpsYU# zXu|86=lvC(blvu_IW$YSNUyJF^5Hv$R2+JOX+^$f$?M5&j43NxJKN6?5y9(b$t%-&`2vtLzP=^Fmi&X zr=>q;6@I{L$0t+IErzHjt8^W{r|7Cszxu-bTq4B}-W*md%5EbVK=-1;m_Yj{Ppn=G z@a80u6UiI}jh_s+xl(E+fqvT~%hwTLI`H;xvLNU;sOmncF8Tsn0x)x&Bu3qDghd1& zX+j!y3eE$22sNwjsEf_a=;p@D)bUR}u)KR>w5F9y}0<<7Y3T zQy{#1>3FY=iF?XPba+!;y#Ae>6U&k816b2n*JHDn1Jm(n&M{odf8XPEX+Abhb@t#j zn+LGj8Nd)=&tFq3(Cu@(8cO>DI$JQ=%>6S!Dih{LrCQW1RtL{9p(gG$doxHpc6{&} zD24zMkTF^MS{sF-bLfxvcV10CJBwXRXKE?d6ddJKeAmxx?_u5){D6pRc7QC9%(_fn z6m1ZR|1pR=x_N;44n0P&FmJ4Z7z_S$v0()SeiBt#^y;=q%;+1stbFy~C?c0lZBrb! z6z+dC1=+0aV7*))ZLA1T2S<+15a!vwg(W}oQ^y|=%LE#@d%4_5@lbbpFRN8Oz z0|4O!;4T2ip+E1}(ZZ5Bf3dXjr0mf6sKsP4XsoqzgAwU#?r(hCUE_%<%V{j@-s? z&&{eJaDPP8vQz0mwYgF|081`t;5 zpI?URBkwLK`eY8i%cgR^Z!q~AE#Zis=H~w&0x?%jt2H56MHUO&FKNIdURPU|zjq~i z+a0inCo9vTM}TFoj1l|9tci|4xcdLHhp{X^$F3P5i+U5u!~`!`)=q?X-#$X-b6i6~ zzqP`7&!choi?aiIGL3GZMAmm;R71kh@Jbbs{^_~Ykm76^0dnBM? zEXu$LI1H++J*H{7;@h)|#1aY+{T=6iIruPu${M)IqeaD_ii)34FSjl(L( zMYA{H&r^m3KWhjo!(z6YZ8}a2=QmD9c|)kl0w}B}Nv|ASZ%7wl{ z3-F`GKruvn%1fW$o-TXHz%Rv()~efd8zczj0V8OIheth?gDjxCQild>cE@9-vI7BruV(z?O3H)JU2g&{X)`JU*L9FY`8Y)Xck*R*6K zbK5lK;w{(j3}3Ek$reUB#~079nb)nB%zelIXvqzdhj&o>b{l{bM1%s6-W#tH<7PBd z@`_BY%W_mUZR`<-SyIMKY%nvckqXiZPeTfJE*azZ{%2(^1Df6G0ebw(x=$wPe3zJC zn+G_O_7Mj_#Q%cI10Ow|f%wbN;k{BHF%eb&i(KIyns)I7K1~kBXI!pauQ^6U)_rKQ zy6m5&gZbeYs5ju_4+QfC*C{9gJxXn)@wJ{OV1a~w#O{l=j4;;Q%i5U|n_%3g8Ig{C zeGWS8pG9oZBr)(F7|(yj(`lR5LrS_qljW;as6S$<8Tp=rMwYx)1JD&HaF7 z2ua?^iI1Of(t_F$EL8<4qu$QgK_rByK&MOVkM1F|w&q+zgW1>L0=_2;0nKF`V8 zDSWz~Xq5pmhl6_n{th%@#SDHxgBM*Q9E|n2DYS{HY+kPsD9hZ0Gok>b#FW#{&37tz zK&^6$S0?lmM4TM?NyBc}Ov^N?CdqtW`qryOCekl_meneKxq3UjRXouH|*jspOr! zYyNXh4#zo!tBEiL-msYwo$@#BM?uwoYm@aFvbV8Rs-E`C>aeSxb_dx~wW$(l+hcQE z4}9Ta{$>3X4A|WAevjsY0&O&=rN-j0)){YuX&e87C77bD9Ux!0I!Iom4rPBJKUa%! zAiVekwS#E0t(6)!EPh(+qDz>;>%g({cSE#7e@3IBrHLp|p$B`|EDVMT0>Ojkre8Ur z@lwRnDaInQ?0Me_EeJrU$gHi=W!607L@OSOzS+cF)~WP+2AV9RKzN3~R%si7&adg6Z1jRp%>71Za6Po8t#(U8`s%o0W#ApaijIWTwf@{P>O5hZEJdL zv;$Xwh&s{14fmVonEvv&Om2%)@JVso=Xwr!fW3a&d7h#6l!T;{oT?u}!c0QIq-c^1 zkIn)z8O*zH;$90_DL^>?6dn4t-PdV97oUB zpIg;rL8JU5Hbktn@?5~B13!sG6|x})*4~5)ofqfBgYt*0q@V7CZE%zSk%|JCCG9(F zDDprwf-$D;`h(8_? zJe_G5F-s#o^Z~8lKPz?MAeMyt|5NRD263Kzn}X~NY}ui?HVTB2EPXMkwzU9pK!9J(8iX@bv{_pY z;L#*5q(Uk8zawJ790!se@GTS<;mw{Z!PJ18v8p8#Eouec+FZs&6gDzBJpBTyxNsn# ziexe(UL^+;s5vg9(;Z+Z5C@_rWz}Sx~VL?G8Ses2x1V?5ApQN+GMx(sC@O4@ew;HYjG}l%ZL_2V5yaeGayf;C0kwr^?zFHQR#$R80A!=?w%F za-c1i&)3}_{TVsQi<3iL-g?id|ILJ9$_=x+b=+(L_h({@QAZN_&3W0An!$TVg3TQ@ zGuPn%hGyYtHynSFPdv>DregF6{m zQ*Kour9!D!4Fvy{^}gu?~3*@qH?bt-g; zTJwKPR3Ro*YHI+R6tFwT>Rw}4&W<6eagEWmr^t2WQ*0j#0=dP3JpbAHsFE_!Nw*ty z&~rlHV}rP#Ep;m|_o^w6C4#585!Hp}r_MLD&ktcmK@>mz@hYvZ;98W3_RQE&-EzU) zX&=|u+pLwCVL_!9q;;xS4K}h)bIvX9HpJ(TN(k>=i_ZIyoD@l|glGee>dlpVTCiqS z8`32Lh-c5U<#zRMm~}(k4BOaYRpZ#t3;Ht)>-xKEhFs<3^}{F+he1L(A7TLJ{V)-3 zv%+!L*3gN&!Cx&5jPmj8(%rq>KbMo10g5=Q3Pqhf!3UfbCn5)AMJ?4^`-qcxI{ptY%(9N%HDFwm# zt}oZ5oVmgaiFp9p@OZlmK z3?!N!Xpr*b-8^AZxk6uEHGHYwqVtkRxyh7Fw(5dLrLXUQVQzWjH`9w&2DH7*^Z&kL z;sIP@!z&%d!vL9WZZKpRF_Dd?`pWWEmt#w0%1Q1W-G^LOjx|lMcC9;TOr82>e+D}^ zq+R^~`(~}%E1F(t&X&d{YgWGjg=f?gjqf8J;0iP)ZMYImBCjSy7<^D$W2f?0)^xto z3>>c%Gz?vvix!z_ zD!~dEY@OBl1z=U8hx1X_uquKI`|Cv&`qsRa8kubc#qJzH$Q2amGs_~8@t+~47GV98 z^e}V(#;tO9c6Xc?30lqRPuM5Meo0Ym14QZ7iGSAxwSLor*CCLP0FB@ubq5}R0dal7 zp6y?|NW}3bNR5*7@1VJIiTx@Z7h&5Eas2NOo^_$`TjeC~FCypC^7I3LvMITC_2w6v z$o+V3V$f-U0302&gYpD&M4*7j4ygu?Y0hfqI>3jmB7%j$JN?3k? zIM&(0wK$XCRE{U-^w`mOE)<7=C#ktzEzIs)!C-^nA7_tOp7$U(Y@;IhqFHZLL`1-& zaj>z6d6(|NU zVGdCdv(YK%dVeJgJe5;v z-T|7y`AoELVv+bRyGWUc{GrQ}Ejy?5dU-gBCQz6?8-I9$h|Oq%gzJE3_KEo+2hrLBVW0@|Ddfcp6UE;^4_t&iSCmYINjH`+ zj^4$RM2JN!z0Z?unVeL--x`4ugz_Ud7h64F-hCjCTDqWKV?@eFQ6u4*mZHYbg&sM6 zX|S`s5)BIryPIx1oUW`ALJNVv6aVl+G#dpw79q6XE)cgF;P+1+Xk31EFMF*~Y%~Yi zi>K|V#yqlpb#bH@*#oQf4!Ur;0$AjYPXzq}vv3S=m`<1PGbBG%fFy(8)w$uiBa5?_wOn=TK~R0!7t}IkF?~QC)eqROeM%ohBp-mI%wsv2r8orzmhUL z^?gD{*b@ygW||AtR0#R+TLxe?DFusYsM25EaJi~9s?D-B-LK`CCe#EDkVFzp{2vGC zMms?F#-KqbL4IlS$P4G`sv=$r$-fe$b|u&Nu+0usp52 zU(W1pSVVuczpU66!D3LZ@l2p7c`OGhAIjx*OTJI;SATBBUFceW5@|pKM`Os&S7A;W zf`%fkJPG2+s+|QTRx-7QX4kpfKQvC*3Q?SH(brK$Ma~Ga-=$#mxpxeLy0<@ItESgZ$97~Q9Hic+u`zjcRj6&x*#=I_W~!iB6gc$oiL zK!zbI`dttiEsG@)X2r}MGXCk&Ncyo}`$Qde#|A_g<>~H%z)N(4k0|1 zmm}Jk!(hwa)H`8YA}u^XP-B3o>cNkFf00Y3yHlgqee^XePB#J2I>4M}4tG#?q>psL zcSHVBQ6hY-7paPpOMt?dUu)&v3_k6@`0j)XUz791SDHpN;f=RClCY{e((oe}d%atV zQ~Z0qoAZx|Yac0hrB>)914QZhP169ANZ%&t>p075jI@u&#eivbF z`LM(HY557lrjOZr|05|XiK&A6sWk#4e1%}5GUACcDn}4Z=+iP=Pq6Xz5IEGDcRBw3 z^Si+*ol`#`&$(%g?xTa5)aVLo%J+AKSsinoTv{R;&;aN+07@iGpgqwWosB{4`@yV3kyZh?%9q%v&Y zI!(3Qhx{GO@f(Lhd8Bj`9_9p0NgX=E%W{*p|CXG<(p#n_0(ol@U&Q!?M5)~PL zg#&WV2HPbu9GuGoyIx2CiIl!_a{XO>8@BF&K0Xp5zYcYi5$0LRnI%h)B@<&h9;BL^$DCe1FGm?cru@BLZ>@T0GE>?XqMZ zcvchsH|a@#6?+yk678d8%K2e7>Z7J76}p}l!l!ZQPlVdx#}rYK z1A)-SuPxv|d4?ncx)}82TU6d!*W02YwLpr^F0;hU%NF z5XE>>KN1U7o80a?H5i5r6jX zZv9E3=dZ+YYwY{(nDGm%-{I&$V~PDZT+V-&;*YzVe&+0tH4X+wC;5-*|2x0s&ZQ=fB z-66lq!v6lzKpA()U0A=N6qgw{fGs%>7&zn)ez;C+F0QxNLTW}jg_*)GzSjscN7To*BtTG&0W&y17~XP8O*f#GLVTEkDIQLWz{uu#hbifw(jig z;(He1sUxb9IOOR+ynuDbnD1 zJ3DmGEelphgsGkETQVa`2_g05@7FRL6v^8xG@zJin||k^RM0el{Pmd~9sggm{qWBJ z!li;xLK`p{B5bpSY#fjg#LQyqnQ620$B{L~31tk{`uKS@kHcrGa6RbV26e#)$Sh^V z_#VT@JYj0(FDGZ@x5maZo10&|O1`n#x?SU4z2Nu%K7@?_GS}fW9%jkRmML5q$g;LR z0E~617+!m{{~_+?mHERwynq4uLc9*Hj~#e(b}2BHL8g=jGtR(I z%rt?84~@Xj?{xlN%wV~!5>}ZnkolLHecX_0G)lZd#;<|eH|T-13Sm|-`adAjpg5P7 znbd=vP?ogHwmcR-_wOW*zfs)Eu+6P(A^VnyPX4&0pTq7I7O_O}#Dbw`o-tk~xgB;Q;x-WpUIKB-Jg z+`CNA4hp)2bNaM?UCyA!sD=)m*N7_rxQ#9G4{VFD~+^~j*?kf zlzThRc}RBE`2U^E@$72u9|FewSXwrRIYNFHir(tF82*!!f{uq*`6u42HiZRkmfCO( zGw`hf&QtpdO#QhPqTPko&YFaRYmaW`#o#f@7==M>)sIu1>?GwaI5E2}p&87|SL&V% zzlSuheyyx#zF8h|zw|bZP+h+DfTGn>m#nkJ44aCviUs>Rm^>D0t9Td?5I`y|DVZ2; z`i$dSORDv&^6GX1w{c=f*&_BfU$lqcFdW=C;}#B^kj4zooAZm8k&#u@PJUcCIb~cn z(=FKB^&;Vh-jD8(3$?hzG5h5QI$LSYR5eAUElsKu^V^1vIW*v30B%XnSP9l_Ra?3SrsAroE8`qazXM>KwWm@ zVRdBa$K#*>-J3r9N_TmFC`EAc)sLptj|;ZnB~u`CnOj(*{3nYCyEBZN1@&b+<;LF5 zX#v)0kHo*1t$KmCP_Vuwo*k@pdXtO(yKueTKRl~(*4-FY!~#CMhf*gsmTIo> z=`&azAx8HY&%1jkAGL{F*v?Qm#$`srb@Tabkj{32q^oc9q~qQCLO)U@`57@5=ROR^ zr%Y1)`?QzOE$kNOA7rI=2M5DSq%-&5&rTYdFwUojK*4!E>p;G|^^_mN7#b|XvIK$b z`?!5GY46|{y~W!eUd%RRXQA5ar_ys1+x!7s(c<^FA)#9$Axu3%9o^rfy1=up6N009 zzZ{lt^QKxU{n=GWW)hJ|Gr~UBFd~26BYU#%3@QiS$G$oBbuVSnzU-lt_`hE&|A<+y z)X>5}^gTGXo+I|RM-lOxlzF6UG=+D==Ho6P`-^TehQTG>V9n?gVCL%f!S}@hi(3cj zRYMOrwPJWN>pxGi6zKonY%HL9RqbPPS9Tux|M!M(O)k%`s-Qnz*`ous=f?4OpTQt_ zm@@2vsb-^@$K0v<&|If4}8 zj#4uI{$2lkFP>budw{{y?>0IODm&J!Y=&c1r+yEGWBfwLx8HTKWAlR>8yt_8znpqU z2H9ixMf7B_xDHEOF~q+p_YpH))_08nPSPy*bZ!#!pJ93IKO~2Awo5&^`n{{0j+wE& ziQ`vIigrcyZ*QCu_$O{Y+Kq+PF``|OBq;Njk9Mv$3=-Eo8S%%4R}my~mxP{;jWZ`#;P^TbEXpmdd*+Q-h!7ib|*b1hQFlf|$gv zv$ZSMY3z)0{Z;@X$SFhRUIf2R3TMj@WRnOu@{TAA_oTDzcAJARL~7Q=ko@(gGQVD? z;b%lkF(EMfQ~6<{M<5w%dasl?Kvw4CS6j5)#f->3VMfNhs!Qfa})y)H(4 zpQ}~3hlF@@cAfpn21jU>LH2w~68huK&OUr0G!CD|HgwB`O;DhX>mVVPJ}uMgUF!r} zI+keiuW(5^^L^^*Wo8OodPe~Ea((+tQLSi;QF_6Qh`PCT8-3u$9oGo-Dk){YwrdXb zOhddu?(iFiUZwZ{U1grIY=&x^EBP&7+$JJ#=Vg`fvr`YnA);CQf2NewEHPZ@?&?Th zoHtSARImA1ac_5U038fnwrez>I}o~Ha*2*WHgBS>DoB4O@<;t{!WhdL_S@M(jNPX& zo$#J&3Wm(~ubf^9`48ls=cCoJ{oRe?*jirQ`j1mjR(LuKwWbBBR9wno1DqR=5DaM#U8P8BB_yX z!hGUw^shf*ZFwpDpI;v@9Qb`9J*(Ai^jNtjW-b{@V zf&g3O^l1O!LOjr`BninX_A+E+o(0@Oj4_U*%c(CYTZ~MjXdcllmkU4hrQqpq1%(@^fmkOqWH% z`#a(K=rh5I-@6MP`hC&(kCu8Oglq-~f6liF0_5!O9|j&%q1$>TkPms1*?J{v@@Xup zr2zTRt+-!~IbI+eCR1(N6pu^7pmFP7R%Y1W%M-4UU#C2Ed6Yb+6S?Bvj-xsJLhg%F zfft9j?8b7ReQkEVr};w`C*?2Hyl8`6TcIG zgJg~qdVcy;ib@G&j##9BFI73MQApDKC8g1thaHYv(|fx1{upix?ZUUTa*eyoVpLGu zUyj~xc^s_trxWu1p@qD7^tp66dkNU+qLB%1 zWwn!os>G2#0p&KKO?TK|nOE8c=IMe1xXifD=Rh6<{IATgxXXMi|HJmjaUyQ>@Y^u` zGM%EH(oZFKS!U{%-4RruOEtM>RDg?e1|DywS1GHW#awj}m;#w1(DWCX5bFS`Z*UIAV4hC__b zh&tZ?vLl34$qS+I3Lpif`4dR^Rk!UhDUGmGW}*m$1cs%+?l#{l1pe!JWYTC)ba8&J z1J<)GV$d507mGyRRQjDO6`-fGi%OtMkz@7QoQMDwEdu|Bl3IyY-t#-=oofD%Vwu`s zswB|}jNr9`_#Btcrl}4CU6Q#ja0OP#Pi{q0|pM-`-lN@Jk1sCIWcn)?Mb@6tG;snVN?`etdqNE{2IgDjOQy zpsF;QC+WwE;rHh%K%C76>x*uqy=Gj7I`hB;-sL+Q+*DMtv0!8(hUjNS}&J_z@)H2pYv4`y78bJavRlZ9{X zgEob`>8$uqk@A!Bm4?-82^-)lnm%Pzm03$N*x;OZu{t~L-)Hgg?YzrBvW-VZ$f`9) zzC}pMh2AgMQ!XvKL2z}nHca+xQNPNV|1N7+$giyQTlZ9YTtL`*eDc$P`ga7Ce<}i* zD|b7gJ_0F!e+aZ>9M5(a1OyznXY12bo4cb*>;>1rYZ%CIf%@y;kGH(aYTbbukPXPF^u&) zIfviot80YK!^(Iz2hS;*5tldbaz|%_0 z-pE6L$K@ruk_G^S%2gmFhQEEYaQf8gf1q&MV%du+5qw^!u^!2QkEGws>w!Ltx){pg zf2nbXnTDl!pXgW}Ivf?Y^bV-Pv4mkUVZSZ(jzrQ|3tJby#XP)eD&I@Ag<+#G`7|Ds z=sDb$grQdEO zdvNdpqqO*Byq=NlR^-bKCP^~P0&{cbJ**@S%_M>`A@0}I1baJLf=};=LjU8N3Rjlv z!DLnFbUXUK^)<|-UNXOA$EXV#u0E5)=IEKuM5q@^+G;gA)GvAHp+D0@<*U4i>ZN7Hxos6??+|1JN z%Iu8gTZGyGCPogGqYwb5YhALVSAszBl#JjNY)@2Ba&M?Og`m;Gvw%r=>$40r#EMVf zx@$sLeo}3*GXN_k>N`G!(9v)9J!nz+533vx#gVaNg0IYDU6yQvu+|YSclpvF(14ew zgmB)c9U`$zmkRI_=iYpY7#V_o1lNm*gQJAaXW#7KFARjUKJjGN69;>(yh0J^p^UNx`Enoh5qYgjaLejS-nf5 zdbM)?)T4Cui%ZTor=Hh^dOm~`>RKS$sgHqqtvP)mJ;DQQk$`h|QA5R`2j7!M<3KT+!8FzMRo$?Wr8i_zGGGghDd3cd> zWcE)G97u9g9PX~h32*=Y>Ch;OGStrEHevl?%jb-Qk23LL1VD7{j$@k$6`;(0F-VqU zSS}I+ADaDLT{Tm3Mw*jW~#9W2fS|ivBCZwnd(PeSCHCf#>k6LByx2wj#~g`GgPG zrO3P$?c+kys5&H^mlr5#Ke_`uLU&DyNg^?)vJvD79JoKNmH|LPldyNBtFnL)cUAAk5?@rvTQJOkHk<+ZcoFZ9_6B_}qrj*o4B8 zqI~f6-p@vo@t+e#>$bQpuwvkAGFlRTgBjSDmv@fw?95T5oaIub2{c{)j91*?m!!sY zcdKQVt>ww=MBQYkedbLV3wC*qsuA6j|LpSO@zAqjXERTAqrIAplu4hM*MVdcv|bbT z5yqV6+(eJqdP5%j5*~}NZp>yi(4W#w(Sd)b6Yg!} zu~-UY*4AjSgu!6>Yb~6HExqhti80J}cAAfJ%`y4WCIsG%Hl?K~oMstEaj}X3~}P!pQ_G`1qzfCRm7jLll0JzBpoDa@_j(=~><5 z-xcj+QNO6C|5*QM&0RicSDniUx_Uq^>TTu#Cr;_@hxvP25r&+EDFW!s%aiq3JQ%Fv zl8z^6UE@E!%g;ag__KHm%s&A*mQ!(cD^RJIyBx9iTN5cYw)x=~r7nc`23#QBR)GxYy z57XMm_CeLUEKmG2*u~%jo?Q&1bRaoOI+Y)4n~uwj7)|0NMN@Zn#?H z?MIyaZwXPn$h!Hzr|Vb?#_6e{Zh!7nDPH(pN5sMztCtGnpqzUZR5pZ_2hR*wIia}6 z?|<@>LbE_7&-9HWIu%Tx3e>s4d*!3cJZnk9AeCy6tRw##v>+O^?|>*U zvPgcVO&w1MkRnD5UI87ubUB5$b)a(8X?FQy`^eJfUABKFNet5=UI>dcm-qM4$!1qG zr%xquS08k41`Vg*YFNO=C*5?T(XEkCO{R-J9Lb{D@0}e;rst}U^bj1;tmMlaSNYX$_0labyI0WES661m? zFyBCO38pSNRTAOy5O`E=mbJ&PQ`ZaYz_lS5=MBPQoDxC^!)om}{nuKrKmq(deFS0G z;4qFZiHleI6W&vOio_xK1nLKTl)57*)1q|;lj(0gi}v1M`PSrY1gif=R;rs+cQg=4 zjW2*9VE1SR)WUi-585^X;pCHhs^B>QTcUIn82#gj-!oQkz@I(}?*-Xq)lV8FsuA{= zi49K7-$4*16&>X_AIKY)W1y)$@>(C!9Y~~J4;0Pp9yrfn)4Uzm2ZX+o+Wq#l07oDd zo24rB_hp0a30NFtYr;PdO%2d*eh= z``vNxxZfDx9pmwz$1%=!uf5hU=A6H|zKy713j5qZJx;fZ+Pp610-ptA%D_XB7d!k6 zrG9qGB{5J@zZ0G8+#1bh4$pXexCJJHS!C<2XYzqJ4Mj@_$VNV*2{cNRI6GGWP*Dj_ zoBgb(4zTxDz@Gr0&pNeId&iXJPo35Y5;6Ncy;4>j`>1CPfT0XpqOZb^A$t&u(JaJx zjksr>b$}j8SL*iAq=q__VX&sWtTWGquXZ4o{~tM`EDB{>)Y#z7REBX+X()}jWuS7p#L1rYQMxyIO(sN{(| zz4$Ww4i@)Kp!LI_k8dww&&4-z^4lDis7}xeO@N+-2HfCzZryYtHtSC|Gx@ai=dAx- zdV)RIl=KZpqW>B9?9JT)J%wliGNzUd)Bgm=Id~2pveA3DN?ENo;F3&o5I&${LYv^R zdCBLp1Hxz3O~QPXGJU2ND~d=txe2h*Nt|YKvSh18FObEIT8Bx>dDoD5>yl`Kx{6_G zK(Ct6($eA$ha3RXggKP3v^C(bxGh* z$?$w15<+DyG+OI<(T$0U3u2dv6|)|mtF;J%b{pNnK=ARL-d7IkP6(WzfzR)>15{_l z00<)c{n-RJ3>^;W_~_zzfkTnlL8XRLIDGu8&+L}cA!|TTNXTp>vayjD&@sgTpG=a= zd^i^nIt_6PY6B^p!D*vkOr{;MOzr1~<40lvjsSZsk^!&XV%!g;;3lyXORL$p+gn$J zKT*8I*0t=o@1I(4Q=>Sr*19+;EW`okSF0V4yMtJLq@211}6HZo+$d;AG7P4klmmV=;-A} zh<378i%6i@6%t|3Ic+ic0$@7r-u%go>QWCWe2&Jlv!cq|K&4u9GP}@de-N6eMIN*Y zAAbVCAY~LmO`RE1!D-c0SlICK=R2#2 znnaYG@bS;agTzQMQ3*}JZzSfW0^pHobo^8Opv1vuYtb;YWnqYb=j9>mxo|FNfkn^@ zv?K9BLZF(2;r-&=h7CSbo&5BMJ^gtQ=cZ!jt7Ir4#2+Z-WE2CnFo$!AgOXT49B^=O z0o`yAJ5fGLPvirWc90_i7wQ;EaI_;^zWrIstXX6ekTxo4+D|qHsDFHQ)Nwxx!xP-0 z4&aj@!G%9UJ}w?^f}KB%#VQ;>wi4+*t?!=HFysU-Wwa zi+aO-%kN@at7%>oRegwsNQM9UVq(e;aucYRM8+srLPcdF@va#kr}y5 z1rYL)+0TJ|iH6Im4#kA%iE^hEfPv^t5=a;2I1N8(IbUZb0eUf8OO=f@K@Vs)1c@QW z1|7bv>V`(0B|w|Od5?|=2MG`z^amkK;Ad!8RlBptND4ex8#bZ@iGHP=L4#t}DT$r| zYLhf<3gP}Ut~)*U35tfSDPS86F=>FdCFPa@B`HD+!aL;qj{qhIPikWPUoF4@lfn2h z|A#{|07hI+VN0KB06Mpd=lVyKKs@>;`yqg8Mdy^uBWXcO)!45Jxv!Z0X)FBj{=&QU zuV6G0zIg7nF;W!HU`wtXfv4$5Ye!C?@min~;FEu;R2=HkA_Hh$3@V~LmX(+TW;3x& z-nXGvs(OTG9+~}@g)PC{&rBf5?CtK=NN5Oo`p)Ha0D!6-Q4Y~Z@uVN$_7_G+jY;RS z(2dU2qK62fPDsfRa{>*krPvJp&Vv86cm@a+uP|7QfuInV>AF+2d)2)T+-jY0{74;v ztV&jEK9a!5Game{mFj>Q=u6@`W$eW>5}AJjEx#!V(V5AYUT_{Fmn9`!6@X*+cZdyb z1Ax8LeR@Hdsr(%P+BKX_#V`0e)gd(XjfpvOH9Bv+`|>AB6ohE^`3``Q_{Hov+7r*- z--rW*fzJqvmx=Jd6S8IU=Zp06+mBI`vwX_&`96=F!&^U}2o*9gRx**lWq>g9859%$ z185|mW36bKPZ5EUz0@?A(BoHs`YKT%EPwzLf_YSfv8JK11L)Ea(*08nEqf4oVb_5U z*ZWl+g~~G2-!Qo6p)?X_J2%Q4(2eJJAv?@4qCx;!K@BE!G4Q7vbm;mh=mC+12XO+Z zexhGcnq#~7H4Q&9R=Vf;p6oEzPvQrPW{!jT`os;4EdXU&}1461QBa}k7 z!|fdK@BT72U^HK8XkZ`KzRJVW^CxZA5yY<`#9m7r8=F(GzO=KV;PK1^>25}M*%djoC_E#*Los% z9q)L+Tc~zbO7e`%zYF@S)xtbjD02OtD4iRMU7qC_{dCSK*1aB2uRT0VTwwI}dP_3u9?puQ{LY?NmJP#Z}@!#Ktt zEApUqVqZT14^^|L|0;%pOoJ&Ggu-6({u3CYi&AD-n$cZs4`?(R5AIsqtK*hM_{9ez zMjLIV7X_$uso()INRb}1AcM)&50Z;PeVsrcmZjwO^zHqJ@)H`VjP`D-Wn=b8(v?{a}Q)07iR<>ZOTYk*N-M!s`kbvf6!hwQ?Tdh+S{z{*rXMHH(mT!brqYh>dA@nuTq}m2Ps^M^^%Go?96O z-PKsXe&1wv3px6>jd-24BUT2jS9#?F0Tx$yJERSr^e6Yy<6y;A2a{tp7`!R=twmjs)CTzJ$-uX$uLY8zzB=jE| zx=%;zcjAu=oTQhRFC#uyq^+kk@q1A|DTw-rzAw<5fD90?y#d7wVlM74Kmtfh*< zK62v{*S3xw(TYq)05>y63&@&(tG!$~MtMD?a!2OFAQhpumD4S~2mEEGza0umgh^BY z^(e{hZ%kBoTXxw$6n}8R9OHz?CG^ts6Mck_sx`*qAmPI?xv>5pO=^5W+-~+m_DOY} zrcTOPEC1v5oh^8-mlmJ{euh^6$Jd_<(#L1;ZD7OeD#-djyuJWpyZ1>^<`8aVxvV3j z1U1E6KT1yG*_9D)M0$C%LXf7JclIaolRh`WZD}xc{`OD2A|MULr8>H~f%p959F>5d zz6~vKs>}ld#oN@ilni`C#+3PT%_i})C|L0WcfR6aNRJ5#|D~K9Aeb*k zuuBGip@wH?i%QO42e6<9Ko`Oz(sfMYAcd$QlKK+-E9w)?&$Jf@pXIBkX7jbJtXn!Q zv;AOyLu3?(L${7ejy_tzlOEzJ&en}9faB-p%kxfM?eO2f`*?PyZ9z4iDT{jUhIy(j z3}_6w5kF=VvoJL`sRzDAARlo}Jx;xJOHH>fAuauj_Dr$HQ=kB%)p!~Ca?$E39*2Ml zfyaMM0MS1gVG9I47Q2zoZ{<_I!ijMN4t<*>2ndkix8@Yye)3{+Z;c?5@^3qTJ70-P zb*chiVj^hKxEOC9wnWxrmU@~9JTB9zg!s!|{XPyfYP%IxsrH#W<(dQ~Aa+=@5k;~1 zw2bKTk|t8$2$Ll=N*PdUhj!l5OYa`%6+<{{*=Ps3Cf|!(3Gk9KMLs`!3rgnXIZaHi z0`%Po@OKr%HsAdHKj$QS*l*Ww{rzTa65Xcd?!BtpS@&AO{@WLVru&(ZkT(*xQUIVA zGFE&|6YfWeF zw&NQf^|3u3y(Cg<`s-wbnRT6XK%>IdYikw$53fq8?em$#hhw#4)5TQzUmi10d33!b zp}N=1*d(dUhL(;BhJ^m)Fx=kT4i530G1+5b6~F+W9x1R#{8EiKre$4YQ7_o#t8>@d zYSW)$+#JRGPXKao`pW1-o!c`a`By@sdsWel-7CtIzxaYWmleLso-H|8VG?r6a5%=Q z;5PcB>4yJZp22yVfPCbrc()+mT=;sCtqce5{nr2g-#4N_eA3F1>Gb@*vCaRB-xon#77?Z?Ffq2U6c6_$f3bu5zpRh* zrGtcAipk5SzJZPZi{JM{{FpX`@gDi`ZA+kNlluxyeZ-|d)KuoQ2z z`&ccmR=Ndk&Mu=Tm9L6NkgUMN97QG-u&;W|M@e}AUUU4r#f;BO z*ppc{Du>em{;AN<*Z`=@x>o;Rbz`ncb(V#JE%Wx^&m!+##>d3 z3R46X#UZ$1DwXd=rp^~G%XCjaa+@1jlxtP;MQ3s5z{9tXkAJic{Cc{ZC?e!>5qNhm zq8?huXuE4&YP<4NKXCHCJslz$W2;U<_t+MAxabE}fBbE$B?9!lcpS#iYh`y9r@_0k zxqTV{bB2o_GefKZXoFi6Tn;TI#GEa6R3L!5I};@ImGg>ki-k&mN9DtY|2o=+&7C*q ziw$)d#&L>VTN4bb?UFgPXM~1hM3q>EH)TYTum12!MTQi+R*5j$Woe7$>(0KPlMo&= zRJ-98QJt#n+R(oFU`IEFLLuU#lv=e?JS{?7!o5xr#{mOwrjUvmCbnGL`+RmhMK8Oq zfLjRoGRN;s*6U4IEWGqQ+enY9)1is+@b*o;8~KT2#w>}@%v}=h{6=M(A->FOA9=dk zgZ$>|7}u3p@MFWBvrL12xs0%`fGeV81o9zZh_Tp4gJ^WLKYXo#&~@ zWS?YWnA*I?i<;=eF1pELeG~?(_2B6OMFi`&pCCThCm{mQiRAYi|0Gt{+3QA1o!Jp~ zS4q&1sxGNlOG~=u}|5D%kGSpA@c5}>yAhY+g(dw z0*xH#C&8B(Ht*#x&LVA(NAZKH3^KKS7pW#g@%%!rxW7WMNM0ujqXKt8`iScFq}7_q zNn3niEeOp?Vhkd94Rm%!6yPg4)b`t@~1IfH@B8R^CRB43u>4^tzvg5i5gi}35Kb@pGM%_ z??)wq5w&(U{^k!9Xe^a?{gf2Xe&2if_7^OT@lP!Nb?yJ|7_ zmmcAuMll)f{?y5?pGvs62ZQ>AF1NWTy%-r@a$(=f5U*NiP$FG;+B%Y7Q8JhGWHlFI znQ8XL#)s3FpK%HYO(!ltYH~3oz+N(HHX@wct)%T~GRq%$y5yho-tBZY^Vi+3q7jd9 zX+clVEEnQPTwjQ%PnHzFgJf8A?hw12_ma=OLe0zP(T#MBN)7HUEyJ+7JKaWFi61n81_5>}-uG_qnhb-`6h3{rFh|DDB)-5#4{jqcW-hJD*K^WK>(S9=!IHYF}-%R#BAd z?2ZBp$ynpS((c#O6fx-gx1tBopxvf2i3w8Ye;E8eO*Q0Dy2+_C#hOA$%=z?}J9HoJ zx5(KCwZBTipqTwZoIU9MCb$;tia(xL7BN5sw)TGjN#9L@cxK|uFG}!;TEP6PN=9l& zIf7B?gN*4UE44!_^vOtOFGhpKpLL>z`s4&AdVE$4MZ@axT42Ms<_X!$e( znoOF(86PN=ZB$Yg1b@70&HX;3J6YiTx`_Q-cv_T|`oIn;(WtF< z0ojt*QCj6vtNbaH<~ins0#;Jtef{2@ciu2L*t=Ri7x7uRFfk zQlpx_tr}m{`Hk~yQ%pBTR7Nu~Cc9mi!HXClI8C7K04X*PSusmO zukgKv)A*z&oBk>&)h`b3W#LA*%o{!^1R1#3GR$beDY5&lJl`zdO<*Mjs9G|ZU~l;y?pRnsH@tQto2e5VVCo08k*_8IhZc6( zRp<}9mIQH=XUwE@Tt__MY%?f6Tq>)idy;Ra#l^VnFC%2oLX3@oRToH>S3ejm+OS7H zUdGLT)DGk(oh)!Q%9)rX$Pcq<7_!Wl|JVpcpMG||kX5w5TeEFTXUx)JdWA^{q^#FO zxEyR>VQ*dg6}rFf4WE7mrW8BpKu`R*knp6ImR3aeVM`3WUO%d!(6T1#c`>1QTQ)JB zR3{BQGK5a?fvL`X)N(MB*=E(z3p*$Om5Ks%z7 zGJ0SjHIPV`V7t`x7?%%?VWIYiNV_F&#BP7~(&*?CB^ht>pqzX6jMg2BSx!jIB>Q=# z{SAnW)YKXbOVg9)RfEqP!&wBL4E^~iaNg`YCe<4;Rz?ie0JScZK_Z7_e*dWDLl22FuX!{TCC=3 zJXQ6b7I#kx-%H?s@EvVb@Bf`tLzG@!AOw?7CBX{|-m`6y3K5&&!NXrR5)^k|Kj1Lx zBN0?AZtp9N5>bwM%prX^QO5@g%erxQG3x|ClIQZy zmq3>el+60*CB~=_iJBe=nhT;5yE`|&*4JP%D#3%(T-4Zp>A^>8CKs=F? zi*t2?&hnhFUaQv%Bo~d_YeR=;g~E1^dOH{;Yq~X*p;$!(WqPIEh=F^JgCn#Y!FaS# z9AIXCXT#qg-JpH`=n*8#Mmf6F;#oX>1=q_SZ24zzuAoQ?6PKeE?Irvy6)?Mr{}s@o zy#+@(RDspIi@idO`yynokusliup-##S3AC$Z+D3pcmZC&ygTW@qxR%x7Iex|r~DGS z_-3)<0%MKK25ayV^_bhT!jncGavHtBT~3v`2XCJ zwe8O8+UeY1qI+`<@subK9fj^`JS&M3KzGFIc_(InzpOgu7F`-E<8$MF`4iiBZEgY& z{Of!typ)JLZMp4{67r!&hBftAT#)d4r%;$OXC%ynI@tX+)?K6<1s@f)(T$6xxW4Xe zqA(AREp^C%khMm+&hZCg4--mpOeJ6j-(Bm)-H-RWt!|ljO=9Ox+;Te&t66}y$OxuE z2SZH7o5|UVu+VEw?Bv8y{dJdL4wj(`(zKt59DUm=)fj7=pqU5?M^Jdz+l}dBjU1b) zSmnK<@{Z~x(!#t@ngiJU&!~-rfW59Akj)4|&NQEg*W4^#Xtgu*a3&VHS zA?)UKAq9ab{a(A@W%VQ7Z=!^JU|yU$XWW+bXra>&o9t=(G<<=(3IA=Hl+>=cCD`+I z(%kXw4f$D$7+|g6?{ley?{{DmrR1s%W@3lmpPOyxr+v(FMohoPeEool+80h zr7i%$oBt*i)b!^^S-NR!G#2Ko@2G?k4Z^-RP!NVhKb=gdkF=6H_P0Z7D2HtRl{jX_ zYfXGoP9obc=b)dSOw;4XjVqF}ovP}DgD<7X-c)P6o5T7}OFyDdRiFy041cSkAb2Nk zxuwr;Pwa~x;+{0Z^%Dh*l-On}q%&Jp*RQx#V+qNtSnI6j+ATtL3}zrEx(HsEia46? zgVf=!#gzHUu~A0?+FMLN6mTdzGDtu3?ov*m%~^Jpu|HDMm!-QKn7PmWO(pZvJNmlK z!NB7=-h;G4hI9$kW$IdpISuA`{W$^dDV@K8c0P_Mda_I==l70@$zqJTNuv4^oo4C{ z_5WED;q-}&2BV_EeFn6qu@)ABr|n>hr3k&R4Z?f z{aX6<3uUa#6uK=#xG#UffRfInry|6~dEmiIKZ20{m8-30tQ`IT`_L+JW;G>&IL48+*)LcRDw+mJLfu&Qx7_g{DfXlZL(pi(AP+167YjQXdGaHU@$X_Q3 zdhyO5&TK+LvyxJM-AZ~t!llfwRX)BT#5Xi9!542^k>3D#lw#0$0&I==D&|=sm~s}N zhNXdPC!?aUi%M66C)ad=@S~eQ;=@n!6d*WEsFvP}LMU}jBVpcRP*H|Fyyz{%wFWrGKV6LpIk;;6Ru znMU&`xUJ@Khj_luA#i|L+#09d8}Q6f@C$Tzv@-fZpr(x#Y6+?9*dCWnr^lGYaHnkU z1%kM%C+Q}GreQIC-iS+wW-^ojaWxHAy$)GZ|JzbHZ~{Zt=Rjp>cqiEdQf=T@tLs*J zC4L&}>}LZ8^rTY2STW}xMBzbNV6wTFw&Xrcj0@bg?+->LhNCmC&?etne0x+Q0zfoi zGtOwc2u^3pXTVa9zX%w|2i6gAfs-#D@5D4)efYf)fMdok2~>-So>^7m>LjfFNa|39 z5%doAHfyuZ>QEe@Jj?ACHt#i#V97V|RZ5MB$!-G4bQ690NFD1E1yWJJh37dD_^AcMwjrMnh@q05G z=yYAYFf?kX@bI)RpskgE1|Q^z%R-Ba%P5&@fxm?S3CVIL*U=-zE|82vRQ||QP46E% znQX&l#`^P*4Q@5|N((SORbhL>)hoJ`PbCIJW^)sZL2dNx`=wI}O&So1Er}*!nJE6> z>NK!dMRgzz#-WM)yl6YWgqcMay^EhQgbqt?3y?5l7F__3mu1S zohkHt{;{w)UmSF%0+)!v<6<#YOuc#(_T6k3ob`4T?GVBRZoY&W$aTY4Avr3dF^5%3G=@&rg@s z{poEp>SuyJ0I!jknh1t=FXDmOk(hW(+Qhe!A-(#@u_c7!bsx@uPpDD%>O#!>mJ6oK ze^Au94>~YqJQAW`ok$i7uVQ09V{DJ4d!ol= z?teCBDO@PP-|pXLMKV~=XjMD@pb-9Den{=^wYC1Pi~@*m5kwS!&~u1=U&!YN@no&=hSpM*^_I;$nBh*?cf zBSFlp5qv=L?4Z36Y}I^dalPJSGNf$`DKDO_9!2rKfDj)Hm63sBK0G(JIQlwwHh395 zJt;OrQ)m+s1`}&pcoY)%Q%Yy&vCNkWhb%~ywQ4g~{*TN6^%~KO2r$r0ED>?=o zG5+mlz7oN=|1h7J!fi99%>#%afrFi#k2^}L#>K_%bIk$=L>@-gAO|-HvOs9**YJqK z@)7MpQP%~k`aWosmW;DVROcfI2x$>BMpc&`u(@l`wQt)3(M8G(pH7j1Ling~=37a*K zLfEOKH6H?Bz({HjVM;1g1}!;;H&YQt+Bq!46NzX(RPRj~%|Rxg&gezD-_9N1{( zat*I7zN83<(bw$o!ZN5j;(RZyfZ z-H&R&`YKo6IfJ2>K+~K1V7WO!p$!`YTN6Vw(!$I)Mw3TxF=qA&CJDVzvC&3U_MY+- zbegJj?I^cr+X{5K8qLN-J@D7G@yyXlt$9@UCX{DsZAzKBb0|ogqzs z%5+l8dkFxUg~5DBWz!>PQf6N3O@D&OWa@K6q51`uy{ceIgO09e^DX8CMGEmr)(v|S z+iV_kkgc2``cj{c2^WX^x9NczWwIZLkC%YLrxup>o_23?11wY~Kje8kFH3%}#Z-Op6Q$Dg3=ksfUJd*Fbv(-bfC#ubKs2=F=q8gFaS;`#W?KFf-$UVH8dYT_oqQ5ri4&yxdn%AGAxr*OZ!;1sB}Dbs-}9M(h^E<+&tKwn0|cA&=^ zo_6JEGNm0)f{k#jE&**_d|f}o0@+%+#ZD5(tM*3}jXt66*Y^(QF@vRC-<)UC#H;Mq zz3UUpmytoTUiex}W1KQ}l{kpUOsTAx)yA#=`fEyPIKyq+kxG;G6Wh0~{r}AY{)fkx~Z&j4jHkzmnz0vP|!fPn9&CHc%R~{V`OO#i7k@gCJP~>{6XH zo|k`~F5RRX4tl=X_bjtIWxTg9wLQR+ljUNXIve?FWsqqNXi{fuj$lDn(Vje{82Y)v z<;Rd-p`awTAiLybcb!cScP)$v`osN&0sB}RTRCvGg>E!5WGnT(hQ*%I@+Po{q$G9SLH$kR}iMcZV zlN622j3hw#O9T8jeo<2$?G3tkx|!#KPW2Ty)HR)HejxamYi-Bg$*%gtzVT}g;uRs!3=K@FNS+SV5+UA%RY{F&-oP%&Vc5pqpzF@quQz=&h#fouE&PIpfo0#Wspvfn9UD>^pxr>4JLT+GOMMD4rlS9 zC?*BC7%h>Nfz?}VMFcz!Ij`T&Q!~5A{3|`=4g>q2aj47S^%4P~=-2SH&%nuVJ+_yN zXQ_VATMs(VX3E#aF=b^$%hyeolcRXdXre&{Bajn9ziC*_2D!23(1nC~Vdl_C`VlIT zkeI63)E`pIKH+V0kW!VIlmv%8mhu7!&j21cNUn@(Ezhave_t-54YQkDzm(y6Yf?rz z4irRhG}9B!MhZ1Arf{N-U(auB2o4B&#cW2j_`Gj6*gGKF#=47dS&sYWO@P=ld-H9Z zwb_9$R1Mz91mKELTZ_c2jdxW5pfK_u62^;9ojdfVY+ z=qnT4K3K)iIW!@<`XQk-E4WVAdtHk~{@Xepnz?R*uau**Nytk5~P5Od5VC0&R*?-5P}RJQi#Q z1q?<;GhV3d3hBXs`;Svl@phKR9N2r`ymr@W~2B(L!Sv<|8d!D1S_rCaz z=FSgb@HZD57w5%V)(vHe&HuK^h)}(#lE7dNs^mzCxwh#1sHHZP*j)g&7>wr+TGS9* z_BXv^Kn)PNsY|ta#*5nV;m>C1eBJ)b>&A!dOw}bOv+hUiqQpmi0*H~L<@a$rje_rg zL@F}NPTvfud9xd|6|)dejjs=M?O0Gry)s!NX?8y#xc_k7jCaly_c{~P`3w|sXb}5R z1p_<@TRDM|5<+{?w};Lppu@~7ywmNEMCm1@%47(~T){4Z?}28&StBxRZ41HmRuQ9D zeHmR5&7gua@=at=*L{LlVjL*0@PlW=s?E?&J)rW30 zM??k&V*YaKCfV;NzK%Qmbz6#p5vgyk&)TlYMQA5mcgAR zsf4D@YG)g?46*^TBEf#&{R3Ury7CN3XwZubC!&xJSuv9MjP)aDKH#``@^@9Q*rj-V^ z%%G!YG0^(X*FZPQqf`L#zVQGCmL>tPfae3@wvnb|hQU`_lUZh)k5%)ndZl@O`SJGx{VN%+q;v%ez!!gG zznG^X?kWUOAOh}pWSTY;iGtXlOH5^PkYkW%LVCw^m-20mon!z00e5__o&O*hR^OFM^vS>dtwB6oNdATA}&*W3FmQFJ^TLL0dGSSyY!x`oP^YG^tA1|JD#Mk@M9_9;)4h>l*g!JU_%V*u*25)mq+@IDza_ zkAf3L!;^2$CXA>6mIe%2TNb=0*nOESM;ISZ!%+3XcMLs)O)WI#^NQH*>}bj^v?Ixi zfm$CE8nx1b&Fv{l53Zk#t_kOK4QgpjVEXMb#7hNT5p|d~nnIeZb^HORbMn0C(Bb)H z((Kr+d@&sWm59nvGSL`TR&ba5Nee)NKRm&1b(WqFqTQk_d^MSwG|rVP?ez6#&nt4M zT`XZIZ{ExOz^*ERqOGgWA!nP-*-Aha*umro_#c9#qJ$h#mAZqqo&tg1dyz%DzollB zs0_e9&ZY}rkpcLb>Myf;Qk91)d(^yTCh^iAQ+C1*eKBGFvrvVeUVW?ENk%OMS4r<& zC~ZM?P_y<@=pL?N$8o_K(x-{qp~uj9?qzc1=xj-5il27o6`Kwkihy0I&-2V8bovZXnwO>e@iJalqQj~`C7vz#*N_X@_)0%k6A)sq` z$kzYM`GAvI4g3LYhf4mm2RGC9adgB?H@^DaY2{2afPOMc6HngJpk;sTq91VbURM4X zBGWCpK`7qJ@R-VFBL#p+xJ3lQh_SGMDh6!Sj&;~sX`Ya-dO-$$A*F*M7#sv6yBaSw z_h_bJ;s$&`ii*4g3&n~`N$}-h4CJ@#{^+W`V2-?GcGD*WB;+3g0sx4F@Dw>Yi4zRq}0=QG_?UnhIYW|8v1M-IOZ&dSVw0JDH&GIX;adTu5-L;orzB4J5DSO z1-xVMK4oyH!WiGy7ey7b(+wK^Y9jbUXYi6w=jdMVv~!65kyS8X%~=e(hh(a)o9@7PL2;bu2;TTT4BVm01#rEnf*Ky zM6BjNa-Ry?J(cXiBCEq1tc0YUpB1kFZIPNaen$E4CaZ7mgL-+4*MfesnnMHywCZ8% zeQ+jL_ZL1j6yC#R6D>>FxK4ipcNc`B}Q84Pf?`hwvGH|@nMHjO2_ zkoy;^8^BcKDiZCi?SgzkFp|wyPB8N1wzJz#vEL9h8aE0jSd&|>u2B&(UN1%wwIS1pcT6yRHo7XI&P@`6p zLg2%IIt~Yd)EK2D6mq{44|~t9Tfk$RCGzoPdsM1J(@rTd>@w+b$*|5=p&O6=>XYDh z8tgl}PDvYO<@3aqmP@J|gt7pjVwo!SCAV6cn9`_rWZ)J zpDPA#FDCW*_VLuVhUok5%J-xGK~I9OSs37li;>fW{daZW;s-Q-_%W~tIP59peogng zldB?0-H$W|_(pnQ=sk3=xJig!s#6zI>@;<#(I{t?e)v4dmm)&=H$e}*H~=+CcKZu5 zJbF>h^+Lh#oQ~%et(S5$bfB21;5Zgol$eHmHw>&eI(?ejj>qN6P3#(!^sp{&aXfv| zQv+`uK7X*&M5*F%2)`zBM)|12BhhfWQ;l6TtQYPrbg5pE_SjOXas`j{Dm1*5gb3me zs5F6cCdq?ovRtR2H1`N4R3=NCqhRU@U7`IS=)jolKXgD#Y9tL<*ki?{GHqK=4}e*S z++rJJ)Ne%4WPXzsPDJ0XLV zYgS9*6Innce&prdU8|H!Y8Z9RtQ(6KV27W@;b0KucxTC*-j47ZXyWSk&chhws&7yr zy+Vp&o*(udjOG&@p_mb3rUPkO4FN7M@XDWkdq)O#UjI$I#~L96L`@D$WH#;k5Q8>f z=BWZvcPMyQsMqc04u6lPKhc8So3TYEQo!j3o*Y+GLadv6hYwasrcDiu?Y*mH>5u1j z45ZwCtaXx#izumII4hDXicpynNZxQ9cY$)pj1>uOT&Vk&(Gvp`qMffq<3y!70aqWq zQ&A>d7M;o(7oAm9LxpRugE8R*|7I^Ic_Rv2&)C8&9Zo<9+M3D~I~?WCE~#5AOOyq&An@tKg(`6XyiW@E^(U2o;y)|Di()5Q^ubpuw5P)% zHq(`kSbNmya%A|XXz%04^Tg^D9Uxl)GF;*mlrIJCmvDE*5v=?fqEuU)$|w^roZ~a5 zJJh*kvsOcxmh3gH!b%qrA;qfO-x34^M+|BViit+Zc~u_#L`9!v-~5p?a*52FU<>M1 zh0h~J$R_^TAQVQ+5eQ2wTn1r4*zP_YT11`)Rp!P^m0j#<4-~Nc0W>$aj z-#PwoDYaBE=zEf6qcF0sWe(|WVt?}@JNpSZMqeFiYNGs&y}2>#x8>JkpLg`oDU_-w7~Fy^Az3$dDO`MB^}wm}POA$|~#J`#f$e#|Mz8`Ju(@0+X0G z^rb4n+rt~OI1>%DiKb9_w0KT#JBK%_lH9bLgfp*?@6s8>1eq3cxx~nRigusjOmOry zvL(ScJ(3AhVu1r1 z`FRNeA0Mxztk>*GUe9t#p)Y zwk9MEcCY5-t$vLnxLEfYdr)I3b&JxY@V5L;pF(jnth#?T@GwR+0~nDy(@9Qn0HSwE zJ4dd+UE@o50?MP!AZ!nc_u}#S-HE$$cpR1_AxMfyFZSx&5NU^nqVnl)k4=Jk4vzUN zgPyp<;_+wU99LCyb?yhRuAPJSHiI4Bqg+qe56mAVczc|6hecq(uP0qyZM%AAM!~*? z)p8M5O&pkH0)*Mk%-|%@@$LZV>vV&oB4ZZDJ~PBv%Whtg0c+{0Qgb;-p)oeNZqEZs zwE+OPpfn0qD^LpB^{13tERZV7!1qfHtOv|GQYsged=RPdq`mzsAi_Vzk}emE_Rkt& z-W+s53;NOC@wZ9Nb`8lyD_W3ZN?PbgtnLU^o-+HsVs5uyV?Ybg5RY7c+lfZ}d8$ML z_j(bl7P!VT z54-1Fscl6KYyEXDBh_8X#vjIxln7-M03*rPGo=)AAiN%mlW~?GrTSf){gn|YUFs&? zdWXgV2KA17^B^CV`EAwi^A0@~Hg~V>2H(Z_$S~rDa!(P}5@c zbMTFu%f;WGNE%K)FVZx4G4sHhX-!Qp9yO5Soay#kqN~B@i`4^PD>;{d+^l6~>_}bd zACwPzqiqb`h(G3))Lu*A7+;h>?os}#)3h*=j8{(VsIkT%!d;pD92nSCW4#b)z>dx_ zNl-P^S>~I%0j2ogSKCZrV^d=-V3`z@b&S82Q$F zZF1fruN9rev)treBW%7|{@EznTptiWV0KX7p`yh-LyPO&r$0KHS8kqh9fsnAU#nN8 za>7D94bcO~BI^FD1t7Hd4d~p*Gft^mDz`2%6+LTQE;KaYfhOT4t{AcL8_ZS#brU%|>4my5s-50RHs2Uz<9xeMJP+Ec#lBtNitfYgDTA(%cg< z;H%VOdFp~;&q9dCj*(c81)sLXYT~K^TMi*G!)&a(ySM37|63SQ?MRN(SfL@yrUKn{ zU?QWlnV#2vsdr|d_c+hGdfRTO>Hlf(yMvnQx_1Q;38D}>NDHAz6GCr-^d=x(Is}j= zN|#=w1%Xf$=^)ZOh=mSH=)G6zMLI|?!ac$F_v-t7-`sm=?%cV5+@F(iLgr+jUDjUf zd7ib-4p~tA3~PRUI000$H95<+)ZpX#4Ua`u4IQ!{MMmk;rIMW@FtfKGgy9VIF*pKW z6_J=hS_p77qip}AV4XY7oG-atQorU-OyWIylzekHw#x^F;)(p1KJ1LC)Q?22>bq_} zAJdMKd-Zku#@9&nvR(nXQTa3b8VrxYqNlrhcVI>udfjQZit0`k!3{Jn+*3 zX>)FB#7<`17rwdJnoOFa#peb%fdo=`aX#*L+G0_lksali5(BkweAfHfDJK$8s9$^^K^qj$b@pN#%5WbOc+n`$Y_6>2SND$`apmOm#hp!?b$>Ag zhF5m?!&fd~coi&@5t#%;n+PHQCagQCz%TB=cBaXvFYnh@sX9T0?x)(s>fB0-<$_*% zxUJe#eh>U4M41NJOuFze)J02n-#YA$8vPm`)pI@c_^@W%c$Rkz$$Z!Exl#F^?~|!B zDrJT(lXj+P5#8Ffiot=sCuK?Y{Mk$S&0$3=C|l!r`!BNZIwys2ev}(x{6N{ z!Ym4w1xc$kvrIJ%x8-aGD{SV0pN+<=r~7L^`n3>MywAFOUgHFqqck#lTgVeQ(RBXX z@(y+)F&vpJm~qiKpT1w-Xz{I&aIqnx(RODzsn5v$EPdW`ZnBAue6pyCEs|syV|Wf&DJ1WQ1-y(>8X61qU0gdS6!Ib3&A!#Q+8H@Yx6W{ROQvwJ>sfJkxg)5Ulw_~&XMSHWZxv#HN~ENd?)w#$_1MZt zzE$p9OLQ0mWozXd1=M>KIX?(6RcZ{9ALXxv_!03t-TLLfov@ysOJI>$# z?j>)()pQ{#c0^KomA9;{6W>#_*!`V3#{Fw0G>@{lb?;_)40K1WJFQ${-M_|IUA^lE ztFQ+SmLRtt`9PY@d88(=5Y-u{QE%{&pScMokrJ)x@*R&AWuTdsHCizUG*kdD5l1^Gn-qd z?0BzRYeL43H9}kh%+r+kE1dbf_l{t=OYQH@Yelg0kp&W4YXxEhZ#~>oz))p&;X4O0 z7I&SH8`DNNc#D_t)-@>&{6xxhmc)j0XgG{MJ{l-ff;1O=4G05;`Vn!GF^igOyV9_B$d)5c!_9t7UYmP-KLW!K!N z30r6j#$+vDc(+>PZqkKkP~|~ArZ|jpaS2qAj<-=3Hl4!%`C9O`+z2&sx>QvTHVOQF zTz*mH*UvVO4CC%b5n_i7?c^JmoMn#?jf<)u(1j8f1rCr=4CFq|glhh5+P7ZGJzY<>d&+p!2#qVyB8=_Jz@MM-%AeADixL zNJEN-hW*;i6)(NV0_S8q5!(rY86NlidjsQ5@9DjJbWWAn__l07%e94t;{&SaA(hTS z32MkzAiDekwZZry6q#}&GeTM8;#~W5+kX2y%Mss7u5B~I?_s58y5;_rWp>>F5D%Hz zP$yUq0meu#CDdAY`6`X3KL!~7p&46%Iph@sRg2E zBEBJkpgC&^h7azUpJof23erFtam5BwFFF~u4#u$`BvexkkQJj27>V{rGnjgYl7rbK z*m4^jx6ZG|^6hDkD8KHcsBfm$5*V1ve`9fM5)?n5)3f5xeEPh9-l*C^spoimo&R1) zfso-f-XQXl3$0~LV}HMuEfZq6(HDxdTtlp6w@N_?)SgrWC`sr#IyhnxR($wGzrDxe zALVCB^w4;Ho-BE7jGywuU0%rJ9R^>oY)X;Vk5-GaDRyO#5AF~b_dlY=5Z>>QNfvvq z_WaB13{gkkmDXmVlk>NHX53^2>9;vs!IYJ*ntZR4gXUa+BFty_1=xYN|`J4U}K^X-2i$(WnT@NCQO_Kx~i}PNN8aP-j z`$3~!eI-wixl5;2;2fbq_i0Z=na7em`=c_N5M)|&ywApdPqRu& zWMfOunH&NPS-dSo1Xhy$in>8{AsF12|*A6{sCLydP0$2#pIPTI2aiVE^@Tw*)%o`eQBJFs{M##tFm{ zO>9{7-iUfvyoD2-4uZw}ROdBz-QW@GE?;hdJ)oX4v`nPB=dK;fVd=80v{H8rFPnPn z8y6nWnsuX5btpL6_WXxSRe3JeGeXGHcJSEIed>Uij!Xie#N)~OBYxe;)5B?B=+klf zldX>7r+t#)&Z-<*<=0f68g8@S^(BQd%(hfbg^NgbMy`D}OFQYTz@XkEk8v+wTZXo# z3KfwS-(vGu3}me|0KxY44~NC$@EC+*wB&|n+hWAD5EQT&lHJAz8%%Jt=y^DpJZ5Ahq*Vtuw85=RP{|HMs3?}bIZsf(>cLQ&~xff9F zB}oLI^Cr06k&V~9^?Vaz9CSk7yQ2S^EtS@?`{zr}y27lO$<$S-Vl=%Bt{NhN*A^sA z98Gx#ta6PIgYNC9C0req& zfNGFV=nt6+ggT#|KYV^ghDp%ElZ8Fk-YWHK^DR_ z$$9~;zNs;@lR!b{AoAzFJZ`k0GjWW8=`VLsTvcAdexIM@KM=?AV!BfC5D3$eboU|6 z(8>EyNyrR`C-!q{>O_LwSXNRIsUbo4?G~w&6v!Cod)jC=i%s0t{HiO;H2qo^_cFuD zR}u&FF37Pu4YRk3^giA3C@5B-p9!>-?HqJxb8g8=(*)0$hl=+ZzRK*i>xI|SdksDt zkQ=EF1riX!uFvvB03tLAhKn74mtxnD@zFn|3T7L5O81JjneC(g!n9O7f`ZHDgg4pwp6b8YHAWI~u7V&XE#0rYMSAql(IGC{|Fn%z3p+ynnh;-I~Cd zvYAMH`tvyps^a!pO(fPNgUN{qc@Vk4mtFo-kXuJ~JK#`!dK|9-JA)qpQ)aI|dyQy6 z8{?^1`vSP?*nyCX93RD*(aQG0p%ib$Jfu{ro5HD0n|*YKW{o7%jP#@vZO5Gtv3@I~ zSp;Ub485CiOf#sC#jFV2#_Pb`el@`qmqc$nQ>Ob6rq1t264!ydrhYLrHwD8pvD?$l za-xktCe*zXCac|%)qI}gv?qoO+njf$->i&unWn87C`Z$JTv+O&u^tf;?F0iej(dXn z|FNTiQfZ3b|QUtAyB!0AP^M36|tj=@|PzBmNk)pNQmxrf1_byRQ{s)(7gM z9%tkhFPECOQ;QycQek5^tfk1)U}&C-9oU}OPs$z1Cp(}K{S&_4q7n+-syc$oEq!=Y zIm?WNxAF3%$aDTxq!?WCt&)b;|r(4I)cBe&mg`~#m>JmSReWafKYxqRvo zQTXNn>B>N6uNnTaDfU^5%7_zxt{Tl%In^NwSR~Co+1=s*x)iIq=FlM0X-%1ZTt>+c za>M%d%FmKTJu!3#PkhOHF=$&N*BsBG%-t0WFf`28EJFB-d13ZjFzE*ml8;s26nlAy zao4DdlKmO%>F_(P@4O~>o8K;^j@j^oolj|EDL;628*k;X`W0N)UI~wP?-)*(s#mMn zKc!~uHg6a`-vF=GJ}2luGt2IjD={S+qQZ|l3=5A>7p$k)h*F3k$&6M(`G7{GhV-r#wk%%MR-!`nxS9~iN zIe5%!CV#lqSExd=N5zd%Ah6N!MrK~Ez+FHZNeq%2>gi@nhXe@IySTQ%IbH-ZpfuTx zsRF9_m35gI^;MLUF}La+{9(rS@O%n`^z0w?6%BhHhB4^?sPYGU>a09XKW; z4-j;gp6OL{6F%k$sx8Qd_)L!8SslUSV~dr(SO31J$)q9Kf}GojX}FUz6rqU6_NX!% z8Odt#(#j_bcexp1RP@nr$>yF!!OTHba#$(Dif5zskApv@ z%a(WFiQ) z7Qc62h^;NyKroO%2c%?qY6@#3XOig}JWQE8ln;`NC- z^LI4Q1{W#?U02C?brOV%-IQee4P&$Brn4%~!?$a_ms5?T9?r5qL_~LzQaIJXAtN7e ze~zMaQVjKd3;<$lW1}iw5WWK?3lqBI+6AMrEAky7_Lrb}QDUxfDG89y z3E-QlDI1ND#;og%1UzaMYyR;*IFIlHZvcx_`Vvi%kLQkENCOOv`JP1LGTsnnMj@`K zJ+P2rIN!@y9{yIK4CRp2)G}^}e3G2u%On|YoNSD=IjcM>JG+Vj%$$Yf6j6&$~ytpgnZ~^DJ zf8414XB+EIy&6i!8%tkDSTm%GJ6Lxa?Y@-QZ}d`1p9mI^y3tD?O_%qy^|80fgH#aF z^J=?sB`uh-7({z|b*=>+#}-~XqS6SVOr&PS%7_uZfa|K43u+~NY3t=@b7+=Ag0$uB zTDNP=DCd3J5OPI=wLS);N17OM)%+f$wvn`Vte z-c+JgXtxK<``12NszfX*X0&8+geeFCMfs@`;V2`bGdO^QpN7K$c^SzD%hK#3jp7{k zAL;qAC^Fl^Ix$O_&$p2oL|Q40$a`3F6KR*4b3vnth-Oc8RkpEFlTIxNt-ljNlFz1L zMFB$-9I%EANZyf{Wn1x8J$Ey!zZ5F?aN7G+mm|?av6TQrjvGFg&GEvUwVE+i*asSC z{!}`YN_WHxm`dGhcV^)O+6d|nrnS>&tg{j}Yw|yD>+C9hLa@=$qo}lNWDo6fT5b@- zDcN9+BwIevtJ@20(@}*al?+l#aW~>Vy3MmfWzP-)#?tcyne*O|0s7dvp~hsH46=IC zH66{XhRIRPyTy$YGX~waePI+M!4NmN5l!FaqUS94W-l)l1j~sPXSmIhc@%A?5vM%oKGR}gYhR|DGikReqvRwohHPXexI5IF{P_GARhNCr5?%qC1s zkwKRsX5-;!8w$hMI;glX)`GdtO5<;&aCjc(d#C0Dne*fXt;cP`91p1s1e7e@0yUvb zypU!<3eIdb!~o6>k?m?Xw%N&w5dO;WwG-(bq8Sl?YgF)AVKG=kjk_NrqmgZI!cnvc3;qLBMIFX;LymDo{#W_%jdTC;iXd(l}{js{jAQ#p! zc`P=TVowd~yu^Fik;P!5WC8}s1RMzT(U4&Eea?dSxC&73{a}@ZrL|JfiO(5zdJ5dmTIOZ9`3jU0G0pX(fW(puig# z1Ni>-u$X`t0A2dsz%(U+x94*ndulc}QD}KC0_*Fn^Ddx8Wd*ZXs`~Tbi9NJ~fnwEMvLXSA^0#4|fi!M!^R>&nNrP_u57xuVowMH;a|SiRW6T z^UhVaF;o<|);=ueXN`M7Za)sETNB0jm~O3}u{+)2>SSPRFHv9?J(^EneY>BqnapS3 z$!mC|8yI&VBD;xieUBJ^^qt;+o3X+B$|jm^R0jeKU>44Boe^z+ z0zu?2=rL3o8Zs18zmtqF+{CJg+{flTS)zQ{y z*xq#tThht4GQ!&$Q#`eMHAg#H11V}7EV<4D ze-OPO$gnL6*e3<}(=RXoBm!%Eqa1B*UZf0UDuDIt;lvZeZSv-YqoFcidpD=&YY0iW zi4PjbsKda3h6&I{uP^wW2W~$WKque(aA5`m$p#u{RPh$`>Z^5rU!8_a$Pl4dk1;0LQLj zN$|iin?iuRAw;*^k$muDC8>(P#T#tA;DY@#*Pp|_NT!d^w3Q~DfA;E0hZ0gK zi|pyF`Os3=740S)SD!>S2HSa-J_7N7emX6Y`eQ$uL&}B&WzMOkf8zms3(aYyBOKg* zJ^_jsPIzPmh8*%4gxYOR>ssSwd4wF6MBhB1$qb5r8sO9WK>95OpL?->rx7vyfX#F@ zC+pRAkNCyRE~c^R34%sGClI2u8~lMuLqZwSOss&E0&>FSSEnQz_MQV-$0;zGK@dLL zy0;RK3OLMFAMf@A6ES z_L`HW%!>z%r8Y}AnGX`Tg*bECjCC#IKgdq4Q|#9tQVL_xd+n|D60gMCySQ9nxUEZF zxk3R}ke1M7l@2=yKG*$WusAz?EP{r|2?RV2OK>!}EQsx87|CKALF4X8u{sPQOO8Hz zRTFKbIk>WMUFI*Q^4{TZrUFPP)yX=;)RT#l1)jUyv#O9K3#%O?Li;qpXKa?wrKHMS z`o|sii+)N%96%}yxt~k)1N)Nu$TwsXlzU!)Q<@xpF4<+O$whqH6!Y5%W5!}b)kJfN z&?Ha2i>$$VjAA#gCOJ3DG5t9S>(PGHSwgX@%@I*B@^lp{ka7BHK)gdM`|io7XD_I9 z`>nq)mb9~jAxnwEpY|fCw$#2V$Eb?;!xe$tsR1r5W(8(!F~I&%mx0r$cz9kBv2yRp zyVRZ%1DK|5Kd6Pj=d>ptNFbw9V>Nc#(H;us}myVTb(y$o>Wa|LDfl)r}z>A(FoCH4w zh%C3@IA30930v%-9V3yi8YP>iKxRXDymfyy;3id4I=yAk0Bs)F7BGkx5QLMY4;t%K1rKm`7b7wdaktZf--4}Zm;TbF@L`6 zb`YH=^FZ+k1_u}@U`LPJy;7)oRffumG*5uHs8F+ zudTK8o#AO^tsFo8q7(}4M~Vcna-YpHQg8r8R*mmMuR0t~T?K$I zenNjXY8~bs^=U>&m?!(`5I0&{)3hB2ksY$j0VOztlHpu2;b{+=Y`#IKv`;STc~v^^Q~t<*5@onbJ`nV+!&&yh*f>X- zoJC`@+DB6)+fJs$gjm&;A}S8bEMZKGGtsPxG3pqZxg6xRduSXexJTib`vANW&(LIP z$!2QVTd`8bwb@N)_-dgCP??9mg=L=hWqvW->x1a5MHed;2gV1tAJC3GYpFC;3UE1S z42j&^;b3WIqfTDc;SA|gj0Y!43&tSTu1BUwo>i1-_07N08;oJQlQER!YSpb%{Ovwd z)8m@_bm&2F4uOV|MH{;Y|8;?9^0wS0JB47gmkccs|7Cyxbs$QAOYl$A7|}$soUYQI zkj{TZ5^yoQdZaU^uUyqzlBKaI2R{ad=sx}|L=0a)pe;HyK$~3gGb`QJzf6wmUrp{I z0ycj?544NUC_MU5_4JUPPv0#83S>*Dl#tSx66g-N{ZBgJCmBw$UT;_*3TSU@l!E># zDV^b+YJmWZY{mcu;sbHLF@#O-rthVs{ov>{oF~dp4GrRCBj!!e(3SuffVOzx|Etip zR05GV@}Bv<#e)E0<5<^0>o6U=uOE)toaLZKC2?1R;zv5t$~`%O&eo26o~q-%)a@sr z!E3w1=&l-FN8F&tAl$YBLa9M@h-CP3Ab{*IE3WRMCpb>r`)~Cce`J;9(r__x$$*@s z$xRIX!1(9Wp`j5IhjX3B#%gqykHgodF}7-`udaRGlnr|t;IK4VazuCFxxLj-1>nFh z)4mrG%^Rnt=Rfwx$!^vc`)w9ceiwgsV$E5%v5wDDnk1r+jTV>D6+txjJi;HRV8dr4 zZ*R|DFMG&t?3!F_zamZnLyM?Ye-(}F4QHj!l<2W(>B(8w^wvzdIS9;^$ri(WObli2`XXy_Iy-N08SC?k6yfrHql%(2D057(aZX!9242 zUz7T#wvXJh2iXA9DOd<_$ zl%s8ySj67gUTN9kdjI@3L#G~YO40}*mN&s{cWlraZ_DS-mKuw-*Y{!IwWaXp6wkwG zz#om)!f~f`UMR&-S(NdbaMe9*Nf|$&@dv87%-R+tzORbk0x}d|<`m8=TuyKOcwG|t zghKs74grcU#|!X{N6V?UJ6Z9@JYE__?5oGILy`{w+yT=7QB53DN&73_bhsEKm5!iX zti12wGOfjUE34H|VvN!+6GSvqefM0?oMND)mK2Vf%DBBur=BSHi(%GAo;u1>fXh(R95XCeSFrn> zV@wPe{U-IHM;kD=@l~O5J7L!ZaAQ0@Mh6aB$NS`!s07%W5ZcxbHDw>vBfEGvyhD%~ zfU0!lvW06<<#==FbuQf)`>sx*Tmg-ggT)1F$~_H07=J)9d{c-!M+Tjqv1INxD7=<5 z1pHQAeaAA9`Q6Zo76CfXym9iW@{gqI3#)w2m|GdPmaktPkaY>ZHPV~7opPE z1bkaM`)WTDlv|AWbgKKlQChbHr1o~=uCVeL7R@}c&sZfEU!sdFZmh&Wovxktbf-+g zjQHb3()V+gcY@VeujU$*dAZF;aTXj=_PF zCk-`6JIPa87XaCaYxUE*ztozgEo7) z?nex3GAL>a=!t&cHgFUfW>9=1bGM1}w5!LufyL^(XQxc9(TvpH7arH#wXh>`V8^Vv z7rwLH04UiVqnvMv2#943u=FP^I6>kxq|fK5Nr%cbdVc!avNP}DMGVLcZe)G;l>kp} zn>TO8AISv6mTwpVZC_hj12^oy^81GM1Pou0j~*0?Uh`{LXVIu;{KT1nKpDRtma|i5 zQbvTu71Jw)mV6|D`XZ@>Vn}(AX<{KIlrHyyN1vU)k+kJf2)qrTS!;X6Ji5ONHrLVR zp+_OOqUDBEq6;hzA$l|D%Hh9CD?&vayNv5@ndRK=)#V4o#VIcRp@L(b?;r&PXtQo8 z={bDnd)}j>_qNhC3Bu2Wv3l7OnfOVC+^tpNCDFg;< zwh^*GGVeIX7KQLkkge$5nSOrzMPB~5y)Nk5ISG$u(d)MSUOQeFtekBfcwN0%;(`iLXfd#-oggl* zaywW+(~feMv8DVaS!;TvbK7XlJq8)11rn&PcKi1w<^dQV!^|4i5$5hb&diBI!&A&p zI52v*CtCYz3>i{b*Ycd`zxmW@86tr?Krn67>6I=Uo#xgyr)bqs4nw^`sgF!4&T;7i z?__0;36Eiga!Q5^t_g%LdViHK3@o$2rs`jbA@?4J5-JPtg&@S}eFjU6(ABEDaM^HY z<<&u7Jj|uL1Kn|*ucq>CW5R#tONNK5r5oA0IDZdk9X>51eO{;YBDC=E$I#kS5X`^j zJ%iG6dVUHt$YXI=O_MC=z*}}MWaY+=v`cLJFX^tZi9@yi4$7@6#44=_P}x2XIenOL zUgw4e!({$dvEj#oy@6&QV*`R2>`Js$)O{}C3l@(?6))*p86Tn5=N>{d3)YP?5Cn?M zZ6Ws|OCL>^GdUIfBs-Nb=QkK;m;e*{hSfA7ioC3Vn0L6FEx|y*jixU@n9$N6Ga$1$ z#PBcUvH=jrl(D5J8X!F37+ZhUVQhsH6}N|h00->`W4#*zC`ng=FYMgU>CL=At8H)T z{I?-!h0%U7cUJY6!swgkfKAAyh}QCQ9jL<5^^KB1*McGNtH3?@-9q`t<^4_{-L92Q z3cBo7W5vG(0bJM{kzTpZ9D;c$a*3Oo8E}d7twQOLUsVN=7JG6+`qtd{-C)LR42mDgW$c-6HDA2ap@kZ52;j$VUt%>?! zu>-1gVHPrDOf(S%6rC6|H;~1b$XyvxMVIRQdby&}mr8w~%`f!TgGOJ=Qhrx{HGuxV zK@nI~y%m1SBD4|ED8nE9(}Mz5^Xpam8nF2{!pO%O{|e;(x_}Nt1RZ&DrmgsXxuspS zTRJA7yYlx1grzY+BidCFvTSG@m3u|5{l6L;TGRT|!~H$}1{E|!S`pCe3MX&A0y+}K zsB7>N!@~Ld0za%mw6-1lG@}pL1fz?648i}Rp8wsize6TKW`L%I(M{dMtnm5!0>aW) zK*wEABD8q`Cv+cEOx2H*D-9n5^Y7^amJmJqtO=_R=-uJY8*2JbU-fst8r0DRwtpl&{$7=TTQ+z99e}?5u_m`c zfXF^5TW(z*NyNoL&kb#Ex%#q$`5)K(b-leZ@Z43#uR`;`*XqCCP|*WC8Pb~^{Ckal zZy`V6p$;zWKmY#yz5xQbTq?{i>)#*!SDTlg0A*$W`1^PJ|9wkfg8m;&Y>hf1UH?xv z`+MaYG%n34-rE0b_r)N>#=z<7?eeIr(U(s-p>u10zWm~VFgwqPT;TrQz#mI3nudOs z>k!OwncM!;X3_7r2?4XIK}8#2|Fh9wH}G2~0-8P+dl&S#qyO`bktCqi#0kc9{IL;! z-vCf20ggE>_aW-Ht^Mv{gAxFwb_nGhDgJEn@As*yK-0^o2vT$k`QKh{AON};&B@>W zkGrU07Y&NMX!|68cjk{CastqyS&6F6;@{f^K5-KRnoiw<>dF5OZh!ZRVTKW~6t_@l zCEkB*x`!EPde>X}#(!Ma8nlMR>A( +#include +#include + +#include +#include +#include +#include +#include + +namespace py = pybind11; + +class __attribute__((visibility("default"))) InterconnectedModel +{ + // Vector of unique names of inputs and outputs of sub-models + std::vector signals_vec_names; + std::vector model_signals_vec; + int num_signals; + + std::vector> submodels; + + // index in "map_in_to_sig_vec" is index in "py_inputs" and value in "map_in_to_sig_vec" is index + // in "all_variables_names" + std::vector map_in_to_sig_vec; + + // index in "map_sig_vec_to_out" is index in "py_model_outputs" and value in "map_sig_vec_to_out" + // is index in "all_variables_names" + std::vector map_sig_vec_to_out; + +public: + py::scoped_interpreter guard{}; // start the interpreter and keep it alive + + /** + * @brief constructor + */ + InterconnectedModel() + { + // Initialize python library + // cspell:ignore libpython + // Manually load libpython3.10.so as we need it for python.h. + dlopen("libpython3.10.so", RTLD_GLOBAL | RTLD_NOW); + /* + More about the line above here: + https://stackoverflow.com/questions/60719987/embedding-python-which-uses-numpy-in-c-doesnt-work-in-library-dynamically-loa + https://mail.python.org/pipermail/new-bugs-announce/2008-November/003322.html + https://stackoverflow.com/questions/67891197/ctypes-cpython-39-x86-64-linux-gnu-so-undefined-symbol-pyfloat-type-in-embedd + https://man7.org/linux/man-pages/man3/dlopen.3.html + */ + } + +private: + /** + * @brief create a mapping between vector of signal input names from PSIM to vector of signals + * @param [in] in_names vector of signal input names from PSIM + */ + void mapInputs(std::vector in_names); + + /** + * @brief create a mapping between vector of signal output names from PSIM to vector of signals + * @param [in] out_names vector of signal output names from PSIM + */ + void mapOutputs(std::vector out_names); + + /** + * @brief add unique names to the vector of signal names + * @param [in] names vector of signal names + */ + void addNamesToSigVec(const std::vector & names); + + /** + * @brief create of signal names from all sub-models and PSIM signal names + */ + void getSignalNames(std::vector in_names, std::vector out_names); + +public: + /** + * @brief automatically create connections between PSIM and all of the sub-models + * @param [in] in_names string names of inputs available from PSIM + * @param [in] out_names string names of outputs required by PSIM + */ + void generateConnections(std::vector in_names, std::vector out_names); + + /** + * @brief add a sub-model consisting of base + error model + * @param [in] submodel_desc descriptor of the sub-model + */ + void addSubmodel(std::tuple submodel_desc); + + /** + * @brief set a new model state if it was changed using PSIM interface (mainly position and + * orientation) + * @param [in] new_state new state set by PSIM + */ + void initState(std::vector new_state); + + /** + * @brief set time step for all the models + * @param [in] dt time step + */ + void dtSet(double dt); + + /** + * @brief compute next step of the PSIM model using python sub-models + * @param [in] psim_input vector of input values provided by PSIM + */ + std::vector updatePyModel(std::vector psim_input); +}; + +#endif // LEARNING_BASED_VEHICLE_MODEL__INTERCONNECTED_MODEL_HPP_ diff --git a/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/model_connections_helpers.hpp b/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/model_connections_helpers.hpp new file mode 100644 index 0000000000000..3f21595662fc5 --- /dev/null +++ b/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/model_connections_helpers.hpp @@ -0,0 +1,27 @@ +// Copyright 2024 The Autoware Foundation. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef LEARNING_BASED_VEHICLE_MODEL__MODEL_CONNECTIONS_HELPERS_HPP_ +#define LEARNING_BASED_VEHICLE_MODEL__MODEL_CONNECTIONS_HELPERS_HPP_ + +#include +#include + +std::vector fillVectorUsingMap( + std::vector vector1, std::vector vector2, std::vector map, bool inverse); + +std::vector createConnectionsMap( + std::vector connection_names_1, std::vector connection_names_2); + +#endif // LEARNING_BASED_VEHICLE_MODEL__MODEL_CONNECTIONS_HELPERS_HPP_ diff --git a/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/simple_pymodel.hpp b/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/simple_pymodel.hpp new file mode 100644 index 0000000000000..fd9cf5cf44de9 --- /dev/null +++ b/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/simple_pymodel.hpp @@ -0,0 +1,102 @@ +// Copyright 2024 The Autoware Foundation. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// cspell:ignore pymodel +#ifndef LEARNING_BASED_VEHICLE_MODEL__SIMPLE_PYMODEL_HPP_ +#define LEARNING_BASED_VEHICLE_MODEL__SIMPLE_PYMODEL_HPP_ + +#include "learning_based_vehicle_model/model_connections_helpers.hpp" +#include "learning_based_vehicle_model/submodel_interface.hpp" + +#include +#include + +#include +#include + +namespace py = pybind11; + +/** + * @class SimplePyModel + * @brief This class is an interface between C++ and python models. + */ +class SimplePyModel : public SubModelInterface +{ +private: + std::string py_model_import_name; + + int num_inputs_py; + int num_outputs_py; + + py::object py_model_class; + + std::vector + map_sig_vec_to_py_model_inputs; // index in "map_sig_vec_to_py_model_inputs" is index in + // "py_inputs" and value in "map_sig_vec_to_py_model_inputs" is + // index in "signals_vec_names" + std::vector map_py_model_outputs_to_sig_vec; // index in "map_py_model_outputs_to_sig_vec" + // is index in "py_model_outputs" and value in + // "map_py_model_outputs_to_sig_vec" is index + // in "signals_vec_names" + + std::vector py_model_input_names; + std::vector py_model_state_names; + +public: + /** + * @brief constructor + * @param [in] py_model_import_name_ path to python model + * @param [in] param_file_path path to saved parameter file of the python sub-model + * @param [in] py_class_name name of the python class + */ + SimplePyModel( + std::string py_model_import_name_, std::string param_file_path, std::string py_class_name); + + /** + * @brief calculate the next state of a python model + * @param [in] model_signals_vec all available inputs from PSIM + */ + std::vector getNextState( + std::vector model_signals_vec, std::vector model_signals_vec_next) override; + + /** + * @brief set time step of the model + * @param [in] dt time step + */ + void dtSet(double dt) override; + + /** + * @brief get names of inputs of python model + */ + std::vector getInputNames() override; + + /** + * @brief get names of states of python model + */ + std::vector getStateNames() override; + + /** + * @brief create a map from model signal vector to python model inputs + * @param [in] signal_vec_names names of signals in model signal vector + */ + void mapInputs(std::vector signals_vec_names) override; + + /** + * @brief create a map from python outputs to model signal vector + * @param [in] signal_vec_names names of signals in model signal vector + */ + void mapOutputs(std::vector signals_vec_names) override; +}; + +#endif // LEARNING_BASED_VEHICLE_MODEL__SIMPLE_PYMODEL_HPP_ diff --git a/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/submodel_interface.hpp b/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/submodel_interface.hpp new file mode 100644 index 0000000000000..d4662036709d5 --- /dev/null +++ b/simulator/learning_based_vehicle_model/include/learning_based_vehicle_model/submodel_interface.hpp @@ -0,0 +1,60 @@ +// Copyright 2024 The Autoware Foundation. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef LEARNING_BASED_VEHICLE_MODEL__SUBMODEL_INTERFACE_HPP_ +#define LEARNING_BASED_VEHICLE_MODEL__SUBMODEL_INTERFACE_HPP_ + +#include + +class SubModelInterface +{ +public: + /** + * @brief set time step of the model + * @param [in] dt time step + */ + virtual void dtSet(double dt) = 0; + + /** + * @brief get names of inputs of python model + */ + virtual std::vector getInputNames() = 0; + + /** + * @brief get names of states of python model + */ + virtual std::vector getStateNames() = 0; + + /** + * @brief create a map from model signal vector to python model inputs + * @param [in] signal_vec_names names of signals in model signal vector + */ + virtual void mapInputs(std::vector signals_vec_names) = 0; + + /** + * @brief create a map from python outputs to model signal vector + * @param [in] signal_vec_names names of signals in model signal vector + */ + virtual void mapOutputs(std::vector signals_vec_names) = 0; + + /** + * @brief calculate the next state of this submodule + * @param [in] model_signals_vec values of signals in model signal vector + * @param [in] model_signals_vec_next values of signals in model signal vector to update + */ + virtual std::vector getNextState( + std::vector model_signals_vec, std::vector model_signals_vec_next) = 0; +}; + +#endif // LEARNING_BASED_VEHICLE_MODEL__SUBMODEL_INTERFACE_HPP_ diff --git a/simulator/learning_based_vehicle_model/package.xml b/simulator/learning_based_vehicle_model/package.xml new file mode 100644 index 0000000000000..18db5236c272e --- /dev/null +++ b/simulator/learning_based_vehicle_model/package.xml @@ -0,0 +1,26 @@ + + + + learning_based_vehicle_model + 1.0.0 + learning_based_vehicle_model for simple_planning_simulator + Maxime Clement + Tomas Nagy + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + autoware_cmake + + pybind11_vendor + python3-dev + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/simulator/learning_based_vehicle_model/src/interconnected_model.cpp b/simulator/learning_based_vehicle_model/src/interconnected_model.cpp new file mode 100644 index 0000000000000..4dd3b321312d0 --- /dev/null +++ b/simulator/learning_based_vehicle_model/src/interconnected_model.cpp @@ -0,0 +1,138 @@ +// Copyright 2024 The Autoware Foundation. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "learning_based_vehicle_model/interconnected_model.hpp" + +void InterconnectedModel::mapInputs(std::vector in_names) +{ + // index in "map_in_to_sig_vec" is index in "in_names" and value in "map_in_to_sig_vec" is index + // in "signals_vec_names" + map_in_to_sig_vec = createConnectionsMap(signals_vec_names, in_names); +} + +void InterconnectedModel::mapOutputs(std::vector out_names) +{ + // index in "map_sig_vec_to_out" is index in "out_names" and value in "map_sig_vec_to_out" is + // index in "signals_vec_names" + map_sig_vec_to_out = createConnectionsMap(signals_vec_names, out_names); +} + +void InterconnectedModel::addNamesToSigVec(const std::vector & names) +{ + // Check if the name is already in the vector. If not add it. + for (char * name : names) { + if ( + std::find(signals_vec_names.begin(), signals_vec_names.end(), name) == + signals_vec_names.end()) { + signals_vec_names.push_back(name); + } + } +} + +void InterconnectedModel::getSignalNames( + std::vector in_names, std::vector out_names) +{ + addNamesToSigVec(in_names); + addNamesToSigVec(out_names); + for (auto & submodel : submodels) { + addNamesToSigVec(submodel->getInputNames()); + addNamesToSigVec(submodel->getStateNames()); + } +} + +void InterconnectedModel::generateConnections( + std::vector in_names, std::vector out_names) +{ + // Create vector of signal names + getSignalNames(in_names, out_names); + num_signals = signals_vec_names.size(); + // Init vector of signal values + for (int i = 0; i < num_signals; i++) model_signals_vec.push_back(0); + + // For every sub-model create mapping from vector of signals to inputs and outputs + for (auto & submodel : submodels) { + submodel->mapInputs(signals_vec_names); + submodel->mapOutputs(signals_vec_names); + } + + // Create mapping from vector of signals to inputs and outputs of PSIM + mapInputs(in_names); + mapOutputs(out_names); +} + +void InterconnectedModel::addSubmodel( + std::tuple submodel_desc) +{ + const auto [lib_path, param_path, class_name] = submodel_desc; + auto new_model = new SimplePyModel(lib_path, param_path, class_name); + submodels.push_back(std::unique_ptr(new_model)); +} + +void InterconnectedModel::initState(std::vector new_state) +{ + bool state_changed_externally = false; + + // Check if some state was changed externally + for (size_t PSIM_STATE_IDX = 0; PSIM_STATE_IDX < new_state.size(); PSIM_STATE_IDX++) { + if ( + abs(model_signals_vec[map_sig_vec_to_out[PSIM_STATE_IDX]] - new_state[PSIM_STATE_IDX]) > + 1e-6) { + state_changed_externally = true; + break; + } + } + + if (state_changed_externally) { + // Reinitialize model + // Currently initializing model to zero -> TODO find a way how to initialize them to some + // other default values + std::fill(model_signals_vec.begin(), model_signals_vec.end(), 0.0); + + for (size_t PSIM_STATE_IDX = 0; PSIM_STATE_IDX < new_state.size(); PSIM_STATE_IDX++) { + model_signals_vec[map_sig_vec_to_out[PSIM_STATE_IDX]] = new_state[PSIM_STATE_IDX]; + } + } +} + +void InterconnectedModel::dtSet(double dt) +{ + for (auto & submodel : submodels) { + submodel->dtSet(dt); + } +} + +std::vector InterconnectedModel::updatePyModel(std::vector psim_input) +{ + // map input to vector of all variables + for (size_t PSIM_INPUT_IDX = 0; PSIM_INPUT_IDX < psim_input.size(); PSIM_INPUT_IDX++) { + model_signals_vec[map_in_to_sig_vec[PSIM_INPUT_IDX]] = psim_input[PSIM_INPUT_IDX]; + } + + // Compute forward pass through all models (order should not matter) + std::vector model_signals_vec_next = model_signals_vec; + for (auto & submodel : submodels) { + model_signals_vec_next = submodel->getNextState(model_signals_vec, model_signals_vec_next); + } + + // Map vector of all variables to + std::vector psim_next_state; + for (size_t PSIM_STATE_IDX = 0; PSIM_STATE_IDX < map_sig_vec_to_out.size(); PSIM_STATE_IDX++) { + psim_next_state.push_back(model_signals_vec_next[map_sig_vec_to_out[PSIM_STATE_IDX]]); + } + + // Update vector of all variables + model_signals_vec = model_signals_vec_next; + + return psim_next_state; +} diff --git a/simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp b/simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp new file mode 100644 index 0000000000000..09f7359af45bf --- /dev/null +++ b/simulator/learning_based_vehicle_model/src/model_connections_helpers.cpp @@ -0,0 +1,47 @@ +// Copyright 2024 The Autoware Foundation. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "learning_based_vehicle_model/model_connections_helpers.hpp" + +std::vector fillVectorUsingMap( + std::vector vector1, std::vector vector2, std::vector map, bool inverse) +{ + // index in "map" is index in "vector1" and value in "map" is index in "vector2" + // inverse = 0 from 1 -> 2; inverse = 1 from 2 -> 1 + for (std::size_t idx = 0; idx < map.size(); idx++) { + if (map[idx] == -1) continue; + inverse ? vector1[idx] = vector2[map[idx]] : vector2[map[idx]] = vector1[idx]; + } + return inverse ? vector1 : vector2; +} + +std::vector createConnectionsMap( + std::vector connection_names_1, std::vector connection_names_2) +{ + std::vector connection_map; + // index in "connection_map" is index in "connection_names_2" and value in "connection_map" is + // index in "connection_names_1" + for (auto name_2 : connection_names_2) { + int mapped_idx = -1; // -1 means that we cannot create a connection between some signals + for (std::size_t NAME_1_IDX = 0; NAME_1_IDX < connection_names_1.size(); NAME_1_IDX++) { + if (strcmp(name_2, connection_names_1[NAME_1_IDX]) == 0) { // 0 means strings are the same + // and we can create connection + mapped_idx = NAME_1_IDX; + break; + } + } + connection_map.push_back(mapped_idx); + } + return connection_map; +} diff --git a/simulator/learning_based_vehicle_model/src/simple_pymodel.cpp b/simulator/learning_based_vehicle_model/src/simple_pymodel.cpp new file mode 100644 index 0000000000000..9c3cb9aa06150 --- /dev/null +++ b/simulator/learning_based_vehicle_model/src/simple_pymodel.cpp @@ -0,0 +1,111 @@ +// Copyright 2024 The Autoware Foundation. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "learning_based_vehicle_model/simple_pymodel.hpp" + +#include +#include + +#include + +namespace py = pybind11; + +SimplePyModel::SimplePyModel( + std::string py_model_import_name_, std::string param_file_path, std::string py_class_name) +{ + // Import model class + py_model_import_name = py_model_import_name_; + if (!py_model_import_name.empty()) { + // Import python module + py::module_ imported_module = py::module_::import(py_model_import_name.c_str()); + // Initialize model class from imported module + py_model_class = imported_module.attr(py_class_name.c_str())(); + } else { + return; + } + + // Load model parameters and reset the model + if (!param_file_path.empty()) { + py::object load_params_succ = py_model_class.attr("load_params")(param_file_path.c_str()); + py_model_class.attr("reset")(); + } + + // Get string names of states of python model, convert them to C++ string and store them in + // py_model_state_names + py::list py_model_state_names_ = py_model_class.attr("get_state_names")(); + num_outputs_py = py_model_state_names_.size(); + for (int STATE_IDX = 0; STATE_IDX < num_outputs_py; STATE_IDX++) { + py_model_state_names.push_back(PyBytes_AS_STRING( + PyUnicode_AsEncodedString(py_model_state_names_[STATE_IDX].ptr(), "UTF-8", "strict"))); + } + + // Get string names of actions (inputs) of python model, convert them to C++ string and store + // them in py_model_input_names + py::list py_model_input_names_ = py_model_class.attr("get_action_names")(); + num_inputs_py = py_model_input_names_.size(); + for (int INPUT_IDX = 0; INPUT_IDX < num_inputs_py; INPUT_IDX++) { + py_model_input_names.push_back(PyBytes_AS_STRING( + PyUnicode_AsEncodedString(py_model_input_names_[INPUT_IDX].ptr(), "UTF-8", "strict"))); + } +} + +std::vector SimplePyModel::getNextState( + std::vector model_signals_vec, std::vector model_signals_vec_next) +{ + // get inputs and states of the python model from the vector of signals + std::vector py_inputs(num_inputs_py); + std::vector py_state(num_outputs_py); + py_inputs = + fillVectorUsingMap(py_inputs, model_signals_vec, map_sig_vec_to_py_model_inputs, true); + py_state = fillVectorUsingMap(py_state, model_signals_vec, map_py_model_outputs_to_sig_vec, true); + + // forward pass through the base model + py::tuple res = py_model_class.attr("forward")(py_inputs, py_state); + std::vector py_state_next = res.cast>(); + + // map outputs from python model to required outputs + std::vector next_state = fillVectorUsingMap( + py_state_next, model_signals_vec_next, map_py_model_outputs_to_sig_vec, false); + + return next_state; +} + +void SimplePyModel::dtSet(double dt) +{ + py_model_class.attr("dtSet")(dt); +} + +std::vector SimplePyModel::getInputNames() +{ + return py_model_input_names; +} + +std::vector SimplePyModel::getStateNames() +{ + return py_model_state_names; +} + +void SimplePyModel::mapInputs(std::vector signals_vec_names) +{ + // index in "map_sig_vec_to_py_model_inputs" is index in "py_inputs" and value in + // "map_sig_vec_to_py_model_inputs" is index in "signals_vec_names" + map_sig_vec_to_py_model_inputs = createConnectionsMap(signals_vec_names, py_model_input_names); +} + +void SimplePyModel::mapOutputs(std::vector signals_vec_names) +{ + // index in "map_py_model_outputs_to_sig_vec" is index in "py_model_outputs" and value in + // "map_py_model_outputs_to_sig_vec" is index in "signals_vec_names" + map_py_model_outputs_to_sig_vec = createConnectionsMap(signals_vec_names, py_model_state_names); +} diff --git a/simulator/learning_based_vehicle_model/src/submodel_interface.cpp b/simulator/learning_based_vehicle_model/src/submodel_interface.cpp new file mode 100644 index 0000000000000..906aff4b01ae0 --- /dev/null +++ b/simulator/learning_based_vehicle_model/src/submodel_interface.cpp @@ -0,0 +1,15 @@ +// Copyright 2024 The Autoware Foundation. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "learning_based_vehicle_model/submodel_interface.hpp" diff --git a/simulator/simple_planning_simulator/CMakeLists.txt b/simulator/simple_planning_simulator/CMakeLists.txt index 87d0f7e5fef0b..331d5e819df77 100644 --- a/simulator/simple_planning_simulator/CMakeLists.txt +++ b/simulator/simple_planning_simulator/CMakeLists.txt @@ -2,6 +2,8 @@ cmake_minimum_required(VERSION 3.14) project(simple_planning_simulator) find_package(autoware_cmake REQUIRED) +find_package(Python3 COMPONENTS Interpreter Development) +find_package(learning_based_vehicle_model REQUIRED) autoware_package() # Component @@ -14,15 +16,13 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc.cpp src/simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.cpp src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp + src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc_geared.cpp src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp src/simple_planning_simulator/utils/csv_loader.cpp ) -target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${tf2_INCLUDE_DIRS}) - -target_compile_options(${PROJECT_NAME} PRIVATE -Wno-old-style-cast) # RCLCPP_ERROR_THROTTLE() has built-in old-style casts. - +target_include_directories(${PROJECT_NAME} PUBLIC ${Python3_INCLUDE_DIRS} ${learning_based_vehicle_model_INCLUDE_DIRS}) # Node executable rclcpp_components_register_node(${PROJECT_NAME} PLUGIN "simulation::simple_planning_simulator::SimplePlanningSimulator" diff --git a/simulator/simple_planning_simulator/README.md b/simulator/simple_planning_simulator/README.md index d2ed19708c5c5..1f8762b722a29 100644 --- a/simulator/simple_planning_simulator/README.md +++ b/simulator/simple_planning_simulator/README.md @@ -63,28 +63,34 @@ The purpose of this simulator is for the integration test of planning and contro - `DELAY_STEER_ACC` - `DELAY_STEER_ACC_GEARED` - `DELAY_STEER_MAP_ACC_GEARED`: applies 1D dynamics and time delay to the steering and acceleration commands. The simulated acceleration is determined by a value converted through the provided acceleration map. This model is valuable for an accurate simulation with acceleration deviations in a real vehicle. +- `LEARNED_STEER_VEL`: launches learned python models. More about this [here](../learning_based_vehicle_model). The `IDEAL` model moves ideally as commanded, while the `DELAY` model moves based on a 1st-order with time delay model. The `STEER` means the model receives the steer command. The `VEL` means the model receives the target velocity command, while the `ACC` model receives the target acceleration command. The `GEARED` suffix means that the motion will consider the gear command: the vehicle moves only one direction following the gear. The table below shows which models correspond to what parameters. The model names are written in abbreviated form (e.g. IDEAL_STEER_VEL = I_ST_V). -| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | D_ST_M_ACC_G | Default value | unit | -| :------------------------- | :----- | :---------------------------------------------------------------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :----------- | :------------ | :------ | -| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | o | 0.1 | [s] | -| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | o | 0.24 | [s] | -| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | x | 0.25 | [s] | -| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | o | 0.1 | [s] | -| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | o | 0.27 | [s] | -| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | x | 0.0 | [rad] | -| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | x | 0.5 | [s] | -| vel_lim | double | limit of velocity | x | x | x | o | o | o | o | 50.0 | [m/s] | -| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | o | 7.0 | [m/ss] | -| steer_lim | double | limit of steering angle | x | x | x | o | o | o | o | 1.0 | [rad] | -| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | o | 5.0 | [rad/s] | -| steer_bias | double | bias for steering angle | x | x | x | o | o | o | o | 0.0 | [rad] | -| debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | x | 1.0 | [-] | -| debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | x | 1.0 | [-] | -| acceleration_map_path | string | path to csv file for acceleration map which converts velocity and ideal acceleration to actual acceleration | x | x | x | x | x | x | o | - | [-] | +| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | D_ST_M_ACC_G | L_S_V | Default value | unit | +| :------------------------- | :----- | :---------------------------------------------------------------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :----------- | :---- | :------------ | :------ | +| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | o | x | 0.1 | [s] | +| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | o | x | 0.24 | [s] | +| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | x | x | 0.25 | [s] | +| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | o | x | 0.1 | [s] | +| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | o | x | 0.27 | [s] | +| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | x | x | 0.0 | [rad] | +| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | x | x | 0.5 | [s] | +| vel_lim | double | limit of velocity | x | x | x | o | o | o | o | x | 50.0 | [m/s] | +| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | o | x | 7.0 | [m/ss] | +| steer_lim | double | limit of steering angle | x | x | x | o | o | o | o | x | 1.0 | [rad] | +| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | o | x | 5.0 | [rad/s] | +| steer_bias | double | bias for steering angle | x | x | x | o | o | o | o | x | 0.0 | [rad] | +| debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | x | x | 1.0 | [-] | +| debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | x | x | 1.0 | [-] | +| acceleration_map_path | string | path to csv file for acceleration map which converts velocity and ideal acceleration to actual acceleration | x | x | x | x | x | x | o | x | - | [-] | +| model_module_paths | string | path to a python module where the model is implemented | x | x | x | x | x | x | x | o | - | [-] | +| model_param_paths | string | path to the file where model parameters are stored (can be empty string if no parameter file is required) | x | x | x | x | x | x | x | o | - | [-] | +| model_class_names | string | name of the class that implements the model | x | x | x | x | x | x | x | o | - | [-] | + +_Note:_ Parameters `model_module_paths`, `model_param_paths`, and `model_class_names` need to have the same length. The `acceleration_map` is used only for `DELAY_STEER_MAP_ACC_GEARED` and it shows the acceleration command on the vertical axis and the current velocity on the horizontal axis, with each cell representing the converted acceleration command that is actually used in the simulator's motion calculation. Values in between are linearly interpolated. @@ -119,6 +125,25 @@ default, 0.00, 1.39, 2.78, 4.17, 5.56, 6.94, 8.33, 9.72, 11.11, 12.50, 1 _Note_: The steering/velocity/acceleration dynamics is modeled by a first order system with a deadtime in a _delay_ model. The definition of the _time constant_ is the time it takes for the step response to rise up to 63% of its final value. The _deadtime_ is a delay in the response to a control input. +### Example of LEARNED_STEER_VEL model + +We created a few basic models to showcase how `LEARNED_STEER_VEL` works. + +1. Install [a library](https://github.com/atomyks/control_analysis_pipeline/tree/v0.1_autoware) that contains basic Python models. (branch: `v0.1_autoware`) + +2. In a file `src/vehicle/sample_vehicle_launch/sample_vehicle_description/config/simulator_model.param.yaml` set `vehicle_model_type` to `LEARNED_STEER_VEL`. In the same file set the following parameters. These models are for testing and do not require any parameter file. + +```yaml +model_module_paths: + [ + "control_analysis_pipeline.autoware_models.vehicle.kinematic", + "control_analysis_pipeline.autoware_models.steering.steer_example", + "control_analysis_pipeline.autoware_models.drive.drive_example", + ] +model_param_paths: ["", "", ""] +model_class_names: ["KinematicModel", "SteerExample", "DriveExample"] +``` + ### Default TF configuration Since the vehicle outputs `odom`->`base_link` tf, this simulator outputs the tf with the same frame_id configuration. diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp index 58914d19552df..e81d4fef00abb 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp @@ -210,7 +210,8 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node DELAY_STEER_ACC_GEARED = 3, IDEAL_STEER_VEL = 4, DELAY_STEER_VEL = 5, - DELAY_STEER_MAP_ACC_GEARED = 6 + DELAY_STEER_MAP_ACC_GEARED = 6, + LEARNED_STEER_VEL = 7 } vehicle_model_type_; //!< @brief vehicle model type to decide the model dynamics std::shared_ptr vehicle_model_ptr_; //!< @brief vehicle model pointer diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp index 9fa4516c1a522..ced7349f28914 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model.hpp @@ -23,5 +23,6 @@ #include "simple_planning_simulator/vehicle_model/sim_model_ideal_steer_acc_geared.hpp" #include "simple_planning_simulator/vehicle_model/sim_model_ideal_steer_vel.hpp" #include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" +#include "simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp" #endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp new file mode 100644 index 0000000000000..c6301db42620e --- /dev/null +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp @@ -0,0 +1,144 @@ +// Copyright 2024 The Autoware Foundation. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_LEARNED_STEER_VEL_HPP_ +#define SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_LEARNED_STEER_VEL_HPP_ + +#include "learning_based_vehicle_model/interconnected_model.hpp" +#include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" + +#include +#include + +#include +#include +#include +#include +#include + +/** + * @class SimModelLearnedSteerVel + * @brief calculate delay steering dynamics + */ +class SimModelLearnedSteerVel : public SimModelInterface /*delay steer velocity*/ +{ +public: + /** + * @brief constructor + * @param [in] dt delta time information to set input buffer for delay + */ + SimModelLearnedSteerVel( + double dt, std::vector model_python_paths, + std::vector model_param_paths, std::vector model_class_names); + + /** + * @brief destructor + */ + ~SimModelLearnedSteerVel() = default; + +private: + /* + Specify string names for states and inputs. So we can automatically map states and + inputs of this model to states and inputs of the python model. + */ + + std::vector state_names = {const_cast("POS_X"), const_cast("POS_Y"), + const_cast("YAW"), const_cast("YAW_RATE"), + const_cast("VX"), const_cast("VY"), + const_cast("STEER")}; + + std::vector input_names = {const_cast("VX_DES"), const_cast("STEER_DES")}; + + enum IDX { + X = 0, + Y, + YAW, + YAW_RATE, + VX, + VY, + STEER, + }; + enum IDX_U { + VX_DES = 0, + STEER_DES, + }; + + InterconnectedModel vehicle; + + double prev_vx_ = 0.0; + double current_ax_ = 0.0; + + std::deque vx_input_queue_; //!< @brief buffer for velocity command + std::deque steer_input_queue_; //!< @brief buffer for angular velocity command + + /** + * @brief get vehicle position x + */ + double getX() override; + + /** + * @brief get vehicle position y + */ + double getY() override; + + /** + * @brief get vehicle angle yaw + */ + double getYaw() override; + + /** + * @brief get vehicle longitudinal velocity + */ + double getVx() override; + + /** + * @brief get vehicle lateral velocity + */ + double getVy() override; + + /** + * @brief get vehicle longitudinal acceleration + */ + double getAx() override; + + /** + * @brief get vehicle angular-velocity wz + */ + double getWz() override; + + /** + * @brief get vehicle steering angle + */ + double getSteer() override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double & dt) override; + + /** + * @brief not used for this model. calculate derivative of states with delay steering model + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel( + [[maybe_unused]] const Eigen::VectorXd & state, + [[maybe_unused]] const Eigen::VectorXd & input) override + { + return Eigen::VectorXd::Zero(dim_x_); + } +}; + +#endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_LEARNED_STEER_VEL_HPP_ diff --git a/simulator/simple_planning_simulator/package.xml b/simulator/simple_planning_simulator/package.xml index a2038486029dc..14509f83ae2fe 100644 --- a/simulator/simple_planning_simulator/package.xml +++ b/simulator/simple_planning_simulator/package.xml @@ -21,6 +21,7 @@ geometry_msgs lanelet2_core lanelet2_extension + learning_based_vehicle_model motion_utils nav_msgs rclcpp diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index e99f6d5f2cf00..524597e927f61 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -238,6 +238,13 @@ void SimplePlanningSimulator::initialize_vehicle_model() const auto vehicle_info = vehicle_info_util::VehicleInfoUtil(*this).getVehicleInfo(); const double wheelbase = vehicle_info.wheel_base_m; + std::vector model_module_paths = declare_parameter>( + "model_module_paths", std::vector({""})); + std::vector model_param_paths = declare_parameter>( + "model_param_paths", std::vector({""})); + std::vector model_class_names = declare_parameter>( + "model_class_names", std::vector({""})); + if (vehicle_model_type_str == "IDEAL_STEER_VEL") { vehicle_model_type_ = VehicleModelType::IDEAL_STEER_VEL; vehicle_model_ptr_ = std::make_shared(wheelbase); @@ -281,6 +288,12 @@ void SimplePlanningSimulator::initialize_vehicle_model() vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, timer_sampling_time_ms_ / 1000.0, acc_time_delay, acc_time_constant, steer_time_delay, steer_time_constant, steer_bias, acceleration_map_path); + } else if (vehicle_model_type_str == "LEARNED_STEER_VEL") { + vehicle_model_type_ = VehicleModelType::LEARNED_STEER_VEL; + + vehicle_model_ptr_ = std::make_shared( + timer_sampling_time_ms_ / 1000.0, model_module_paths, model_param_paths, model_class_names); + } else { throw std::invalid_argument("Invalid vehicle_model_type: " + vehicle_model_type_str); } @@ -478,7 +491,8 @@ void SimplePlanningSimulator::set_input( if ( vehicle_model_type_ == VehicleModelType::IDEAL_STEER_VEL || - vehicle_model_type_ == VehicleModelType::DELAY_STEER_VEL) { + vehicle_model_type_ == VehicleModelType::DELAY_STEER_VEL || + vehicle_model_type_ == VehicleModelType::LEARNED_STEER_VEL) { input << vel, steer; } else if ( // NOLINT vehicle_model_type_ == VehicleModelType::IDEAL_STEER_ACC || @@ -566,7 +580,9 @@ void SimplePlanningSimulator::set_initial_state(const Pose & pose, const Twist & const double x = pose.position.x; const double y = pose.position.y; const double yaw = tf2::getYaw(pose.orientation); + const double yaw_rate = 0.0; const double vx = twist.linear.x; + const double vy = 0.0; const double steer = 0.0; const double accx = 0.0; @@ -581,6 +597,8 @@ void SimplePlanningSimulator::set_initial_state(const Pose & pose, const Twist & } else if ( // NOLINT vehicle_model_type_ == VehicleModelType::DELAY_STEER_VEL) { state << x, y, yaw, vx, steer; + } else if (vehicle_model_type_ == VehicleModelType::LEARNED_STEER_VEL) { + state << x, y, yaw, yaw_rate, vx, vy, steer; } else if ( // NOLINT vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC || vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC_GEARED || diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp new file mode 100644 index 0000000000000..fba34e04ade7c --- /dev/null +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.cpp @@ -0,0 +1,88 @@ +// Copyright 2024 The Autoware Foundation. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "simple_planning_simulator/vehicle_model/sim_model_learned_steer_vel.hpp" + +#include "learning_based_vehicle_model/interconnected_model.hpp" + +#include + +SimModelLearnedSteerVel::SimModelLearnedSteerVel( + double dt, std::vector model_python_paths, + std::vector model_param_paths, std::vector model_class_names) +: SimModelInterface(7 /* dim x */, 2 /* dim u */) +{ + for (size_t i = 0; i < model_python_paths.size(); i++) { + std::tuple descriptor = { + model_python_paths[i], model_param_paths[i], model_class_names[i]}; + vehicle.addSubmodel(descriptor); + } + + vehicle.generateConnections(input_names, state_names); + + vehicle.dtSet(dt); +} + +double SimModelLearnedSteerVel::getX() +{ + return state_(IDX::X); +} +double SimModelLearnedSteerVel::getY() +{ + return state_(IDX::Y); +} +double SimModelLearnedSteerVel::getYaw() +{ + return state_(IDX::YAW); +} +double SimModelLearnedSteerVel::getVx() +{ + return state_(IDX::VX); +} +double SimModelLearnedSteerVel::getVy() +{ + return state_(IDX::VY); +} +double SimModelLearnedSteerVel::getAx() +{ + return current_ax_; +} +double SimModelLearnedSteerVel::getWz() +{ + return state_(IDX::YAW_RATE); +} +double SimModelLearnedSteerVel::getSteer() +{ + return state_(IDX::STEER); +} +void SimModelLearnedSteerVel::update(const double & dt) +{ + // Eigen::VectorXd to std::vector for model input + std::vector vehicle_input_(input_.data(), input_.data() + input_.size()); + + // Eigen::VectorXd to std::vector for model state + std::vector new_state(state_.data(), state_.data() + state_.size()); + // set model state + vehicle.initState(new_state); + + // model forward + std::vector vehicle_state_ = vehicle.updatePyModel(vehicle_input_); + + // std::vector to Eigen::VectorXd + for (size_t i = 0; i < vehicle_state_.size(); i++) state_[i] = vehicle_state_[i]; + + // Calculate + current_ax_ = (input_(IDX_U::VX_DES) - prev_vx_) / dt; + prev_vx_ = input_(IDX_U::VX_DES); +}