From 5d6905f870b91e12e4eb093e9ec546128938e525 Mon Sep 17 00:00:00 2001 From: Davide Risi Date: Thu, 4 Sep 2025 20:18:28 +0200 Subject: [PATCH 1/9] [ADD] Add gravity compensation PD controller implementation and documentation --- .../CMakeLists.txt | 106 +++++ gravity_compensation_pd_controller/README.md | 27 ++ ...y_compensation_pd_controller_parameters.md | 130 ++++++ ...vity_compensation_pd_controller_scheme.png | Bin 0 -> 176636 bytes .../gravity_compensation_pd_controller.xml | 9 + .../gravity_compensation_pd_controller.hpp | 175 ++++++++ .../package.xml | 26 ++ .../gravity_compensation_pd_controller.cpp | 393 ++++++++++++++++++ ...compensation_pd_controller_parameters.yaml | 74 ++++ 9 files changed, 940 insertions(+) create mode 100644 gravity_compensation_pd_controller/CMakeLists.txt create mode 100644 gravity_compensation_pd_controller/README.md create mode 100644 gravity_compensation_pd_controller/doc/gravity_compensation_pd_controller_parameters.md create mode 100644 gravity_compensation_pd_controller/doc/media/gravity_compensation_pd_controller_scheme.png create mode 100644 gravity_compensation_pd_controller/gravity_compensation_pd_controller.xml create mode 100644 gravity_compensation_pd_controller/include/gravity_compensation_pd_controller/gravity_compensation_pd_controller.hpp create mode 100644 gravity_compensation_pd_controller/package.xml create mode 100644 gravity_compensation_pd_controller/src/gravity_compensation_pd_controller.cpp create mode 100644 gravity_compensation_pd_controller/src/gravity_compensation_pd_controller_parameters.yaml diff --git a/gravity_compensation_pd_controller/CMakeLists.txt b/gravity_compensation_pd_controller/CMakeLists.txt new file mode 100644 index 0000000000..d245ad14d7 --- /dev/null +++ b/gravity_compensation_pd_controller/CMakeLists.txt @@ -0,0 +1,106 @@ +cmake_minimum_required(VERSION 3.8) +project(gravity_compensation_pd_controller + LANGUAGES CXX +) + +if(CMAKE_COMPILER_IS_GNUCXX + OR CMAKE_CXX_COMPILER_ID + MATCHES + "Clang" +) + add_compile_options( + -Wall + -Wextra + -Wpedantic + ) +endif() + +set(THIS_PACKAGE_INCLUDE_DEPENDS + acg_control_msgs + acg_hardware_interface_facade + controller_interface + Eigen3 + generate_parameter_library + hardware_interface + inverse_dynamics_solver + pluginlib + rclcpp + rclcpp_lifecycle + realtime_tools + urdf +) + +find_package(ament_cmake REQUIRED) + +foreach(dependency IN + ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS} +) + find_package(${dependency} REQUIRED) +endforeach() + +generate_parameter_library(gravity_compensation_pd_controller_parameters + src/gravity_compensation_pd_controller_parameters.yaml +) + +add_library(gravity_compensation_pd_controller SHARED + src/gravity_compensation_pd_controller.cpp +) + +target_compile_features( + gravity_compensation_pd_controller + PUBLIC cxx_std_17 +) + +target_include_directories( + gravity_compensation_pd_controller + PUBLIC $ + $ +) + +target_link_libraries( + gravity_compensation_pd_controller + PUBLIC gravity_compensation_pd_controller_parameters +) + +target_link_libraries( + gravity_compensation_pd_controller + PUBLIC ${acg_control_msgs_TARGETS} + acg_hardware_interface_facade::hardware_interface_facade + controller_interface::controller_interface + hardware_interface::hardware_interface + hardware_interface::mock_components + inverse_dynamics_solver::inverse_dynamics_solver_lib + pluginlib::pluginlib + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle + realtime_tools::realtime_tools + realtime_tools::thread_priority + urdf::urdf +) + +# Causes the visibility macros to use dllexport rather than dllimport, which is appropriate when +# building the dll but not consuming it. +target_compile_definitions( + gravity_compensation_pd_controller + PRIVATE "GRAVITY_COMPENSATION_PD_CONTROLLER_BUILDING_DLL" +) + +pluginlib_export_plugin_description_file( + controller_interface gravity_compensation_pd_controller.xml +) + +install(DIRECTORY include + DESTINATION include/${PROJECT_NAME} +) + +install(TARGETS gravity_compensation_pd_controller gravity_compensation_pd_controller_parameters + EXPORT export_gravity_compensation_pd_controller + RUNTIME DESTINATION bin + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib +) + +ament_export_targets(export_gravity_compensation_pd_controller HAS_LIBRARY_TARGET) +ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) + +ament_package() diff --git a/gravity_compensation_pd_controller/README.md b/gravity_compensation_pd_controller/README.md new file mode 100644 index 0000000000..b051094acf --- /dev/null +++ b/gravity_compensation_pd_controller/README.md @@ -0,0 +1,27 @@ +# gravity_compensation_pd_controller + +This package provides a PD controller with gravity compensation that converts joint position references to joint effort commands for a robotic manipulator. +It is a chainable controller; therefore, it requires another controller to provide joint position references via chaining. + +## Control Law + +The implemented control law follows the scheme shown in the figure, based on the formulation presented in _B. Siciliano, L. Sciavicco, L. Villani, G. Oriolo, "Robotics: Modelling, Planning and Control"_. + +![gravity_compensation_pd_controller_scheme](./doc/media/gravity_compensation_pd_controller_scheme.png) + +## Controller Configuration + +The controller uses the robot's dynamic model to compute the control action. +In particular, it relies on the [InverseDynamicsSolver](https://index.ros.org/p/inverse_dynamics_solver/) interface to estimate the gravity torque vector. +Control parameters for the PD controller with gravity compensation are defined in the file [gravity_compensation_pd_controller_parameters.yaml](./src/gravity_compensation_pd_controller_parameters.yaml). +Please refer to [`gravity_compensation_pd_controller_parameters.md`](./doc/gravity_compensation_pd_controller_parameters.md) for the documentation. + +## Behavior in Edge Cases + +The controller is designed to handle the following edge cases: + +- **Computed torque exceeding joint limits**. If the computed torque exceeds the joint limits, the controller will saturate the output to remain within the range specified in the robot description. + +- **Invalid joint position reference**. If the joint position reference is `NaN`, the controller will fall back to the last valid reference to compute the control action. Initially, the first valid reference is set to the robot's starting joint positions. + +- **Invalid joint position state**. If the controller detects a `NaN` value in the joint position state reported by the robot, it will return an error to the controller manager. In this case, the controller cannot compute a valid control action and will output `NaN` values. It is assumed that the hardware interface is capable of handling `NaN` values appropriately. diff --git a/gravity_compensation_pd_controller/doc/gravity_compensation_pd_controller_parameters.md b/gravity_compensation_pd_controller/doc/gravity_compensation_pd_controller_parameters.md new file mode 100644 index 0000000000..3336b056d3 --- /dev/null +++ b/gravity_compensation_pd_controller/doc/gravity_compensation_pd_controller_parameters.md @@ -0,0 +1,130 @@ +# Gravity Compensation Pd Controller Parameters + +Default Config +```yaml +gravity_compensation_pd_controller: + ros__parameters: + command_interfaces_names_override: + effort: '{}' + compensate_gravity: true + d_gains: '{}' + dynamics_solver: + dynamics_solver_plugin: '' + root: '' + tip: '' + joint_space_reference_controller: '' + joints: '{}' + p_gains: '{}' + robot_name: '' + state_interfaces_names_override: + position: '{}' + velocity: '{}' + +``` + +## joints + +Specifies which joints will be used by the controller. + +* Type: `string_array` +* Default Value: {} + +## robot_name + +Name of the robot to control. + +* Type: `string` +* Default Value: "" +* Read only: True + +## joint_space_reference_controller + +Name of the joint space reference controller. + +* Type: `string` +* Default Value: "" +* Read only: True + +## state_interfaces_names_override.position + +If this parameter is set, it will override the default names for the position interface of the state interfaces. + +* Type: `string_array` +* Default Value: {} +* Read only: True + +## state_interfaces_names_override.velocity + +If this parameter is set, it will override the default names for the velocity interface of the state interfaces. + +* Type: `string_array` +* Default Value: {} +* Read only: True + +## command_interfaces_names_override.effort + +If this parameter is set, it will override the default names for the effort interface of the command interfaces. + +* Type: `string_array` +* Default Value: {} +* Read only: True + +## p_gains + +* Type: `double_array` +* Default Value: {} + +## d_gains + +* Type: `double_array` +* Default Value: {} + +## compensate_gravity + +If true, the controller will compensate for gravity. + +* Type: `bool` +* Default Value: true + +## dynamics_solver.dynamics_solver_plugin + +Name of the dynamics solver to use. + +* Type: `string` +* Read only: True + +*Constraints:* + - parameter is not empty + +*Additional Constraints:* + + + +## dynamics_solver.root + +Specifies the base link of the robot description used by the inverse dynamics solver. + +* Type: `string` +* Read only: True + +*Constraints:* + - parameter is not empty + +*Additional Constraints:* + + + +## dynamics_solver.tip + +Specifies the end effector link of the robot description used by the inverse dynamics solver. + +* Type: `string` +* Read only: True + +*Constraints:* + - parameter is not empty + +*Additional Constraints:* + + + diff --git a/gravity_compensation_pd_controller/doc/media/gravity_compensation_pd_controller_scheme.png b/gravity_compensation_pd_controller/doc/media/gravity_compensation_pd_controller_scheme.png new file mode 100644 index 0000000000000000000000000000000000000000..c6c9a5f6b3417511dfca80f36a8cab3f84b6ede6 GIT binary patch literal 176636 zcmeFZc{r5q8$YZFB}-9SENLN2r0lyQMW}39M`X!5*0By*vsXe0MfQ+=EHg|(*2x}b zj3qlW_Q4qQ-c!&1^!)K2$M27K`OZI6b6oeie$LN%Ue|r!BJOFaF&;T{go=ua@y>0P z2UJw-U@EF3m+7g2U#^)^O#@#vHp-gHR8*yL4113b0slYX_CW0hRdF}RJn-+pdv|qJ z)xdZ0c>K9@=bW9Lb{6FE1~FKtLc6K0ZF`>godn1Ix?Ha&mI2 zs;W{_Qs>W~PfJVt{{1_VNSvIUTw7b4pPz?7ApZXT-QC?UU%qT=YD!K{HZd`I`t+%- zt*x@MvVwv_baeF6($e(w^v=#sSy|cp_wO4U8$W#b@a@~Tjg5_a_wH$EXkaiH2L}gD zO-*58VO?EaOH0e6M~@~ZCg$emj*gCIW@ZKj1?A=Cjg5_EXJ^mO&Q?@ZJbd^tEG*34 z-rmd0%goG7MMcHk-5m;r>g(%&`SL|aN9XqK+g)8 zXFWYV(G*I)4!A$i(xFnC`DRUZ@FU|L6=hwok)>~< z2dJ(dZF~z|$HNY8%?N%mrv;Y&|Lqfqq6CO4FgQf^hwC)|`~E*42O(KcA&S(iU$8#M zWf?92@qP-Xqx|x}@BhW&|G_vow}mSf?-n@HboEY7wq}KX%ZPeIqnP~V?30<R{c-qq-JagIRy8Snyv1wmZ#YgLnVMKFhsxvI;0~9yk9zb$Z zzW?9#e9 z0Z{oFguCF9n_#+gH-0)BtKqI1dPX5r&ZN+CbppdrWr%Fh2( z$O{_+q_g}q?-~-$gyamQ|DP(Vi~qL+*vCj`qqW`Q4IqVV|3@w`=O~GnKmU7}`xq(t z`Fi2^1-?4?rL^z7Oq4_gavl3UYpF)khA}9UvXY&{0Nj=0=zmYU=3yKI>p#{WN3-+( zU5n%;n8;lUDtuIahlsN}81$L~fQ@IrqhajTIN~ZL*K@~yPduC->HjE5c16UOu*;#E zKnsSohotd0mpx-o45U3=W^$wEg@!uI3n5pABj?X$9z1kDWIRYn-}3?+dH2)t_u3#{ zX&Ws^y*|`>sdfX2$?wIk^Z+&0SDqkWUjVV6S##a8!c<6~Svz(i>XA7}`Ve}wM;h_JFlgtN|masdIOUgS#uS;XG- z7du{rx8Gdw6p@(9E8^r2-Y0()`RGns*jtU*Ct^A4;E@w3Yc-r^EFpIczEdJt2Qp!! zB!cM}dX!RyVdLp~>ErwBUs927yY|lAxKnbj(`Hw}0bOgG*P9E&!^a3d6FD9MX7YQ= zE?$^Ve8CFyd|9oL5bfwU{!kM3hjW~NMyj0!EeRs$fu<_2Q(KP>KY)`L$!RpFiA!IJ zL5kS5%4XT=;TVHd#RY>@fkI)@{?d5FkC27`8L}`YTtMBHX#=t*J1m)+u;7FRFAonF zO=f4mBVdHbzzf3(+UyI~_&9ODe&QdEee0}z-+`#z=|KU6~Aq} zTg~)u2NF?RRRi_z{?GicH}~~rJJ*L>3vhclX|H39XP`f-2*>hALI%J{f9-%vQwfBE z28Fq;wz2-V<6I4R_0<(0{L0o$PfTw6q5^ltJnqB4j6Q;^ZlWRW@6Ao6l`}Xq`RQ~t zA(49v#O93qoKWo4e~QKgKB($_m7e& zXB523LATg$&hRRs*9zr`M@wwdoHQFQSubZ4urj@gZMqA;;uq1;ql}b) z0>aO>SI=Mt-zXeLRk3k*fGbV6@E|-8xk%L7-d0^Gt8zV*ejn=d?-UI1ACFC zr-!fV-~}{E@^a~?d_dwb5n9XYPfhWmS=>SK`MrqjjvtkB>CZ}0XT~AV8r*8ntveDv zYi6dPFn&Tc($zHx$m48m9*N_99%t8Ts9$5ti@4Yl>zB$&Vn4=GvQoYR*TJ`o|5j6e~-? z3UEJ1|6z?nMdOdhJ^dhKU&3KxJW=87QlI;5#)Elzus%r3*&~8pdnQFPme1Y zm~OvSNF}p%n&uJnn17&M_D{4YoIww%99pUC&`FA7#}COv@_Asn%YugpG2#qri{(3@ zpjpm^BIt3TIH>`CqK%D=`UqNOQ_B~xLrD(zu6q+yO>VYxe3-DP2xhc8|;S> zJ$|vg1Xx}*oxeKSEboCL6;WcK!Hf&|u*XC&{KfK>1VP1OSGxj4Bzt`y3%YL$DAaj# z>~gJI+>w7Y2_P}thi9zyrNs?7jEo_zw!fLeOhdf2z~z7Y-`MdtxJs~1&}j|IN7>;t&@p;|zx9Z<#pRNh)j4-#Jme>`0G$LhKFpbzY8iZt&Lmw`@4!z6-8H zk16dTe`=hm6J>cAJPki+O`6=%s9I0s899>!zn24;n} zfP!HBCWVXN{uNFf=-_+sN9zLQEN+KUM3!sQ7=AF@Kp<)R}N< zLC9u3EloyfZf6tJ@@J-kk^9XHxj-0y@vv)Z0^Sgn`&A}dn;cG38^}- za!E?9zT%5sfo;wGUe~01%03VH7eNhao-ZQqSX`?ibjp#S&_%iH-essaJIJA>ED`dj z25zqb%Vu}Yh7(6~qv#0jGlg<6J~r%UQ8O=7B%b!iZi4FbEwCgrV7L-PkguK|2ReIm zk3kZ|#-uF;U&N>x$01Z()?x*)I@NDB1d5+ju`%Nkx(vL*NuMH1*6LSke{MViL5GnT zIf}q5^f)~|Z!q)aVu#D8I9)L@HR1SJLBgxj_iH8md8>zz@Uk5NW?X#a&IgHUD{|S7 ztqRqiIz4Vi8Az$EGPtCmJ-Dtv3s#{j?UktL=?>Y;JExngI2Ik9B^_L_^{v`7X)&M zSn?*K;`q7Hf+;0y1R~a5hNyppcj$v6Is3JESNvf> zgpw@{WSz2ys5l2RNJt+SmTyp8TCRay&U#ad_#Ey$qi_=YASZJNke>LG;XZ2zdFZM( zFGcygW9Tjl*1rago9WdC5i@5Gu=k(PIt^yS-n$j~>Im*cXD%O1!!3KJ&5VC5^%pLy z8-SC7aAmW(IMhz9HmM)se`n;%3AEsAZ38e$ItsOJwsUZg{ukPIgX-8;6Qto;23EZe zF(dhdON4hSZR5rM3Z_U?8H|ub+^C3^x`Qq=#m*p}zXZvh7Q&w*?6Eep$vR+2q7$eq zo&Eme8q###50JUGCYNrGG${I&sm|b}_dS!N^&G`35wPb<-dS^o*DPjvEh#YP{Q)d>uS|uO^Ogp!xBvexbz5UztTl> zeV!5bpn^E261$jjb8yd6F8POuztsy5Oyj`@*0=c6x_&B&`88BBUWeNDK8Pb$zB$Jv5{5C3k5! znXoQ@*KbnldqoHckxcs94yPQuuLz$1BW|X)rF-LuRv(I0fubyb-`J|-%2cU0L zQJtdxvo3GQb~59-{{4HvhNnTxMXjA&$xI&jJsRN&dMX0xhOt}jx95x2sLN9#e|ExSz`{5j2d4XeI_rXk3*X~+1`Ke zOF7*E_(8Jrr0Roe2Yy<$6P9VvLDznGe#d@Re^=3c z!+|RkGvjen$!_*YDtpS!E2^+Z-^Ud;u1M^3=$imGJ*;o(`jq6x~-6j;IAWg^C z%^XGir~;+valDe#ALUe{6An^zPF-~cgPv(K?H5}-{%GkKkh`f-<3`6f#c&=|Xh#e2 zM)_94R}N53o`a=gwr=_meFrHlLUr`>7o>cWUwzN}PjFGln@G*!jZYnHwFW*xb@jLIli7*et)ZdpFHCTmmn8Ck4@cjk z|A4+swX;*{ZHjT`mx1_iyvM&Zt@} zzK?Th-ZgD| zUt?`>(vWR|6`!ZKzl8LCS)$p#YS@U`HWif%3p(`qX`#f?+2ZY{*&kkr0bZ;b53ddK zF*b1xb)gc4QQ)Q?TM1Eae;?w_oGTB=4#Ygm_bv0TU#9ZgNVPrNx>qgYj%)_!0kmGy zqvxPFAn*Tj-|g`QA?Jat-(#gL#Lb8Z)|n8 zaYhqd-CfjtFt=v(wUcj8!-h;%hTTKX!_~fi?>2|am%YsSbsFsP$Cu5XFyhukE|@I| z69PI~;!78^)*IsbctF}P(=i|5n1^ce0%gbph%CT*W84WeVr0BIh{jFe%rc%Fo(VhY z+(IH{RK*U;^jjXrcHU?LzJKazd9I?MFt%7=kqqSgiyDw+p9f=kJr zm75gWJWDpE*-33K;}s}7j>Uf59BeuNVpUDc+2<`LeSkm`fZ_Z50VCN$o*QP(uCUrw&fsii8P$o%WXo#=$0dva^ z3%*w{TjO6$ah8&m6jWd*emAb1%h~iA;4ZfAS)PL7uxOC828y|scR@jN^pyLdWc&<7iRC><>vNLV#{*kkK zlre@DGOK#U297Q>3x~A*~(h|5nkoAQoqT z>s(d1J|CCj>F8%MYr`+lF>T42Hd_t}4~YkMvo@PWJ_0&eYIL;VcuO=;1 zl0x^Fq+onYjEI)D4@D1_)^2aOe-wfEJV|>kqfRT{H7oML^G%VOJ-gO*xk8ackkz>3 zl?LlQifh`;gD0IKxonbvY4_A98@u0vCu^hTx=0tHjWm_5*wS-LiXU#YsOQ+&xezN18KT63>x85^g=92M}}LZydI|9*`WEutX?E3^JEufJSOq%O(am(?Wk}aK{Tc9Cf zlyz9J6Tk}|1DLIbLy$_7*CX57F*;NgCDHbBU6Oq3=YMn#CF;+rFD1t5jwQX^XG3C& z-bbgomeUf#OB`;dkCsNh4?S*xaU{R_VB8*>55J>z;44DdZNLQ~o&0mRNOdOSdCi_O z`%3V$w!{n`Sd@kiU`RPFWN2?{I-5CwyR3MpxOQ|OC`kkVwk%VM0H!r*>#V!cKUtRX ziwW1~D~-&V3kfSI7IXk(M_H+k6VRDh{Xc?^7Cd;Eh^83e>ynfmS#0~};9LJ@X5s68 zZr4P9Vn|HM#MO}5%Bc=VReY!9%ayZeh*ptlXqg=iBwvdu%KNm&s(IbQM#}7`{-+f~ zHR1$U$$6dcA5D5Zh@du8CeVf2@aCux0{z!Syyt4{_6nlHeHc2G8t+XRT7kMba2^)L z|4jEQcLSqIJUy)F4BBQk$DsYBsl<$SH0XQyrMlxjL+kB#lMY07ytE(f<632a7_MHL z+Ba9%;jA^T-9@2QVFs2MO6Z`UWpC7r9LCN3IDe!HqZF zc@q~~`23BDe#6BZt!~bGxnJe6X*>xlw2O65{|U>nJ}WLS8)Jl$o)%?Pu{A z-|02p{mCTP#pwC^-JY~dF>QaFDf{GW5RqF4r(pm z+EjY{Ww}C{i=+t=Wq?k3^|jVf<;nNX9zv45f2J((=y{m&o2OysU%;f}UYYagFue$* zX_7o4ba193)a9B4#C#_260Q)-S#z6N`g7%D?NpM-)IeR?yOFb+J18H*BKNo~O27Hx z85i4yN**=`dZ{aeF=+R8tU}uA>B-S|JMkUE8@C!AuPaEvqD1AdH;{>MAP4UGzDF?x z5!Zi0lj`&lqDW zrdg4llR$Kw3ydk~d~}r8zBtToUo^lEmcR3U-%8ElLtVd2?S1m(&nY40MB^Eg)Ulr6fA|-

-pR;Y}y=gLwYeWg!MjP%jq z@{vLG*FD!sW0H_R2S#su;x*=NODcxmOTE1l{t1fu3^D#>PZyUw4KzGEfO!x8YzBYW zi?MdDIf=c2=Zf+W3bj6hBpJlD=~lZwAWLN9FIUD6H8glX=B{|cHC|E34%t#y^Ua3y zl3Bm5l|(psqh+ri>rxNDcpQCz<)1d6GNVJ_!x&b-Szg<8ce2V}9L5ZWh~=U=U=Ai5 zaSQ527nnfu$)_vSv%2K(gjWh{r$C%=z9fXac+Y)CRDp>SE5YdXv{QLXmr-~QS`HE< zd#{cj$MUl)o&#E1!kD)D(Gu3=R4q|1)#zB4{3`72p{!N&46$63v&m_Z8OuURMrr{1 zV>r@ki(()1DDZ{TNuF7I?>)OC-oI(Uome3FODOD-7RPC~URkww7MCk@J)ns$d_B$efSXptrtj?ZObsjg>4+*gTsy)reFhJEqk##%X&==7t_||AJF!2Um#~aXA;}%cG#Xr!C2C@Ph=f% zqb>al@;*?%07Rz`roaqDJN)zI*DGBXEXw{nV3T+Ol}Gjl7v=Gz@x|=iId(3zXFkDr63$wk?fC_S5v*U^b8i%wNuX?Bs_uGB{13Y(syh>!eTZbNo2dE;Awo9*eqVe@Z8 z-4`XWS~ej*GuSuH-ow#tb<0_h33n@1_N#Y%^5yD8Hnb*FYPra%xRWJ1QAqijn4CQu zII&lbAPtGzK~U=+#wjhIhu!=+hy@;{f#~`u@=L?`d`Ff_qHZDB=m?X6W|3^@C~E&J zbOg~f1I60%?@2Q?C5}h8UW?xX9+imx7xXyLS4{oOvHLRQ^QIz9xaJEM>Mw$PSLsuX zm~iAXQ66)Nta)Z@noH*%A@ebb5fIw4f3Z3M)7A4 zbHO+sh*b?67sG466+T#8w(4h`{MtWxQ{P?&#(r!a&6wJH_E=J%^`MMcbCwnTue`fb z-$GkP3R|hwQ+c$EHu?fdAGo8~XNB^AS1Db@76X*}%>d7H`gU+zx%%`xx7Qpu=c7W$ zvRz!3YiJ;%D7b&X_erlo1lO~pHE9yzz(WW93jfST?oD%KHk=`!ZY= zGB3FtAA1TwtICCn<&(yRXKHLnePPRA_u8f%d@hVvou;JX!aq}SrT%1GOpWZd94~aI z{{NLsZ2ms#N zhixqqi9ma}jvh|>XjsXlnLaEHQwJCgNZ;QX?Fo{E(VMadj*faQuNfULuOlDD)s-Kf zUqSue?pz5EPidFCzP_Uh4_y_jMq)<9rQ+9@^_t3k)RkDv(Ifz%b&^PZ;_jP5e$xN{h`UNz-h?W!*Vi( zE$i;cBSJ32&5ASW13Cv&UQa6kSSF`O;HyH0m{QjD^%Wdh0A^76Co>pMRQ8b&YIWH1p7Wp zB(A|A=I2x35+Oka^_ATlz!Qymn*UeY-sJ<<3ukWU!1UEK}S8i`DDPmX61zdOwWgdIdDM*OcwEl z?8dj$(t+g;iOIiRKJ560r=)hOtp(vK$#+QdH zerM~xKTrI;%D*1&6h5BvwS|C)lPs3Bcs0Hw=Ck3nedBOLg2@3*j&e8rNb`1?i}zNW zSim7AJP+*V-$Qm2oB_R7SKn|=2gNvq5aNBXn?aZ9#22Rsf{r$9iwob1Zf@=zn)<$l zl0>WS>RO1dU$YUDaz?o{oPt8ccH1sUp~Khj2YeZ-H#4l;{aAYCC`>z}ISguwx26%J zT4JB0`I~EuNKzZL*r>w<*CM929>Ev~zMg@3H?lvgX);^V&lp4e>~gs>d_jA(AR{~{ zk_L5a(ygESwP^R4kMZdCHGKsJHP4NHp=RvrQoOv~=fxUc*mc@qT^`D}-P{~7%9dVJebdHuCC#TOHmwx6 zS!5`m-}ImpOWxmlm`qB!C5T{j#zZoQE=+Yv<2&?B=dYeXm-?lQ7KZ7wiMGD^wK5R{ z$ZVzYqogkD%4c*r`_2k=ZGdyjE$+c+C-b9%hASlT6?^Q_YYLq<*4UkaL#o!d$hgrLg;cpg+YKh+ulLS-y7DGC{t#1!5oI)#N{u z=F@9eIs9q5BYALf5)f?gc|lW!nlPAlL4CW3-j?c{$k)R^_tCeNz~Sh{{IfxIUeD&k zCAZ4y9M?*iliEv@y2w?V1n%oS7b@W-M7DI7mBdvKLD&%C_~^28Ta>kM$0NOqr|u?V zPcnATHzceWANz&Dk~D;<_7S}&#UBvUd-Z+*@`v8#>pWdbn$ycCRrLy*&S-~c3_`Ff zG^6Han^$%+hSW@{2j5C^qdM=#?G-)yFVsYZzq7-!Y=-;A5Z|;+-jFCavTexyn9?T9 z7Slb5=eTp$56d;;nDga3wTIBCAL2E_CX z&h4m#UC>aNhuhh)w|XB#lC+Fwn*^u5e}L!Qp}(=lA`&y9@J6JbvjAFRwdFn}Hd}&G zPUu=_L#Z17=SAyC{|CNo82`E|g5^GF#6FkREMXw$NSK=V{@~7vx;NL46y2sg%>aCU zc92aU@KEmY6pZa7QH5PUV~;ND(^n4+9(w;blJU6$i=z7& zxjxds*gR9oDvT7Z+2HQ#@iW}>3+Qx^NcNinv8o1txjga-M_0Zrz?K>z{CF(}#Q?1{&e?OZN{3M!jGZOS> z$O)@nYbp^w?BJrA!;1lqGJ`Hnx+wY}#BysoX>*RM`w0IEla=E*hMla*de2lnJj>mg zQqlF;n|SciXBl0)U(D^A(xoDH-EL((GWxZ0d3H24UFb`BhqJb`UyXHx^XXbsQHWb4 zo{Zk~s9#Vd5UStVB-pV&K0jiwboaZSGGrd$es$mfFc7i7Z^`TPzDm({eOJl_n%T3t zQ$C=cr;x5c;`S>}KyjwXocIEbFiYrnoKX;2*ySRSE1gXcE2n!e{HGF}*h%)XF<0#Ig;Aj`SGrw zMp~l&armtMI;bT3=~roYtcQyhyPrY>zvPM>Gy701R#eV^dS&lRSC=4~BU#aJdSm78 zAQ9kXV$c~1aVi}^rpqMer3J267bfPV8mw>uk|7x>}MywI>HjKhU_mseVKIwy|U{LNqf21LB z{O_k9;rU-Aeh13`XCfi*mghb9!R7$f3YibaDz6>n%XILJIq2R^aCkapzQ1-19g)t5 zl&3qu_)#Q}2iA8Xx42UqTc@znehUhmu~8}U2FdoUUxdw`dwXE(kT?yb)^WV0t#mN9 z;elH@9s}8B+H~$zyU&HjqIaC{rbrS06JR(Hp8*k|hgl(|;jG(ofE8s;qT!+_=bWs?ZlOCsniXTr84y66Y z-p_(IG{y>(4iczQB~W(@QEtgBcrBVA7-IsNC$7=;La0hnu;lBcsuGVj7Ul-et?nf_G4fllh=oeNxL;A!z5Xf|x z9~p}6=MJ~#maeEvHZ4It_7Q!DzwC9)+kLflB3y=ZxR+nLLXmAnDFJ~;GO^XuD_g`=_c(26O# zd26tu|72l&s{*DcI7ElLw zoM^*zZO=(+2khT$^L+!C@NoJd{!J`cB--q?jEl7(Rb#-#zn3I)zukz@7NchaDcR#J zT104UlI~I~)*I~EXMnBpwI>hA1`Beb8QeIbC-?ip=@g*bv-366cqw=9ot@O>hO1p$ zCqQVrY@hFtt?m&1$SlUj6Q<}BqO@|)Z}!A+2-=AWJZm|n6hePrZ2C}8fNv;9sI(EGv;mC??bCRpoyJhNF}PV)=GBUWKFha=Ni z`%Ftd<;`iOE9cP2O`jXEAv$_7D)WXwsdH$~va=Ih-|u9kOxS+kGHs2tC?h1ImM1HX zmy?V@fxr^a`KiI=7 z<6m@bY`rVR`vk_pEESw#77e{4DgAQ(Io=xj_@yQ{V8hE`Fx}AN;R!SDb6=@|o%3WM z7()LE9#m}?Gm#_^Uc=zp!np+?^D1AE&J^) zD3l{a(s#Pb@p;YDov}z|=;4Vm-||+Oobmwus<>-CS&G#WaSH0>jOQ<29vnE27V)zy zM?>acCQ7-D$xN9*Q%otg9RIZ~2d~uPhfdj+V9q4-~>3fc(;^s#Gu z%{)Bc>WaTs_BK{g9&o**3=3Y|3;~xgv)EEKLJzno!DMMBxZZ=bSG*jbZh3~=O_>;k zx)`K;V>DdPb3hQ;qXw+F+zzs7r`C)k1aj5yc}>e(7i|!X8Ge-e0oMGZT1bRb_2^RW zuI^sJX|WoxNL3gU=qfJP`cp2tWmE^a`FoC^9s-7^v*0!l9ApHx%IBEqA>rrH!Am_m zx<2-i>l^7VMKW0HncPSQU#J8#ToQGtHV^W?+a}{x-0fU=xb+%zsMHiscmSu+Qgm!B%+-1(&vpTJd&{`|-jj(hEY5JOiJ{ zs`hD-e1C&;bl3#Vyq7?c1~9WH|T0}!3TTXG^+33E?F;ILu3b-GI{Dmw7b=jradQ$X*M0^X&`kgR1*d1OSe@` z??>Tf5o;Bpb`r@9^WEi0>e}v%d(FaVJ+19H%^Gy0cEZ%019zW7-qGI&2fr9Ux4WWejl|HntWi(rMz;?+qR3378uq3ELMTXafg!oB*F6 zp+%7{B(NbbeYROzj>YZUdm*&P5z?%MO&Yb0RJRJ9ZVBYZbjq}2PFsj?i%%lrb4Bl} zcNX}z{IC~~2fw@Y9T&w^Fq>IJpMApSJv=Tr^NL=f$Np80AUdM}weGyN{HhJhL2un7e>RuKvBL=xmRLfJMsBc%G8EHmmz8 z)1<_7tH5yKFyU6dPJ@X(U_gD2#*O;3dg({J;tpw@4xK*&Ny{dMqP=f(x@6Rx@Xz#_ z7-O^a$$#nR-OGBIz%0@!fhi8>2cJ@c5SBv^Cp=@PfS~f?X(BsDKs~{Yf{Jcq}b)wl=#O zidr<^h$zsRz3%#jKb#Le;O}_lp-;Y?d>TB#VB_N1V}RoKE2`WROtF8j@AQN8gli+) zW*>OIsCb=UV;s9(GHAloF^*77$s{mA5+H2z)Z1kNVAeh$h-uchFZ*(y*D zdzfQb4sJN>*$a)5P4IrIFt18j_NY1!L=k-S*RCxM^x5Cxdi=0i%G$Y{_c14^_&hNQ z;CPEU`u$>s7q?1;G$)|%i$*%E%ZD#b6y;B_a+V}snoGMrQ4EbiRK|fwCo8=JZn(4% zv+Yv6+N~+|srBzJpG)=0KPq0D$I;v5q;9n2mINe34BviM(s0*7TL7(^on8V>+2iBs z@=f_f3Mw!vhk)37>%+C(mAp0!%%9&#R5vS6oo%>Qz9t)iwFjS zMY6gd&URmn6D_pZvvyv;RrzG4{gvdH^?dw87Qlj*p4k!C$YNC9kz$5*6-*`evLe()MyJT(&#KZ`R9(lL_r&-ohE^rfR$J`HY<@ z$GiYHyo^Ey9kVa4$@KBFii`(d7^51WEEN63$x)I!cvF5>!9P8PNV`9H2MTLJmM*MWA~)Lc(j8M z;Hv*I*VWE^36Tq08!w-;^EC!un1Bkzf-}T}HD^OlIzoo{hEo9DZ*TpGYNe-VhJVd9 zS3A1B!qd<<-cT=c#Oc3i2IA~yCfbjOQWJ+sP;2c2 z+}$CCz=<9c%F1&p9^u#`QM~kV9QPzWAr4_1YG9F7tgR}+2Pn-u{G-ktyQt;uTe+6) z0t3Vwtn|6|_DNOxe^=U zW2#67Hf1@66C!LZjsmxdB>|>Z)^WfAv4#Y5?9jTTjg3Td*URvF$aZH3mB%>wxc{xC zs=R}c>7574yaL>ccRO+}QxjU-2e3}A$X%tzh%p_Zh@rb~)lZ4$qECr=vwp*{S}giH zA{}@!NSFnd)lbm*uzAIA-k=Z2h*;104sr{p$y2|EN>Mexfp2vMhLUlMzlf8l(IhB-Ya35J< zYH!mTN#U1p@2jXex_NmOA;r^!_Meoe>1on>jF zIvcDb_c9@a-BZ_%+Ip5XQWdx7a};=8@H|*8AD{d91AouRoB0A{`rv>;k4ciP`ti31 zE{FUKDGQ9jBIDk=$J`M2vD`27#G?Wy-IBz?NtItqh@BV9`*ORTBCmmyLYECTnz%3P z&k(hA6>ikz$=kRA9*Q>Wykf~|NfhzANeK5-1K!96)1&V%5ZmtZT9)R7em=bPBqB5? z=b_M(zi6a6j8@yy7)J<}TR{CCA8D`Ne>0hgK%p|@EHygIXmMeAro9u_Sxe(=GB9jb zxdig-a&}Y^|^+=u@6Q} zKBQe}9|O(Uu}jvt9oXgphle)GA5=a_Pzyf~ZV=>yaeCbiCT19XK3%rUlNEUnQUBBz z)7^7@S5o@%O!yiAoig;U9%<#x`B#LDJj3y_kr#gV1<`8j1~BJH)`7(D`e>i&Z$><3 zsA^!MqYrN6%og*u-#FN8w3Wn=Rn7Ysr8Kx34Nqtv?k?|xW^Y6Z`WG{O{AzeYHc1l9 z9@?Sl|I%06-P^tz01&r|;p26s7o0zITvbpZpCX_yK7o3`GRHxp@r7sg&&mn~=$v5?P)XErTqRk&M0gak=& z!{rvvK1ACs)tyA3F!LWmySz$XWZJKO=@qIaTaQUJy?RwsAT?(6(MPj%-{9Cd573DM zxt_|Z=Lguk?9p!}tTq=xaVAvI->ahT@zAUJQ%A(co8m&d)2_*suuu1(7U&{^gk98( zy{QT77HHGuRNaA=h-+X;-p{3}BNKSlB;BtO#V1F^AkB*4q5d^(!IRynXH``%F|mu2 z*4NH%rvOFC1F*rXS{?b|gl`74z7H_y8mc`OSksMhuBRzfPkjd_=+QCO(#-)u?j;!= z#%>rM*P$oN0lLkvPper1db2Fh-pl#-L(r0)6P`)5J$ z6&0&HB$qA`Mp3JAXfq)kDZGa}igr_#FF0&%^rk$egrACvN8*D?&y zNjLfJjnhWv+^WoqiemD9!hmyfd!s4z8NB`eR6(QZ{=}!@<708l+03g4s2X`FHDi}r zfZsn%RELms&q9Q$6n}D2BP&d>?4I*sLhxDGsC}ycaW|gobG0qYSo1R~nB{2e{*u)+ zrU(#6krfjb z(8~*At&w$?;RC57mV6Mcn$96gAw6vb-k15kT$e+sA=*j7#!Z-0u5wVXsfJVLcW0Jo z4Aj=^ZTB?g?}pWsyrJmzZEnywJUmyt7ny%jR%%ReyPm&fz|}Ot?Agt5?7*RHsC_?erVc4rr(B zUu+16JS84rLdVF)KItY7)OCz_6OC;)lN z&bW*VYgA<1BP(3iSk*l#df)IfyrgTkz=s-QC`+ncVEu5P4yWTX&A0g4Jgri)v3a_0 zvgrM1-j9s64EhG(3x+@^mp@4Pb1mUNIr@zN8%!~Ol@_;5x9#d6HDg$wy(muV#p(6n zWpsH)+zOr=ZbGvs4iW@M1b9QclQyGX#kifG9xUmh#clPR80dLbKgOtfccUB|{9aUt z6*kKJ4vONgTsk!^vr^lb!5IC_&vYL#I@^!~a{8Q7-}dihSmLh2dwt~;oh9j*R5NC- z1C$m{%{HRjPw?+Zbr2G@v=dEY1 ztwajhmKx>mLN$}q+&T(Fllbq?aX6DVCEZek$e*1m#@TnQinAI$;pYoHL(PIep>=qY zn7_ChD>Mo)g2HaI08OMn<4W!YE{O1t5_3UzP3kqLvXdP@L+0+;y{1+|a=a|cMjCju zeTbn5(#_lldmlr#Z|YXFH{KoO#5Gv4?g}>RsC>;F${AgAICAg>f0l~$~YZoKT~93Wz#t~kGy*25WZ(zX^j=fNd99v z7;{mrRiwz%4C7iahe!e|#RlHE1_;{U;uF*EWa5OTY!ZKMR;ZuiAA!G)Oy@xxF~b{P zA~OmR#?vusV53?)zkFARynu#p=qWQ!I8RLM_ep*2Ue9?uvxbJHjLW0(ZcVoHI6n>d zMbzEXg+V|2m)*5ml<9#E@aw+=-5CXHxz8@#8_od9mFD4yuj$P)<;YGW@smDws|z|} zsd9v&W=4pE)GxBgw0%8e4hJfxjLPka^)2V_xzLkWRp6E#?_Dnnwy?3>;d_4M>daDL zHtkL(jY%FI<0r|6c4Yh(eED~221I)r00V*%SyBm`j=EZk4F<(DF%|KMr5%qbSNvjj zy<2emmD)3DU7J4wQ`k>Bzjy|l3;}=qw9+O!8MCk!M5#uHOyEiowrG+^`f(KN6Eat3 zv~x?yCu?&KYXDv&S%(T-O_pTT(T1s>hRh()2d*9>O|KX*k(Pq)L~>x3Eolb;Bn{v5 zWBC<21ZZ0eEN<-pMA`dGQRrC!5@Yee(>cR3>3XQDQ}ukamg;My<6KhEA&n&atw$k& zLu;&{Q(Nchut6uDs9y$SzErHOg;#_TzV}DUz%7OcidXzfeddYon^Rp)r#pMMEJJ=^ z?fjKEQN;@C%(E-=4d_Y4?o$^0FmW*)y7w&^4{M7U>g)z@nD_V0Zs`k7ELPj;UyUz{-yz~(q`f-dZdHvmq4o(b{<+u&a?9Zk^+bfArC zGfsayg(`Lpn5YdmP2{F}tl}ZEo5)b_V#4^hL!_lXCjbP6(pR&^r&>AWHOqVgRh+D~ zOg@UtZRF*3YNISZAlOj15+F&RjvU6DSCx>S=s_uDJwj*(xw`?TOV|u)x7nWBIAC3) zws2G=*K0YzkpZOS{ahC4|FJd$GlX7wrqS~SRMmcDNWi>(CpDF+t#y25t*xyfKYvRp zG~0%-HG(Oh_40iCDx`K}yy57mtV{`e3YWGYxD1Ub!1bP$L^L*1eEh#D0623cdDLR9 z6aeUh00Rg5UHxQdx911vt?>-_g_dL^Xw)^_^8|y-JZ&ad(a(A&=U@*gNy=pH@%9=R zYWuRBC^|@OtUj+NSu{=Djosq8gxHvWnz#mIf ztJx|(mCe6HNo^#Va?#aAEZA9Ww=JP?W@k25QyTa@iR15g78y&ny1sXq)@ZBPeGajw z)XU59$yTgICBEt5h`kPK%I|dmAbbSQ!GT%CcQ*n7i`>=*?l}HlUHBOQW$KbI{pSW) z6quNg0R|S|0i*690ioXy0KM2g8{p?P-G$U|3jr4?A4;DNyd;0MWU|tuKfgeY@ zjj<2W!H&}C{cd@>*)zM+!Hl};{o&Jey)!BTw^hRC=s)|y{lA<%u%Q5^!2Vo15X|Xt zw7=I4oS6V4oqsNRf28BD6@x%x^zpUd%LRe{_}h?xitR8kQS@8RKmrB^i~bby|C0It zPH5D7ZR~U$j$^prr9XS`tC` z;D`HCk4bf64<5M6)nc8h_~J=&%e5EHdas z(2?E^Vfhe4qwGUPt)qs@z-2(tB_J{F&mRMqG#Np1Pt^AT4qwxMzXK_cKAJ?o845ZE zN{1uZmr_rgA=rqX=`SYyEh~QYX3a$4 zZ+-fIORTbUu7RodPNV%l{7XXc6QN>E88!>JTn2h10%Y44K-Iwn0q$#h(E&T&rP6aI zP^cV3xo|fl>8KlFPV{2pRCDGfaDgooshW-}nRW|!`~ee$p*b_a#T?vd69mFditx?Z zProH48Fpiql%yJL9qs4VK%g1=3xRn!;DyO|4wB|}r$+3>;00+0?7-F?(D$F_Fet;X z1IA=vSelXavAAvU-^=+FAv@{;rj6cU!RH17EMmXWYpH!3s^A*&0@EG}F_Bn-f4H}w z@ArAPWWy=LIlP`>8;pRL-KAF*zt=hPweBdMdxPg3977*MzeB&H`gL4L=NgGM7oucHv|<3trn$I)n;#To_qht5xr`6v+r&dxS4QKHX`i*!%Nm zp6b3ZJ%cPzZo9E{WQH7R)D_S$9=dQfmar}Hgq&AsUl51+nZ&Pc{FAgYJjgHae=Z{t z08aa%Pa5JcvEc_@D%L^)xVr#$JK&NveYIcjHnd`su2^)xxMBx33i#p{@NR2nwk@et zn0-b1DBOhNx>oyc2bR=u+P4Zi0YwDJlGfX`LI_su+&Te&H1e%17mj^PDBRxb#`Fv! zoqH1sdL0y!lAq(8&T6Qrd*^#&hX=MEoYGGC@}u_c+EG2*Gll83^K;kM`*1A>^15Z? zwnh!>!H*ko>bbWY)c^L=j9rABAThDCW)iR(ty7Ya>HJV55GtlWOgl^YSW>BBq--chZBi10qUoksLKsf@+ zV8N?LKA6Y1mhY~$H&e7*xNB%T^A;}Z#fMuYIqBR7 zmf-7Yu3kHIrBKGGs~Q`MRBf?IoqI&8CJa;qO)0dy1f~>`D$nf)fjDLzmlD) zzKh+PCKNTwk~*g?_)u}?rOB|nL4pfi(|NhR6^hAAjh-p+s-TUvmcr4_bP=>Z$M@3c zvRcK??VsH}6_Z9cT(e}LRY8vjpOELxpL+Q>rv9wl3vyk%_NanN6 zrWWmjNoAfPAkYdu_U=bwbnwxdgwv>g3zT1Ja3{X`ihmL}N-wBbkT}zuIGW5>sC>>eXM&`XOkqmbucq;l&p(yfJjH``X)tNe4<%}R^k$ioU3AC zmda&iOBe?`^Q=SUu`9#2=1Fb^`sSheSz5*Q^}aqvvofUK;#Os*%^E!k`@6KF${%hn zz&W6q@Ongt8nxfNR+)NxGD?Etb#SnjnLtG#_mJ7yh0C6y=KtwY`ECm<--a9SXZt0; ze9(x^I)<9>n0IXJt+KXzn~TGjxhb7zCT##V))3P&m|RrDnJG(5fII5#&hcxbz+&M2OCxqZ*@Chy}qkNIRd)My{JZ;i+Fw_>do_{*ub#}1gQ)Ior zDwrm18VtE$q4jh0Are;77@E=)ayir2%F40cC~o2V3qsQetqaGOd@Mv!dT5^#_L|5m z1)GH!p(RbDjJzgW+0aTWo*2N_di zf?I(W^XT`-{nmh(4o$*;c zQgz(91?r`!1TH&K7gWH$wcPJ-Bd(n_Xc+o4p ziI<%Lg1Exgu_s1}3(^ipoQ2C4t_!byI+wT-5GaI#HzD1O7IeMN2DMrA0R2kYv!k5f zCF?7OCuYCfTbi1pWHTVqqw-ZIYj3sLM@kkSFQ~c-gJJnHdB0w6!*>h!Caj4}c!z=Q zq2`1_jem*b76G;(&UkEbr=%RL8oVEWPm>gBOdstu~7Ydp8EX{P$8^9=q ztDj}U--!@`YbQ-epMdLyBkb_O9bl{UasADofiLtf+`4TN=Cfs2@7awI4U~fPo}YTVS{* z+#w5A))+EC27a_Q4TNRhmw^=-cobO?M$Y6-TIBv@LAg!OO(80XH5%7>;iK(r{mUPx z7ynK0r^hHXBhdrbTx9~~9+OrEBhFJiIQM;Ga1F~ulFd(&1X|=+^jq;PMVVgWm6TI_ zz)?Eal~k^)>p+|T+xNW@P6_A;Ik>CX)Q$&%Jezg5bc9+)=vg0dXToz1$ZKg`U8)K9 z&B|d%&GOzh^&0Z-m5@`7`&;tzzNFS!3DBF}8odS-LPa~{L!$=+M1=+AVbvAnu_eod z|J4+7ZT#k-m&H$WMG-Jf55M>U?&cO6PJZ`3A}bkFAi=YqRbr?7mF<&z;lPR%rwdOw zB2>^VhQl;B?Qy7BzYyw8Z>>;0>EBHswh=kY2@+H!DmMmi)+-yIKCrKCrH6=|BXmo% zD4x>UfSf&-5XXu-+FN3E4cTweEepmdRHm35)hh1LGf!0rfNEs4Yxl?b;XUpoI|+d; z277Q_92J6&>uO+ane1HAp56j>Z7txW>#HD``QAq8RPfGXk^01?Plul=W|ZJ`r<`Se zQ>|iRAn7{jF+k3NM{zA0a@ijP43Kk44;UaM}PN_+h^TQ!&RwxeXbu^#0NAR_~ zb0J;i{6#T}Dt-WH>y4T(B6sdW&_Ko2+YWox#2Z#ZZg1vtGRS0f zk70dw)K4i>7_4J*9BzFvjhI!)gg3!92)BL<4N~q@7J2(u^FyS$A9qZ{KQit$CnTbjpQG~B<<=2?; z^GA3?BAO_fg)RCYuP2Z5Ud+L8{Sw!;KibeHp_YvAPN@Uted5?Ah7L`dc~Aq~)WF$M zwHNKNSEa))*Yao|>_Sg1qSgZ7NpAF6)^)6>u^5=v|MQ}1IQenJ z@>M(J%W(3r)BxV1CN8kt$w-;Y$tawNJ^KM z@%0L}p->mnWuYdt7YhE-q*?PHgnU*LH=7;(Rl{B{wKK>3DcN0CRE6*%Jn_LHe8FgY z*+^avD{9n0di=>m(NaWzy3p=0CzX4TSZla*(#6J}g}x-%2i>?Xiz3)<_|gbFFMMA9 zKa4a(R?VQhV5@=g*cV7qZPafW_LDDNx$EVri=3NXAD`?exH&l5-Wd~U5HWZf{u~%XQ!l!B%Db?6EpMF_<$LNs?1UKuW1S5XBBttL z*_p!;*A<(aGEd`09$?Wag_*G`#=T%zsor%?c(#1iO=jmX5^Ho;T?m;wu^*HB4~Ijmzc<+$E%M1{e^kz&9HdKL)Id5Ezy>Yi*36DwAX)7_ zqc!Ms$Apj0rjUGpT)|Rp645EL(~V!BQR*2$@@t^TKDPu z&EMW)A9)InQ(Q%Ki+UC-k@p4uv9Kl0)mzWJPCg>`MJO(!;AWq)92P3;5f}@^AR>oM zW4i2ni>jUW5=&Op^#4TSN;twh<~RdH91Kgje#n}WeKuMIEGt*l$4YuzlyPSwEDgb1 z^h5A1ZIrruus3}%AKG*UYsa@+F5qs#GFx&GZ%ogb*iP-R8MF}#Dm<6;mmc2_Tf8#O zYTRkE^%7d@{zi<~7@p(g`4;sUa5WACX+HsEu7uhpLmosXhs+*d;n1XmUw?@e3#yS@ z>Dti&p5ju3VmiPay)X>kVFmyzS;N)An_9lVYqCIvkB6D?immyWAS_isrXFLu_wl7e z>&E!A)HT3ZWYet{F4dWtZ%T;Iwt5yv_*)5T4Exd~sYBPLY-9A_u zdg2R{rGet1+ULN`vFN{2z%Y;k0vtNM1i{(TnEEyR*Jpk=jWD5D@vZNr-SOk525FO4 zz*_wCyY1|YxHOA=ZkgkG5WJ=aB3}@%@FMF)u*lG zqyg5mE7o5iMDt>-UaKd>EMZ)#%)xNw`>shcklNMX+p}F!lb60jyH7x4(r$2Fhy|`a z%z*G6*DZCE53^Lhdwk&KOY_6gf;G}7uj2)mjISMcY{Bi8$=+|jn0!mmRVC#YdBeSA#zsKO-3|s0U}_Z5@4Yn+f%<7c0q@WmfSWRgLtooO!n4$?T3qibgoJQ77iZj`53l>xk?Z;|}$9< zl@oJ?3dp3dSVqV#8X%avdyFiE$ADlyD$fJ{bqUM&kxvI}_se|k(|R~rSRrC~Fupi% zV8cYBYrxA6qR6jwrbfekbDkBYJbNZ7$wZ<&t6d;ieL zu?vPim<$SK3P&Jd03j*rfoBj6K;J{@fJNOG0CT+cjV8Oq1&P~I6i_W=n3~B^HQf*1 zxa^25&Yt34*$8%%iOdiMflj(C*RX`QX$T5<2r&uSwTSiUCa$HL`kNj%3UGXrD| z#=PqsH|h}|Qf1m60U4OOIw#{FffL0fF)oQWXehhZsm<4|$D)?#MgA*8_xs>ZAy-R`HfLqq&# z+X63V!pWi)o5dSk>$~6Lg}i;f%V`IdRQ-fu?XLZ^C4H`(zMc9JcRTeu1YPQcl@YW+ zK5PnjUp!vlhj$nHGKq+v?rSNZ+l{YM`O#z>e6lZaJJgDi^pTvg(E|_k?yy3k;ze5l zaEE}F`K_+eb|Zi8E*QthUd`Kg_}-PJzFyP ztGE`T6FJSdzB}%*7RP+rV!owcWuv&7?YhRrVc0*5MP*bDe=@1@Gr^Jqlx6C*>^)^E z6Y|s2Yhf?xj2yRA&$^zfUI3b#6RBcc6BgJ=>RVEAOE2P{M5-Nw_ z>*cho^S32D0ui_FPGs z3+!&AwtNt2rX^#=<)BAZEEh0N-$4FHf6RT|Gj}wNc=P)5H75KxrCKBVD`s8E!6Q%` z@m#d$Q1~JIL@BpMFt*`S2q}1CSnmrap>?lOBs=41z!H%`aQ+iflVMZbq5>!&wiIcd zTdHxTvJzm@q&5&-xoDuT>RCW3v(#P7guieM&L2~&K_1IJnPgfy%#Nz+H7+wc*RV1? z7wVSPR8=%#uHDx}vHG;#gtW)OSBQ$?dotF;fpy~|syC>5@-RM4H=_xuS_Vur?vj;t!WPY2PXUobJ%#7(c_xh%9W}ObvwDaQocvnQX=gp zw$ueP_mF^i*om7iT? zx!4wKe|N+6wW^r@g-$9Xq{P8ww+mAgH-J8Q8cxRX1Hz1kfqwA8#rY zTcve`WQ-O98!F+J1wsx61n3cc-tUrIMeWR0sm8y$rz-ahxOm~@#eZPXbLhNlS(#H^ z2gy%*@{_^Pt85NvHVY~)^uHW9%9irYoh;BL zRNKE=2>SG)gpeFjb+s~O=kuEtx9A?+F!#hLjXIvWI?=9|i)>B4v@#Z%o9Uo69`a}@ z)!+^;$ls^BV9~nUm~tc(4*Oja?9KdLz+XJ)a?snDA}W z9}eOre3^mH9K9|A9c=w8%}qAWjpwPGawf19Y#j-ikhZtgdlk9=$kQfUUit(kz3gZr z{axRX9WpSX(iIBEs_;ySN#C6z$NAbk>+bsm?r`#&0N8>#9BA{>4PaICZ*QWWny+yV zNUp)e)d%f$X5|m8y#JD!y7-wC-9&kO3|CLm2ZJDJQ9m476FTbIT*qbYV;vndJz~# z_&ZsWoCO9oYbiytH?W3SJ|+f;KM+{)Jm%k5Co0Op2HP(lpxC^?E8 z{AGR(_a4~TheM738-?viBqGFhNuNM~8eQ$NX{LaE3S)@K zuglTuPZOlOnd?LvFmE`AbR<1G()gGC3?j>E5t;2qf9g95i9-|9hydp28zrQeWLyhGItmsIhdgLK`Du3 z#pYEl6YPf_TQ;k6(H!I1=Tf>^Q{%sL_B`lIZGS3)Cv|gg<2hq*L2H9X^}qz@e?CEz zeaKljGgY-X75OmDu*Y%oAd7Pr3;yOAaxV9eccSeFzu)*!`<)Un}%}7zv7Og;*#iw1*@3VR^0O= zBD$Z4Cp;Wa%hs!7JJtiJ;{Cd_X9+8wAgXNFb&>bSA8o$Bsb%8v=_%VT4<1Z~Mm^Q$ z+q1Q|CwXfN0E5jQJ4P}kq5iZ0+K)AP19xOr0JlH}UB0uuC@W4B#%S|bVH^906SY~# z?BeLOZ@0|C))pZoBctj{*lm$c^=FDkdv<^R_o)405OW)98RbhL^h+-AWk#x7);98a zM|N$M2%M9y4p0$%&q&*I!E4c-3_uI%&PQR~KJKMjyFF3ghbVpbvJ+N*;lcpgF2IX> zPT+Ik6zPlvY;GhCYq$?9`f+OAK6rg?w0m~Rb8*4z@$yyEbMOAe@!u?PZ&V~3CA+LH zWlHvH8F|6~LqgYp-Z3alLWVXr98= z^n7~3`UFn$pZ^z3A|cCFYH$g;H&Ec#ZU;H=H5D*BGiq0fVsqw;KZU1ljJlOAHaJ+m z@~f)Ftmi+pExP|%3p4MX-WYBLgNJAA>>88wg}?j{)Qn`_sNKmQ>e9_oPUiLb54HUk z!U0*@rH~!~pZKe~??H$lVA-HcO`Y1ev;XqC-%K4_UFR5@|I3ko^T1TU$4FEK1i?b+ zI*Iy!{dLoSpek||APKUj3Q^a*WRh1-7Y+L#c?ji{6xJNfcp!6+8E3>^;1m zV_$b+$*^}?^MIrL%B=N1jL+rig!;}uAAK1;+GZMMV^mTqq@IvL{d{eaxH)s8a19sT zGPOC?I+@z4!N^atP&Gv|lOk0!L0+<(F=$ znVI=rK5M)C-~Iq%-!|>H80pUW&5v!cdAbMQu>akJN zRDyWIA1iYwllEt+{$1$GhRq=kjcYTx;oZs`5wcco)%HkeWtV;q34n~ydfQDbtw*Kw zbj=p@ynRtR&p$8U;wbUPK+0*(s!^<~7ef|CCR?73=_K!?xwAapVP5hDLeDXDDo+8n zA;tc&%GzMG_L*uK>AmsCPD{5!X*Iv97H5n#do|N<3Xeht;^r|L7z+HFpQhIx!ff*M zGGUXlb!RRa55?tBNJU>zY08U#ez_JU$nC-U1KRf$$z*;s%=_0^TScR`OQzfII>33B zo^+{4Benk5NG`K>mh^Gk-e~Or?mOA+1*HU<*6Qkd;sl4Gr;?VXRaVqLzu!*k$Y#jI z7;18$-2Afs84R(8Ouzn!R#e$ZB@_3mWnk%lwlJifuWA8zvdDw=Fiys zUAOn-+Z!E8-ID~8lz?Z>Jd2&RJ)ft<8}ZorJ;yMWe{;p@v#5!>LuK{bPNcx;!aelr z`fk<2RlVX`h%|val)Bv9(o=&(mQ>7cH`m1R$tuXH4EQ(Twtoy;vl$t#*e$*Qu0_x& z%VuhHB(d)Xn`fJUt&|st>VAMsZT!*z(&~%e-_ESu(~LwSipyYAZOq)&=s&VzJvhpw z?+^gMC3KZV3KBd&wNqV#K~y+=q4j$@Y#u1WptPYuGml4i-b~aed1;(+59L9XW$iU9 z0CD?)SWqn1go<``h*F^>|M8!6C<$BDunI_-fy?=$e}qXgG!#GT3cE6M=DNY9&KFY$ z%}(5qVa+*rtf}(}i|(zyUyQHcg@y ze>4U=%|gTIH7E!Rt7$ufP_vhKOE5}$=#L7fMMy%oYAqw*`x>tlF(v1>povsh^M{#s zhws#diOUdkI2#S!sRu5lZLk6b>7u5uB|8d-KqVWYCG{Q}Y&$Re+BN!=YUzy-YhYy+ zr)wo-3vDtJTmtX6$Tht0}C-8y+=$!63u;?$+ z4K!q_r+p{8y!V_egSm#A>Nv*mYN*$oPtZ-|#EyIjv3f%8lc=JCuUd#ScvSVUc$_A1 z`yLQMnDEFNa^VFc9JHwmed5lxu^wYVcUrh9+RtCWmQ5{vP6XYw(3TEDv{%9UkaEsAT` z4U=*Vr$MzQh5?s=(qu9>%X+d!+O3822iY`tp*pa>#8h_It zOmcKF`^|H9ZP3L$pjgvC1Ua{*o|SeG|5Xd(Q()e5va2Xtx+rbZZTPT>{}>^L2hR{% zlBJhoh_?d^au+3`jBP0@N8W6-PksW5et;fGk4u+1bo}`Cw=2FEm(*`1egh~1{Xhl? zU{oM#XYi9izDq&9Hg$7Ozhai#nD8HZGf^&yb?k|ngs-JeB&(_ikHiD_7FULB-<2x9 zI;4*`dvoV;snyeVADIUq`6JhEQl+6=n=rD){@wy~dseqoir99BAbs&*^d&B3MizkD zRk9~w!5JH@bAfaVUQA2B^WpOa4$WtqwF&AaHxAqF1iO5x7(?DExqWaY%dGjm+m=s) z=|gk38J$*WxH_Zgp`|~iSM=eA$RiyrhvxGq4zW_6hmOI8z>!;%fY?<2B{pRw)7yx^ zg>(B$QPkih*ik><@eC+4mo!Us;E~<%HNdH77GJ#|Iva}3$~G!hvq%2zpW}SB8EuAK z{$7WetHw*lbK-68x?BW1A-9wwyoRQ!yW|JAwbf?T8@03??ynhfcf(`NP)FuUlvy5p z-eCs0^opj;ANWA*3aKjk5`Z-03s8SfgiOvi=ed*vU&u{qqF^{1S!u@0jtyob&$4$@ zxd4|-hdFg^(n_N1^u7wv&_9cyl~HfZBJv2b`y0?l(4Om6oxT9xVd~>`GH>6jz zdY^S9KUnec5(e{Mgq(Mp3QScOod?+YG)>uSev>zkVKer9c;DQB^798@x1b*4?k*J= z4FFuXTKNNd%^|$s zS{ajZt`|k%Me`g#=!1Ipy)5R}BMQl8d14$Jj586uyYZcDB=Z}eZ1E*bc(3ZN=TYC6 zM<2~Rnk~#;)KBP%+0!g4LmV>~s()1#>h2gfr!6M^d6Tj~5e4!vnqA7s(54je%*+Kb z8Yje^r7aiLEzD2O+^-fZrjc~{N{odtvTuBhVzGTbxrj6!JHe0Hh;3C`6oN0 zt~K5KbIfWtg@sGJ_4Q*Ow~WuCb+LvWsG6XzjGlYJ>&_<7Z3fM5OE#3nHaNti01WWL zH8#ffwDKP{B3Q9F4fFR} zt@zqY*vIslexKpsjN(r1xa#0=zf2f7J_o#f9R1+2W&$otF`;GJ$CGRnbS?fYn?Yu$ z5<~7G=@oCxFFn2i%bU9s3D*x2&^0NRMQ<hgG%pT zrUvzG{YYOvucB;$F;oV-q|hzNX%=;L#=!hj@kO8aDq>pUYk}H_2R zqp$zz#he??*RVb4|B%ED28de##MbkS2xaBT(#G>d@ds&NU^8E2LhrE3_Uzg^1d4$Bo#o>V>^-|p14qK{ zwz7lhA!U{4zRRTA2kJnf%B!U_2Zv&04xSv;*tCDssSnsb;dRZ}Q%hnl0>!N*&EdDO zS=EGec6SJbdZBjve%}4*#=0Lr0rw3_U84e56mi|1_99P5puEpMsO6{lq(6#NUy+)b zRfV`?XmmqY_=oIFp69eARztDOqF&s z?xf`$D1XHZy3osb^Oy41fjWP=#oC6k3_0b)`A6T_SiZtNEjWb#;5pbQC#S~KogFkA zyj%YMvGBBB-x9A37RtX{P2PF`?mQw1kW&gjada$;!j|v&OyRoW0D* zLwIeO8}fx0-yc&u5^i8u+vhTtd?RS$TzajHzibWfhEPRxPJn~MH{0UV`CL$CR_s#7*;%GE0_zRLPu#D`3(k(0bUJfvIu_G5dJ9`jb=nLW+ag8zemm&-?F(i(BI4k_rsm59#WTN`{Poz2idM z7PGb2;e~(zQT36}xQr@CxCo9_{0tv{^XTNwg#7IGxcD=Jt@=TOn?m61H-~33;8nW2 zHhBsKP$HXN?xf{HvX7i}$I5HppOfY1z&iVWFLllC0HvW?DH!ASy4xR>o_=sAx*%Gg z_6n$ezF*)iOzpwQYF6BVW2_Z>gI<-tQtH3$dfK+kukzqi&3mSS1Byf5%%J5B5VGt| zK!|CINJwkR_B1U-CGz$ocMZt7oj3bJ+C2eJh)>sz%-XCS@Qzkbwj8{VsOXcOePDI* zt?>M3gu_*A?0z=5`{JUiuCoFG@3A>()<#KgvRybe`E!g-o}vICIUW1v_rYm5bn$fL zm!g;LNJ}BkR>4O;!&qFtUE#ZvRk!&pcq5G4ctM|g88;hlj1vv+r{&(Awamy(syh53 z?``uPOMeBt?`!l$7*W_;G&1+QdA4N5NaOnr>6G!zh)`CPMLn*2*7=9(GX5vMKBJet zTqkO8%$+CRESYRxEs7;u-s*I@!k$>}c&%%*7uXeCJ~H=czLWuyXnRw6b7}7DEf2gl zy`KCze;~+SNWRvRymODdEzAbC0O06M`T!iMcEv5%>lRMqDcaYkUxqTRFjU#xqFlnn z@Eu0+EP6TZzPg^sWpZwQW^;w3Ks0kIIb{rYN z59^q;Q94HzWy)9sJ=V*!TUUT1btbu#+)PAJV(nRf8_j<7tmN>S;qkM&9iYFg`Nph% zg;nABt;O0TBe*0n{85B*Po-Rf(`tygFy}{4vvo<~UC+(iw@#0?rCiR0YdIJfmHXz3 zUA#qeA6FH29ZG2P(+o~c8>nA@_S8MSasQbA9#+*p+V<$^gU`0U{3dN7q`tSml+VS4 z3syu6=EH6<;aMJB&{5Y(^G|I^KH?MZmp_qzf83mKE-jzoH(M|C4Hj3bpT@@?)MZve zP|@-7x!KARk`wwozFPMTH*+mr9}b6H)R?n zqV(-1T!|`;H0oGekiqHwi?cVP;-QcGZM0Xpd-{gR2^lzo2**L9K7h8fuRoEig1N#W zXR$v{e({val8?yX6m!<9oYVt>r~ppIy97l+POM zjUO0ux2koIjDvo89j3d5%X4b;u9W!`oNe_}qvt~rZ(rTMr8>3coL=wKO#YB$b!KVr zz=sSMkCviFs%^W+?B*BY$K>kOw~t9SU#dL{_=9e{ZDbuxX!%jS6TRBy;!;%RGEX9Q zYqH!eOwW|SOskL`{^aM#)3>@$oDI@e99wK$nV3BYna$6LX#(HoW6Q=IS}HT`Os%?W zW|U0i+;y-Uynprkf8&F9?Mscm^74||*ZZ1c(BzhsW>8oN-#e1x6>4ed_}cUAic6Xq zmSU?^o_h&u^K114NzS&t^1F#NL#*La(Y!-Lxu4R8jE#NP=U^80sC+fq0*L?I#Ho{& zMg3Z^H$)Geqq=q8NS{H`@{4npqptv%FF+AZpi9_TfkVEP>Y|*fPfA-7Tvx<4&27&q zct1J4uL;1fX9!E|Fd1Q|@Rp&Q(u0CcBK|!kHdIy4w%~0MBg#H?Xnp*~A@QGCoY|)^ zjV!971?tqAkj$5kJ)R920`@n5)}H33RAekld5ubPeo4hO5Z}5kqr?syeDV0bVF8^2 z(L?aP*nqZ2a?+32$4l+1oZK>v>6&QzuJ|?I*X>8jM2yY)joB+z*rmng)2aFr24c_H zkw}x*Gby|3_a4FY=nIGd=lf^J+BZuR<9ZEZ8?UD|JejedbUy`&l+tr_W=;Ys&`IYZ z+s~tCbfweZNIcVxwe+g-@PH0f)##%m)jZxxDD&*~$8>Z6gQydofuiTpykn9dr>?a4 z14j@mDPAv!*kzY~Ew5(ouFyByKnoCb;S5l5*vcP=YnS!~e-m8ukN{u~$E=+Hpa=8| z-Z7sSQEI18oaX7Iam8BbSt~ILCyLLoBe%wi_m(=V{6Z*-38eS243NT0p4FZ$8WH!s zlx!LoX6vVer2|6NS{Y)~MaK?4mnK=o(-fhLr^~jdYlsua|BUnZE&@d@!chSQ3bneG%lU^asz~=L67BTGUrV6OYK>AU~n2B zM)z`Oj4)?7dD{0O+^Vi&;i*w*p?J5Xk;;oPHu`#ZD{lM@@H~3@Y2lcxFZ9F3m$BBU za}Q0D|TM9F8|8htlz18lL?-HUF2drdlS6mIHeVnW~dQF_)Z8W#mjdyZukV2k&nKkUgZb z^CODvSU1L?*e9nI&V*x`o{HTQ7yMxm4`rxj<%mD^PJs7T_v-T;JeAlTt=}CWty;=n z^PVuTbFbuVT3{fW(6ph?AKGiM-Bq>QTsb>;VD^I7A5RYO6js1*XCF!DeLH^mxBq*A z!V#-VfHt7Ab=gKfl91-&JO?0bZ?@ig=lL>h%itLNiR4I88llIf6n|}AxED9tG}Rp30S?`V*asU zl_s3rtCHYds=?QozgK^Gay-+2p&Y$(hBtLjLQ4?2V32rb7!S+d^wvI+oX~kZ{r;!e zqh1F5k%O-Ibil~z{@oPz&h;ecX&;5%ux%wz?-)l;djdMDwk-?l#g-|i0a82g7vauF zawU)Tq&D6*+48ZLv^3&FngCO|JAYu@H|Cw^N{`y+T|&S&A94TlZ`j}1ZDwxgoL-#P zI-htpGoph(dpOag+548O?+sy7Af3^R+^5f;NnWNru-XhW(8lYfV9?*oI;2QEHjc_#T8L{B&dI1x@XjWnI`B-@RXHb|w-#dd*mZcH=r>k*9PkTP%ZloQ1+{K`N z$h$-dfUf+W&&|4kI*HPaUD49UU7FiTMdlHq-;^1{Hof=*#WknKnY+YKntn(=yK^hu z)%#a(%+j?C{`w2Tru{6@^hG)4!glXva{_@us! z&zg`mm3~_*c@R_Lho+E0=#G+}+kdr#g~`$%7bLnhcnssqlKtzd&sB}w*rUXLh+Qt> zg_Romgd<*)CiX*4+D+P4@<6VNcu1~;C@?_odximb=(c^EPj%nX79BQXMGd$2 z4!aM%sO9?)!O?z9D7>J8# z!rt1Y8#WT{{4a2La6or?bkQjM%GUt- zt{&ewOAdk!C0Gh@?b-vtts94)6s2Dr8q#2nZO-u&UoK}^(7jCNN4<(q>Z;Un$Fi?v zvNNw|ODHA_Em_K&@RoTjRdErUJ@#?|mAch>AbdOxSIHjx6{G=oBBHo&sw;#R(DF7o z^#2g{mSI(XTfZ<3k}BP$bcl2#DP7W~fOL0vN=Y|}bb~aD?(VKdH;e8%x9sQtoW0Mr z-|PLdKCCbI9Q7Mxj+(B#pWXV2;Y;X}(;sVV_)H0_2II9^{Lm)8rk3J*SI@@{B3hu% zPI}X2E6~K-KO0&2K1|PF;6gmeMsqW9%^p4YUd~8R?HJ?{7Akn}bL`e}{GOAme^~A# zn|V&4)rd^N)u&!3)gi%-LKz9}HHiF664F15k zmDN#!RYHtBsZBM}oOCr>Y@)>4vEk%bWgwB_l>Ta&rN9aVC;&d8vUL6hpSCrqgexgC zqzLaD%zjf>74`vdE377@+`|yjuQ(nmf;s zmnD$vx%4e}7w?3wALu^t8|I}5VkdA~LCF*zuK7y`D}c5B#aOXPke#9UGSbpk^w`4B z(YNoLH{Uw1Feb2v?}-+L$IPli5$3e#AG<;A}^AhyWy{yMczsEH!BdHoE=?|J&p=2G*MF1A8}F>~GM zmaPw!I(XyM+(3{NXxjte2!Syq6tWZhpn=zFXeDO~hUm)6FYMq_TV5sjg2MR)PUMp! zxa^@9v{JjPu`aVBe^*!j_1S~7yfqQC0+*M7m$_@j5nf)D zV&E_S-j{NGtI0L(4azJO*KA4vC;t%kw0;R*9}Wb*)-(yGZY~6-5tZEhQ8WnWlW+qi z;#xYz9~%Ed%CF;zObp8vT#wDPIpp+hNDlAuXWsCrSRQWg5Q@%(re+3(OrUQLh(7%B zy11AyI{wlTR~Ji|kp)>k(H0zaZO}lE`c|?C2Fu=WADuV*s}dgp<=W4`Lh9mAaCWuv2ju8 z-0;*00^`&*&P(_+pQDJ|jmzteU+3YkoC}oEZg7+<1l!8KLSU zpSF`78+eH}44vZhC2_@$H;+E50b?R>OEZ4gX6yOT=B7 zHB*_%iuK8vT@i3HDe2;$B;uUZBTk>_~UR_Zcqg*aIM=`nx}|Pe-pp z*_l8aP5q7%+G;>lLQ@{7Q1_%^7#qDqMeVvr5L6v2*|ieF(0AWVuvj2bGlECf_=GKKxVo#F1o;{aERJM9_qzn2{mg;{i`u z=Hgk+5KiZ4-G=G+XNEphg)-1a%f&s9(!{lgwH~xktZASazWuT1b!3hvkF=%|<;tzi zOgDDZ&!?l9)e+mBbd6JQa;-%P0F~qZn&LCVgt+onf`=PG+tBC$LhkxJe5-GAs<>u7 z)#SuVqJ{lA@5`;=!E-j-c`Apz*>_mbP$SXKD5W{X9+$I5<L*snrIWPryhm$;v*EQ6&#Hob-@pysUbxaIL zJ=k0qe|EGR}(7sn0on38J&I??s|3Ul!odHS!Sv^62erx&aQZcx-xa$~C z2h4-K(;!Sf(Yo9it9jH|l@eXJ(tGnrM&!#Yv;nxM1Jah+NZcL^mc+AM^Q5zf5`8IW zUCpm7_J8_CoIiq6F!O&8^Ny-dao0>)_9|>*efw}wD zXh^(jX+mP*wC4E?pYZ|J#1peuli5!&OS)Spm?G5MHWTp|=*7CCRhbg-yW6B^KRBOP zp_)B9k+O0|G`TYEOXa1{u+S~mzt~ngrKj+s=482^?7;oq#qS75YnxDW#fz%Iz9qGm z<21is+zi*`vgfR0&3XC*BK99{kfQdMtacaQ<6fX8qeU!l%nz?6BO7`~;mGa7B=~tVglD=Puc%O#yo$&;#O^Kwo~rgO$7>f9nl4 z62JulI|unDsJ~EHYNUNJzjLc5d~&j7YOkRws(!7(KhT}w0}&ctL1K1y^~a($z+ zT-l_?H;yzAYUs{8Bg!P;H7S||G?%Rf2mp~`-Mv&T7hBqo8=U{`NY!d-9%3DFN0Rr6 zalNIRnpi5DA!$EA@i?e`=HfZQzl?{Oy>~%Ih!9VL%be$%11xY9kQMO^1JY0rLLIG@ zTQaz=G+N9yy)qa+`C=q?Th~sGVN{kF$=NZd?>Qx3XV+O{TQ5~MV$_v2UPmH~$`YjP z11TM-i1Ig6r5$Y|;X?rYfU+w_PO}*KE@K^WF>bv<9%9>M zO6|KV5%A(5A$cDxF_XY=0n1xrKQ(gowP(rai~X&Mk- zlqXO+#@J9jsJ0XJq#fGXmf#V^o6kaPW*c`3*nUFe!uZR!=|LkS=6H6lRhV3pZ;`W+) z<}O4unbc1arc=(I_O}0KN8Vp*Qi{-)SYE98WBks|)SM#8=d_4$>c-A3ci34G8$W=z z|MvNyJ^b9_2!CmAk*z$0zkxiNi%g&WBEhPgi=g5%!K$p#xBfwgN11xRj`9XZ&lR2T zL6lcAa!ppJU+ThKd5Q5tTyW@i{8wDKcB&&aOt?pFpC+pQ>MChXXWaZ`)Bdn4lus{c ze}(r1YYxBtS~@?Jm#-g zb*VU-`?R@yliAXl1vVfA6_)otN!H{Y*Xj(dui46ik^p}=&nN&i#MnKj^tvf3jM-&u zJmeZj|5XaCK$K#@##S1)&7TS9Pfp-#9A>l!<)*cfX+zc&x=&)ju34MqY{?QU7{3taY_hQwpbW!(J!sVN(#bH`?;% zQIAD?Inz@J-~HKf`_~u%DaTo;Ff&yRp zKE}krpR0gt^apTajELgf(h~xK9UVNQA^=jhd*SuYWmH?|@makeQTNHO%4vMizs{6M zwn;DSbQA3vm(w_IJ}7mn{lUX?9e?4~>q+ACq>1E6KlYORMAFS}do)nx`F%jJkXLHV z`LF_$bg(us@T6h0Qbz+M(?)Gc0I0!m0?`Kj4{8Ro;;in`h-4%LGJ**vCn5?v>tU`J z=IIuuvx)W|Bk%bhGMn8kr6^51p|t6L5Khq`zV{J|6A?vy!%d5~;zRT1^_$-@c#0>l zLw{4yg)}}~CaQ`P!2D53&Dpil1Aopf5zfyC9VdH{d zRhyrVao;(iylzX?3T8)HI&d$hVO^%ox#ESKLmid}R#?HS{?&Y+$XPlYaOy+S)q!|! z$@F2+b1ifko9+Rm;o-}q%kbAFup8;@HPFWgwk4*pu_pC>OyBjS|V4y$+`MZ`3E$o1OYQfz#Az zT>Xful*%yqXMbLGD211~H&dfrm5qyu!pF1UR5tnMck+EXKZdigFlT{YNT5RlX=!oL z<4MkZnm*TIl}UR&s|&A9p33e_Hpb&7rnqyYv@?ZWHrKtlg6+ky`NjVs56a^3$Gqh6 z-GqoNWZb2H0}EspNj~`#@o+Nx0!4G4mcUpeFY^JB^@2CvF?Svb&!czhwAJ_#L!#c3XPc z9{A7_4tgWvuCQT+D${VdHJf0$!w<1XD_75 zy%jo!;Xxo$(u{gjqUEddH}m;xqZ$1NDyKi)mWaz4|IUZgbard{iTC0Ism;E-BVJIg zHG;T0!Uc+}a; zOimZ~bVzB(L=&)|=hr1(dn2~`OSJ`DJUi`;+MixMO;E?cHS=oK|*>eTy= zFq;w**rTHWFj;jGE?BSg4en!|=eYe@49e#H<>|H7y*TW@eLJ^>WkY0@gfS_`{jYy$ zMM`$2T!DYD#*_z~_FDCusjfKSOWnf1E+dz`G@s}-?_Y=9kuOX~SX=|3o)B+=i zW!`JpQ~0}Z;Io_!hDUEQIKLy969P_P(bE#ITBUXYP5}3w+rKxSs=es`LA$R1ZxV+? z^F4a_<`9Rz6rT*4Y^Gn@fcC=vcpT|q92c(~geE;O)~uqQk_aS3s!1sS(QBv+)dMGb zhn+E@LW=dlsfv9a@Yb2VU|7J%9_2|d`T3T;sXq2c7>+T=lw7Ap>5RHNpTGx8 zJ;!{+jFh4~T)_ajSaSvsU{e*)cJ`*e4wvV~9eGK`pA$jxguP7NN6+7DY`VmhZdofZ z*A*WKZ4Oxc{(%Z1>l&+TT+n;3!^;pt%Mg+kml;`R97vVg=p%!Y6B&`_{65p7=BvQx zI!193{vhB42jDzP@5PK*6I``PpqK43FrtbArv+H}^DkRNRasc4wUOto^|vnvul|6) zVc%7f8z%TY@!x1yNUb?Df`ERF8Q`c59mB)qPZ35$NR3Rn6MoPOdbSlE>0<1S^SYm!4Qh8~rkO>|3JH&1j%FM)04aS;WREw z@O(wlec&fsOVkpGv;Myr36xuLZ}j&wTdnG*5_gs8%(#I1x^z-Ae@%hsu`e~_+b3RQ zrTl$qVjFwiOKU&!LtA#-lI z-`0`nWo?1Jv6o_;*Y>%yrk%A*SrfbvtHJs^?;P}GttQVxm5-x8M>Wo!-k1l`sdZJ` zMb{RR68=U;2CXe5l6=PJ>b)>QSh#$GGD0?b|DTsMj#nd$GOcW%>d*ru%z^Wk(^I9Vw_S5)eqi1+x}TdUsyi+JW2fm?#LAZuM=uRHAC9*Y(BjZz(Jz2+MD zE%z;zB*6HSNRRh_sff)e!3U`DxAi{o)CNDRXFhT%>Sd<0@d#>E^fml9eW4?4q>L9U zOrX!_VBE1)5qnrF&m=fXRFMwBk}2irFceAWQZ$Y0V8-;8?=!rT*;C24$N&$)zu@4I z$FG~;p}*}pDyVf^%yuZx4PlS(Ez&90cwS9ME(b5?Qd)YLR^6Qh*4z!hP~oKcx^p=g z6f{X4DOr_8d~D45wmcPmX<4^_SQ-B{fT{7nFucke>dLm7eX2~Z0*L$pV>mk#I*Ax! z-K^rQq+>~6vEaQ<(D}`xEx)vMS%I*45*XgSMaD0lN%C`ccyQ^4y}qx)Vl?IEKYa(3 z8)+0nq6>bQuED7m=SLVzvAZF&NtOLe)kwO`TAqDkEb7}BkTuv5gS`z~_)$=cGTn|Z zEzTfWRy@4!R-vdovR8U6HxYRs7h(H9bY;z+a+Tx zQ#a+tE-3(loO_tTOE&H^UODB}%W@w(Rk6dj{h>qb%|8tXF%Gn`ZMoykl5U$G{Y$A8 zZ}-ui59$8{n#TspOugjt*!+V;3?91LJ1PuC`cKfH3WEA#1Zz#prO(RM(OsZ=OKqlD z+RdxAr5_E-1izw#vj4*Q{s{j&6X8MLh1>dRXE3_2=HxMpGMjr@GjGl(y7{&Pc8*rD z?5e1uR=)VyZ>3&984&>1bet}m>$M9>aIupM+3c=Y-h%qXn5;6pG$GyDu?Pe-_18s6 zRf*p;Ye#$hUUV+e3F&RYm?gIl^EC5_1q6E@A^# z-kT%BD{UGlFik)pvY?FbCMj>*${A^iTSrdD*g7j1%mp0ssWk(tonf9|FL|!?4IE;m z5+`L3Ea$`z_1`%r59wLw=DaN~B}IlHO}IsV1^@VrjkWX!?$hfWD}%h(Hck+FE)uxw zd>1Egnq`8uA5~K;eoy5-LTCcL(d`rQZfip|Dj#e+7vjn!eB=@*u0E*R({Q|nIyN}5 zfBwKuB?UIX!(7Xb)=gQz8Ab2Vd?bV@EkgbJzvMkbI=Kpr6QxsR63srpxD zYiFv%%F|mYV!n*Nh3NuBe=Qc94=W}*L7D9jj@H3pH1(7r4({ZKT5k&d{CNGyko+D_ zH})%)gzgwBBwq+LW>Cpo?lQ@}!nyE%ddeH%IN`pci(K0AwfM6-Hc7O>c8UCXw^S~9 z(u^Hnw;A>?iOimL@!h-bs0Qo$j&;0O(^fvC=reC5L9Bs(yc1>rBf)1Y5N&~RcNlw^ zQfZ$EzkjE4!E>`L6fX*wwyY8Cj%%PM?NvB(j%QnGgnx1KMMovG$qX;PxDk7Ddj-GS zy18M)Hg9N8o(MW?cwwBtF7K#X^G}Si{*BNQod~yzLH#X)5->sO;0bF|tCqw8rwOe; z*~C#`g|%1?G9Xld(zD(u8^(B_7*5>xe)q~Ns(K_`_eM@iooQ=hj7A4>dQ^0AVK^t; zRQkS>$A;fuxo63@HOJU6^Z59nc|qzj8O2!cNIH||P7jy2N9*KPt2&`SU0U-7{|AY- zZ}v6Bnwygnjk84`0`9=Ga1?$1KM95h&hB!5gJa{tc?E*z3J3;kh~r zC3tveKsn){jnu^NIk$UtkwQxDV?}Me2Nw4Szd1vT642pYJ9UV=4jCmwXByZMXJl&_ zQ``*G;GX2(S43$SBLbw_bKV&<{J!9CA;e@J;53(7S=3`fL?M!A@Bg(LS#2IWZ!0_` zLj1J6jyF|x(C<>qJVj4=MWXP$C0n2|VuQtafOh#WtxTyoa$z&6_`{Y+;baC(R;Un! zJFxrA{aKDG#6nzQ{Wmc+@HhBQm=bC>w~u~(N`cuUuH4=QK1No$gLG9I^5s)IF+kKO zl5e+PITsFcT-uv^(;O^G!=J17($i;$UU3fRuP{5|cba}5Z#v@+-hFd?l?q+%Ui|Y{ zh#+GzX8;GtUP4&@q3BuNipilfQjKA+FbYFi`BP(5smq#BR9*~oAA^uqbu_HV zwY-~3l@KKd&A`;@yTisuR?Y&a?q9)Br)jcFq&<8%Wm=?DC?Y?kmr1YMe2=xa?L@*| zsgE>40p?5>q@2tW>M`YQ_bY;Yuyx-Nu&ED~|2S8SP=;{*C;4lS)3#%h2QKaD_J*UX z)D-6(#@o((*lRU5Vthu8i}aJt8r?tfj+DHxyFib*f?n!2N$TtJAnvz)x7aKES=3K= z#x-hdqxcdW{s^%uJs(Pj%rXSR?{QTTnJAL$^zR>y?wMIhRWhJ&4q-D+KU%DYt}@ju zqR`Y!TgQe9%eX^BTi@nYBVHaZ)B8)7bG{D&bIiHXq$*hF$NM~gce%8BrzV?SDzgLQ zckDI(C!b560N{XoQpe}CIzpZ#E@JB$+@D0SUNY|u^oZS3>R4f%RN@sk^q6Q`&x;1IFB{4q@(iz~ZVzhkh zop#vU=?n*>A=#ufq`O-`+oqN}V3leNd`NwQriGu+`isI;$SgTw=E4{Ho5`OMGs#$u4Ek9H!jf>g;tiU7%9$fMJ%-SuYuK>R@h5j{ zZ`pa(Cc9n}iux)_X6r73uB#*yUqakHi;s#Srp#3a$)2Oq+5YOfilH4ir;AL?-brrb za23-OD~ny4VRk7ZEk*DB!DhxVGauFtN_=zOtH(ra(7|PQs}~01RSw)7t>fToW|uw| zAC~Xu0me?A=;#)TWanK!o6!Z0!y5nLgr~{s=N6com0068UO}UurkVeZ6BBUj7*cSm zJlidAt(^2mBd-?QX77hjK7=rkO}zHi9ZV9Q@7|%WA8JY0Tc91@l>AC&`Nz8UEWZ>? z6RRNnW75>!aQo|(h37-(lzOW=22CHf<5SfA_Hczgy$-M{2L;}F&+;$Tq~)Z-F_R4- zZuCp-Ud5R`#^=^TW1(Spck=~gcG*FekN3F8rulbP&L2+_+yM9dH&hX2;3RFF#4Ku{ z) z-6jrYffNECp=uP;T{p`%dU@}f8mb+jM{>VPz^Uz8ClLWreX3?B&(f~`GPM}y>dHaD zwyV)o$SF@4B@o}TIG|s%IzK0f=I_&SaP+zh=O)~b_so0Q@b~LU0ik!xe;r#(viq+L z|4<1fuk}vFG>$+nQV#*(LjcDx#tSDfyMNha^SafMqwg48 zR75)Yd2`>y#QvO)yPWRJ(e&V;ZT)fknbwn0uu?<;|0d^7`-c?0_d?3g4=T0T%rgvR zQf&$IW{v|gfsp>i(S+aX{J>QVv)EVzu@?ohK(avoOzOV#6wgr`w5B4IC|00U`MKWk zN6e}4L7*1)H*8U2M$Ilt7qP&B=+mGdnx&D?cc;=3vhg#fXlVgWqvdmD-9|fuE7ndK z)&`=XS@0Z81M`LyA%(LzDNH*1hT?yWouJcvWgA5p3-i^7FBlaV~9 zT5l}1{bU4#YzA1a(2cx_1#}h zn$3%5K@V$9Oc8RqAQP(OQHe9(&_l^^f&;_)=UZv0LIW{8s( zrth;1lhwo(3kq4}T5gtuz1LI3zy114XCMg`bvcD8Ia$5{l)MJwmkfFHQ32HFtdv_( z3{YLVZgAGylF+>-&qWJEM_<;;!)1vnHF1ch;FK#AN$cMPw-h|^MEah|T?SSV@Pa!Q z6#RhXxzyY|MB^#B>VETN@d8kLoW?fy!f>*zr}o7qmaKoodFmHngEZLFY#` z;-3-D55Vzk=)uhmgP+v~Qf)!n7iZ1d#5LK*i8?u{z?xfSA6~AHK)p<5`L8;EYZe?N ziMCIzCNBK#bnSep3J}zYQsY)Pjl4JE=BT6l30lMxD&r4&0b3?A>o^K`=0XC&M1zj` zbyE+r&68y2Sek$}lZEUZFZUYjK7G|$q5MoR$$yARrPqbormkFH2I!Q9PBl8aEyL*v zoZJ_*bE+Hesb+qFM%m!CdZ8*c%Cku(yy>@{Q?LL$kL^r3a|1hcRKESGdZM%fXj1RF z49h_W)r%W65!fr`Rp-Aj*gvhvn;wFyu-eYqRRd}^nAPLFl>*wb&wwI>zM1-Q)f;N= zI@+Ld&% z>CAK$>O_J#Q=T~ugtOMfNSTUy$@4AFe*`Xkcre;FW`T=1uvN{boTD)B9*>0vsC|0x zvRj=?xkSMvWpab^hb0iT+YEDqiZ+?4nQ!TrGyI)fc(q0jF0lx>%_hAt%q!gMZ*9(t z!}i9rz;|Vv{1AKs*((I+L@E5(?w)}eMfYg);W7G0k5$O3hYoP{kh&XwT~80ha%6c< zmjbq%Lkgdz1|owZdv?Bzdr8Am7MbS!QUXw?RN**rnT6S)xk2T`KJ*TX?>n)=Hv#<1 z#Hv)+OTM-&&V4!m*~JCqfT$Ht>MPEj-Q$92P}%GGHv-u$AML!W;2cSOddvS-ACx|= z>RMg^-JkA=;_y&VhA8Z`D6(4;G36t2f#TnVR|QIlksLhJ(xbq89Lq_ZuO-HsqNN#=J68WJI5|11)$Z9V>A%pkjEtm!d!DSfDTIRr3 zU&BZI-mP&>SKq{pQU=_d)E65t$x2k&KCM;yMpu6;a}i+4Ju%}>_RdbQ%|+C&3Qfk= zfmbzpTh)Q5jCmiVT_JWO^NQc$Kh$oz=bp^Qdg9v`K<#Q#gBQeOzMq@PsD&_C+;W{& zAWPwwxh&Irv8OrL=;Crqv~7{RW*^Jx{&xM*{2HPiF|~m=Zd#@7F?4L#z^cTpw8#Fi zy{r!+O7Fek4O97~FyNyJB=)t#lZJ`1xm-fMtpOw3ko)q1rF_#T@? z-Prame?K0W>CwgibP=e0s=Q3y!%`Zok2x!}em=?%LiTV2fvLk!gKLL-Qneg~{|g;K zFYUZi>zBhpM+{o(c#G1*@(zte4kV{%%SqUlj~yxW*_%l z^czWfLmrM64KPW97xiKWqNTE&B+jiA0TJA#cMsc)vtdt}{Z*&CkjEng$k!b^%0?=& z4|42`ZUkDm1eF~dWswb75vHC~P-$+d78fK|QkOr)_%ai8Fby~-O{Ew&q%c0NSW?{+ z(2pf9c~FP55GUQp+ns3t7ZR9WW1L^*eF%C{qvn{j2n$>E;B=NsjF@KrNL(E3gQ(*_x>N^vA3A39F zIxcw8@SXQZ>UiQTgRN>Gc2rm^HY+nxF8PXuBOQm&15_Q#_muSI>*?`J~LBVRk`g(zizD|u9bb+o%!zf_E)YgBcc=^HA0Jk-$;%m zQ0&@&OIf*oZOscgBnXgMJZvbapN!1;h}ndJxvvc1o7@);lIy@th4C;lZbyqm@{5)b zCADuG(~`>(qou9sOILZJfk|-etehX9+p)24DxL z>)%LVTI|p|k;f)KxEyyp+0V&hg}HYHOUUgexQEle-^>6ecELyz*0%AQio=gFFgbcL{2r56bR;U0=;OKkAY#C!is>XKoHhV?+ncEd@TxT1Zp?NCmW(VtqZM z-o&Mn2^wiWN@^(2U+IxJsf+b$&xlOTMNN}bp)}Fj+~muU6Gd1eiO@N@eeT<1cK!!3 z8vzwpLWFcO%b)EK9*j&pcxXm8)B0R&xpfua-(nGy(1 z>1oE{cv*|@^SJ->btz`}k&!-Q$x!XLDMjGe*Z+I$^m~aVjU|~}cwbOc4=|6dz(?wK zmKtHK#_}%^T}N{mb^ZN)#|MP+p?^M=*?0r1ENMYY>+P1IR>4k=CEZ0H6BdkveiaKS zeVfn8KM>}+^g39{vu=$utFUGIiEYO&3AH5j8)|~q&Z*|;390v!w@BPH{KyyIHt-!6 zV3xx#W=YO9bDNhp^F2YQ)`>OOri_p4?cGV&Z;@wb6T^zM#V1mC%)i_G5p`$v1D zkKC*eG2F(g#fGfhb?f1fcbVcQqjxuonq%#I`R$LDwgZCe(YCe2MtV}6+C@xJH8qJf z_r!s@un~s^LiF#eS&aDE1QQ3HO7k5kNj+85E)#CQ)g0_)+?sTyInBv3iZoyMwh^16 zz78xlCpj=xD-3r%LZC-ck4e&ASx(Y9Csd!tef`e7lIy+Z+*@Ubtl#K3AQR;OTk57mVl(* z`PlUb5zDiK9QOGkR#X=7_n3eFF&+Saar19*UO3 zZ_($vr#<9BM%eR5y?%s_=fU1!&0}XRR&VStOGoVHOnHUo5}XKMi${~P)ZSJ ztqj~vl6wvm-EExK+iF6KXMs0J3h#|8IchdrLxdikj~0&)aVK?)@2Ix%$?sK#>i}L| zb!NFL*Gyy(Bi`Dhc5ffN_j7kA_v6i?7Q?Hd|CV6zAvkJh{GAEP+L)wj`_ub+fAvUO#sI(JCMo{NGfKMJc_#*|HKbcKFEmxy?w0D(BU>y0ppO_XZhCc;w3P5 zm5;1#LUr-!_78M;9_Q)u8Mbo%ki13;dT;uJQd0ROBA=VkCCR-RmQSjk|baLhmTLz#?JaO9X%9Y*~%RiPt8x|vaNA} z4PSIfsw%Fe@^0gEVP)rV;vz*e&?Fg}*3K#qnL{#LNd+;^3)3oe!c`k8-VX@3pfjpT zcrh@EPQ=}*N6z@0|C{pJt}b*4yGcS?3WPb?O8t`H+UVW1}bUqYkNXn z5|Yx2JKN@fweqI!4F~&vrYs1BM_`k**4#~FULQZRV~jjywW+6JwE-rm(&RbEppSN3 z5l5nFufm|FAyZk9!HKUs&*M?;+X%dPw;tO&^()-2QE=?4Zn}Ie%1BP3{yLL| za0`=9T=BUkO+lC*R#8_V^5M(knv{r?|s_R5MLUXZ%E zi;fTa3&C9*kpa&mk43j3IFbp{XRXSg;Hc^Hao{R*w#DFg1`M zNIkG$%{sQHe!P7xU55nuFnb3lq-TQ^e~_0*mj15mBJFvl+Sc(++O451RcR((5pvaz zz$=}^`?190=RiR)Lf+lLY!>DjesiippMruPSeg zHng>!7N(|Lj;%S>jl{6i#QmTI0!%(F8KS(~qzVo)_r%ROOqtG9nH&B{ZDEH_)WW1o z`fCO7xuVwXta8zFiL)HeN5NZKsj!+oIe`shB;2K>_7$TiVb%{G5(=O(_m8A4E|Dvp z3wYWAJGQQ*0e9zvb8y^?t%13wJFLQR&Mz==Z;#z903~W;jQ}7k60xL^C&TO)tjTK6 z9X4iJTd>rh&DnY#jM27L2l7OIz5Qq1)uYPkRioMKOWAp&qBMdUEU|W$E2)v!wl_y5 zoj>_elXp_zW~iKRkA0h2^$D=Cfz#{k2hWP|(>#vD4#W0JVpQMmo_LNk`tc62H$a&n zk!IN~V{PZh1|;cbXIv0;G#T3I#`dQU-bCO?>5noj=hO$NM`Lx(!X-9p49vafxl(2W zfN7`L;jd=nsCULdnsw4+jUG-1MdsUv-vs#hzBZ+op3tf^H)O;WvR$mIUe6x~ZYV1W z?oqxcR=f?R2S$2sm~OqJ#oA|Y)0zS*TpnEyiX6z)yGoN+N!3bkz1YGt#!Qj>+Le)4 zsH_{{R4uGf2ZPOVYl?M^xLo-CK_oT#r#$4pS_axxUwh)%UNT84liRyej)luQH(;Q= zf;jy`wi^0s-I<#sP3a6*gVIc$7w1ge9IRlqoceL?OaSQ;acjS6o&Qxr%kniz7!oAF z3b5;ddp{(|un_R-bQYyA^A~Z%v#JvBD`h_F93Lzus`akgA@|{A_+&<_ zqhs?gs8?%eymI`x_QJn8h7*k0HBVSk%PUAcK5#l3di6Z4wH2-6_vnQP$8g(sLmP;tYAHBDg)^EWvtP{z{ zuH?4ER?f9R_xshKXB6M$VNu(I&+YQOmpo4c#k4__HfO*8$0!m~s}E>Wwy=vO<#ZW5 zect8&gj*tEsqZd}uHl1SoaY*yz)A^VALGn)ft=2h`*NF~1a!UFgzIZJ{+S!}cV5@L zMh3CB$Q+|kH@$Nuol#UjMh)5LCR0uvs~y;_``o$NA=f=!=k-pCp#ATtoVj94KqwJ0 z`wIFJyG5_`_b5f#%4bLCFSt3~3l8~$Lus7l1%8CAbBphoJu8j>C5r=9Jp@1&OdC~Y z8!a8U`xpcBBP#P^csqW{Q( zhaghG2vGD?E}~BPp`WmG3tWVTw>|Jz3JCr4VPlT5N5Xj?SGxo(KPP~66)KXqN2oQn z@V3}`N`kk~96xgqIqqKIaNzJG6{Z$y5%YxfsE6t9grE;{Ep89_nH4cBqPlsQ4|on% zNglLy_7nu(KcM@Y6@em8onM4S_aZFqDwbGx6~MD<7kVWS5V;p>pS${LtCynNe;N(R zBmmDUi^R^a+6i0uwRPEj;N=$GyY79Dzt?-w(@`uGFL!1dFmq;rW-qskFW@Ecn(o?? z!D=A3At`!>mbQnk~jj0W3fo$ zk{;t@6>E;D-`-OGsxtaYNhT1~|2y0->1)6^nm7@-;8lNX%aWh;k3U)@ABD_41%;h2 zkF=)iidq^kfOO8t8K=>sY+sA}uKlfpA2bUKcPvK0Vli+c9_V z8EcoJVifCtTCg=}K`1}rtouKQq_O_|kU7Nwvxbi5X~@63{#J}{gcB)-FPc#0QyL|R zrE~?lcC@5NLX=i6@&HaTQehN_4fewd_OOVW(%p&>Q`m3GF)b;1M!~Bd`&a!InNmp% zg_0rZJYl+Rm8=bV6*+WNvvdBN)$aqn6P}nnnf)ZORIo$*BKc;2W#W6-ja}ny+$~Yp zMAW_-J#RaAHA$5kC6bR1FRJVpg=AQCN!UHbpW#PN1LI4cS#`Tgf~4$L)w|NnNTc$; zx3SY#u%{-Me7w#N-*`p0$u4SgVZK_uU3jt?f{eXu8O!~wal@qY{Ap{i=lh~Gb<3N- zBE^0YY22s!Yr*vZcmJE7SI+3@Fl0-ahxbJ2i@Q@(1;Z?qc(2y1Dhl4ditmQHYioF) z_`4r_Ecy}evGP@{dphf0Fk=H*>Ic#@O`4g&!1C#zTyv=QjtNv4psiZfsIa< z#7z-6e2eqiAn@YV=UzO9-;Q)AtWKY9F;kYvcCF5noT3)q5+xO>Fbjj_W5J?ER9LpD zqVb?uLQ{{?*p(`kPdh0RQaV3>2sDE$~6H8Oc~(a{1Qd zVFt$a-q(G`@4Gk+Fb2wRO8lUY0*~LfBw(O@`FYKwa-!|8n56N={GO%ESVy{nAeC;% zb@i67S~iw8tUvwaXp$qDa~1N3^x*dMNUM@S_ABR$?iS{?p6g(+MKl^KADG2}LX@YL zG(>{8w@m(6svU7ZpasVwutD%fqw&S9cmLX$7X6t=3>G}Wiz%3^b> zT2|y+J!rj`MouZx4aw$cU+yeH!v zvOQ+;u}Pv19$Cw0x1|@!SUY{Te}x!6Sd%E{K?zuy0v*@d$T->s(^|$xfP1!rEdZSU zP)OJHqostT^7s*jr~5Ns=FVR&3Wl<^uZqAuq0h{)=tOYI=GzE zWVMDx@>+prsUtZ$_ip2h0z_&aKCKCutX{*!3D@fx2VwHykG&RKr+{JzG(4zXJ= z|40?@c;KkkCmb@TzD9wEck=s?;$FML{H`wEyze1sZcorPzq^ukDe5h43BL`vyq8jQ z?v>wF$F-dzUf3G+wSlI08ed|}Ykxa6XY}l9S(gmNj8TzAI3nI%|6?<5i8gh19nGJH_}2q?5fPzDaB^dO8J+QuW_*o4Xtr~H9qInwP5@>*nY z=-QPjx98NKvSLX7lbKlYMT;SZeMd8nO+pvo#q_EvafF;G`g2OsB-?w~Oq7Ss3?}c6 z#&mP_2^c=~SQecI6HU6oAMKNp$LhH6W9Nhv5D;GrvCPP%#}dD(G8+w-!pgz%{<$0c z$5h8Ga-=%_e9L(LuxjfZ_Zuc*7|?R#jDQW_+rrBgzXknZl3ZiXBhBt(=DkdkhYk{)_! z0SW0CVCWv2p?Syq`8~1L`xnft^V!!v`+Lql*WOa@mp;MzHenJfyE^4cn`Ba=T&puo zJ8Mo)3odJECIT(Qdd{+3Ni3F3$FjC`miqjCnzJborl*T}NXQ!hxut*m;v~vhs6FO5 z!CItj@aXB`=;Ly!VKha8=JtS@Xjba(U-y7zFm76v*Ga#{k0|W#{hcGnx|8_j&6>Qk zLw>!;OvM~Q45wa}8YhB}B#5l7yps4QlR|!AJn7_*6Y{$-ylIvGUOQWyMT~iZJN~9~ z=L)PJ`Z!T7k3ENbojJ?O&nSKCAKxfcP&Hnp1`hrRO=WK8jnGghzmRUIne5{v<_dCE zc*hZSnH!K+NZIitZr3-N|0>syK^UMnTN0&Mf? zn65vKTwRR2vZ*^+Urb58AIbIJr}b1lAZ@4!jr^l&Xp@*^oaY05=Nng%@izLAk4BM2 zm%u_+d8I6XMXKDzIPFKFfa}inVaLejZ?5)gBx4Zt1s3Y%ytKN7dt z38)#V zl(=#n5832h&meJ8jS!lt6cVahB{+{yIhNK-!N%2a|gwuq#fnbm(qL(Z24L zXx)}@LTd%?p0>yHdlXsmHVS!ScqMX)Iq6mHgQq;Q8|-!n0`!~vBJ8g!5QYm|?7zwPsj{Bg0={ndXr`t$6A9PlMsWbrt7uWB-&|+M=glJZ)b8OXSubW60Np&09LrTs<7np@MQ}x>rY=G}z$t z$+1+VHO=J0J<@6!x;m-f#CuPjr_AAYP^An$3fCkoUK9$SB~zE{SJ8UG@j0Qt4WsId zRe$Tjm4zgyjU~1K4vv-d_FZ}Zb32xyA46gStEd{cti;FL`E=pdJF9Bq(iN*C@Mag2 zSg|)~K<*D_kTF-pI(Ju0`lUM8;CnoXorI8u zn(E#6n|I$lO+>ZNgp2vAex-zJ*4Xn^jol3f_4Fozf1a2JJdLXp$o^%~DvRmn*rTf| zQJ-66AuTz6YoGk9@I6>3qP!`*bNcSs@%Yadf2#gM4X>x0&q=OA@3RK)4D!?7!ujIS z%+Ib*wx6Lm1NzoRJN(P}us6j3k|$866j(->XW}9%7QE*SY1+PbSJwF+5+~!e_~!Ql z^g`lz*Z#{^~PnKHsnZ>QX$l@mI zExxwdNh?2WtWURv0$Ae_H2*oOw|!=^di^H7x$E#4L_;&@eXK=_g2<29(^)AzYM@gu zk+jf#$UK&;sU8J4VCvm{2#B6sr@J7;hdu=+`=vVVG|)a?+u*}UmtvKS8t|0*9sfa!}*mPDtBSZIt(9$ z>8`-}Bwm)1XQ)SRyA1P*>82{`NROz+9NmpKU&2rw?|9sB83zYxR-Jh46wo-@&Ehk@ zXQh-RIK4^?{u@SW1f&VZq6&Qz0*}Lka-r6^0<@Rx$GB|RBK`-h7@2bjhFD0E^`PZT zlGRq^yugy9x9+TH?Mw6*&}x>FEr`xaS9X8HEg7IczI-NFyqdiu?YVg20($=4kPWER z${_8SJ!ZKqw88l3?~BIJaJ$v8B>XKu;UBpXVdl1q zeH1Wm$FxU+2V1&0=&w*Lrx65|`5TxznJPl6Gs4t!>~LQGT6LNljCAsRLI*}aMvn)U zCofh4ptVSj35SjoZd^gyy-qnaJ=R$BIkp5n@;`#riy_&_E?GW3ZcM0iSqyItS7PnE zN;Xl3N?S;FC7)WK=Axgm1Puf2VjO`XL^5t$^8O3AeC35pQ`}_zq2rJfaRmldbmiBM z&%x3iUGTUQjha$B%^)uK(e@yZMY9m0Ii7nzW=KaP;51E^;8{TgCVD9LQF6#HuT+s| z#5yjVEj)WX;w+g#ba;F9WyZE-mOnR0Sy7o28!xm>klv?LfwSTSQfNQDwv~xE6!#9N zky35ctLAyv=n))zfJu^I)!Wtl$#}q4V{sY{NWMtFM!TWSOQ|NfO+Y<;V1{<;j7*7! zLy&4EiY4sa7-KY0zT^!Z3Vh)ai)GKjRo{WNva;cp@s7^sJe=87Zl@rvHpY3R0KO3Ts4jzDVidDa~0wpIV>YeAS(*O--oX12rqLhlX)l%#Qe0z zaL+oW^ftrog_!vZ;CNo)9|kPuMnA1*RCfj%H%b~=6QMBxM70rPRR?CS)*Qu!$Zrdy zu7_8DJM{nv16=(K=7)?T2}NVGZx~c8EVbmmE!c#2gQ+|d7IiTboo2S29}{ljn;S2%kYvz3m@4=U z1$0{Deuu06IB&NrW8e1sWuW5&}oUk6)de;yi)HR9_7*^gqUIHpPm+ysOGFL;T866 zF-iJqx1qokV)Uab4xI6!QL7Kc5Sm*$Qv19nBe&?U8NwNUULT@Ks~*kf?A4$Ce!)^R z%~KMYfA@{yuppe8A^4Z#N6U}>$jy4{0jY(>$SCuw^u=Q9Bw)K3obkfODyvpxE@_9roBqB1er?TpXIJ!WL|;@sex_cSm2i*k_S;;} z$AvR{lmtiR`{oag?Qh-$OVzJw5=|{mGG=`b6~i|2u01fe@E~1Q@$|IGiy;d$u_BYk z2-_x*luWRHZ?!Xcrw}+V#%|}69N}8=QT?^#2+j!*8G;Lb(yBlI^T3u#gGVokIFVZSz3?oPQ_mD60xGExve4AnU^n95^f1q2 zLjf$6#Pw6vS?>z&5TLm%nx<)xO;)!00UFIuK6A&)XPQ22oi#9(LnLKUQ@+N@Cpr0a z#|Ag~`tuMTwm{zXTugFB@(hitl%idZI9VH#yBETY4u77Y%8ixFUo$+Grh|;}bVXeP zpn|@!;D6C=DNnrLvrIV(faX7;yks}dsvMNel5L^= zRvMD~cT8jDEhwrBAJ?IP{cBDG$0uerTdUSkKA1V$i!dg8{6OoVzv?oi&aPZP#&}`o z(->n*G@bD@JLaZ^1MhU8J&$SFeu*6c?LJ~%saaq9J`qn1qTIIz@le;`ftyLNMK8bg z6u?~%dtbrVh{mpp$F2_n=0kPof5QTYh=A6{#DsRfZ-cH25M%CJQOe)bfBQk3CY7V* zmJHZ{p#tH@x{9GIzd3J8PewkxW`r|uot-#4tqO2PBzzB)Al6B)*o?w)5k507j1RUj ztsZ~vBE7Y!!?&2~(~>jjc}Nxc_hO87cX#IvvTIcWh#-fy|9$z$EQX5LvtV*Y6 zu$-gNi--%M2%OfDzf0(x6;i<@Rgb)TLLTS-6k7pOIkyc;Qolaq$qt1gcWKEBzbq6` zi98t^98tqBMrrLH`lvx1CHr%L_Y)U#&%+G(qcQL`aUCx;e3te4*^3i`P05SZ{QXPW z?q5ZLWF|sp^SKgpgzTL6aD_$E8b#eilG<4@x&8C}Iy-X8bm zuNsXHe9F0A7Z(^d|7`yZ*1bdJu9D-iGRy04tkLWK!ZBMh7y581JI18SGSv4|d^d}Z zSdpJqz@8;Hm(mcQ z--g}#Pej1+#xO~O_v=zSSHj;qm^0IZE{Y+4A{cLg51+IA8rKYEsXz2INGz5Uvhe>x zL>r(c=FP>zYX#@uC=L(c{zZ8%%Ol?+o!T(Dz^`?*D^|&ymo;9B>iJfJ0 zP}qK4mmb!3wxN!LmiLHvIHy+``G6c)U*dU&;jTSm6^uarv)_zS(DhF6RU>*~40+^t z`H3*{pdWFLM_r71bKD8p+>`ZZFRM8t7iXlng{r^a z^RVbc@M7_JIB>$&AK`m4GVr&qK|lon`q1+y0|0M!V_$*m%fs!r6ra zdk%?FjgIKf@9vZ~WLNq^0V!tMU^9~7p zmm@Qa+0Ok7fRmox9=kkdjM-IXiqoVfPg=0I4##;gbRmZAHZAHrLltHcoB@crGg^$F zF0wwQhpYF*Hg-&pIju^YEwg_jc|Y_R(y{ut8AFNJdM|8$$HMvWe9az@(6~CR*%~~D z`yftP1kPU*41S_qu%+n)6X0k&{FW4#=d}T)aNd$NaTR9j!$C$35VP84Gvm=lCmI|L zFfm}=dMUL*i-!FQ#3S`1#6;@hXlo{!Zh|PbC`$8FuY-wrO+)lT`lmMGi-!0p(rRw$ zc)S(xvq{2l?HQ~kAri*4QQ#R^#>=@$4`B{l^iN5&4C*8$p~DAhq%F*T8(Q=q#Z-+| z#QI+^2z{sFLxoeQe2B(SE}959;p~z&DrG3_a4Q`lK;$&&&QE9%(twF`w}Oxe74>`` z_aF1WH&3!ZS&p6#7?}JbU~;tV8Porefv)y|sZnC<)%a*g6J71~c_PGMC4w7Qm57Nk z?X**Whl8GtQ8itZ81m4hR@^LI!xJxnZjTNeUx=+NKZ}1HC!wTl-i|Yw4@20)VL1)@ zIi31ELl&8#P(dIaWZANfN)jT*OcFb+d_`AX@%BT3)Kpq%I6hP|86SmKFZ8V--DR^;~RYF(om#Q#r~A^*sH)IaZ?Q@w`nvz9`mtN^+=BoJ@X|P&?AE8 zPl29`FPhWKhrUH}IT7q9kP(2~O@{}(Yyn{g8WtfzycxvJ*xKVXI969~>+6cIYZufFWW zBF-svmVQT?b;K-KDAQd{ZU(5oLs#0{NPp@i^zubxAAz>s?bZRNp9~ZCBXEck1@+Q- zy;#ETxR#LqLSqbYRB)kMk{q&;MOkYyZrj5t7?x8r9WSrxX4GjD>j--!DR0VtM=LSV zh_dvhTkx-2xz&BIh5Yo6QO*z+{GDuUlvb48Q1QTdJXVbQ2;dDjv|A~ z65BL2DS5b1#D8YMm?^Qp3tf(aoF&%P7}7DC0~Dp+_D=Zl%b97fr@|kvLTu_oZiGS? z4W0oSrP89f5HET`FV1r>cW=+G5i1P%@X@Sh=)f@O)(j``r7CJlXVbethaqiTe5)^2 zTzQYa2IsPP#^HbUL8c$zc+mv`o`l2c+b2;|#;$){R5Kp}be(8&D`%(PlIeq6(LbaJ zS6kJY=A_?-Fa}%%Gi?ASii2R_+8B!5veq@*gGQ-27uBiI?}2x&mU* z6$x<_rkI9dLQfvGHwIl*H)mu;4$4!tMBjdT+&p%)W3%Xe)#d%)u)7R(da(y`94jBC5p^B#RYR|_=xrCAFDSt5?pu}Z5q~b@=ANO zFDWL2(sFb0<^*e3ZTV0@XMFKE{rfJBZ;qaBo*!WsZBQm0=*cwJ``-zkeIwp`26LyTY!);s6VCUT z^U=FV>-jQ+4(u}1!5MD1!@$o4z+GSx3DJS+PgJsM$4zf+pR57Ur4Rvbxm3^4VKEn4 zFd-wIg;mbLbOH0(^9NT+ZeIJHJ7|x6nE|aWDu^KjZZByn>fCt$oHom5MvXy6pzPS9 z9+E9`ANKBAis|~j$8#E6+s7?MDxe^b(LY)J@dG}xwhp!j3{Fa|NS#wi1hli3p2n_j zY|fNMRaJIXOMHj-p!$y%AyTr z2?ZMnb=_GybJ*ieS;5ZeNHzK%pNFv$p_3#*AA>(c!^w zooBj}T=CdLe%`SnxfTB77X0F%bzsa8w^fS|_apgjnbu4Fr}AKS)pXwK?wj1*e&7a6rxwFbfD#K6HwCu~%gZ1dxg z!P^@Ll|MTk2(fow=d&~M4~^06tU8L%bt+v^ET1)?Pp|5;WEC!TD~b!X@Y+#p@RqbJ z=k!acyjHY0X5n)Mf_-26wM@STyie?#nNEKLoOGS~sq$RM-%|L(*1mgh^i)&>?O&OQ z9OHBX2>9|3lQ<+h{vW1q5E=;kG)>n0fc+*0Tx4P6EZX4t@Bi7foIklNK-Q4&qsl$W zAvDFg0GFw+((sqyi1Dic)_We%4&n2lgPU07Ad+;Q_qUtyqnkjd$gAaJ`Rw&Hy^l9tH8-#LKjar7fTvOb?W_ zA_yS<11%B;z-p50wSs6>FM1a+ydE<;%;_XF%SS=SS9b8e~|h0Mwsd3Ov=8 z8^?rjKssI$#yg4cQH|jT=@=vtyeNypX^Wvm0hupbnzhvjG>zt(xwStOE7p%wh1UYqJUZFflaJL2uHb?%zppb-AZPLMX?A zfs<`#!Ak(5+lfZ*%I?x^am4$LLv>|DV_hZ&R5Ilux5Mj6<>g+_wLMA|Mul&O<_jB+ zv?F$R_ZPp6=fkn9FZB)4y&H8oI8ereT9Jc=`U5{n# zOxN>`e_g8Qo;IJEHw8uZ%vRb37F<0Pqr;s%1ZLTz`kG(R?2j83*jYKrUWNrWj=vVn zWx5HSx~9R+mu}qQ^P}l9e`gdlM=lr(-n^S?67&0x_9@c3MbcQri|5unQQX=D11wWn zd26qhLRaAU)Yrpd5xrWG9oe7tLMJwpEB?4)WL^NKE=djvT}louJ@5;;N2ott(vkvR z3k1h3cdoELoO%6l?t6aNw%ztnFRC_=m%axdNTR*3DDW2^`ug%iGgR~$uHe_3zlMzo zV!B;5=6>Z5OD1eJtE@w)aQ?t;C<_qlcf8(gdIHcOpBhGhA4qR!*0N5#+Zd6XW*kO@ z3fgr%DN6UkPs^;gYHTEe&{QWpZdg3-uYQ!%anMwD+6|b3(7-91yHYdnc4;Lq7p+O#`r5ANdw8KO6nu7IS zbkX~J0UzeML=;isyLMBTru(|AR;`_%qmw){vXOsvi7cI&=ls2?U&7OG$QPgVbgD!b znE4gusFODh(~~<@m-V;r|0vajEDs})&*hpgwH6*5jtFSW!vY;S>F_@hN4X^KQZBJu zmQ2DbO>fAMNbb}h=nC7CeSdLydU*JFY&}LOV?tl%;=;OUG{#Bm&L5espKvRpy2E>a zW{(bGz=PCZZmF`^gEe;l0m46|Hs4i$v|U)nt}P)tLX8{!vF?rm9Egbv(s-5q`_VML2%!khNNhN4pYCwaXa6}b1^*Qi-L zfgdUE7CHuBNiJQ=9X__Pm5R>aFsv{$;)2swm|au5)85(Acpx!Z^5)5D4;&wK?HStM z#FgvyhqWa=GmtcA&drp=gdz_bUCHx3wta$`{R-w#;H8@am(Q0CsZijnirGq`yNsPb zpBN-qyfey)dM;nDr9THReX~-5iv+W~eWQZNWFk4CLLMG?hr%C!u=_k1Ae@@djwn6s zt(>GhKZ@PPewy0n9D2$eIHq9Q@{i4<-)$(j@;FX44PErbN)WXCOs5i^y_C=wlT%xT zYWGV2B>MIJiC28UvWfk^-vqzi`a>M@#Sm7F)&C%J1$|3kz!d%MkexWtGB)?l3>`@GQIGs*EmuU%IXg&r8Kd~2W*B@I}+e{<+T$SKH%0$sb^ zl?=&WN{?oE4!A3l8_UFm1IJCr8b>MvgM1W!DQeYVp}hg7m8GYlLD$SC%RJ|4Q*6B` zM=iIa)xvm!G6jTbDmc6N8j&~e2HIJw3Y3`87)Y>`4ITGbGdha}7FY#pQb{0eF1Cmb z4CQ56peKK_GXT0&l|;R*c}*XJ4SAU3E+Bk(BMRiO-omaH#2aztFGUB|a4PRI@to@) z&Ufl%&^Mu_R%E1?F_R;|7|Zsx%Az-))HXnPNoV2%RTr4a!~NyU*@C0ol)yBVPs-LU zE3QHmv9jay`X~a=IlwbiO+r|pnHwpq$xc ze+EJG4U~OT1txBro3+imGzu`_jRF6qve#epsLx+q9U;%@$D1n&J}=}z)gEb&ke7@XpX9jHV z`S?_HY^~fTyxMhhgxDWPYVW?SC?vS3tuoQ);TNq?uTw|Jui2j~IDy2q!)GsbD!!nA zm~E>AT4|L+lK$l}4W+a%27;UeGd^K$eKC)E1mK-waoc#MoQv&N+j~MmzxUk*f+*m- zlMDSl9h#W^1&^H{YC`oo05D>`mVWQR^5xR>41KqIeh>P{EW%K8>+JTZ=SGG_&gXu7 zaKZ9VS(@2L=94F~oSi4M5claHsYjqctl?X64k8X7^In1Qk6RmhBIEm~XJLUn_MrZ( zh=#|dd8sK1p4&xN>fnBGZ3Rlcz00Mc6YHQn{FX3{FqgpZRg?$izEVYP?b5IAwLis} zi>TTRpB)Fm22R{~2^6}iS@vkJP;%@QcVfb#s~35?T7&G{MZ|VvTfPrF@-{tRdXeDv zInL!^TkkV7;FI95?-pgEDki$j3xoneF6yxd+WX6S_+gw!)mSdyv3dC#H^rW!%J<$P zxQb6QWK$A`-+4veU|VacZx z?3@ew4i7v9K!}R(CO<~=-T!gtN8We!#Y_*QAlS;IPzlXteqrC^h8S`L_Yk~yHbe!k zR(CPxX>(fC`aexD8zrpD!py&|Sx4a8c^O2n;Mm8=2|R@DPyhlM?Xqs@ZVFVPMTF{*K38U{|g`?rdMyqRc^8$FJRB zQ9FLZ%$5DBB@Y-V&q*r&%o#@i@%?ZgMk^GDKCuqk<9W z%VLqAJGm+q&ksqt-0q-d>}I_|No5p#Jj%UURzf!iHkJ_Jp3G3fsmxJQx9n+{08RF>yt13CtY!u2-C))xN)9tz3>=6k_Ip z#YCzhP%*N^RyBnu=EAwZDY!@F@Ue)CgFKe9TYI2ft%?`fP}3K7S2e`gW{t)fdzJI~GW@zL)zMh7qiqJd>2R|$?mD+0SwkeG975YCIF+Q&LoX1vU zaHURYrDK94c20MuHuWhP?nM%PxPRdMxod7p=0IxFy(^>{^|d+3bDEg#X~IPTwi54AGi@5CjP!sU6Aq|=L@2dA6Zb}2S~Z^% zFV#<4`m!ZRVIt9Vlq@P#SCwf%pPKhJ4f)#%ccmMrOkLPNvc>LSWX6o_eie`uoGChW z-}zweukhT^lj%xOg+^6vF3FDPMWXcr>t6wd^aNhA1AjkZT<`{}aFDRc{Kl;9R7C1z z=BswE8C3X#L?~vb*f!rr$b@2D1=tJd*hEGVKlIe^?a9D zFj{UdohqaQ68Onq)_a`4RkHZ-Y!i8a-)mCt*Te2-2*ZYFt0z{|8ym*TyG#hqq~e?axjwqMM*0IZ`-Fk z-je<4*m;LfLg?iH7#kmmHNJsNPUjmo=7D_+H&yKfVxXc?)`ao#(o%+R8edrKi@oqRmT|R*Xxn{-jno?fK>RNXv-O+qID~!TFf13zoy@nFJ$` zYhC9Y*~Oa1d8h6Q4&@xGRFDX;I&bRKZzvcG;he+WjP#46->Z1s2v+#@|i(cv7{SQd+J@V!1K z8~jd;5P=KEdv_t5nVMix3X?=+2~a@$=B9stYTm4fBbe_Dl_^Nbm$3Ie0;Xc0JvCVU zUhb%|ujC3F$SNNTKn$QDCjtTBA&DrxdPg7I+MX>28&@}Jhr%ACm3Wz7uP}_g6JfK} zO)bNQ?o@n(ovw?T-Jgl;5Q9TgP9~X|`N>G%_AkGY32JT%yX*U~-nU=Z{z_jbf=Qu7 z%Sbgp=w*kSpYb!Gf*5ZJzgzS|5y|&6;_rMoFEWd%nX7*2vdCcwpinz)#*A2m*5K8} z^rbtNcdvhLli>uCr!zUxf`zq$4T`zK%-zHTIQ1|~QYGTPSNZNIK_k-uFIRU3`Xf_L zH3L`DH=NChVby%d7K2xY)TPp0?d@r!<;5HEknGGNYAKH79otO?d`*2kaJ^--cneEC zpdS{u;7)VDOcewpz(lw&FM9%)inL+e#qUy?sLYDyq89Uz$A`&Yx5wlqB^P(X24kiO znbpdqO3gPA8ayxBm`jgW3BJ@^Sq$GAULJQpJplVaIBkqk!`}fQt3GU?!RX>m_O2Hy zv>1S(&qCJ&pXiC&R7(QwQ#7oYHyjQxFQJ8!MX^0@9HaA0CboH zL)1aaBee0v=;cyhp!093P{GwC4k|GJCyBrD%CX3$Q73H^ z6@i!vf`>H{F!D4*W$HK$nVid3n0sW!F=m{ z>5>0;DNWJA9H?+RX-sn`7v1LC#IQR;dbJD>al^@E|6;t}AkvRw75>L0p>;ALsH;U% z7xx=zpoH(u+fhE1F%tn!2u2T>F<&}ofDYGeTA!0sS~Ym=zM#1p@=(hF{h&S1x%GQS zOV0}6E&ujN<{PXgk(C=dB+1m?pdftdy)qY$vmZ$m>_`I^)(JK!Q6T+xsG% z`(6znL<@&bzOO8?Ys2pM>6dPwWq{IqmKqHwRuuj$!z=gOJv&Hho3eIrfQ>D$n5U=j zn+{&w^nnp?MO=>+@J*w+GMrgpE2@`faZQj0tb{vT+zx%=T=`*rF&`yv;IX-iOP$ta zVTt*;e4gsL@iXvovj&z<#Uqrik9OJfafW1xmCXp7=fXooJt9OD7~EF*U(i;^zLbZ) zObrisxBK%e03>u;(mmBe(ui4WhEesGnZlZPF4kp~m4I~sxy;|DUL9&+f?ey(AOP8bsumT}2L7@xZ5zFY2@6CT%M$PC<3bm(eG?_B1LNHM_pUC&yTBbhDOoSj z;Mk}CkN5+wA=$EE6;!zHX?lK7luP8@2SyZ-{vONl#}n*N65q30Sdq(H!2oPtcLc2y z+L6QopUPQ)2`c{1C|~&J1DGge&o0BRfoc?hrpDh+;bq~ov%U#Drj3h2JXqj}ft}k9 z9-;NTTQ!V>QfkK9C zWL6&)DOeGQ0S636LGNCh9bA{Ag63B=#DAPMLDY0v2TP@ywwE83{+7n^-=J^a3Tihk zmZ_wFHf9Iz%rYyIIPzT}e#q32F)UnCmcND1OA@^*&N+<$Y+j9|=C3guXyMWZe_Vvn zJjyS-2Z;l^yj2uQz@c5OT~QcV^ZCg*WA*-M+UMPP@;`Bveqf`52p~1WK=Nc&$L{Gv}?SBXu0vJ3B>HAYUF zpn@BnVzmu=Re!}|2+{)Sg^5)(>GrD}KSLDJnM7=#IXQGPsGH(q5)l#aBuC4VHZ;xF zI=4}?$&XH>{abzT%C_e&=l2%N?{YiH4w|biCet1q^nDscR*sLLif9j+jjhS--3M*D z#b4Q*Y2(J~g{aBp^8C|`cEmVjEV1C=Y-G?5->v#~-I*M8zR0hnZ%`smC~4;kd!iud zuQcHvw-=SbCyTg3`|5V$nAd_k3GfW2Vl#1_W_IQj#KT?E{wUVWy(e!ckfE7X2NpIr zV|AY`=7v3oJzj)~U5)TL^Wx)hwscClDp6j)^yyl-nQ?iWp*sGfKkV+#WspR19}t$U z!Q519=E|ylPEk%^xo~xES4{;QJKi|JfZiSbtt)e9h6KCxDCXLH%0N_YXLeAGWlhMh zVSAQCXwb;6p9mFDYr$?1^vgJlIpjCq@Pt%GNbAGe{c+kQPNOIObC`N80E7xPx|0oS zV}QX2B1k`F9BpYW#{r;E((quN`U!5iqTDOwGkZ(-91yMmfjkLexcE%JOPb+2DC z%gjso2JH7nmpf{~;yo3gGiT2W+0~la#x3E*>PE|zJ6f=vkfOowB|6O^9cgtu+1v?q z)6c-6q4jBXW{Y=g{y%T*9M(z+B&MZk{st`&JfAs8$K) zuy<3`mCU#A#<(*7M-~_NE8Zr^<6jTe=g8>4CN1I0@LW#(1c2KIsbxInp%44-#SjO@ zk>5Zbs6yEpLX60Bk~wL?J!p<^K8l&R44-Gc-CIZ+@RDr@vwXfAe&wRU^fRxqFC|qaE<9MN91W%hE9^O5BgAy&)l<}=PGnN>8T1?_#H*ke>%WuxM@ii(OQ)9=a zEy2yKZRF^JnUd?`U%^6*v%X2Z83SJJzQ4=_)g2u`T|;xE>nxCOD`gtj$o{w*}I%q*3}ofmB@M&FW$OU?YY!W+MQu36Md(ar0DK zdR~Sl9lSC3h7b1murEXFYbBNOw#nB-8dH~Rj}a9b^8%(G)+PcRC;qqVGWG;Faff`+ z5dH3s4SOWC(6O_CVPu#S9G@uj0WBc81^qndr}_6|^=EVeNJrdW>ow!)9B6gKRKTMG zRD{opAudfo#NelvGp(mwF{Hffi_$L%vjKcS5kH0u`1$#AjY_uWx{ao5+?0HHwdcq< ziW5J|v4~VwDZoy1=K?g@_|@BB)2&iO$vgcEQGJTH`c3k6Mhg($^7-F)hSUDHVXiG5utrfiLF?T#}&f*77P0Aaw~~6IZlb5oa>;*C$~k;pd;i zdO?_AN{>=vgHBoIUj%-|_u|yB^YNet(bIw7%gK*RIUN-0wQS~VZ-1Qe@aGRARlG~tcUs(sF=;E@oKvHMkr-B9)Ba41BK6%#m@#%Hu5 zv-EPPchk1FN`X~L1fv89l^A+S+zCA6mO^s+j7zrRMX6n4Lq1Ot1 zB_DLJ~>JZbOwM(KUzeajR#6@eK#5p>xZ{+ zH#M{z{ln7~M_(1FoN{{WFb7i!zQT87OZthtnGqa0iZ0moUsT0Bn>eEezoJz!IYA#Hz48te-OpYf27KbJsbKE`knwB z34Ijbm2EF$KofU@OQ57_f-yl|9GMPT1gYhCevt=*eB|nc9;xQ{U2t7MQvW)^;ND3z38-)?GkW5 z{K>;>_qOBysfSB#|TkSD=D% zXDX04EG4aFsWa8!9Sam_+Dn9KbfIcj@~f3w1*<}QVJA`z|Br2WM6NPw07U%znwP9c zd)&CCorqJe5B31WRpPx+#o34XbKc)3Hdq%F$Ju%SXq$&gyHn#q1{4SS!oyUtY_Dm| zznHeMqIZZ#9H?x}&_+Y!D)6I!(AkJv8!EYn9H0=Ibo71`=YSorAU0&+^g^xLOC}$i{=q zuI1RsJauqlrOaL<9b&h}P1?6}wG+sMT~om_9!g z`TFkBEXN+l_ibA(wc@8v&I<-hqA+$CEwK1Q9rnMxh*{w9HEiogGU(t3QeN})1+_3_G);EwIkN|+XpEj9gf(6z%R)05~O$4?VOA=P9K&` zFkqcoxhJbZh8^=G)M^g z^jMyYgYkmDL2lByeI+4Oz;6>nhB5eng_qKE=+pW`F-3`ni0FR0gC`9 zN%?Wa|FQ;g0TBW?d<$#V#{wc_5oQMH+6>Xj{42hh0C)GEoQM`Kkyd~9oAIL%FTe^l zqZ|8=Uvxkp@l=jPjuB?MoD6>cVx@|W>ayQU!w)F3`l#f}NKwAo5Z8*9Q zHsbwx{9YAm+ODI*TMTW|>wMoSR(Fb*E^W2NpBM3n8rMjPi}^(1`*jpL-=f0Q2ShGV z?6+#dyeu&JvEsF4=x&3t>N20gSl?2EY7BD2MTYBw=sW&oqzc%#l36g#VdYtK<3w() za(OjkiKeq(icOy9){)aaiuq5yi1?_d_!TcWNhsI%qxq2Rc2@ofcD%c{(-D@8AhMio(|BtY@V2G<*wncF#xCIaH4hb3{Sa1k# z!GgQH2Z9C&?(XjHE{$vB?$SWxyw11xd3WD)&wcL?^r|&$)EHx~p0f%F*riR~I}2fu zNQ)V%z&}lxBl4JKu+=st zpQ+B6H9ET9gFTlQPN!5J2r;{R{{gg*nz)H3Dm=6#d0^uVN~a-Psv|F}`CMrzFbai*qMr_HM1Y&f&NEPc z_5CHJD~b$sH7w;PO>~nc-5_=(xZ5zgLdxpgq%+j{A9^2*j}L0>09yD&^%}Kt5EQiV zyJEL3Ehir1RK*DFcWl;7W0uMZcI$;p;Cnr8`VCbP@ZD%Qw|Or*WZuvWsbOIPCbwIt zOYA$;tDFMs|4b%Wf!}%r2J!)NNP@ncXs=H>|93-5rD!UFKEEtv<&{j;*ambz9wa_K5 zXkCz%MQ+}+XmA@fZ*aj}<)m}MqSi~#H4JE%1o~cjyOg8LZdnR2A)RZCo6P|%%I&4SWeqZMs(6c zUGe$k6Ii#a3dWLfngM(S%uvPQ?ct3=Vq#)5W5qDd;1q7Gr=k4ByW$M;XkRr58-!4d z9#oqTV<5tz|EQzsJ$a$`_j=IgdlDQfIe}Lfn}V=_iQ`-YL-2xuPBMd zeYkG-nm;iBh#paH=vvfW-{Pl%335kP^Fw<7V4%worIs)spTL!W4ZwEP@6*nK?x^C= z0~JU@q6r5uES3`FK;LAfrq0KiMgA8EK%3{>Ovuz{3FXv@egf8^qRF!0)sJ&@5EDfb zxhsRq@GZsNzYRBHa1ncv*bWv-_{jC4a!2q;_8oGz;S}PwmYc8)qi&VKiQtF$!Z?n1 zKHXXmO!=BeawH$@la8)uL|GzuFq=KL3M)jX)#AbTN(w1G zUj-d=Q5bH5%+|VQUb=nnrm9g9JU2ac`zQteh%otu!5!lus?!@k@|*4R|5#g`hOX8B z&(upOI@qZ#*>yeu!1hvNz*EN84b_%-VrsrFEA{=kINDTH)%g9DRtOWwTlGVUH@ko6 zEa!fe%uC&-4)7Y1ws2j)!IjE=`n4_!2iYQ(xy>OF%xPkDO4JHI5 z&Z09y5gu7~OaZ;Pk3KFX6or!=Y<~|GT2z?~xTb7vu--0_1DN0HQmPcwh0o2KTyWTe z1l4WCjtAg@c1Fr8UY)b6LJr6aWdDmBcrgKisAN?7cJ3P~A%qgm=%XA8KUX84@$Anh zLx(8g&Xtn>b!Dr@336qtS;-AomQ++5GdzJ&AFfQDDQwBJ;=0*CHy7OcP2yz1vSIPg zz)z?zJsFwk$6*=%YI>GCA#Hq=-1WrB!JOI~AG(|~kxT8W3c?OO*coGh^I(497T9g7 zx{q+0yz0R*|6Ay0VWtR06T_AzXri)zUK(53)joI6{Pbqm3eao&@PsjaR;P|ndc7AQ^FV8TeZX9ZRIV++}51V{NY{LvJF^lLn zWehWq)-npBV1K1nALJ*jel7;?!rXgv6A)Yod*X&dj7Gi)UXMd)Gr@1#F%x`Ow?d|7 z)eDm@0bzkxmltA$?dSO&!453>x>k;lLhhk#nTZCbwLXl&NVdFUQx++(mDT-6AL*S} z;Dq8Lwb(pyKm_X9IS1!K2MZT~@tvRi?;S^%TQ@y4jeX5|+rMJ+5^6vn6w+6&rr*_m zd#(;zPY!iObK(AS$QvvuR6>-QH-_Q?6N*RAv>tQ&Wl@V6$0N$r>?D%zXJ4JLgvh9% zJ5~Clu7}DyGk&^C@#^)o>->!9xi3NjuTy7VuOBX&x-R+eFi6NRoP=57+zc_6gExKK z23wm~TkI4TvnZOoc&whva4x_cx8Qz|$e{c+x%be=qa9hd56y31;K~R_nY;DW5*WUr z)mD5L-lv;GrZlkjSyjw*D3wz)PD@rn<;#Ha-12_rBL|UAbKAHyupd6AH`;i&4rYSC?+Xxm^+>tT;&Vs;~P&?m>{NO1x|I67(#0 z^Zql)++72VjeMU(L0)8s!B3L2ESVRnjh%hM9|IjkR^pdFY;IMzH1c&0 z@Fh@1uX$={MGJ%HFqE$ClO&V9Lez~Ek)3l#9K511<`*X1_!!TaffwpcnucQLfkuMB zwyQUoNSyVlFB_+o7Ua2vm(jqTWPHv|Xqgxb=HsCKX5w4>#E^NuvLP-ZXc;7=g4LvI za#6u}F=NJUp2*Dr%-inkRkfXjnXK@wW^o{@^lY(IRrTA(4V>F!2GDRti?}0I0ZP39 zchKW~gJfMRU6CZrrYQRQf$`3=&x&#Se(r3K!17<5eA!338JE*B6Xx#s|C!mQIJm(4 zMTC;`9lC@;BkNCfDh-iN#EkamDQouxBxCkUm`Qmoaw?g)4rV;T+-aw&=)$)`&m#y} z60%rZk7~s-p+=BQ2cBv&5BbZ4wL}JM>s$u=I)(w-$sj0e!2x77ue8(N?MSvCJB1dtd@$>IVxQ^PI)h)3`s*M#$y8^@h9U?es(p5ycQ2@EQ5~i@ zhtD4gckVr({0AoKS|Y2b!uo4d*NvSQ4w>(073x}*?L#K=F4}ZL%l)Htoz>k7cCx1| za8mNv(mq8D3OCY;PP$^x$(8ze#jg$b;!s)ZaZBYc4}AYPF@`bmQ^TX1z~LBazmWQK zskkHmnIQ(LF6oNH%d=6OtvKXMZ&p(zE7LAA?@@NSyT}5Lo|)Iqo;tIDj+r1y^mDoU zXf)ZrXSydnK+ah}0N<^^0fY#Gon&7=J4E|SC!;v?%Tb9>=`pB1dQ0NGl+7Ep5`;W! znTQEmBeSc1sy#j#e*gtDI;E}5sSe`5^2rY5*peo6AMb4--OQOb_Y`sO#af#Dx=TcL zMwU$tx0SkLnku>pfWPu>5AN%|sb=F$=fP|vpr>UWY?J-_FGaq{wd>=Je+DmPzUU&_ z5$7&P)gjiZ*KDKHJzMtsAnT|mKrYI4wOx?6l>qn^rBR-(v}}j+bBrWTS(0UoG^v{Ix(c7@YM8x#Yjg04@-CT|3H#4+ zFZ?55c{sgaKpp+1djH#}?Q>AW`=gld;58@$uzwMHbdre5>DbdgdKewlP?^n^QU`;! zCjHaA4I7->&Ko=--A_eHD@g8zf6^leQX@uNY|;3@Nr{dlhNLk_`v308m3N51#QfUC zW+(z9_$7w}Pw_hu@=P&%9L+!4qkW$%hTy9CL3B`aL&V-8$Vyaw$zt5ahd(mWm&!RgXl9D3QR6)hVxxGS_Dfd~E^$*{CZ8|K|F?O6MW z>4uiPA`^8x7;BY+)@Tvft$>GSOkjwR2~OaXjZXgv{W+SUX9!6BRR|u;$j6W!sy-}& z)3KI5G8@Xg;tygV&r)_u3w$Cfba~{0SMQBw&9pjN4$p`~(H!d{q;le!FHd1>)@b;B z-|kThVl0ux$omD3m11At7dPRe&(`ST3;9ku&g1)*EcdnVK{ZGXri)|E`_~efxX5kA z@`jM7H~8gBUCAEY=P`Wu1$Qr1dkGQ z=V0)+VbByRSXy7ONwP4wc?IzTpMqZ5c3+X9fIn-jANuB;DRZ#-TyF@wN-!0T~2csgx>z%(@(H<@B5Ifp_`R%Pe!T+ zkq_NlxI<^%*!#2Ps8E*hkexOm_9mDu{sk;)(Ty0ji`bKT4+3=rL=F7*8#i|mHXHWE zQw7>Ot`nnK$BB2~tS+^#zP;BsmqpTX{Sx(vQ?8@u%gmAeu`omS<;TQUPMJ7nPmpni zAQ4CFsmDW?FKdJV)3;X`P|5lDaN?q2Xs@QUN4=5CWu|Bm8yKU&AQ)U~41PGr{x7@h zGS=6up=t*puiF=qvVZed?Y(*b?gTW?x8eAkvEOvnyZ8>|7|@D0O`1zbPI4?4^`O^n+p4#605^eW_$`2(4v{+fHSwMUqvrKbcC7a03PT zypx+G*#&XOCt&wf^vQMyX)5|b%Fc9rC?=>n&rX!uC;@^4toSlLxB z0>K{)?jy_-9%tPS1`(MOH-u^O@p_!TJw&>X4tQFm*dM4W&t?@ywz_NwI$DA*ifY`( zcr+mY|H|sw7kxTo#vyt%1h=^ocz*vR-bP2>iqrZcDje>E>o|?-j;2rV)r{Knvh_yr z=gQj7)&Xs>cH&%7FGPtXjCIENSxlrQ(t8P^AJN_p!|jpEy7jkuzTW{mVX0HdiqvC8 z77npzS{Oz3DM_ zc(_st38jG2Fco*D>cE-Y;@hgOQ)v?YTV0L9DFT(uB*G;n7QJ<$6C=a>YuqM8 zlC9{;vi#@~jI9I19y?d&_s10!xTI+zEqJG_8$xdFFsm`79t&O^(uIG11#>2Rsd6}S z@PG|WK@T#d!r48*V+M%b7g6-Q`ssRGj5Me77;|>X)eARsKHSE^&=Y%7tmb|kmp}Cy z*dNO0mw{e!^?k|FeYIf7xx-nVt(#SkELZ@>P6;Qm)raE7!)PF+iYy_T5u9Y^E%`+2 z{jo1{AI%PaI@^hB8tM@Aul=yk#+Mg78{x;W3$V>k`rJtHS=hJLAa8C5;gU3%D4Y8$!|M;Pb2qBL4M(u(3%d4p9D%CXtWFFQ`wyoOV*oGn{I#x!*XAw8 z=cHS=4QyS)5sj3}e;6F~BV2qcOC?YopoNDxKkYMqCZPdl-8XeV)LkcS!WjHOJN3pz z;T?fLz@uvKQBc@fE%y~TT#s%+a}j0MTC)kVlEbQ9u}+khWmKm|klKYRVs-vh*cF@Y zi|b}3n=T?G$0(?BcIf$dk)^YUu{!s-LF|+71~`)ItNraI=_<<4f^heZ>;u3IxNb;D z6>pIgfLonFst7wkI4pVjLNh=bqej?EnxP>>8c*H}=#!~M)nEjb2Fi`PKszyM;_@>+ zy7k;;I4qAdp^?<|K6_K{fBqK+XNX@LdEX>cvlb(nJ0bA*+gp88SjRlT*?Z=ke%u`0 zU6e)1wmuA4SUSDa+;^9^_LVD*$IZ4mSR@}kyUvQ1wh^fjQWc612y~ovNfFw=4!Qen zq_R2s8Dz#c|Lrta*YDszFsSztUU=tKtm4>OJvId9O}*D=fU&rasINdvVrh|Jhwjb* zVR2mTnfqOxx55!GvYXJOwm1751NYRXuKW|6^Jaqi9Ko2YhZts3!5aSVhd!NZTC8*O zDb5Nf;wvLBSBgk=sz3%2)wU1$xAQmlEWhL_ru=e|-tFCKN9JaIv#v%}`L-ieALHJxyoq`cjd-W1AWl zP9|%L93pg*&G^U0Mh8!1{moli65V)$M(9Y^>tt2fiD8=SP1V}$%$N@7m42538Q4ww z0g+`o{vP{!Rcz_VhB9AA0o(&c zer9{7eSXi?8@sjb^2X96(@Z{(w}iB{u3tC$fm>YU1fMsSKf?)oi}me2)+9qXDcV7B z+!x_rV76R1KcQ({-%i0;hlpVQolq&3Fa)n}x5{qfqN3C;_rYE?_A}p`w7IOcG`i2p zgShPQsY0RR$GC(G!Aepnan226vzbx*y=zAKvqg*Yvqe`e`84H67w-;&M?yzq&aQIQ zX}ztvPkc4 zZDATgQN;l@q*RyRcQAgqn220lo9F%aIO#A5G*LK)pd(`$BVf9wf*$33oDf-|Xa?2- zh-F)@2w_Zl`KvtXMKJD6Ck4<)QS5KwvkLp6tRwv}$}lSB zRNAO-0p24^2P8aU1$6T=C{v9aH$Kv5Z6X$mdP=LKT;MY+`Yna4KafIb6IJ>y(xy$B zB!bhcr>_$4xwS#1lIl?b)w9B(EduC}?|td&Ny9u>JsiB{=#hebPf50{LpLl*4TKD1 zK{mOu3s>rlO#kuu>)Ys_tP65TR;WP`evTw~^#nV8Ir!o3lKPeh7uN*aU#c0_BHxym zL;K>_#*_krU;h;QHQcisYAJMu@CL-{?6D7{KvlP z4d4D%PTDhXl9iPcKYl%l>VbPwfiv_mn$L2Oj`|E*y9Ggme`LfWV<tngL&@YPj z9KIX&hk=RgT+Hu3Vn(;zS!WQPMnj)mvg6>RP#`9=W}XasHAE_XZaom=tnF0K%L+U7 zh_2&&sx_?t&1WlrCw-PQB-bq7U0a})p(b=6HE*sV#hUSKyhkzMU|!?112d=PQYUL9 ziZ0uh$v*tiULa*UI~dcyVf7%k0bgB%4AfQ>?Df**4>A+$p*h(v`jF3OMu+1$k>*Rg zi-n?(tlc6BTfD0WAE|E5h97*Y5_wwG?A6_T-G!n_yrO#-BqGFvs7_o%1x0Y$l0^hg z*WLAt83P?YB2`3B=sWoW*@x2!+sfuZhh6Uy{)# zQw$?v5M-M~sCxBSHwLiUY`5?gw;QC|Z8Q~*)REm<&S`_&uHQ~Gjto}h2!8s(e~FNV zw@G-3MXE?_6|Gjwsnsb+%oQ6zL9x`!uF_^qXnj6mqr*ny_zlIV1h`cmp*B(Ykt|?# zuG)CWu(;dv!jflIMnYam-Q2_^s9c$dmV^g*3p~mA?WMN#G66~}=j|i)RdaUKct>kw zN_+m@u3nc`*tTEtcQ_CWxYua=7Cw1mf17pi13%uUOX>$+cn%F~)@|E%@b2i>#HP=O zI_sLKI+2Vm3*S*LhVn-g>n=tcpB}p~#OqXLEUZPWInDPN^Jv-|YjhXHy&UM)#eY*T z?;!66>z;HmbE>ojpsA<4ICs|BT<*9!p5xqX|DJl984r9?+SniBRUGEc&cC^PSFy@7 zq8~XsKx<(~sxv%$=TPTZsK(l8JDb)kQrQJWGPKX^&aBiah+#~yTX!y|9qejfNhh}4 z@099!Ij`&fl!=UM2PLeNWR&iV-YuK*;Lo+BQR#C`V>CsSd~sXyN4cX^r-`5#H_6+T zces!1mTwD-p!rvhH)fCfSE44=7^-89`$%p97U4e_=JG@94>c{0AgaBM^-uTdig4qK zv9j3@YvZxJ2@c>tT$zU)b+X31xA~pr>RxNoXH!lLLgZPd2JmGsdh^8&WZPC2(mD6q z{wJP>a!;es{e(|`<2%bXNdi9~p9Hp=O15w9)9Zj>?EcVa5Lh8+Q=k*bgBL+DKtnml_%%yr6n5?zAt(2CfQ)>8cIFqV^>feAcjpX9?#k#) zO~aDMuvWFX-l_EAa)q`mHP^1|=%;@Sp!s!3VZUk8DMA4c9(;EfdxT6g)^aG7c(GPz zWY)orDZl6>cERTItY*P4v~hrH0;aM~qPfxx8GByY?|=*+aD*i&LF$Dyfi3dElAq2? zybS3M2?mHX>gs%p?W*6!^Rg0Xs1T|l=S|_U>_{o6&)mSGl&;gS;7IFzLRPT)y%-{v zg3v2+^{q~{WZ+|86+b7(>GC~^<~~j;(=WJ*dixwyFL(n}z<$T;HuqQ4WZFU1a@C(su7>Ycn(Fj7>kXreV?>JKz>#9B z2}H3jJU3ZE$LIF7Wx^y<;**pZhjb~-EdUbAxpY}z;8Pz4*5n0t+soq<1t>=Gt33b& zx>+(gIi6aTQ-3P%W+d*pr!<@@7MObvYZ#R!vOd6iE`HoN7}sd`(Tx1rdU?)1d2Zhh z-2v!DS}ZP+nffkXQdvXlnhsX~XL*eoSqyv5>EDZpbp1iPtGyou_rrj!RX z$hMYKQwFQ6OgiiLfT1ZQ8zP-Yo7$x`yEQ*RSgC{+Og@aDKP&&cUh1scU8J*m+GFH^ zT&I#{m|0!R&!zTdp(l%X%OU(X4=+WgiLPgF=bh2OuQA!= zk<7B9RCE+n^g;uds+|utTz4RrtOOK-3Hs(f{JrmmZ*8)*2bYzE^G#YP8jCv1APLMW zig%9jes!BcX!zs<)_yxEMIo>gGv91$H*gj{<8R+T7pSHVdF+SJ9zfgK>Up2EYgxf& zWA;7zs9&xj0CuMWKB}F#50cDs8!C#dZU-?srbK0kr7Ll4hne1I@{I=4?oT~Lr4pm2 zY9`LQrA5oM*iERNG*I2b8oB5Mcs@Zt`YJh2p*y9RYI2T7((ON+qb(PeeInqII%d{p zAv)d*r*pU1T%x&Q@7%KeH3V-ROnpUVCj{b%1|fZTCKBx-wNO*Cw?k8uw}&Ezda3}aHgrwxVHLu>8yieK#ZPgP^hjFP zZp7v6c>*`*07B1d_EctK;}Eo|;^i);yK%bDx)Co}et7`c-ote>v&w%KOcmv<%}2E_ zyRKs4D)LjI1M-I0fD^5lgeO03OR(?ml|KRb%wMG6bkwV!9$?R>fT(mL2{@$&Nj5%w zpgP(Kr>hv8H@fCeeQsB3O81)d%nt zFJVwzpEqrPA&l!>Y_OVf%}jXi826t&E8xmRQeYNTtz=pky^>hbv0we zXq#I-F6N*FZ)AR3b@FsT&Xu^FQEu>SQ{o65MZnYHS+OszAd8t(|M5dsZtg@wel{{t zfW_MpZ>X@&Ule%Xc_4J&I3jzJ(5}ol(N|MTQ}36h`+BADdC;MMv5x5p+K6Qj8YA=G zvV+3zT#}7bIjkk*Zmn{WE9FyR&DqCn|Fyb_*gZ*yVpxYhWgd8#8hYCa% zU)3wzG3uNRs|veb>gBE^TJ(pKq}y%8ZEk`~r4L>7H_it`lF)!hpEW1Qdj`M#FR(-M zjTA_MF{-lB$XzG+zL_9q#aky}E*zy?{&`!0A!Fd(>a`S2U!vv9s>OZdYEX9~|78SP zYeZ~aS?DfpJTY&K=yci-ab+ET+v0`48u>-v$|pX~6$HI^N0e)AMHMzX0_f5g zTU|qp>nY+F;XMVby=rw;c}4FC244Q3&<-&AQ`R#A^13RXXxeLkEriaAYiUM=wq7CQ zR6p5J=+jVo_a(B7Y(~yqkM7nzzmfBIfnJpXk31L3x%1Umg`PD}Tqgxq#_Z2)nc$`F z`gG_`_}_MK<<=v1OQJPmVF=xsgFkq`WN*^CclSBao}8y*{vUZ|xYh0prmEI_ZrgUd z_GZ#g@OwI|VJ3Hr4s8Fnr4j!N$;%e-t6sQX4YNP~wirZp<5h7hpFF+~%Xm(EdzvJI zSyaVaDL2InqWO3&-Boq{|CQkr4Ds-)Iw~sgmNKf1d@E49di%SrK@sQF8opY?>lwEk zxmzQc1!_4P$G3M=WJSATh^iqW;Pl+{rPKn#U>8oU(Vbe>%B($l=WSQ#h+CtXv}#{X zf32@W<4fh-D`;(DyCN#Vt8CCCBIH`SXpmj{hwhYfhRXita|rOj0n7N?Z_M% z=U^d!e=Kd6YkpD79S79!{OzK#2U+iHNK+y`W^r_weJRIZ>tUmEB%{>J)OUwnuzF|& z+auZWN`DiMLwga|Gw$|O6K-P%=fLlt(I~nqm&UgnJ1lYnb^-jA=~pv2c(;5t(Vh;D z?9FHjq`-Py3furq83J>!3Gw=Z3xDSlaclrZ*^{O1~Mjogx!k%nb<6%vxFqWqDpcClm@uSyi@F0QT^Du&{5m>@Y=e{ zb2mF(uUke<83p5zJ3$(mi*{)`2jxJICSfj6I}a>3S_kW9`GIGF(7D)jmsYqb-O=K( zY7J~^VDpv(?VWg!us4jGm4cfIHqNdf@|E{c02R-wwV!~)8ajoif)!J&zX;@*1D^pE z5->mm32281;|2w_iBcj);X?9b>;TFGJ0n;sdMDmw+6IsKtcd2&3YIXT@_j1VNTB%*_`z^Tw|1px|_wWAJU5}KVfyD*IdP@sy)M7d9YAQ)T{Z51{{e` z-8+=fe!@w6DOj@30?68Sdb3E0Ecgm_xI7|y?KV?Ge`^sKi=jr?4l!rK3dJB{wtu(ZKf$XYCKcu{@3zpuA;~(DNWAo+}JS2+vM`8+^)vK zIkOO_sOLr~c2dvE2H0`5QsbW-;7@QT&?qp8)V{O?>R_X}fSblDHCA?PF{#}s7a?Qx zNLu@ofKaVSh2HmY=L_kycvicRk+h6NeiyobQ*fwyG1D<8;stF!F%5Qltk^~;hw5TK zfVSQ@^O`6WrsD4F-BErO{Q19%38Eu z6Sx?+1_udj-{ZrRw0_z)>cm~sVkX_njzXe&-Nz#TPZ-@}Jb~S$?jhYTt`K-YK~+wL z6Fi1{hpNY4=($AX&d%A3oPo0gZ<^E6a}V{;Xn5XH-^X=j#uSMzn-_IwuoiPCOB_k~ z0}9%ZjI;%2ADLzX`ddej-|@|CC`^-qt5-|472#&`6@t~xVihi2RL^mi<^2^mZ8Pa= zV|E9OBN~=p?^ZxxynvwhHi!{UD3Cn2>;AWj(=+-i9^CHfrbb53gZFJ*P$w1V>$$ zuq_Ov=s|+9KGX}y^Gc8uH5~l9Ypyyk1u;)DK+5FO@!w@)S0O) zt5c8a!h!ElP>45%o!)oYExRkj?>`Gp2Q@$d3d&wqKVlOr@+UfjAc1rezSi@yYJu~2 zR%V;u(b|6SK0fPzmiZ^hw*K{ezowUh$1n6SZue^`lE3*ellXD18wt|By^qx{cPXRR z!VY~uVc6SSI!lb}n<=Ld+nzCSefHiXrmctGT`>21qMTi3-v1?v&ifca3o}=M>C7Hs zd`MxZ=BJDlr!<*i{qk(oZO5@5t~TEzhR&x6tD^2T0s~%Au^uHmg)8G z(zG=?($N}iL{@}tS#fO(3Vf3M03?tOEQ9ZNXTqz# zazhYeXBhYy#z%z>ho#`0#Um?vyKSQ#0*{gS!q?ym;sAl?S2-?1=aYe5Z+=3HR)WU~d`-v)_bh>LQbT#!<9i2{-_@oNuME3dUzdbnZ@zJ4kjD~2$K&Q2%4o5h8=qV_yu5%b~3Aa8%^ z5qCy45*!^AUB^J{7dm3MSq;pBf#CCN*MHT8dW=?Fx_^WW(l6K zZqnlv3ueIB%v?&I-)r9#_`s6T)icO(1RP5}M`xklzWyNWih|LB>S98CUn(RzV3!wX;*H2-?Hg!}KMZf3h3`s(}u0Qx#6Ft1B&zH^!2 z{&^4r{37UMf^D%mSr4fP+0Gb~-h^~Bm-syc7hAOd=}FSrL=!2Va2YLL!`O=Z4T@w- zXPs`3TZ2Ik*o_!nb!>&BvkxZImb})|o#Hc> zU9fGCkz75B(*`EvPt?cjMSRTX(lFCD2VxxwT=VeEw)c5%Opi&+#1p>fLVG{aN;zHY z6_~PsPzuo!8k@jMFY!YL{fr{(jo6npleMQVsg8A;j*E38UQRFG?AsxmxMC`^5ut1P z<_w9o6+MX9*n|EpHl&dCI!40zP%`6K$kcgIubJ+3wbp(&QbN_pyLw>N{1_sL{OEXA zkLy#q$uL%O%d|y>NyEj&#yxToOm8BkK3r4P&WKJa3sZq)3;k<|@|U|C1b{ zp`fy(*?ZQLP;4^}Fyi5{TSe99IWxH6AIdgB`Ovz$? z0y;KW%>dWLCNk5xk(S=$hz|Isy8FfR=tRI?AcV2`W*adEn_dCy8NvmzuF6ns%a$<3 zqDuKkjZ#x&%90XVoW;}>VLFkq6!cgG!5VPesoCQnUr*SY;wLd_OzkTYK~EpmKs2{E zK8LWGt7Oq;7KI*05Ai!wZ3S)P_4+%Fgci_WnkRXAt%mQE!e&GBqpcY?t`C-?hJOwDD^R6|gGXqvJ&AB94m?}5K5g+ip!!mlU9scYsFB3MPJ6B7GBg&OlEV739p32aH1uD6JXg%}{QM9v2|exs zl_CsrBBGTLrv}k~@!~vn)lMWlPzK7eAS;|B zI)~~fjPpXkADUL;k~SfZmC(AI@xMm@e@j6QN-{=jwv5KOo65nJs5&vjuGqz>UmIhT zI<3;d-S+C7=~>ps!OWiN->82e0SO{k=i^)OEUT1-6mT4UM!sNz-1!-$f{u2EkDI^m zv}Y#Y<+~HDXyupi-i;Z&vP7!s`Xv##i6sr-*sL~BEFUi`G6H6Tq!Qjeqw+11%J5hu zdHFD%7fS)rmBQsnyRLll5gPN-CUGB zdLb5HYcyuX_yG8BCp(#(35s~Iuth>g^-TBa`BAg{wX7WB)OXAuI_4LD(O2_ zj*wuCKpcKR+IlB46UaunO%L;Qx-TJ9no=-rMi1y*cu1mms8T0UaMyiifp;N!Y-@Le zO3|H;=>84>QQqJG5`rnr1=QP|9=lq-A){O~R zX~*Idu%J5AGuq&r%Tb|Gg?^A}ckQGXxZ$wK=ko++vq)1CWHS;I;R=-xs}*2uQL2TI zA5xSM{-!pl=_eI(PXo{$R0KuhS6Qy{p7;+~7x>_gh>gx2CjGwjzIo55KdZrRGp!yX z+GWeZH7|~J@=JQlLzdK;Z{}0@O@D4+{Cw4k2kadb1R2~Qu0TKq1!Ol4Vckvj{>dFK zQ^!Hu9ZiKTT;Q@hMG>}F3_x#;{CV(~RTp#Ov3c=Z4*Pr2|&!dr>Chk8$cdG(Y1)hZR|HS?NtR5_op&!B( zAOr=`iiwxVO(&*dyuTk1pqllPKW7XXh^66je8M9cTR!EgNr+qWl1tm-US0HCW?<1R z$TYT58)2bGQwMdo+WheR+7ME?gBaYc=gXFYWJH#Po4JT^P+#uIlAHdh<-Y#Jl3(PZ zPCOU!MDL3|BOae#^e!}Z;jq-D)JX8t`SSwz92?7LwM9`ks*F6}qCnFQUPEu5s(v!4 zaS#6=zLJ+Mc)O6!7?8+-C@v-Q(e+6!uRQzDF`>v^QDr5^jD-Pv(wdxwyu{UYt z*^9uuC1EQ4C~4QIiQu~p7K%|6U9%wQu~ja8eB&;^(>qsAzFqYn_z;32#{0XHV5;v$ zbd$B~FEkZ*y7r0;f)u#`jHd-9xM#)9{Ij|}5*z#Vp;Z}XQLH*42Y!mFDj_Cwwmbb^ zwVs7&5Fs!n-TrXR$S>7+rFJ%Vy2|-~iDgYWhGL$9#H1lMe%n;qEu>1%MO{#fNm;MY zf7$Z)YrAl!Y|@F^6r^kXe+3hCr#h$ZrGyjaB*<|7HxvkY#vc)_dY%d9wPHHkik}HB zH=GEte(_X4%FO2)xb=FsdK`8Zv#L{eNOFtU%eawbi2i?xM)AW#{+t){lF;;vrlYo( zL}yXGSO5$>2%ib$69AN&J#y@zDYN&(Y#zJ#E2gvAFSre3OdTYBTneHp`AAN-1rs;Zdc1R?b>r(7E7H5G7ee@p?b`K-0mn<1Tg!g|iS~a3 z5~a+2Rh~L{-~H>c&;qDEz)(}c0e;A#{F{(5hr3Q*O{O%32|w6upO)Wq+U5E8e}-cm z55hZkjQLymNgO&0x7*R-R$Ni0guX9B9_lGsB;p6W&+dxvxyYk`4tS{us`5@|R|Pc; z^_LP|kvtr54JIO=LPNOC{MZaGOXuI(-JPK?z0e=Nd3kC`gk(mNI^OocxdE)bGF)ejCBmp6G~e6IKa;p?2@s!^Eif~F zCv~Ks|LW(0H;J_`2nDfN9^!v@cu;PVqzzS#NukByWPD^5$i=&<@Ry;;TdyvTmnIWo zN3k))Sseq2jqHHf$N~qFD)$IwE~4&O3+=#c(f6E_#bGe|SlrOu-?3e|KZYlTM{tC{ z=cToMy}gC>h{IOlsnKl1c<|LfPHO~IWRYLrMEhOcB^_X#~rwG-Zj6=r}u5_{H>opx(oysv`K8T z8pO(A8g~j+%;ZgbgFed!-;v+jzHI$@5(V`rez13gQ(Pf{H6EwB^MJy$3O-OD4*!pz zw#CI6^Mv%&ptlXnIzuBtaFmIv8r$H2$WFLiAR*|?B4OrrU^bCO_;WuPhvkR%3h{x2 zEYTJD`B7g5vs;J{S@#4_uM?9AWPb<+WvOr@jPGMEThkjy*35=yL~~X5`G?hbp;q62 z3v{Swyey1m)c5B_mZ~-<*lPAw{A%Xg;;^rSAqCD}WiA*kR+;=&;DsDigpvKVV&B`HxWR%h01<&^7=zWAZ%Y%slkrRSkV@{5738 zQ_W1LASl~PtV|tBroYlgP50RS1JFpd4R8J9QE}}0wSK#xM1+)EguMA!57`Thi7B6?2$FYt$5J7j)SUP|P>QV_diK+kHNlPo-1g!Dj*){v$MZEA~X+Ni};qnE!>lOhFOUAPEnUY6s^Ayqxdw9 zcz3z2WxQG-WH5TUeYXR$b^67 zfA}Tdmy4J6pR#=+5n(BnvKNZ0$EtsR76k2=q)$wQ5&gR&5Q+`7znl3O&971}v?$h; zF^L=iTK@YoX{;kI$VuotxF9FCEONYEwIpD1A^gAV^HX?l$42!3A?zy{qFlGOk&seS zL0Y5)q)SN=DJkg&=@J;Jp@v38N?J()>F%LRx?5oAk{X%;hWH-Xd!MtuZR~T-XK)T9JrdkGC!1=Z+@%zzN#7wy0;dH2g(#nu9%OSut|e;|yZABs z%+i^X#NWSlFPm*PHisCQ0|67t5<#*w+msStQ2@_cB zyR~N*y`=h~Zm$-fC;@JZ22*@)9b&2|G+*%tgj^v!h8lIfXo$+8JtP2yj^Cw#GZ_3E zaRUXu9)N7A`jxK48NMFcVEhbom~a{>GP{fZ(;d4`+Zk(S+wBIsI@1mUT|L9|h0F|L zP&K%?uaYmeicAC`fysZ9K=(I3Q1SLHK8BVziuOGwIREo+lPtKD6)Pqt5*?D1 z7o}NdRqRi0f7+5-C=w)J!%ZxPF;5o(^BkJQ8Z7(*Tk?8^Z!2^I+n|EIGgq$^0HKEz^6s4_aQ$&|Lrc@pr4qNPkju?$Q`NQme|Chfd zDDm>8HuiA;hh!Dv*S}ZnimlKPI|B`~gb@+|>$AFyAD&LVWY67a;{VMyM9BAxm~UO= z1*tPY{$@4ciiOPuKW}eFBfIsmdDR|2q^m*Y(CS zD@=k%%K$;>gRjyZ~1aw`Z_&&{44s?L8`@BnAd(Ttax(Tu@N$2~--K1c#)7(w4OzU7(|``*Hd2q=;(yEs=DOi%IJ8ya{ScZT{?U-pAoTA*`tCI# zne6sEI0>C>ER0K`1Yf~^E#W);zFex{sXWnYKU_2QI(Yq&b z!?G_+-a5`)ag?_y)i&Y4ASZa8GRx)x|5L;=-Jp$)pY@s606Jee+KcU_@dBiTM2CwJ z?R!O+7RrCm>{~c{n|A>A?VI?jQ2x>EH1Q@*J=V&pF}2ul5HMA4#DP7mtBvYP<@p=X zZY0;|=fgUDA2egKAxV+IzmEW7+lmmc zpEu=dD4A0;9}~+_zp{hSHaw3lulbwcrKH47ywBA#by5~QFMemtMdO3T{^REosR#R2 z-=%FY?+(cPNg@;1O(`+zJb41OzXwx9X2MNt-_T5FhY*LE;YnSR4U0-u7>{}*PNt;R zt;~@EWN_9S$41BHBb|Cr`N8QIWV|&1zUrF&&#~s+b5Fge>L#;zqeSj4JQUx2{Tl6S zN%K8=zak$qwY|H7ge%4mv;%T-GV^mNwa3_spZ1)OD^05wMw<%059OKOKWi|{qohKf za9-MnM*d#EvoOQ&=azqNj%kAyp-z!JW-%{(WdHMsVdJ?ndquar!tbqb%{i+_C0>eR ziPN@9H*iMrv7mT1_Bog#yC1j;D=`|EOD7t?;##bwH853@(eIIup@rTL^AVLM<8Hn` z#z?#!<5{J|waK^?)A1Dk=4fs1rJiUE`6hoix}$-Wv(UoKfl~a2h3xJb%^!V%sk^w9 z$E!vj5yo>@G}RW;>3nA|k=Mk}^iH*bs{hWZb4UBke(CAwvq0VsnWICLJu`}ydUZ(S zo$IbY1{qy9i+GBI7c@1?vi=)~oxQ-kVDWx(kk>?FG_X1WGy|LcX^(fF9TLvtVpRUt zV;-Jg{ZVOX$Z4sb7%_II-Vz*Kz}YfIW*tn*fw`|%8Q7fMbUVA$t=$wIiYF#+{QT{d zH1-``MOQ!FF83ZN5nc+TOamRH$}q`-#gOo?ydQY2g!3D_C(JuAA%tb7p2#{9v3YLt zu166P;WOoJwuY7|>^-@551HpA{7o<`Yk6)EKyAO&BG4DL>}Y82w_GGeAHGODc2 zIHwQA_N<>|H2pngXYo17P^^!h$J)A z43f&-;~Out=_%ji)jn5$3|hC341RofVg0-=d*UPc4ock=hB-C=>J_YmofE*jCD7I8 z+X`B-u!R`#@LPx$*jjzKnp`mBnj_kD8adyQE6U(?6Az{4RD=h4Db7uA9u+wrj*#4T zukgMQAaDGe`M3AZ2D!`goeEKR3V%6Ga#@=91No3*8l})(D+M?6g@Iw0W=wri&sH)O#4d()PvPf-`YFv89l z3%*sfeqKgcxjUYqt^b{GRohi?Z%xy;Ie8F+0H7Hp0<2Vczk7bgBu>BlML+ed)T4j- zVBtCKnYM1qf}xw{s=I#3VUuNv;#M_Hp=LS#O18Lg4b6GY>}*BFqxE%4&fA4QN-X=| z!g%F%>cNif=H)XUc3TBHkH8!o(jszr3(%n!H*O6N~xxpvSbwJ z7<@M(C}_Q@`kfC;`T*?S0BE(Xdk9kDLdrOX2lJ*$gdob?io+&iEV!6Rjj!4gFqAZe z05^Ys2w37lM?!TfCWYKjgkKs-GV5^p>(`n{j4eU7&C#Cz_t)QSctuA%PPEPEmt-?i zF=w&tF1!?=PAD9THjBfX|zF*7zx7yr6lK?0y%_0~pWFK$BS!XOemO^AkfuEdaLj-^9uCmMhOX22nd%CaHq66g7 zV~QLx#GNX#G^|&m&0y?dXQ9Fr3EclQQYu#_`tt}>94ajw5VQk~qjxLD4L>o0fN(K=l3+N(Z67!Mvcr|q!IKcmv3l)s*}2Hf z;jQ~8o+nvb81E``)@>MZi?G`HIwxm)rf3Lhy-lEGZsgk^|A8|W^rt7G1WKNtPE%Yb zT{VQ$F7{+w7CIeBQEt`FZbkA`Hhs#HAxjEzi9fY(eB60UJAsStogjj=)sGxoDdgP_Pm69Ro(2VyF_R-2HeS_<7 z!?m&TU{;`|wFgwvT&pOcFZR}BtA6A}40sAM-`4-T=wIy2*^!{c)L%-MoFA5UU6~y+ z@rEhHb;6ll-|F>_ip|*eJKOJcjZZHUo2hPfhcXZBMNks0{dV6HqR|CGrb(HM47{p` zG^7+siJ7+HA0toiUeJw%cNQK=me<4X71uT0rURhIWh8|ZWYf#ILTPsU*ShQe*Lvke zGkY|4c_NFdf(ud~5|=bFmwnC&poi66uL;nawSE}>n3?x*lwkZ=G{@)*$mMLQJ&A#E zp0uW6R0N30<}~wY-2)y!!s9vuZf(dA-+4~!LPtJZMyf8?}NWQWP?rmJ|xXt+!}vZm**UaS(7{`|xNUf|kV3z#s<@_hPOeMA>xNb~HjjKJ?`&HSPjF+! z6TBuM_=!#SK$#^YNIc|i%ZMLZtTh|U=kz13>thdNxvk6}M5WqO@rX0^i6>u^8=?ie z5!!`fQKqaG;k&wZ);~R?4brY6g!JRboY-}yo+sDkRnzys(!L}gLb9nr#USbTs6 zY;@ze$vG-W^B-Q06pa3|<=J1iDqRtLyI@9T>|RPKBytvxhGTD z`m0+C`6~KP!qzOEvs>;$JZmPjj%Y!h!uUg@omjH#g>)Z}n_N)q;^mgQX5KO+e<*~q zksv;^+DL*SDqn9z8B|@S7KF zpJ4KoVT1J!-$bpg{Kgmt#*3{dw}jG)%?z^NZtUYrWvN&4YSq?GzDOF%E!qzE&|c@2Fnkgz=`&_y?eS4vz6Q`=NhPC3O$b;~RMqzVCJ z%V*(k)Zeos2%`pc8xERCimTc@B;ZNX*%{1lvS=O+^*)UdqB|zF;Q}nFzs{7p&EGWwfRB^GMfd!fGR|YT~qK;e9I(P$0zMcuA0nAqKaZ|#l`sfg@7Yp)Hg>m3C&A24(E6F^ z(SEYZ_)C)yfa{3>uJ;hyN$#?$@H@W7plebX|31uqt0q;g@iTsQTYOYY4WdWqvs_Jl zHU=iOz-jb{s1A;QDKK6jZ@DEbC-g?j`wk0(;r{~d zJ8ZtI1dd<%mCfE-^!~auiTB^+MqeV{r{?Q7XnV?(3l!b^oXpfc+VeV_VX_f}VB`Q! zP99>Cg86&LB;d#4M7K&_)sE6N_ayFF!g`vo&|#wRnzF?hU$lbeM|}RCcER|MSqFhk zs*V<^IctKm(`x)iA*7qDM-iAcV}c>QM@o>$ANwJ<*&XN=Hq17B|HbuOPKq4WOC>=V zBJZVQ_1Se0kp3kn-Iho@VGJvxGj8%NS)AidW`bNc_BM@hHq9wf((*zIqPfUYv4#fu zk|A%`S2hJy>pM!vas8R#H+A>_X7nCXgYoqNy{3U<)W$V8%LOl8U@iTDQ?{i}_NeyB zMLRQ|Lf5WnPJ6*9*Zj)0FqQq=2L}45JZgtq6;koM^+>b0zYA>9wEZ!YJtMBSCgE8v zA!RYJF;%n^8x`!pe#2p38rb;@n{tn3pRjVXZ)Hq)8nf8v50naU4Wb<#aJ8ZrUVT5< zB)dcDy8_ebnmt*hn|fnQ)9`EFZpZQyuFlR=0Tb0ShnV(HDNJXmq~U8-9K1q(`*md5ME5PBX6Y; z2HI2m3C@NKa5;s-6zYq5<^FowFT&H>OjZ{+s{=qkZV$N6mBUewyftzfCFtm;LJ+@) zG9l?TRTSkP)ERe2aWT*!ruSp?hi!$MaON4R#b;e;Ahq=xeQ5YW=3sRbNm*Vc_vZ<0 zIC$v1{uo%d%4aODeqV3++i8A|6gsm_Gsk9or6<5VsePRQNy*{<@#l1%Z2J;9fB4Z- zt!LAkrmSxi;$uBKb4x2*ER_e%5McwJ01!v%Z{LI+FB12bM_qtUHbtqg&tL^OtqkxjmKABciR=j1!(IEMfOqDW7OS&zYCpfuEa`3lU(Zcbget~w1wz@xM^106 zPoO(%gRNWtmLvNGxW+}4~}x0CJd z#5x3pyE$2|VcbzndO^tdy{b&al>X=Z2Z1qo-bbNMZp)ADua1w8?zNL-RiE6oA??8h zHmL$N3p%bo&r_UY_6xGjJH<5CjL+-6ux4+9EKt>zuph{kl00Yvc|ZfnHS#+SNw(Y{C*I3Qsz`odj&9(ri;|? z+kE!1*6##>q9?r9(y1N%vM8wQ%esl_ennq|{%f@Sz+|-&ot|^k@r)+mp8<*O}zBTIA@oup69RR6D(KpE+yG=ng>Ema&E7^ zy>zd}liu!(RrQF%vv7`A61HRm9j@EX7%Lyju-< z+HEK1#^jA-W1AbkNO2{Zu5^l)eQSwuk?z6g;=oavnwEM-O{%h~y*(rnni)U% zxKS@OZO>Y1l24IiER4U@L*Pi=iOu>N!;C5=&M3LapP@_;T;cafnRbMQh`}<0KA_19 zNx=1tJj007xz(%jphf4cb51$i$xN>eJ)clo-yvRu#Dl%YJ;()Xily#w>#sMSCP#T) zz!mFbwN82r8ACJS)o2+Tz&%_KdmFtrErcGDkl9JcelB+AtsNf~=s*f4SnUtLUAfRz zXFj8t9$bAmJpiQN0Kl+FYRx$t<{g=i{S@uS)Dlc0MlHD(qCHa%fer6KE$qo5T73Lz zz0B=&MzwOQ5~JV{#osBc%W3VMU7PM%7;1<_hrAv15=~}>R8D(;nr|k&hR_}SCadbc zhv#zj!%24++q2_n@5p0oYv%f0;lk@3vS9g~Me17e;$S@q$AJ;D(F+08Z%Vio$xVN` z^-ir;19pNl)%{sofsuYOx`3;cKlo(9W8W>33C3p~{&wh9T$Id@0D1-+h{AUjZ0AlI zputr-fOhYI@6{;8#^xe-~t1#iS zMlH&9n$xDsV^DY_l(TYt#7IFe4 z_pk@@GFhd&@GLK+e`_e>q-tv?zv@(@MQrUXX`_PNNo0vj!0S?y1)QEGsqC6&yia`q zyZUnOWtdx*>IM7i;Vveud)rNYSu*6$X=E={v?wFEd9`f0G~=PnCEC6ILWux6S`KW+ zLVLN3FfQL(GG`NWN${L%6;2!O7kuEL*y=uYKHa_#0?k>38dO3@ivZ@r<^Gf>qkpZ*!#Pku4?4jy*`kUdeSC3$& z`QMP_{EOCm5nVwU)qk@dn~kSqZC*5(1X_Ks$M@EB8&fwG!FPm5>6F8>bGr(cl=Uhs zmgW2e!rAvvoYHI|Y`fk2BT~_>g7rr@sZVbtYq*gNQpw9!c6#yId)JvL&B)*d@DM#T zdd>yWDR$}|&twvN9E;)qRCv65-rzI_``*l0*&1faJ(3I_PS3TsnT;C#ykeJ%GiQI~ zQx2x@HiAd;9_zdJqgkX71M9{kMds6p(E-n$a}Sh^a`*x^;>rg7E${tQa?>zc4Zy^L zhP%HU?nfHTlaj4JEtX_&0*PwH}930gvI$G*9739Jw;j$SweM?zdL$kTSj2{rlb z)j9pnuhvuVe^GlP+r4t$tE!ZceEdy}2s$XE%Ax{Obe}=+KN+^O2>l{bQ1{NF%Y)&e zpwyDx)yfWZa1?9Niso_nZT{!bTUrxFUj2?i-(74=_QOHIs}hiv{iG6WjI6oLZfE+d?PiNV1t!m@3mHzb}35KHm>H8>Y|PlUQ(Q6 zJs89epVN2?58w?G&%6H_)jq1jjq#R)o-*n1N?yB6D9Xgo4U#{VxC^VF>8+VL9u0pU zpfYmY32Ck&mRL+_gDkL57TWEsISRky8!VLye0=wN-ElbEB*Dfpr0zXug@&|xJw=Vm z9`9Ku$&@{$|DBc>Yl4(FvKZL1+`K%AW$P<+hPg#QPsN0!QHd@i*StHJyn0!=Iw|)a z5|K&{&ELL4v-oL~i>Qh&&SAfS%yymLUR1s2@j2Cbzw-yhnaVZFwyfw_xIT@lCaR z=8j1HMwV+Lpl@{eVZgDnr*wFptJ4(aPgt{on94c?vQ4igywu%mMZDYA8V0~<2(nyy z20GQ&M>TqBZ+}OKY#0oX&?2QXc)mkkq=CE0q<$4}@y7Pukqb3r;Z6C2+Mkm07wjgA z_BHHE#v4?34i%;H10)uZW;-u2PS#Yp^?j7-Sp64-NUy|tzA}&1J@9GcGi5~e(cQdf@Pw2>WS&KR;ee8 zH2;aU@0l>TAXw~&Vx-Aq$L5OEUe>?#Wm)~;N(XPopS{5@0&pGMp@L}Un2hQsk>JU;62Z{|EO~)iu~B?59O+y1 z_0Yl1uAv05euitlGq(1v_2}wqFrL9`Bky}{H@UW&DkYk9*=o(k)Qh7;{~#C0HPKDU z$drVFqQxmq1Z$TBVTN{Mwan_F1x?8Y89y66Q4+lb*{$s3x3M8;oB;_OaZPC2TE5); z;=sOmZTtL+;im7Y`1}q^$-8iRXh_Hc-lGWMwUQe5^W|K3NtU^J)%#mVAgd$AB&4Ol0nt`EGJJra+T$)fO`TCImcRL`P}%dl9w3 z&h97lPFM;HzE&$RKXT}wo^5tzz*nH^roc3F($uPi`#AfPMNyAS}3|p9eNN z_|~BEe>W)m$C|*>#wN^_MSJ=^w$hTF%{y%@C2v?I4s}Bfwkrah%9Y=oqPTMEYwz1`mAHA`mjWft&?aBh?mRVU4hwlR3ts`OI zOno8548X{903*gSG`kF&PV^_?wo^G+aL(h?r(_?zf9V%|q^LZ;eb60gK9pz2)KZM&VTyol(V)!f9LQrG{_cNvQlM-hS}g>4brP=!CoTMf~z%i8H#uMw@h zdah~&0_V|4A`g1RYSkgR$jLI=!~>1`{4nrAT$#lci`P5E%JukcSv=;?Q0yBFe-{BL z0i#ii5sLN^AU3?ZKNP3dm`idJU$6vhpTx@~$AQ;sRQe0u62McF|4;#yizFy0x3d$+ zukL}JMbHbIr%)PfLYV%a250}TzhB;1PftO**j&#plkSSqheRViPPFc0An*wNJeppE zFmIfAVdOteRKn^f1n9{c6Ffc%d%vRhA$6^ayOJ2T^%@J#>?d>!==fBCFaE9PAbmoZ z(dK@s6Nuxt=p#X0SbSaJyhSAuY%~h1r2*iu8z?ldt^>5(Oxg>uDhOazBh6dA^4^1E z)U@!lU;6GL3pD(Y;RG#^u>bRmXG~C`%;Fn(yTd1V${7f_T(<=x4@3(D4YsHYBB9SpL8-IIg`#9$w;V&ONe;>(q z|2(HDr^}vixLOeP-19QYDl zgU6yj)SuIxcQ;tDWa&%JSL$nN@IYBpk<4Z*94hBD+k&as)>mJzV}8M^RsvVsf|w%o zY(Vyg<1jS%lv`LJpMPDgDEsQQUq_agFhX-Q9v^=)XXd?2?rT0Gn%8(s!>Z- z$D~-D8pgBPg!iQhns)Xi4J~bc?krhTf7uRq5P_k1V6^&>8yze#V#H!lkIWmlzT2; zINwF66^yZeg=*H=@fJmny_U){+@a2yB-$e-jkmq zxojRru|bi$i+VP%71@~cqgzE{*(kBUnrlO=?X(heGr4Q3t0*R~$GyhlK{Oyrzs>I- zvjT-EC?DYkc|WRl)+tDB0$I3Sm@I6JCJ%JdFkn=<@D{c@V?>cXxJN@X&2I z#ZyV>fGzSP{x1t{M8YKw?tm?QNCEdiSy)JoB!B~#Ckvs#ZO~h(Vps^^$PU!xrF1h5 z9R}1zcAf!gMn5^Jm0X_a>Qt~2zNdkG85x*?Ru(cVh1 zfae$s8lUCjKvci?eQ)DSy;MDqcsQrL(=ihi4MxR=XP_L3MW$JE> z?M56}k!a(Msdy!^?pwstjZ;v)88}BmWzp(^uz`Ytc@-J};xK#+y8|+$BY=Nb^99W_ zkt}s|jcEB5j@?}>8tO5wqnjMZ7+w0^@AaTPY~-sHr+x$|dkc5z*g0n{EyqE^AoT(K zP|uuuLz_@cw-^fnHugx2aJ8EB=~`DVZV<_4*y3odY%1ER8X8}chNi|S*6bS7kQ>P5 zN>z=sRDdk9H~Plqb&@|5kk0Y2J{eZTH}u|L!RxzQooad{Sl8;kzGrv7uPUrLq>|?s znl)IL|D?Eg%B{OVfH5#yl(D!N`$#_C_1z_SqMK~=T>A$;$3P>AwCQtthw|#2d4quK zh2Usze{M%sVMyQb%m{(6pnfy-v}n!Wshd*ilX!L(8!Y>d0g$kv`1pHCy#ik7B!Htp ziwUv7Z}VP4cL!}3zw&*Pn1%Co()rTD$_vWI#aP?hxY&!U$8my+Ut5;C#dk7$->di# z6BIw$Q~h2A%475GV$d#W&oisSNa~StnmZCrcG2*FK@8Oc^ig+YAXeP1B}4u?f2#ot z!93hkCMdD3wu!E*#`WV_TA+t?)t(&VfN-YkAsLt9`-PX~eJA-ZlGwe=ZOs~$EOEN$ zAM+MGB92=h9=Gw-J@keAzLdvX8bZA+v8wN+hmoFrRk4-ncW_jb{~(w@@y&EyLTW+@ z78&m>vRJ9|h9NSA`S}1>Kc=j~g5v!>Ag4h=p*-RtYHbKDyaPDIz`qPH$@)wA&4uwBJ7I*rx!B@l(t{mI^kWSpx z9UOKF8}1y-$WKBKV0>nx{jCAW`@Jz`GkQo-jh>xWk!Vj(!IIoUbBU2S&j1fP8ZBDm zkxb#8eNdWyL;oA;;|3Y&U>SF%)@1KfZm^yWB9Jz>j~l6GvYz_7WI|FjlqsHi{lGxX zila1|-vtk0{ikF5{1?YYiEI;`;7^q4kmLnPsyNsaz(XTEJKnhAblG}+zZ%Z>T-EVV zW}*5_t^&4rC+#J{LKi5MSmOv`>g4A`GHW(a#UBR>hj|9+%ne!`jOE=EJz{{>xmqF^ zm6`fgM!+olBQA?Y=GGPg_ZptbKzFylr5In_r&35&(nQ*>uaZYEsiyZufOgj!kcpOH z6{W%QwlW6Qx*rpCaz90K4mr}Pyu`y6&HpmR-i;|deLV_=8)G@F(=JOfV^oINB2~YzA)+$!JS_-c)2+d3#28Q3gu5UprCL7aT}$% z3GojWL4>c(%&f2$t*F>*wv4!w&*0!$B9$MX_L|`BdI_5CgMn*!e*Y{XVo&rtXxl0+a!W#QxhaE)pU;2 zGh^T&Y8Z^qu*gtTq%{q-8^4`OvN#5IF#X_k;%J2g@4OjZEjjj78M(q;oI7jR*r-x- zZReM&L^83|$r4UUMRb`8*FLH$pgK zTX}wwlj1a3?+cE8E5v7d#QtamHPFLPN7U2rIqAX1=A*<1K1IU>30DU`SIoFXaA7$l z`7Hb~?uXQ9UDDQu1mSPFnFZT|vqR0j_NR$>f5zL7H}UoibrH`8Ne;jz6DOd~f<&(| znHvrOTvo)Rk3f#cvG?t|e1vGHS!zajxCAtsqP96M{1N|oo@#1JtVPV!_bvK*ECe=p zVi>wo?V$#X6BZ&)!&*2eU;!NhX)E}v^D zC0Ac#;_PP96`@qI$Zr~yKf+1-!9Rf@ugjTwuT+t!b@u0{qLLbPYCiQ%;2>!zk7T_? z+9m-UO^u3Coi0d0w;@w{dUD7sp?pUY%7aa@!#!qg*0RKvJ46c;=w{P557CTSY6adH zX?XSNSFC5Ppo#jgs`*-iMK9RH5RUZYd6~f8s(bK}T#ERfuhZ9|7L?7nK;r`C?bx6U z7UBS-l?nyH2Po{#Lo9HUCAL|PJiYop@IUqOU$34j>*HX5b$kf-yy`VGs95THN@t}L z$(R+HL_GFU0&1AC`Ew^&w$=FA!W*sKL4N(ft;JUXLZm(BvyjM7RW4Xy_lUuvsCv#t zyH6TTMcHG6`T6%J#x5R+1_)8y{S4!*?qMSfaiTwI>YCEIG1_{)@Q|1_oH zCMpXgPS56<;i9NUgYqOvc{V+B5z-{Q^)i!sv98Db8=uBzn7O9xVY=LVq2VKH#27nF zD2GM0U>18>qeh%WDM(wx)IB%cg8fG{ahsL-E^?E9x8i!JZKagW@~ z-EhF|>(^p9U^~6k5~7qeL93$nHTE51$tRUc^K&{?xL}oBZxcD2P+h7Cb&i>G;w(W~ z{MO{4;dvg7eA?HQ`cTB9DyPrFG8ow4WdXDc@MV5U(bd9wXQYtFG#^cC^8L)${r&XV zOoM@Si~L;T_hd!ZFSkxPs2%@s;+OlP|8U|4qI;kSiV2F4RR&moj83o$RBY`jY}bYm zzCL@W&-3CHx!)tw&RpQdV3CUVq;ONbFY~ZFy}~Wem27$1St=9reh6bB?rWTkYlV56 zD=ScXsX!A)ik(hL;Y#v0!o&B#UiuC60}<0Ravs0<@LMnC$G9A5uTRm^Lvg_p$!41r zUvP$7`VU=)?)>Q-=l^sLSq0AK%WSKDQ-fBBcrKp?4x*DXPzb;8(m$56Oi{PCH%rup zC6&)1D64vAAa1AivZhd5^(vZbx;($$0wW~yo$MDRb$~~rP@MbME{Gi|d@EdHT^XvG zFp)DRm}sFn-y1*D9zXDtl{x@9F5;OO#rV)T@I?Sv;V>D8;sprS=>%s# zJxt}|i+1%@UTg6x=0>y+-tf*W>xXPzea!%+t}E9R1mGJ}a!)R$tx2SBC!WiVi6)A@ zx1C~#)#b9tiip?UJ*>Sf@KHjZ{Zd=az+9xJJ1)T?w6-UO+fxM%WPl8L3R^@DTz&Ot ztyPu2jE{+I6}b_>h4Z{dV0|Jxs06JIt)({oE8jZVn|~gWq=5gl^svZ3EDb4}4CQvi zMcfPa<_q*t_cOPrEw8~r@Ks%5v0_U)EaX+>Dou|}2QeRN-f>w}oX{OK8iayZrH+%W zlp0+L;K}cM}M|_^pul_@g*` z`(J6&-%s&7+W(@5QJhy^B||(BijV%Hz@z_SWx1Ci_3MZR9&a0Rx8~Dw)Oqxu&dice zV^p*)%}UPDt?_*zBiIJ-RHjWi-S2u2m};FwS#+BB@$77Bo@)#eDEgDn=XVyk=Ng6J~1 zoo2a6u3~ByT1D2)jrF4r^z9$Kz(q9iuB&Fhh2mzXWlBQ{OL7zVM?21vj5(UjY7*Z* zhGqOXXgrm13zoPFsN+9P0@I!t?nqQ)?ls@!j1LrPuon&LUqaCyH%UK+iEH_SG(WMm z>Tmz_$3h%xKZ!pa&AGq<6S)$lox@}qP*pw=;vN{Vgw&( zy`W82RksfrkVvjNC*m6ZCoaA9Bs5pA!Io7W+8X75)>$ZeyrKtRu zP>v~s`4XO-^0ezafM(cEm7ZP+1~uX@_}&)6pG1KS&J_sBFTEmw46X!qvFHoNgiWw? z)LjDj`tonX)m&w_hw!l!{-Jbb4h*0+6a3(#2$lbpsTVSAlg| zvFf~_naSrq1Aj>r@K1>d5<#TlqxYY{f)2cLSP1@og+hH>U8T-Tzk-t9R99WQKy^i+@fh~dSWb*^Ugu5# zvglcn6dRxyr-V-YiceXs7biO5@7_7>cAF^TKC_;U04YUgvWIW;ZBXC+AwJi60~u6r zc*&gS9Si90Cu`5Fb>Vla{q+=X?PQp9_8Y_M=1^}!nhmsAGI)UA)N>}GY%e7=6#UzC zbr23PNXSjXw}Jp#6^B=dqAK(rA?t3EAX0jTK{A>1t-gnxedTNYaF_z_XmWAXj? zrTYP}vjth4#UKh)du2|oZG>a{#J2LUA7UX`xCOG>a))-ZYTpGQ1(d^#bWI@q>dn{J z*8H>ageJbIi;AofpAp_aBM*84kl=7b@V7=+>NHIBKlB7_@cKlbw_DgxAI)Qf$Rm!d z$onUzzf5_`CnT(6A->N?7zETs8mO8-h@1Mzi)q>(v+mXZ^n@0M-!(#pU)RLgPssta zr*hT9urw2gcckh8$^q#N2UW@av``JC?+Dv!izzRD35|DTd~HT%#Iwm)*?M_&&b{_F zSrQ-X55|GgCw|qEg*z1&gLmmQ8Hu$2o33zyoa*>2>{e6aP_Q0T>~7VgOj#@R5Q{jc z0ZwBeugRK)9hEo=cCXjxbl?IUhsVL!`6hY=aMe&ks%r7FbXV($+h`Dy!I# z(^`bOI499_MNq`w=jQzVMo|ocTp#$~sV4uTtJ$mFZl-T#pZ<&SZU||;@stG4l=c~fcmj)%eN=5QW5LdJ zRiizt?EHSJqL5}$QTmzpLD^x9snZAPa@0iwMsJPd=k-$)tSH7v9;Z6~PhyHP3arx# z@puTYXf0|bdwsZn`P%@B7#&qMX1M5uB61jh5Q&emPnYgK+eHDd36 zufmoAw25=z<8h)>^6nzqhk5q>ODqJfTS9P~^!1k}Px(O5Bs{7W)34Gp&a+2N>v?NK zjG=D_UKoaL9*=Dmi0)x4L@{ChT4Vj5NE6DUD0^ZJDT?rIr?8LXlK{iyR(=92g{nfL z+*WtMtrnlN(?tX#amZBDlok!Hq@{i}X0PYNq)7jAOj0omj%t<|F#!z>S_*Z_?%}oa@#@c18ZWS3dF9KV=FeQZB1$y*)WJD_c3Ut~=`dA(h7hXz~huP0+ z*Y11BPc{W>$m9pdq@nWh)BRH3y2#G&<4zc!>(*z^WhI2mcI%R`tqckEE7V~vUj1rY zHO2y8b(7Ka3}|He^HyepkH2TNY$OLW8PJ)9|6&7eUAK{aw_o!Lt&RgPdNpk?AD-{B zI(?d+^p_#?!My2AH`kp4G)wwHVUY|QW&baiee<3co|&Ei5Abkn$B)!d(TRWY;(m0E z6N4ThoIMaZ=e(?^Hfs^Dl15G{ui)fbHFwg5!~9qx0Vyfu`I_JA!5I-;?fd5}1(8I^ zA^eo$khkQaX(mPe|6}h<SOeuR|sKHrBC?iHPhHLdd?8 zeHddIJ0XNH_Uw$^U=07S>b|b7`*%P2Kl%Nh+>gBK%sJ!xcd2Q>;atQfy~#{3Z4$!IT)9v|tf?f1JlH@39DY@Rq)5 zz*lq`@E^_a10x2BkJ^p!DW9QYwY&6sY#ie*T6O+jX+s`rgEz^u+q51PR{BiVDQM~5 zL@T;vQ_fdeZX9H^N(!GtL29n~YCHhEj{9sWL*pQ>y{H^7FcCDqsKKs-XNUc6e)GXaYVQ5h{QH?^@rnv68RD68^@ACJ0v8!2l@W6$9 z!`jSh=AvSxf?Ee_kKABCHfy4IqwZ*NZ!h#d42AsYAG`utYZ}yTm$SabeIy2=zM}~h zy^gpC#FLsO<5l&&R>^ZiZxsN32*+`^t;@i}RgxbvCl}Kw3_fS|clAp&q^4od zBjX7zBkn48P$oCBBFn9RnC?hhcrvm7LAV06uh_sDXZH9J!LRk~a)&wzo%yrcq|3pn)aYe^e}0i z>|_`mJ^Tt=9X~Lk@?dD&Yzr3QHppcp3Zl+=t4MctrTV#bk>WMPgkr3I)}V&L)w#ps z;`Fo5Lh|yWd!ENy{3dVKH(CyQyx#QQF6uz)JmMUWV5g{}m3d{8r|V_pE|}hjGMM7^ z=Jg4Z56&K1CUdwi1H({IU&nKKnV;NtIQbyUywQLb9U?`C%qe-l-U?}H3u$>P`a@;) zB07J&m}Xs2+6btYKhP(F*(zga4w=l8nU+K>_lwVhg-1m%tQ@F}->3W(xRd6SG#8>f zi=&a9hl}dEs|81CDNGr28% z;bYDn_llkH%$30w{|O#sJN!!n$f>$U@>X>$Vp=0@-@nwmU8qB`K3dv?KcUuh%kY(Z zt|6v#=^SRIWlNYxv*r6PK7VE@#GkdgQV85jJ6y_4gNrk`GZJ%us?N!%5L&iDD)KSf z`&*|b{Se}g_=38~?e5(aRSZ>|!J$RA)(aBCVsA-Npu|+zOr>GKN@x$?9 zwBT9nOxVkD-+%&JJX;HuD%mPQ<0)n?fBLqsdew(h_GMZf zX@XsOwID9AY_-hYTV5LtR_th=bC@M#{IJI@LolBQFQTTZjAi`Y`j1OS{pZt{0@=oz zBq@aGmNO|Rp3uLihePl@9xbEu%L#G1@0eHmeLB+f=&koU0_Bdn$KtaJU&JSRmrI%3 z)32Pvl+u4bFJ&qct=noYcxLH!C)dZdi)h)$i0{{~h&}2kqCSh=^ghVg-{?0Gtsdur zmRxd`?*c(tp^fdfn%g~NXL@Zj)DJhb3(sVde1+WX;%ja0b?pTo%v|z{Kpn3UYp&T8 z)4qfW8@yLEoFl>v^hYJ{u|5{obZIe9mmd6cWZI@TL3&;q=Lt7KHI^E^O1s;ElqArTUiZLuZNoDx6QdgzPTNS&BU zs`#PRH3s0u%NE~(IEgSPBz>VhV@3TkS4&2XWJ`fA7bMCF#SGsfyIQ+h+45xxOVFU)}x6fOj$sww(6a6V; zFLt+&oz3Ipi}g?E#BO6g9g%wquZMer@{4e4b(~M$tWAuhx<>QG_V-l0E>4rUq_gX{ z(Q|zeczqF0CT3l(mia)(%O!C&*T!c*TysK_{jB}D^ajx737agC5$#wj&#qlBUmZW0mn)aFBjMZ zJ7i|}Xlp!erNxW$xM!i*A6cG{@dQYa4kFX1;@g(uty`0~^Dgkz8T#ZQZAW|&H>9M+ z(vFkb1~YL-VZSVi>HB4Pllg4)YY6A{vsXiq&Wy_A$(Y%FVpaJm<7;H+hs(q~i5l+$ zXb2mHl^(8X<1>96i4KB=K2@>|DdWbSvGyCn6~d*12|09Z$NMdkHYRuWhMbfnRSbD5 zFs-qQ^shULZyD^!x+jJ2k0(XUTaYKmAx1TPaj9)ZeM3D>0(5y2Xd{GYdHk`r`TIT zK%s@QxWf3c7iU`&jEdhyucye){bHLX*X7ZAQP2!s&s}h@rOx{fu^BQl&MUqM%^X4q zK~EcC5@1?DZ1&jtx~pzy_{%*akB;E85$8FeRpQ6KK@G?k8o>LgF9ernixVBEFhkr! zmgBLovz{0JSGhy-4dSu+R)e;=cNjze;3TB!xFbAaQV}Gxu1OxbAZGp(L{I(0>bnvHGF9SW)v>E1O92pvW!`0 zAy42<{*FL;r!sJBmctE*Xsz{u{EisGn>45zy}jxVdgiBud?bM3$=V{`%&FX-CRgD) zcwRogfBGJS1tk!k8uU+7GN<;5%_-q2}A;V$MXnk=@{1?%) z2@u7Y7;ycR8{cOdmh0^l>Evw?Ad}+RDN?fcw1!~ACdC(4uq>lFP?z>KFs#V36jOa3 z*yrl5cpdN_fL!Lz4hVxEKaY&Vd7kcGdRRBl$6|49&Yrl2Z;jsRchxWXBcxx;>(*KF zM6WQKoa7gG?bN*kM($w>hu!!&w0*)I*i&F9Q=1bXM$!lNq3#y1=leN!VaA?~?dKGO z5^wtmV0~#Iy@gr8K)Y4zzK#(y9nq1!y`t^#xx&lTeE;2$U_LH-WPE9tmkaj@5dB?4 zK$}4gco#tXR)q~99gBItv83m0_b=B?@Pwu@E?|MAu$=c@xv6#$mns7_VhMi=lf$wd zY6;u4`>g7~e3w~?JNSyW$?dD*p*^BjJOj1TM#zLDQK(bGpY*@+#g!^t!bay$L}i&0P9*J_4pcqDTcNY#2dpQam8SWH<4H)fi>D!oHbuD7}d|7MpSl z{QjoChIZtt6Gx9+9PotSlMZA~Vm{tD)f3iSp#T`p-RLw%zBtju7x$3k&l*-FFQCWm zWKxC^SHBu$0mw4UUUsg~#VN1?*H)=Dw_wt3lDf=i-}IkS=D&D$olM~?PnuiQQjmY> zr=EjS%9CBk&gHL-9ags)JZg(5Zaup);8VShqjOH6U-g;bg%f&rqh%iuVO^TfW5X<9?%Jw=_mm{iUW3Q!54`a%vCYTxwsnE~!(aCU6-m1qOf%fD*lglvcX`&ks*dV>i zKJ7=wXiM@v#-)S0(J=~_HA%F~VY6rPwFDU-xAkVkeQ6;LFfmC8E-+{+IedR=!T`UL z^}2#NeW8QF7;3iTyac0gU*OuY0;iBq^N?abYZuiX;P#VMJo#mhm)EvJhG|s^?hA_` z?m9a14j}s&7^FOY$n9RkfC70x-W~F=M-IDK7*BlPZNuk!nrBRrU#7)UP&P_4ZZ_g4 zv*Fl6nHD5<#ommi(wewXpUEKw#+wQqx5ZM+-pE+lc~I}e*k!A+G`G9=wq+#O^TZDL za4mW7xW6Gume0q%u8+Z%esv}9JQhmlB)0AvQH)I}8|gS+zoYB95+CI!DW~^ServmT z5zA#$#s+x1rP&o7<~svg+%cnhd^}L#fo|Km-j8bUL>lp9)%+9hrpOK14_V=>x1)q0bc(0AyBYB878mFcCPFMN|kTd@Ep`OX2B?+{|w zUnUen7&F$v<`;0~RZ@l#9CS@jYTFi=a5kG6tNq$*pu|h4w=8-EX?|k4jn6LLZrc6w zsFCpoH-?$j54ZP(0S&2A9X_V>R$JRdXBu^lDs~gdl?H*2@f6*O!eGdrh9Zl{gU{fz zpQA4>kTJ%Yuanyf6JsOrMtGgVz-&nbU8$PFa8gW67gu_zcX{$PPB@`|3ts*Kc+$Az zH4Zagm_E|4k+n9JFe#O+Z_xSPJCxwttfjcgzIpToHqC>Htqo2`iuH93wT8 z61Wz(DlF~l(#nd})|oTUrioth0ci7AxWEkHcMU-B75LZh2~WERvA_wZj#)T?#2`Q> zauD-s)0pJl{UIUo-bl9uFUkvlR)07~9-)11M0elkq z9*7PACpX^wpHC@s9ve;ZBqI3|^>q=pa}a>5Y0BTE=A6SOryj&bTVTS4trad{05(tn zRQ{(p)X6Y7`*4#Ky^l%O-$DT$p=JFQfi#^{{?lpE6qo9(>xICalR2k$0jMV8H^Z%S za{(^~f=#!9$2YYlJn8>^&c&<9lCPDl&Ndz;PKc-W|30*7hF}f4Zszex$Vm8oA0QPN z2uR?Q%S^x35;`3f-c`uOD+`q#G-Q$){P)=d{*9Xd{`;TW`M;3INmDpudL^ZtI`ui- z>-Re4_|Lq?Mycdnu{>FM#6YL|v3#a+P<&2VjQ{9_4{*=ls&07p%OE{}d+Y08nqB;D zyBANFkE!F--zLfb0SNH_?R@IN{}mYQzee(3$N1k42K805Zqg>OBW(BJ@R`%?1%>3V z)mGXM2W4DX7)V^`lC2-v^sL#J`?<$axA<2CtIr22{=&9*IIEe}>Y0p>ynnXe`@21T zc4bKo#*Q6}o9s0{g8pn4_@f!9pf}k&IWg&-v7fR!jx!u+Kij%#k=mac+eUo3StCva zNX(`r)0(5sJa@0}A;O7M$3=b9=Ry9^ZeLTqPsWer$A+JL?YHnpXS-iI*^I_}kUpjh zBqfjw1n!gMDx-k&Y{NeBvHTP!NpzZ8ZGIrYyBWTm)CAlPGy%WjA3Hq@K06{jVF6>6 z<8q3^D3}RekpowiXYANW(Pv(5QXB;~jB`a@-`dloX!||xt3St$67~R6x?N6B@?RBz zGa11w^FD zwxunXcOFkXIP-I2oYfx_lLd%MYpW@2Jr1ZHS0cg`0Vny>;XXzENw-{n?B_P;ISO4H zmW3~4&J5WSEMN#wq3h>xVdy`IA~qQGMi#aSaJCOuRqZ_To;YzLMT3AN=ucs=RsA8Z zfFyThx1ik}Dxn#-%*zewrJRV8p0CGoN>iBAw|*Fb+k)%WVK;$YRjcd<^I3?4Eoq-w zifGKb=DP3zO}pv+DW9qTNNu~0hM;3!q}rXRM{=@`L>S`JA}{}AI0oQiiV(PM{U1C? zk_YSh;%fH@hAdps$}om4)wQo5D`{-sLrSyfe~XZ*{BK6WU(aYy8JoZg4sU}Y6*nmW zot~@a%tad}j1-yJ~xG3EZxe0s@Ks7pI^85FEpsH$V}`kQ+ppuHTb?CHTkW z!nRXBH%WYP{y@#6pJsjD@^1@a3`~7ah;;!-oBdaBl7H_#LF3;5J-t%-Ddp6^=f)C# z9UYzBW8uo^ItzJZeF4p9_r?2Bc*tIJqV4AV0Bd9r_wB%G^A$aFiZlXs2U}tb_AhA_doNZvq(oPh4%qN` z>-wE)_nyt)5*pVm?2ba4YbulU(P@f0vv{FKu8%#I0m`-jZ+)0t;@Q2B|8ld=Wk}WT zjn{ncvh%$b`Q2TuiJEeub1NFjWYy`~ShJ@|WsjlK{R|b{&xJIreY$oE?2`Jr)lBXT z-lm~xbK}jtNxI>ulXrgh3a?~5B!03azs0|BJ~!sQ_s~Pv^M(63@D~F|`)3ggs%--W zuIevV2j6$;XY_n}Z<6FiU6JHE*r~z=@?xx7^JJC1ZIb^&JSc7l+j+=Ye{9*YDRU9I zHm`K$G{TT*(LV;xDxt6`St1P6Xz+K!3U@(=cs8IWm{}2Ta^xI}!=zIpZL0wvE3s*M zpuO_J*-Ab(zW~bwhf&Yx&p4dS8MW#KD8(V-GV<+G5+V5lcW+Mi?{$pr>91S|KD3VT z6@J{mGu8>Qw#qrmV_PYp15I|t3#Ev&j|GX*y%aL(>&I_-yf^}x=CnGgwCN~+tJ7KI zk2#SMHvM9E{GQ^=$GCc$^tOW;qElNt`|WQhLFgK6t6P1d?Yb6Moqf(1k+Gq=O&a%1 zZ%4*s>H~-gZc~j-8RL7hRvPf|M7X;i+W>u#=!$!{7Uj64aSOCO(O$ild(}jeBY$(Q z!sZes(k8Jw+!t3J;4{2?>tqGp<6u3Ky+$|O`)I{(?XXrHqUJdAW}C8unUpCf09x-O zYj>E~^)zfwQeuAQg_zACt;_82xDK$C1XpX}O1cKjeKJv^57+aTQMR&IOBwgUP zQmoQ0OyZ6~ku%eH`w=(eV>>f1E)bnVwMdt{Q>KStY5Zp?kXxga*Z5iNq>50nLZyb{ z6Imhp#2B~r90`0uU0;6s$PA)o)ogoyZ+$uAn#f7E{HA$od1Sn3eG)RfSvqfWZ6P4? z-119TP-RP;2?UOj1mk)Wl&&eb|1s2wQ}F-`(Z%H8qO$VEK@^^>_@Kj8C6Vahr?J z5x?hm#+9s~s+WcD1kxteQo=gMt=Njz@GlZ3DL=(Q9@l?94y=sEj?e4H^LAiN#P()o zS!O5pp_PQ0c*A?5N7f73$NXPIY+45%w~X?tULU}J4WS5YN)Zg#ML<8Ljd#tDnA!=& zAzD=|Kow52(}*zyxZ{J=i_s6fV^1npk8}4ZO|)yM@>{dfckwdRp_h{HT6>}~!joyg zc2$3@e#Ho#wzZdstezt}(V_xzv_zPm25E=p50zwr^~h<%xSE^SI;)dE@_Bbq3gxMv0e!r-_ zwYPI@ujRIW9VqyjcB0)_$HnW5GsU}c^+oRTiY2wO895I!5Nx=zjYBTbuXpVYd`v+OHrd{2k&VJ7|GICO)IEy_g zgY228v*{B^r(0G9eJ%}BdVS#qTM+qJ+UKB9?;z&IyMA5w?;w2Ixs^R zSlyehfc`6|>-=r#-wWx%o-IF^ z?iAz|7ye?B`taymZrWtGyT`8jg9W?i(RPC=QSIn3uq@!iDWo{YIKH`e)jey^7C$ao zWoKq&>#IGb=6l2CYOs@5Zv>^{XCQA>)0#}@(DYAP%uu~5jN#HXu{zR^?!^Y&qCTH! zOM2LqQyu2odh0)s-KN!Y;5PXp7f3A2T&r~7V07`JNC^+6!6^C{eM7|_IM>arQ)1}8 zWJ(2iR=l%5&eE5#H6+}lFVpCuuejTA$?-}>N}O>N{q(T}GiGF}_Sqp61;spWUjGs2 zZ&9t%ttoFlS{EnYZ>c_In=%FJgJ89t|!eXzlCW-RvTX!2=_ zyYRR<`0P*6eJQ^JD{v?3e&W013x+83dqY#c&I_T&S<$WvVN8zsXXe}_RRZWa(2|p6 zprrtLhl5})8caRuu7sSFgF=2vY*_t^djaqi*%g{SeGbP?Tc~#Z8bz1^2MV7n@qRvJ z#s}9zwEPCl9D6LIt)IBTy@Iq28e9(#!P6kquSSW61rFs^qP3KB#l z?m!MiM${)qO|aKK{scb0;tq`h(D(!sup7`D=y5@M{-tx9!y*A-x&SZala_HbyF*st zifcN*DqL4d+O?~K<^p7-tCFl^biF0VsCVvoH6}OBCbq0>M_}U<<^g<#d#(7#__9@G z_2cw!S1{1Rew{nwo+hX=sdOK8LMOZr&2>yy1%`B2#4-QFp;A=eVrzMOg7?bc#Wz*z zODmJ@Ah(EQ!)HdnWGE=~rwo<&8=yM2A{ugVB@|Sv=j~cw)|Sb-tHFzdfXCx7 z$|nqQe)EsB%h8qs^ZgHo`Sf(IZ+uii<}7*)`-{WCvJ>?#{2@L9O_MD9=yE;*+qm!WGo$|w;A09tTwlTfn|+p$6t z-)RBV_&buhH@7>uu3%ytj)tz!CA&(z$Mwalb{5fCU9EY32j4UifD>CZzds8gK3A@cSdMoK3^sqb-3Ob_s_iZWjpHB*D1DE!ixpNd z!3!Y*@m^^w+H1LI##G0)?)!ZhY$yHjjvRl|yifQOGyT#h^Z{_>-#8{*BAmv&OKlEG z^-+KaLaV~@U(GN-aP{^f$IF&VaLOH=}U?DJ0chpDoIxM@x67qCg_h|)_a)cDKxx;)R-G465C z^qE@|!#vU#<$fY_<%ZfG0Vr*Pb=gRn%NSm9s*N?|P%H`L9(=`HAYzSPG@#72nFOMw zn2!m-8QGu*jkVZU@_xLo7^7t2>yufJ9a&WcTax>G*=V9ssjUGk*v{A&S=6y^?C6!5 zrd3x1Zz1gv+U3}*yX~IPb3NZ7HM|)%CSk@ouHO(r3$Ub@7k_(_^q-#enB@jKuz-gW z&0diVdtFHpH%^8nHw>A)FRq~478qti(_c%GD5l~y7z3AgzJWeT z4<1@W9Nf(C7`~6U`;y8|g-KNJio|@a8~9P7t`i#16I5^_eH;>kE{~jtikORLw!nkB z`6{mk{E9ahBmRgtj8vVsUxTYyE?~{nDR9-)J>M94&{%zm!!s!So5BE5v;<*wLV`GB zUoq{9!idcYbU?rb3;LESei@Vbf#!J^`pQ-XU(4;SaZ;>4=RGe1S9@N1vxh7#p1fB0 zT6fcfk*9X#{tig*#M*AflZOQ!cVUrHBtH{d+83|B1@1_u@WlPZsBsqgx5LVKdQz;s zyrAx#Wo>HAia=WFmqhRmxEu_;b9G8jSYgY9oQD>nB)rZ~?mpa&dyUnrGd&z8HKZf= z$361%pB>gptgjX1L36wy=ZONtqSeC1->Qd__C^$#M3th5bEx`nh947&!ncTa|+x#^D`?f{`#MBEJI?kcU6|hA8`XsmPUw8 zPYgjCYnHJWL=zSxPT#4o=(c?>&{4uRV1f4t~6EeBtDFu%RWHhATN!l6qQ z3h6+H8rM_PCEL|js*l?BRPiMtJ66^!X2A^MJUf#O$$gUee>1K052klm(b23Iu=5{W zRlAII>3NsZq}kAcg(_Mh@kubTJU=>0e35?4uJ5w>X2Qos3SpNUXouXi;~@D<$58QM z6u#O1H2o=?b=sJ|3}X{-H)t+#P>2nq;9A?7PC06T|JJzqKQzAkN}THk+Aau%WEaI& zP);8!)2&^bHny-)XAULcn=^F^iR+`pyq>P9BX|+s z8JbDko0dE$v2^e{$j9Ob117kGa5iAWjB~#zq>BLq8;#gmrs$n6l4a6YZcv*xv>xnt zc!}(pt}~PUtcFS`eH(zIdy?WnB3tCB@Oz`i_7Bl&m04PAJeV$$uOX)TXv(+j-b;dA zsif8Qv&mS_SP)}9TnnMt=j%?fB{hnJzOi>>LA$=&(%oy?FTVVFT?byQs3xPA`v|^L z%vrf6xkx8N@I4I7H+k_=uUFz(-ICx`(qDev`VYS@v!cexo>zyjyq5y)T`~#WezSUQ zTIQuq$tQ!*+;=@metSVaWGGIm+hN9A<4Ro$Nrcly97e{Y6sd+4; zDDdP{Nuy(H`Hy9b3F{NFeFPpVP({^OoBQ0rU(j?G5XAMq@j`4;$d8%o0mU>09V zODvyzKRnM&b#0vd$CXD14&HiF4rt}!+6%-e{4>ka8(%7K%#B~b3gzuKV=!gG{IeNucJ0=Oom!xq4Vo^ta#qWBtE*6J5yC8&8Mvyr!=CWSNiX`YL^;f7m|Y zIuv$1<&hIw>;{p;h6p6H@(~ks-NPnF)gu!KT`bSuL!`UQQ zjj{j6539FRZ>wIeOM({V;FAZkUJJ*=4~kl+d(Q}Sz6aeq#~Je?HB;*;<>(z7eJ($e zpr?F~?#Zb?cu>ux-nVOFBKNN2%T1v*tD3;10~y(Q!2xB$c&W#e5_V=^JPfs+=kkY)EHX z-DS)b3lj>vy+^Z-8*5{|0nHgUwzOL@G*&|Ws$pOUb;i9K^MRIO{Z7+4vk+2C)_!Qb zw%)web$>~ZhJL0y4&7`8*lSjv0bWs>`p-fNir%Y!RC}^U<14`Yj3|C-R_cp##2l~g)keN=>GWpVQXl) zCL1~i^MP#1u+q&)*VwJ<+Z3zj7mDJ|n~W&vFx1(j?eSZ`$Shs>HgqpBa~D(&C_kjvtzWn-s2~o~LIk!nrC<>fbZKIvJ#p z=|CkjoEwabjYA}PgPIXI|JVe1)_IoRx@k>|(Z^nu670N!x#l)tVIP5Z>2c6UK_fwq z6zNxf)y|lDEkFeva|!rQ&P))ZKwQo(=N*f&J{KWOIIs5PVQu!o!ie!6(lyg_mHy2G zZ0N+fvEu5g@z0aSQWoEuYi-wsS$x~X=ZLRK<~lYV%XMAG7(EGD@Jq0a<|(wK#ZCmbbRxmwaowD2TJE$;pA`&a72C}$GqtJ(r@cS zO6^?~O7~~3Zt%-~6IS}lgGMAK>E7Brpap{DG3yp+F@&pm5m%#Rk)5OhSi&mM0R~e*gX9eYo@7lXTbz!6MP8G1@=u zAzD=ANr58Sd@V1NP)U5}ZiYBy-$pm>-CcN0OY%|mZHI0e`E>*|dOcWd?~6&KqHC2a z(tK7&Uv>Q>tr)>?AE@|;4~PwIta{k^o_m64K|dyTFi{r%;f1am zQ@beLyKQY3m#Exs`fZUKlah((OQH;r3_BivC&~EU;kD?@ccmGRh({?;l{q^ja-y4! zqR4gH3^Mlny+@^dy z8aw#G!?nExKpDp58F#kMky}Mx{~aaWUH_qWm7W^dxGe#p{xbb^orUn{&&}R*0|so` zRM!$6II|MXHNECM$s*p%n0EGYqN@&wk9Ayxs=*GD$Kd(PE72?ypQM$f>k{kD+PQ7p z!X748y^w%>a~U>=A>!Q4RW+Ila@g(+7T%YTZ!nV226MDh-RmxKnk+)h z4L#vS_g*}bAQ>WI6dJVhUVd(aq)AV2X1aDBKakg_*gvl)#W`!$vlem<$0k)nnslX~ z<}5UcP6o0XoZY)B9?OAK5K5*OOMYB;rJtv8fDhdvK5LIx_~_Zc?={-~nFz^g2&YHj zI14eexsceZ(4Ff_Gz&$L#+(m%lxpsvT!Fets^kj8)KGaXj_LI&Ot9vQKv2M2gykr!lbg2*}&5ORh^XW;c!1#GO44Il* zIpnZuT(Kh{toyv<$Xr(8%sEHtG`9l#E!6k2LLC7Ciz0p=BmO9#Eyp5HJJXljzWdFV z8{tpyv3!LDYy}*rudSFcbkQq%Ftyzmw;tbGHmY|Y``{Y<^vv`G?t!g^h01s$S$vZ7 zL1d)0^!ZBf=?Sh6t_d}=^|dBdeWF~V_<)LFrQv*9u88?SMH%!Y<3t{vBpD;BUj6qv z$^0j;Ugz2$H+!}hOaXq<(e&Z9!-@8EVc2>6q z1IEPbht`Fkhm}Dj@iXsl6CJ)UOh^QCOeQ%bmcA(}_6KuR1%iO&QB{C4)mz4QC!LGN z4Vp4nDo*D2*!!_nnHv`FgBKwvObo<-z$^+AvC(;JI^!?tr3 z7qE#@Cm^`Rqv1&FcsZY#wex{ltv8?lpy=&S}HC;-f=3zuWY5?06ibkkxn*c#h2?LYy5D2k(fE{vAkCTmJl zgh#jHwp`yc_xEE^_zkkBJPbSErc*e6$J6vb<0;bV$Cjwb)$ksC=XMmB`R#4&>=({s$#4a4d%#@ zbZ*+pf3<;tKFrvC;V;Pol^r&;&39aP0`0ev{-^c5_@-~bkxuz>oDs#tt%`~xhi+XI zK2lB6aMLAHp?}lYwzLE;F`%@<*azmayQC<2KDO@Inc2;I&2rcSeq!n-gAMd@6VP&Rmw>2KBQ$N(S z{1ld*{uf|Wj0j8K$asp$Qv3xc{>lb-Ai*#Kh*1FB9sU=R zbn-G<5Z+69YA>lNNBL|Ul^}9QxgD! z{1m)y`7huq_EIAffQkcf@`k?uRRZw_Y7xvb$4qG0u@_d3FY@07QoMW6UGKg1pIX@A z*nejiZ{X(zpu7Jm)8ha9!=Ffexu1}2cDRWWfRhKL4h)E4P9wtFAQ9s!n25IR?d{pP zbyw1Ebgp%28yxaSY8JBU%4rwSFf(+0x|U@G6J|L_;2_Bithj0Y>*D; zUpI*WVTcCz6r3=UjgX85_-azItiN7*1W%4anJjzBFwoao_Pm zSot2o4Ipz4*ketTKRaPz4)CH_O%jhkErHOiboh2Z~0d!aj{Y9g$olReO1fs^w zIoKS6l6XS)bRtCtjYl%4grgWwWhMIevcDx0dnZ zW+4-UJKz~Wfc(_`mx&vf&C{zYCgIzHv}oou~+g8avEv8%yS{<+=g5 z7NEDU=6?nF;$cTksR+ao3rIo~dUZz^A;e23bcmRtSPWaU0M2CFy_lq^4Tyz@>J}-f2+EdE z-yt%p5o)|CggJXMRKS@Cxas`HM1qM4E;Y-eA*-@%X&MHrvlAwKEi&ZG#t6Dw4x z?K)RvICmM%2OL`n2mz$=E9-T()9ktrCvt1PQ^vXFaXnTb5l6N6)dotSt*=luB$aVu zh1!t$qx5opVM5WesyGprlnfyBDggK-(DGt_3m~$AuPxRTL|6@~wRZEe_%CkG zx1#Oty02aa-q>DCX6q16?z5iI>EK4QMXmLZ3{pS)>SjL4^Ir5o`4&dn~SzKP?)XbNHtq*x3@s?MpujTTncB35}?VsANY;{?uu&rVDDKHY`h1jYnDN99OgMk~n+8(LV2_oLIV=~~u3_9}QE@|FHQ zO0jE%yLSz*fxl_e#g6fe-BNY8uy(8KS?-n^Zrj&tdBHMB&{Z3?j$&GP90 zb5O$kaBtrnS~$NgDr!D5=~~yk;-iGM?46E39HyHc(mU+iT9dx!Ip1M1BwsYYJDB90 z7`PydEja%6E``CuJXVpHyj&0D+U;B>HmtV6efAfa~ z8*6bDw4q`1J;cdo%=A}sB>Ry2Amj0C)2`tkd3twcr&K?nlR%DDt^+-;5W%IA?U3P- z_TifYDJS(GaabK*pMG#-x?tv9?zQ@@vO^dO9C=iH(_q-d4MDYQzU#nyRB5sDB`Cf2 zU=aP~+0!cIni21YvF{#Qw0V6<)+PD)d!a(_*xcdr>sq&K-zA#1NnV`+QVrxX_o9G9 zBJfS))1Dld?@Y9-&Qrl6R`LRk3z%?_CP&vWf7RSQ&11of96)X4C6sf^N9m)5o!Y{p zntl59gyR8d7dV#o{nqPn{k!3Nljv`#jbqR;cW1fc(Ekdp##(^r1iQX zl;Y5X`^+zMZvNApQ)m0f2BJswnqG1zwO=9Uph?+-uju9&z_I?Y@Ugrml@SATb*Am% zS=tz`Y@rv3_#dRr13bpX5+C<|l<7QIbD7TS$IA0I)KA%aUF1pVg0b}1Zs%3=HR5;7 ziu1&foLSOhJ=cR1PaNDn$K$-7^6Xso!_^HR^e$eIoI7~IRnq*L^q1n!{i!&L#L#=^ z!&F7ZUo0o7t{0g+_p+jKtk`!SNibJp+8T8Xp~CQzMd6ap`@#zw+Rl-W=-e_EWpYaI zMbcXnG(ruI@a;y~0@DdI`p&X`xFzHDJZvrLL^2)k^$>a$h333{4(rqwGK^YnFHDw7 zIMCJYb)fWbU9J47D?!!1ihE(fm6FOTS%c*m?bT(^eZ75)cswg2>q+suTvIxBW8)pg zWPMLx_gp2?^(VGHs`f|*$J*_uNyy^2gBzO}OOZ}}yN@ZUE4+LyNOkFz*!i{Z&+zH$ZSRiybdvW7E}nj$x>FQ!8cKohy%ofMUT|f}2VdPR zUJ6g6IV#xf(ZYi^@`INxpLWUK)*MrAm*$aWKyddt(c8>~wKVMsXy34}c({OJ4t%*0 zlUO+bsk+mM3Hk~eUhvdZB*WM+29m@dya=2EQ+$K2Nqz{Lzj%1zVr4||d!H@b z%#C1+&W}(#i~6$Hft8^U^Xa{#9KH7MD&^SaGR5vBfpMf(!Bkxi8W)UIP2AcH8auF% zYpwOMt(t7^@N$bylv+FUD~KEY8N|Vk*E`{6jcu{cW*)8OodB9fS%yL4+ZIRHH_`q| zv$^l#f|Moh2iV^5*%B_rRLC*MmD-p=`fG0H&|K)i#yz5AtGhG1M-=3|He%w?A8yIw zY4v5Vo-1qAlDe;DA9F}aEvSuh^+A#ZbZrekFu$%?@W{2qBAtwoI7Q6bLX9idI?4}s z>3}J(#r2q@^`fYftdf^!)d}9JTCjeJiwXN%@`Zm&KIcJ_&WJ~!V_Q*fl;!BB+_opR zXU82`yUnZ_syP?uH@ot>Xhd9YHySf_s@+(7;E5Yo?{a#J^QTIR2K{scw*-^oEXAG)pI_H1lvJEu=A(eZl3v zxgR0F&quMe!Hv!gXpcDGm6WYf4(f_{zfud+JUdCd@t$(o6C}vj9yc|Sx*D4=zlhr0 z_E}zMfm3wuPAAYW6z%lY)8t4ic4K!cyrwT;5V39fZ>5)h6d4b{RV}Vmp~sq^`?c1a zzyXm38cZMEw>i;$>bg_K`*8tdc1$?^dWz{zcNUb}Ib(Y^{krC5iyDn1xhp2m0ua;( zCnW1fUOYB(7BpM!U3?4asxHU(hrcb z#}OgErXdKNlamFDANbafJ#Qq!j-~lW)NE<8x^?K{yZvwutmaxNnm$q`OrNCZlFz=b zVVyMeY>EeNH*wI3R{5E2|669tH;h&ccl7IIx5_4u%Bj!%5?st6ut}0H{91#(HAteZ zxZG{b1>xIfCSfMRK6Si+IZ$#*@U@B5gs%Qkjn zj4{tezx#jR_wWAS&+F&K(~J4^!gZa;`aO>8Jdg7@s!e+5V=88r_|~pb~jzW>*fCygzt1g?Z_JRLT|ZUjUZm@0K$$EMksJ>9Duv zhH^cVshw^26BE5g^X-n|4UBj?oM`F<+v=xvNJ3M%sY7qO+wN?2d-w3R0RsG0W%M}J zO02dgT`Rxy>M49fK~0W+o+%(cle*I^+Xd^oaP>Df82jubrXksdl^^w#9u$9qOTbZZ z(cnJ^d+S-smK&C+4m#(G7a{wtKL9gC`agWNfq6QcHjDE0?sn&h9u91+Zqnjl zAwP}jzun#M0O7pqIdGN_uDJYoQ`&U1$|8XHK%Y5F?Yg7T`-b%U2RU(Q z%^Qx|kH}ZP<H3Zq z8^{Gm@l5ih8P${@7%oexzxiWSI)97`Z0)>6w91x7rW(}zoM=CwZlJE0Q~e%r5+8?B z)AFaqt)7t7?|hqT&HK5%js3kw+~p6cjFH4ozvK!7l?`K6Jg!MU4wMiV`#R|;Gg{-? zB9MQOT3br~IQD{ST}pZM$HOb9mMPs=cd7EhQc2O8$~LsxOV7(nhL#F%3|Z6)_QgumP<;HFX_qazdYsOQ6{0RTHnTEEpe~`F zO5rr7dUgSqSnb{wpfakOCdE?N5xZ{`S8efX6e|CG;z8jtK{Jh{;H zl`PUfB7maK7wDRL1CIx4!^=YHrJl>~O_84FJjVr~wH%}9&z-V(lLGrHegiFgR}Kx-o2IXEPVZ*m=rfyR+Mw_rby&&bsji2?{uPT zXb3^O(jMja3?5SS^+R7celyn+X2Qe|8W1Pk0tiwPdm~Oj)9EBKbVc^Ew4eI(WwIWF z21;>zglMKrn6p)PAK~Kj&qV=)VaWHF@58N?zi6!8y*GQFsB0kqc+gR3$oJPu!4AhF zixlg8dc_9>m|d-$pLxpUUS{zibZO7YdP-=#>VmP)Soktq@w4R2OE?jy@COsv=jk4j zy9>6{PM0vP%5YSgl!#fyOlc-#;6v-S$s&Z&$e-w6!+I3#PAI_HL&R42&~}P_k}f4GwYMQmI4q|VezcPix*Cpw;Ww+( zb9<{<5|Ttvxg0gX5R`Qfx6fqdcky9qmvDG-Wl%?qdD{yMn2#VIx>vj^G8zo}meeKD zru5v3>&33#_NzrC1Qi(~^CvSr!2Ux>DMl}3&Qw`Dn3a42FA%5=s2k)Aze`!_CJf=c z+~bX`jJ4Xf$Ab@i4cch%1bt2|MjgwFNE3$(kSS#Rk6xC_pmPoqw0QO?*EGiF$L1TT zw5H?$FSAaqz!LJ5u+MAg^*0U1UG4ihNXH7nW}%pm4V16< z#eab*7*)#COHT=@pY*p&(HwEMfXOpnK@RS|(FJx(n5N_}jJ7^_5{wH6n|=jPJnRaZi8m_4vG+_;~j~?tLjJJiTP`N4AEll+Du3 z_rz=JclEP$mQPQa3^+M?9MnFxlo`}sV7Y0_u|$-FEwZa+OavfgO~YFlW8vHfOWfSOT&PV5;UqbtuD~5H$GYr*?Vl{IsEA>frc4k^S?q7jXM+?9@$k z5N@^G?Ex-+93}bwA6i^aRDFXP7`@R@!JiwcW`Nd*2O0aI)CdU+uYW^(;L)XpKUZX9=OH(Fr0cEFU zW!V=Yk(zL<{afDmh&R}&r)$)=@ZPS?v6mZ24TQIS3D%r*QTYmQ8b}k3rWY=sMSPUf z2qlevTNSE*q1ynhe*yg*v<-gDCFZPQ~D(w3K9fyg4*G`4Tpu=%JU5T zYrg;Dbv2CL;0yo@+wa-2w7c|rYaYNUlff`k0a#Aa_yY6PVW?(SkQCsSsF_=6cAhb# z2~De*YqIqLe|<92uN~w1dH8kVNdh$`AR{dmiGXO=c`nVza1_#{E4dWYnrkURu%hQc zJALTOSf-zde+Fl#-CdnoQw+(vdPs@_d@Zz5VpZ`lR!DkV*_+?%4znp@9N=>v%uVpuKY#P+>flB_e9#N9E?YkZ7o=Mz(UFr zM^wQzw`E?yiP&_`%{%IYrF;N)>rOI;PVhcab_e`T`|3W=CH*sa?(g4zW*Da~5;F`o zuYUo)`i^(pBwdaj&bMyv?TK#Cd0%jM0!(n)syM%RRVU=r;)N;so{zAely%0irL*fw zAJaDg3PeW_)!p5! zBuh7=;n`8`22u+g97`O6{4RCKTwA<93o43i|11BinK%Z?8(=Aux-Ev20AgD`dEf8u z#*^e#?iejBmv9<6cmX$;wv?D<9x{=&%AWynytwzZuaZe<5ddh7$l}9>?h~S$9{Kis zQzqwG-cG}I%eU`l6%L$%5IPrj+)$cNJuF};Dyr=zQOa<9O90XTvQ5~ws_+DDQx&Rx zj_pszhxrrp|7jc7ww!#u2$QL~b`@zRc{|!|(aLV62Ko9bjfH+uyh8<`gOV;4 z&teG=`e`8X3gn#XPR?3zEJ|o^knFAF6xx3Vzwz4fQ1~F6<(YBLB^7fK@0?}-y|Fsx-d!0%GtH*cJE73MGB9zF8yRZ7a(nNvVmr2ysv@x`b6joQ0y zE`o_ofH-UjY*VGQU0zE!&{@=S4%+)CSWizK_L&Z@ySAzBr?NMN90k(U&UXLs1|9O` zK(zFfkCp%`tB4;NQE5GzIxOqJ?3Kz7Xq5m5qoU$!o8yTl4a-b_Mfm3b5J#k%w&#RR zm=5HYC}Jo)-?e#8g6zJk!8GNgGCbbwQv|H?dacnR~su7kZ`(Hh@ z5eL>DQ}>;LelHs5=c4|x+WoNdS5KOqOD_+aI2b*P417-vQ1Bi#izw2QpZ8?=llEBu ziR&~*VNB}>R40Jgq~F{1BR)5t%64>Z-X|mg87TMdMQwA6L-J){D9S)pkxeNuY2w!G z!Crk9Q{eU-ZvgQTs_yqPL*B+2RfnE4_=cdv&AyVtr6+?PmW()^=X3GZt;_z(z-6Tv zvIsLw>pAz&;8TIaO@W23^?#vQ(I5CfDbzyy_Rx>wy;lWIT&2T(M6}xU2AalN^T;0C#r#Dve)@ADKGbu_agyxD=t40yT>iG_g8py`@6Tscq*7J zCKg=5HEC?kajc}oa+W8Ee|`v850*~lf)aVPurN|L){DzJNfXYLvd@VmEv$8KpV;Oq zYcTe~%T(uzU_DbEU~P9`Alk59T5;CF@3$aoAKV7d9FBw>)ZMs*eC^lx*CxCEpLFk^ zPFl)I!&=0~m!~TDs?n>2%uo=RP{d|Qwr}s0kS^d;O+Sxgc$~b@#w8rn(Lj34Lur&f zFRoKx)&Ld%#fyy8JY^R^ycSWuAgb1BwlNc2&tOj!{neW$rH2D%6RAeSdIxBqPay?L z`nR9SxcwUGs`0S|CTIMyiq!wGiba}`P1|zayemHkY=Yu`qZ zL@&*@EgptHA?Sr(ZZK9*%ENjXok1cr`?|#5RmpR!*+4oPpwGz#kL@8@;J&VY4|m(h znh%{`2{`CnPIVWsuaVAPm0`e|{yX?A9;zcyJDao5eI4>i_>oEJ4`lhJiVgMyA99+y zatdBq&nzKIy)2_)<)Jp`@twlAYs879lxxK3T>#@wFT1 zCnIp_=k1#2-9mfr1oNqcy9N^iXu6BW?6tT_6~tOiojQ97R!dsgn!_A5?}s-^4mv7UcHujgLRRnC-<#= zpRat1b-6T5tq6{@WK8~E>PX(1>$}apD5Z4i-KrI~h<)B8)244espod;b(HmUHaJ6K zQRd}-B-^&5%X0lkLW8DdKvHfoE-`Ty&o=oEXxDXG2Iy(bAw&aS6b6&2Sp2*iQTl-< zX-4&;idgxsr!@jGz;!bi*_^P)xmGDua~?yCwTQ63?`?wr)q2S~AQbc2#}Tn3Ow0B* ztRjXQXDB|P_W#W3YX6`h#W z$U?_38Ej9A-clzv5~`bO}-Kg0~xYir)9pgh7R|@yrrGNuR zNncYIfId`>r%niwPT^oLIl$o~C2Ws@=J%`VX@_5?dA6p99ls@VnA2Vk%y2SzyZlx! zQYH>h|Dh;;8MXniQ;#V z-Ixv7i=ftzE84^Sg5RlpX@OHb=E>_ylVR{1bs4BS5`+Co+;j5los-JwMD02A>*Y4m z901LC4vNSNuu64%KR?XDXVI%E#)4s0ZEM=bFi+}6PCK=Q#|i#HRU4wE%EZI63=yWz zsTq?deQiI4xRWEUx|*)h?6BII^DW2jFFY9gZbz6(r0|2spmer$pnq9bW^FNlAqd7% z@q7D0KuRREuWo{Gy3k45^UemCT;4uEZP?Yl-z2mj36T?l$CWb5#k_f+QvG75lihlj zYVpLep-?3q8;Zcc7)pUYL+00!XS#2@TR))EUNqFwtBJuE9p49O$snwiw`S(Ni+l72 zAAhM*hf8Rgc`bE18PaRbFgc8&@?qvTgc)ZJ=q)~yK2zh|$3VN5V3-p(XU0-X zxU@sT#QO#MlC1zO_I%4r4H2TYwfm$54T)N*7hclJb+;jbe8Lr#*Td}D5t6s)(B)C( znzm!P_|3(^2OzOz9$w|uqR~`0o5f7heq_+@JIM6e)rQh|E3;FpYNg3N%d`h*DkI>a zv*-2SEy?KS%jv@GMa}%1Q4BdoEf;arg(mbp^2V@8`+Dvhhe}V|+qbgD%sk{--`Vf;N59&>VyW?9&(--|p^9%Ia8 zjqX$vE{N_raMw@rt*Cxo<232x)JSlmmvFS#R~O&@BCeH}SHyO2iMzHYCKaxGwNy7j zjJ*;LT8W+s9>DG8^ey4KJPqDDw^ubNwe%-840I3|lXF&wUJ2IH9NXIxB|>wk_)%Fv7G!+E#9aMt06FDQmD>R5IQ(=k5v@)YY2blLlIijaed|R z>3UUq>5p(P(s)=?(G?lMH_CInai8;vsx;q!icQYsvX)Xo9B>)kqAC0*#$CHVenX?h z)kJ6g5W5;xePNlT413>=6Kkv^?rKlH=2);)HZ$}fH3}x+P+ANv1+)<=R(kjs6w>;6 z&2BFG`XP!1Cc^HidPwy-jTm4*iclA#)P{P*Cf2aO^zcBpCwtAg)gT>Yss}YL?CXnb zANVQpO9DnExF5CK53*0Aw`tJj{48vt((4j$y>L~i>=Dd>4kEoq2CRNtE=43XHf8B5LAm3trMZP2>7r1zfJbdB5V6*ruz&Bwc-X%n!bs-1hRYnfv>G2_!>#S`Indi>g4)N^SR_M z6DZuxc6B(~Kz%WRS0_!Lw=LX$;+}~_Z<`dv`0kat+71oKw4k#~MNRw=6_$cVdOk-m zKXy3NL9pZpiN^-|%-@~8+L&VGCd_`F+$DZie#dU{+1@VN6*A`ho<)Y8k9NS%Yv<)o z!OhMp-O5}l$OPvkVtBX)iFxf&3XDS8SbhaUZT+#W-^aEU{OF&y6?J`PymY+DD%QJr z3}FQp=9erU8|LR`54kd)x_wH zREfRWiDviap3pZq0x^TxeR6TOufxh}?d1}3AeK1aJjU%ab3zFCLVZ2y3iR8Ye)m_f zz5rLuz7hC)NuT*r@I0g5Zy_>E2V1+wwhNVN{8@)){5=A@ON$Ip@qLQ>$p4;p1N|dE z&{7)h)1t|B3X^O%Z$6Rq&XiKS+{irr@x)5!zVkU}VKL1o@npkN*61@j)H6RMf%c0> zA@@edk$jyW_^QDCi0mUkOG%D%tVL#A9o}t{&(vuip+h1_xo4@+g#Mz$WR7R?V=sW7 zk;gt3_ji)HO|>3eYd?k6*D6=~={4PX=WNUQX$~G&UxfVikcpee+`*PYzs{M z&>psM(tlrU?xmj>GVlV<{6yUAOto^!xcT2jv4^Sr(9glG^gw6PV|Tst_u#RPSAN<< zd+4M-tm((qd+Al=VcT=+JsPuz;lmUVpd;&1$T`3Cw`|}-+tLZ;!jLOix!fGutxSc8 z&*M~RVetBJyZ5Z<)DR2MVD(7%G_HR`b(-M*uM)}mq}r67QQGJ9&ca$6nYjIS<7oNc z(yX!2TmMav8EiKntIyT?j5Si?FjJ6Q#>8w7Q~k4T1LKKmc?^z?R!8kV|992xhYZgA z>eZndzSP9E0hOPEH1P42LI*&D-esqN7WNu_Oa6+k#iRWHV0Hd)tVS5P-^O{`6-%qA zU#_HUN!+$d4Q2e!Jng86zZ^vv>ncKd?buq0T0)3VKMCamjcWgQGV=Q4;me+O-#!aN z+_}mge=kiEo}aKmIPT4@8Z;=QwG{bJS~#@)p8Z8`19BtdHMY=R%zxF{z9N4?`_;gk zP~+~Q^#yCaTq#Y?IG0X~r3+G!Nk?>e|Iwp+!d?)vmgTk6VDCq+{R)c@vNmtM^G)Wk zJ3;x5%>~I2H`V)6RW!q(+8|gsCws6vIWZ z^1?3#_}ZDk$)9O(WFlfH1)shH+rqTepe)kh!=P#Qp~A|At!H4^08J1AY5C(^m7b&krltX48q#-@Ce?i81a3N2So@tfg zakLb`!aoH6jcBJ%!_kEB12&c>XnEao5vZY)Iai+6C-a;%+G-#LJq9~vN;XzD)y@rZq1IQim6dB7GAHYR0?Uf_ zu*>M+hjrq@XxP(}_)JelwAOEbbqJD_`^d+i0?=7q#lMLkW8@SZ;>0$K8A0m}Vz+mx ze4xjFB{BA|O2WKy6gL@PVOgABF3KTJoH!zA+~!{;DsxQawSVK4>WKf(X8-@s{$a8I zUmz6!uUQBq#QS@e=3@LkM-v>V@u*hyUu>39(z)8frDS#cy+;-KJaF;v$TjW<{sBEh zBlYnKV+5{ZCoY!A;0zQP9)a7dkw1RZq{9V)66Ok9KmNy~Pa1u_yv;Kg#(<76dYRql z^!P;;+dY%*B-vn_o&8L%{E=Ci>v|4=Uj7u6)_M{{(6Kf=VUa&+#f%jfMiOOCY*{2S4L!Z zTyiREG!1Bq=m(oq)#R3z$DP-RiJ+A11b~rFb)Z)4I&g31=Mj?JGOt^;A>x)tt?}W4 z-h&Xc8VPOSLHShD0frPw@^29mN7j0jch;a`uYG_*)+1o}qvBpl+}PH5&;na`%7j-A z6#F~ERD}-rsC>h;JG>0?hMv9ysBA%A>2_v9Pr!I$|5dh6%6t*K2fI~SmFzf&Pwt_{ zKuhHK@Ti=8f#K%m(8I36nEKu=rkILpDcm~*kzwv=G!8Ji`PYvl1pUAWOhU&V?(Ggl zsHBkusqlJsmOihSI@a4X9IUawUaIIVOlEB1|Len8Srln1B4D>Lrno)akwNEJIR$B= z(M#yO9D-kcR~W9omr(FF3^9p2d{lKbJ_NvBkz;iJehO^|fhEd$ZEPZc5}Qx^z~Hdz zm0_8!ZA)ycU!i}IX_1@H(x6eiA7~no*ofobpXP2aN-?g%V4cDC+oh}vZRC)xDJB)B z-K3S(d+1(yiN4Cx0mYHWNr0ZlfoVhkG)F*W#7C=bq;^s=wG3k+xn{p}GqS|ANLrgE zb${^%o{3s!cSmw*#?t4hU84u76_X6gh!CK-F6^(g>iPKEr^~UwZi>A8M9t>=<-^C* zpT8Ei^uIhmkQF`n`uq3nR@7mI{`27m7fE7V?*@?&U64@1vYN8?%o9$ofAk2j7YchI zsnakEy$yfFU&aW2q@S$fbk}p0%FU2nYY|*t#C?UqyEh>2kg2Hk6^@+@{WZ)lYKkUL zZXDHhQ%C^$eD)88i|B7x49>!*IWx1=93(cjep^((E>D$UYE&@@=h(7xRtpi;kc^O7 zwm<^Q&OG`1vX{Y^piP*V;3s)|9vyz&b{4f8xzzag*SjxQ%qtIzjme(Cdzif^OdnE* zGXcIq@dIc_b3Z^Fn8H=iqghugjd^kspCZXlFTxRKYbwgq8aOmI(WkY;h3Fi;q|_WQ zjDxMeJ*r=)U;(zlv|n(X!S$RKJcZt*Rc-3FFiv{CD7ed+>(l$PAtEd+_8nsQRhfYJ z!p9CKJm_uBQT4Ge9Z-tQmmhHw@;V@f(h;lg_+4nSEb1K*t%Ub9dB)>BVP5FbYA)u{ zBe8meR_i?69nc~!a# z!)~97hC9k$TXY^<;o?lmCs!W7>Yge=BCOO-A6sAjK-cOMAV-S_{~<@TQ{b8{$i}C? zv!^Ir@G+G7$>O)J*n10y-+kQn`zyK%5|JbAjnM=>3P6L!H~vF|IGEI!r8Q3^O$CI{ zc_LA9bi_C@;-+cQfyRPLk}GV}%FJ45e#vDu={DBt9K8=MK!x~G4g5=B+Jo;|yW91w z2H&D5g}S&v4z^k=a~YDYhoOVLmg@fSil%GXiNBI}Ij+TzbF=Ci~j~9!pUd2vqD`8G8CortBeq zy>XHnoAHOm=nt66&cZcLtlBf+|0Ix%skyhyLd1MUQ(Ru!a=gy5KggI`SNEI!Usw*e zuU=8UzU-1HwxT`=qm7Hc*EMgwpz^8vJ;J)xYH(bTUm>k^mXuLnDqCGW6-)Rp%o019 zVkN|o1B3Fg=V=4wtbrZlGrzof;jtzoV?%HFRD#_H=krSC;-1#TG;Btg-DVGG2>O^& zI^I5`mAQS-ne5-<3!n?d2=IybwSid)9Hjf26CQrKYvM$BXSTxAXTLU7&Fs1i=tqZ| zf@3h|rVk4UOXs9-6QJ@@8eVB=)xv`7B|F6d*=t{Ua>Pwn!$uRl?~>f}Ia%b$8{#6li3j2T*VmbJhzsj~;ws|1 zDHR7!Pn*%JpTLcMI!ExdET8A+8T@px1QIZMTq%!eL9L*eUoZPpBe_{$!%I} zw^VpZ^{hF|iy9tozLKf0-GuPK_MGiXvVNKyAKukHN7tel)=+e*e)pNeg3VE~;hWoh z@<=w(!^hUtIVluoe$7OkXlf+AszzoMdGB8dLafQY;S7IMrNWcvx+vJJ>1?{_Ik=m7 zxL(`0rNdVGGsdXDwJ{q<#QC7IEPAXQ?|7cU;bBbuf_Z5UMb)}1BrGi7GF-BnL4;si zd%(zWjDFhUTtJTjitL(W*tIaH{9*l zHwWdq=m}TX~k@+NXW;v4hVyc&@$knp^w)whoHf>41xjpjL()V4jc& z<%RI{8);i*M=Raev7kJZ!L7iMt0GQXt?`3nDr%3a7AAxr_N{i~WY`oADqA8v zT%~T0k0m^d_7RanZrBt$YmlwMmF}vms>Ds@Zat3)&G_iJaSx(!8o9K0L9nMW0TIlfR-8eKcmEU zCc}`nWoHc;1`O2>vmYFCS|M3|&X`=;H!0a3t?W+2CkF}95w&)(lzR2Xp(HzuWG#nz z0UW6W8o7rDnz|2omy_=%Ksh$dJ!F?DpS26afNM(o#21lLstO!#ew$>m3$AdiEYv%$ z3pHQV*#Gbda&y1xN@7dgBDVX@^oru==@mOrPnwVWE_#G4ldm$|i zzjq-OI*KOvU_E}{>Ov(Z_2ped)8!1Fa=xy_J7mz|U%WbFmNC!YtG6P@f7^9#6 zm2BFnRS3akv1Xm}ha5ZY&OE zoD75Uu2X)PkQej7Iox#cL2F7FDBNWuLDd*n{#|p66TctGg_cv9+o)OQ%sGiipu%&u zs+;?kE!!XATdo_}clk{e#K^)pQyBkq{Q(+W(bnS6@HC>Hbzw+Wa3@g8ZDRAo-Gi~x zHLIW;QGp^-_K_7=7+XFL7=8I!`i0}d%0YbX)?kPsBv2&yrI&U2e7gjjn#xoHxfrr$ zsx%9wXz9M?;a)rNj*5nLOzeeeX*aR6x*3US6S8>5{1zdDs|B zn|+i_Qha@VEXf0 zRYZtHUtPGRFx)IE7s(#j6kyn1F8=|ImgqA$Y8E!8rgo=p}%-=Xo-@(6BO_Dbm zL%Y8t>V&6uI@GQ%OB&0|3q1;HWutSN*s1khQaG~hkAFaIa{&M~+oo_pp2*pU5ihKD z&n8+~^X(tJ_-Q*fJb3MVP4QC`<_nQK@@1Hc*S4ID0#_EkVr5DP5WS+YVD3MJERTgY zO|%6WEbd&))ZJzFLebl_3|${8y9cc)t6Dt?i654~dndt=rG^XKqTtK&TVC>IGHonoL|J-g_mJXUgEPI_8Jj&TAF8}fT+3pC! zV&)DxjBDQKL@v6XD(^|>B-;RDoH>Zun>linC)Bs~MI|@#`gl9*sz6Jv{@sMi({H%L zE8ld=rW!9fW6L@l`wpVE4>YZi?W_Ii*1xrW#xINuCvr>3ALw_LZ&gkrSL3fAJ}I6Q z!ld7;dJu5|C#yU^4rAO_)H4ZZTq23yLI2i&VY4qWogHTb&LXIF|40!vB^_sUPma-= zg5df}-d3$(;b(2={pd)>5bfmzbr5=siz%Ts&fuI7?`OkDRl<=i6|z#RV+)0h&H}2F z0>8!&^2Uq2xKlA@ol`}GxPMUiZP#P=Fg||pcb5Yy7lj+sF94$5)CI-$S7H!$PL2yL zJNY))@FAl0%Wadl#5HXN_g?*t=4N9jeAoB;FjFzW;`)^7?fT?912`)3y#s z74)oBrgwpL^}$9x;!xRS6%bPPd8YU)_WF8N^~N<)8$v};gWTc!{P~R9)cQk58K@n6Y7nPCdF16;zEUnD^1VC;=MOp?&8;H(<-5) zOjF}#i^4C8o|j$di~h(27ujuN8!_^R%j+jG!lf{I@GOp7lG9#rR79Z?MvHqVD!=3C zkbwbFjnfU)7nVjm)|*Gi-sz($5BPUGvWw^(Qe7!cJCW_8=AUdO?(elx<7VT7DC4p0 ztKItsfhoi9Jd(Mx?>YWGTJyaSyFi$U#GG{=NPK6Id9N_3;#b@LScZA8ClbmZC2}vLEd< z>6PD_)7b?o81&4nL`(jLX*bP zq+kk<{e~FpDQwT0+I_mXjZ-DIz?F{3hWo@925=jBFK1aM#gq{iOgOq?BGozlQ(yhW z>(VzEv9lTJ*KjT4KU(^RJjv%CTWPYBlDS5oXt@P#)h;W7y;O&dl=1EMixY434&So0IDXnNdfmElRX5NOOp zbo1u+h(GZD_u=xZkIj?yt1ND(w~SGrRsWJiSo))6U`jECudK5`bEI`}gVTMwt8xh! z2F~K9?`8IsOt|+0BC0oLdYznLstj-d*iUc6<0Y5(F+ zts(+6p30!Uk@1=en<|%c;n?(K&itFce}TYJ{!TF<54b~~a3^#q2$L@cssV{bz#U=F z-XWS(5>lZ3x=UCM$H(qR*u-(S=xDJXVaRH}E||$W1jS(2;;yUZlcmRDl=46wENon| z`e>%_qqr;KYITW3eWm-ohRVm#<7JwTQfLa>Q~+QOI6c}5?>^o7$x6n_Ask_k_17NR znQq1EWgODYDZCV*&vM{knOfYNvv^%*16;@sK8d}!^9Nmy_jR(NK!W$=I38Y2Crnw;l4Yv^_I^TO zN>fBHf3G0Sg!_-r>ME{iw~gQJ!J!PW7}vkpTdNS{IxRb;{@jkw$K$kIeeIix`j&kZ z#-|!axXS!qHD3u)`RhOVt9|R-$4K;)M`LD$d}?H_sy++kh}pU!uytK30FChNo!j5Z z{0w8+7{+VeMd-P9Age(ee+A`*5Qjqg&QmhgS75b`0k84IOuZ&(B@I_(K~vHd>S}}$ zkO(3Vr?12Od)-Qq_d_}}`$ve0539z>KPmr$)PFL46uHDIe$IPA-rSSMm+fs#va6dq z)EWV~kxO@k){75T9fAE=XvbrALFXN@X&6;x)6Y9nBIFG96GD*5D-$Hp7?!ZW$5c(ZRUOW$fu0;Ig1MMi)M#AMU}xuddnoM9XJ`jg{yUy zu|{`!xbI41QgT=OqZ`ZodwGR`GjEFfVn@Fe0qSja6Kq1_=|Y)Nq)M46p33(Aafh&o zSL>68u6*Z_%kf?qnXiR}9Sl*(0{Tg#1?m8*(S&l@2N&>lxEKoAEwtA`YYPvG;wyBE z7uvD0E1|2W1Rr82vP|7!IPW#d#c~m~)4?)+M4&dY%&bf(>bG`7tORx_uenk^k7YMA zt>{|v^uwdz^7zrwuf|^bIdmj{v(VrZ`h0q*$MeIrof5&r)>qbbqOfal>`sSqAXbJ& zMd(=2qPGOLw>iEoXTLn$lC%uY-rFLs8hHAaE@L2baQ?gqPt*?rO1)xu5 z-Cgcr`U@kZ!6*rz-A&vjeDiMi&gbDC`H}pXMO!xM#b=W~$+vzBL8b0w4_q5Ec6$`T zG;!@aR@+L_o>c(Vb;Cck`AZ7#pX7o6ApBf}@ zIax>})ERJ&Q#nUiP0iYsXQe$^%_2Ckj+m3tFN~Nm4AG6$RhmqRN2YzqYRerK>-J)% z_sSxd^IwmOncN3yNz61u4Fl<6M6A*LZiF1=tU)}S5~+$= zj>Dzw7rW^Yjd{-WC9Z6#NQM0*CSLNlRU3jb*&z?Cur3S3xbk1cc}Pp2h8~PgpFls4 z3=MjeJZW|k=OJeJ{M*ptPI>vhD5;VL<~fw!pTp0WBnk5JJRBX{>c;FxJu8^cx=c|A zROnJrbVo$_5uZ+v#O3l9_8R8NMx-IP-HEO4uu|NN2T%S$LVoj1<5RA+WPK9zRaShP z=7UY+tc4~khFE4zKX-{EitJrV&EL9JZ}D9CFyJvi?g3AZ?w9Vgw~V z=sXYrUmSH-%8K&CIJClv`hwGN(p;}9$@9Q7d zZZZoVwxW)8T_!wMU`Atj!=Sx!FZ1D99gAwByinEK#9 z*?g^AQ)k?w&P(BY3OH_{NZ|ko^pi8PeHty+i;EKH?Qls1KP25LkxKQ+v94fB<>J_( zO$cGp%b@>aIze;LR8zJCnQwOrD`X2`Xtw4)XUu8M==q5)M>y7!?7t9JCzp!)A#d!A zkx%zY7&7wcwpO?6dq^l-0BxvW`5yxWD%}P)9oxq--acQ99VQCs-Rau{_E#@-kNauo zT=KIw?{Wy{oQp>eGl6%0msfL3RY6PB)heK|wn+QUw{N81itKxo4!m&7#JF9*ke9jw zThF=$W@^n!%5C_xD9rBUF7n|oUB2B-r$^5eNBVDQAm(MSN(xHH4oP=DB<*%qUNX*! zTwCaEtI7H%Il9ojUCR+{kv5pFBmZR5XRB|>o+vcveI~>5dwVgioV2dI6aVyv^KD%a z;B@LwCWXEvQR3Ch_0(hU2L5BILtrUuUDRoXmRgaiHSL(I4_#Fr1Zbe3K3`R`G>zw1 zuZ+c1KPp9I6BfOQVYgEF@=Ufa`*|gr6H=jiPm}Gi83{#t1rlUCMejyQdv)CurG16{ z#wBhd`#}y3`pFlSNfY-S@GAD))K66=4sjoAJA8dt-OGSXyO)R7##VH{BKtyudqpq* zWqN0Fs313!d^S9aRkAA!zt9Z@CJm~o4R&dGl6H;uEpX-MpdRBzj1Rp+F$QzN*LRe} z10O0SEg3I+08JVOex1uO^ZM4oL}b6rLJ5hO1qLHWLxs&K*taw$<;y=y-~v^dKOYs$ z{blDlR7T$p+Tsucd;^AhHUs{FO%o+06Hgu;FUFzXEbypn)cu=4sHR;BbND3=&CscG zEn?>?rT`N2`k%|ZVuwqb$c?>#&)i~Xfoj>>d)Pon&CxrbaO`vod*6vv_`Q{KXGvL% zuk2CD*Abq59eK(+d6wzZE{@&%{89mJR=tYqP%>*?&h1(sFCo$fp3_Uvvf1Y*TyL># zpAG21FnCou6OrX(Pxt%1kKNd#8EWq0xBo%`3tZ16+Np?VU|BP0LWj08Fymn<(!6WR z5`P-!koghey5q(2S^b}kw^A7;qBWm@WUXZA2ptolam{$M+&x_Oi8KKyE5zBC_(PVBv)h< zh`ppho*hvbsCf5L;GOS{8x^+=xzlgg3;-Xi; z!eLCutCw60W${686x4e>lXDPqV|8+>J+n(?r+So+!1H*J62Ui2M_Se9; zVtq~1Nn{Sc?xhXqdz#jd-S(5E4by4SwOk2C$rTg^XMq?y2^@U`Dw>d0^i?UWM7jy8 z-kVQqPLcK3`T9L3+UAW?+{1NJBHzX&UKz?JwEyT7Y4)O&oZ|QTfp=1ES;PPWL)oR1 zIDs5~Fjo7r?asMP@Ez}m-z!pumuw@2z#svK{yWwhQg&DFs{qxF6vrd7D9RESXuz#I zLnQL)ilPR^;9-wTBu}bxXWO*IlrK(Q-PeD++U4-as9Ol5it(8qIRPUbC(F;QB>h;< z7!cT4U-U6Mq*^`cC!?}-2K}T-Sz7)O%QJXM6)v=76D0(eygVkO94^Y|8*`MW9?ub? zcrDp|Ve-pzf$+!yt8r;;e?!d=PmeGom|UerQrAuTRm`)YaUsII_e;*cL=~5?BJ`Sx zC#TUiH-hM{#v7S9TU(eioW+_v#^a?jdIQ{YKs^#rm(1yQ5;tw0>?2SAWJviA2ciI6 z&aK4A3X%fd*;72|Ww#F)+P%hj-!5ZQa-KSnlHz!D6GabK3V+?8vKBj&MXKaukJtwP zrvS~Zb7#HQ2ONsyS!_xzWXw2!I)#!@L0+)77I)Aub_PdGc96^Hhx@3Sl472@8B)Um z_1Gy&NX#7uG%-YHh;Z+sshj0baLug}ql2yGXt9*As-jD6eIn8L#ktDIb9KoIfwt|f zWq_vt5JA!Twva;7*5qj@>1`!8Vj<b0n)ml{H{p%=6NFyNj1*l2bJL; z1S(cul|@K6kWGprS>pKU7C5kw(>}!$;U$*#*Y%7;EZA>**O&tB=MeWNyDkR$c`0EE z&u_Tg*#F1@j>&!TbHX@(b51Fz8d+ESgAMuK2KW^CW8V}B8}=s(xpSkvcj8TFLr;a} zyHo|=7=B=yTos#Vy`XR0&hW3uI?@;0VCR2Xv|h(|c|)l-8D+_o z$;BSDnBt7h3K{jk`R-2q7fO=H+uaH6wA4qZC$kL1W5Rg z&HGw`uT1W19uf<&?iTUmE$vO8)|&c(4smB2ZpZR|%9~myh6KjGyBYh|nLXv2v9!N4 zf%MG6sZCUDsaIK=I8Ww?{SiTTjgPui*r?}F1oyDcW2Z>Du9B} zjbd90Zym*c8+Cyv&DWT`RBF!Ip^!gTpQSEH*oYs>dR#)>-I_agc>u3euAaoHG?j27 z>HT$;1bMVbMN$wm9`|Q06Q6t)1u}mc7m_b?9?j9^V+QH zq1KdP-@CL_>hjNsZKk)Uz!O486O2y>8hxL4k-K&Nx@4uST4%Qs0a7@;${gQzCkunA zGIJ#`7p^hQgL(i-mZmFABK6T++Bc^+?wrgv*&WQjs@9e~RaZA->dbT|(+}ZrM^SY( zRQhRE7XQ_+cD63=oOi7`qu!;=kO*{X8^ohi${f-Zy7J zJ{e)X42@9CWVg4Y+0U242K7wiOfADEj0H#Oa&PzA4a(@Esnp0>8#oPFGwt(dlSS{Y zE&L!;9M7Aipm;4_NQq`3vnd#z%`oEX5iYV9VC0${;L74t>r3xt?>K2rg|U*9=9Dz6 zWnj(MUkxUUm!7Z_jI2c5EPj-w%^dR+3nG@y; zEwr!;uc{+MNYdja`-5)^_*4>mt8yrH4pnRVbkgEqZf;2aMt)bS4bUFX;9lF}ZX#H0 z<$udBpFJZ<`bSKppoO0WGwoK!dK%TbY&xu`d9<^+VeCuc>i+K0s*blVFZ3g95{H>~ z&V@^C=^p_}qR=6B z{;5HOw%9Rg)t_YJB`SUGCzO5P3EVYQpn4RYAkUUod&|v;F#fA)BW9q8%j+=xTC|Mb zt#4ucwW-)*T>}3HJRkIFQ=MESh_KZ?g`e#odS+6Lf&By5f4s}1(5r?Qmn@apM)Bo2 z?~vx>w)>1B*i~~ixc=%KOoajrNskt6GX<3HfT2{+U@0;bU-@QVGe{-1bFMCx_&wh2~ z3gVx_R{@0IX+dNOs{f!Pe*1@X6BZ@#f7*NVcqqUBe^>|+D%lcB3)#z7)=Cnxuh}JJ zAECi8lZ46^Dj}4T-HWjmo`$MHB9ItAD}wJK>T*QGJ12+aaX2W_!MkMT#Y4Y!!6x zIM>^w8*L`?B{h3t*_LC!Ev3e*nkv+;BAgBEav@el!&T`r6Pi`iBoXx?m-u1ACi0oE zGYH(E_4tMiTeah&snqqJmTpQsFzQpRQsg9@#*Ik;SNiVi`*h2SFGjHzxmhPIg#E4_ zz2;?n^{PJY73AJ zHr-GH(?#QpKP~tyi)LunWQ!h{8 zFPZI(p}o$A;yp=NdKdj!M$jK{L%fzD02;W#juoitFsWO{0mf%aZI65z>R1%i+E_1;Dr@qPxIw)TO|1rO7CBqJVAq}!&pZ?Ll_kKg& zGZ!Ozb`@MYH6RPy56hvt$|FHzsozBMF}^p^wv#BD7Hl?&4{BW^u7BUPOO(b)o)Ge* znSWH?@ZrrJ(I6jG>(Zc7qn~v*nNLJpXHe#;br44z!%COK@^^yqwtImG4L&|r20XVB)f66TGvS3{+0s<+9N;5s{0Sj%+iBm_(+crqhf@HqvdKXl@oNc}1>- zE3mF~zTV`I$qkQR?c2WZCZl+N`J&+}>9KAc9nSDBIqLmVQ@&X#!d3ASY$wj9XLmmc zh>9wx@-Qe$9=CGCSYT}XGEj)KMC|3$!*CU0U*2_WmM1vF(RH^u&4$jW*A!N`gF$Y{ zBFpvqh~C!$xPy>aABYLabsutyi`VazvPPn#LK+6&!sH$ zS{xvLzA?PIRRpsm)tY^QccZV^h7V1uerp}QAroMX8eLp#Ah8M`4Mv{-TtfmD+cEf7 zfO^udzYc=rSX*CXWqoY-ZI@F}i@g1fu8_?Sdku4KoA}b;tpwI|&sDC)gZlxgRBw;KY0z%G zgjt@x(aZ-GxpJv6i-;g0087`}6i(Kl>`#N?N@BrVK0Yqa?>Y&!WecNBhPo4hfRm=C zDz>2cZoUF>8hJc9)SH((xg7eIDI z(;tu-eqR5|5Z;yJkgKIXGL3*^fcd_UJqPZ5wpIkCCGfu6`dDh8$GIP=M+LfG$pR|Q zFtdi~Ule?JkjCW$uPM3yY`1#CS{O0q7hhfK6j;bx7E9^_3 zWwyCaB}?~pMw*{MM}uvRUN(OVNC=n?Cc*@G%Uc$^Q=%iH#5FPt7|@V}d&FUmQ7!Ws z)}KhuP5C~8oaQtdm|lvqPN}%a#r(R0We3k$plx&5I_73b59gQLQ?`VJ$MoU>rYO?c zj^8w9(GbEoitqWRmakexEKWYpcyrQK_*ezx1OoPY?>H=Jk+;LOQdE}P@FXGUTVYzF zd%Rldg{g;?AtG^#3Z00FLtqrS_Nr*&Hbk|ePo$_THKY6%7OGYOS4fB4Z2hhCDGZ=1 zloo^eyRy0WFw2JD@1=qJtOIt>1j@h`rwF}ONo{gvd=LHf$Ck~_Bid=D@G8|3?Hk6O2Z2^_#M(Q8As@e0FZj0c@5ew>eSc1sutv#<@zYu-ON`}xNxwwDSvs7;=S?;) zjY}%ww@J3681=eC~kEUFbFpOjLrJ^Rb+UI2r=~v2`%C+C5H*yzBN*MNqFQnsyBTOaH92uUFR*2xy5&H^AgDPp?p> z+iS?~&|{OR?T?R6!6sh4F1rudp&kq#;DTbotJO}-Bltfw_&@yB=f{EBLVoX(Rr z4GG&)^~quHKhWYdws9H3kmmo1=XY7rs-dv&9eXy%Uu7dN$OWKz2}%}aDpNLGc@QoH zK`7er7y^~6RH-vmy;>c12exTkb5C6DFqDd0fTd!9nvlw*2`bm0BrO@~Vsrv__%BSAiyUOId6 zld$&W!^-P7UI$yWWz!J)7Ouu#IG?e2jumY>l?G=(Yf1lBkiQ_K^w50?XB?q2bmI#h zjy`>(KMtq;dMr%}6oX(uC+9<47hXi4$SFTf_9>gpI98rt@$yWCaqikXRQcTT`0fp1 zHLP{|Z{q*v_Q~@g!oV$IU+LX@4rpI`+)xZ6UAT5No(^}2GZ?aba1m!Rz&=?)_{fic zSQ+VegOvB+YuH`iha;>P>p%KbX|f>_?)`_1?$(cu!epYByiTex^?fO^EGaytSF3jP z+VPB$#}8V~4~|YdAB~AHzN&WZNp63p+8wLC4W^Rj+anso-wz*}t+YWUCTd7YEhPm$ z#jNhqP|!^R(&@yhKWatrU&nfI6?Y@|Xdb9a(h!P0s0rh%Y^5GUk^B|#N~$uFi0^Pg zy0cZ4ymw4JlpbddD5o6d2#ungBx)d~956{{i-BUY7#)}BTm-_8A$a8I^Vz`7O(EO} ziHbvLc8R+L2OeY3Xd6xPhicj~Qfnfr$h*>k|Fmw>AqSEJCBF=AswI&0$ z5(omJqRM9g4M_kA!6?)YQxneUHIhKoVEbO-9)q}TIw_ED(!kCaI+bi)g|he0mrdO` zzq!K_%S$=kAva#-_MB4AB6Rv~zo}u9VRPWdih!YP2N%)Q+Tn+589#cjb z2JVmKv#b|Da*p{@{0Y%Ovz^IsvjMqj&fNGahuq<@1v^-4`e)_pC6%1M?Ylv3&c-ZI zL@-1NSX)qHd8ob!)Ht9h8SMaz?!t_Yxz0^c_38kk$c1^C9kF|jmAyL=Ps!j7-{$_z z$+1m|TkHyHCCjl!c^yuk{cgMe-ruT6U?B;ljX`+QVpxHwp674PS|#f*JYb z(Y3v>BIjz>F{gnK>P7NpZ8393WY@4(;NX@%>3;&l8|!h8-2u(k;ec+%JjdXxq`OWH z1b6b6w<+DTCcf~Id=pGmUo)6hN+Lcq-+lA73QsmIu{nbFG|h|NFf7gBlb$rhLLULE z^Lky|kfcLvcY4AbV~y|a z_Nu8|B5TkCqF0ubP=OnjSCZ`9ZXxcy7xpUibFeW_@n0J>e-*lN1_VY~{{mh1AJCsg z)Qkpk6YdY{IQu8z^5CvV$UY*&KH2^9BWGreRbp8H2}zR`DXd)cC`w{$@IGIK_pGW> z_UIW;7XWqUY^wH8x?*t;tEhg;u=_tU%q9oqg_-&siM#~Ddqg^R+z?2tv}_4#?vyc; zlQ?6ng+EkGxHxYsNdunrSTS=OM)nO0rAjRak)M`-0rxE%+5tzFd73wsIX7iM;HuxG zi~mJ>Zq2AWHvte9*&f5B&Ik#O_GbQt*%Ov!;`Rk$W66%QCiAveX$X=2`LKX8^Wp}> zQs+60${54uVNc3tK#w|LP>gK;0ptNQ`uZMP@ohD+u2bH*446QBDpc}`y-jK3L35q#Be|8|+0qP3XX!m%KnXYEodD5{%6J zt+ap3rzIV((cta0H`($w#sVQUw>{wvpmz(Y^no+Rr>3~hnK_%OFzdJo0(8rB{D8Q)D6qk&v zXQ(YVnSivCr$7T=eX)ER720TCYH)cqBqk;oWE0?t$u4LPg&MGGM#Wz`tFmy2RB-Q;Jk6NL@v-}LSI6lT{+6JaY16Q4#x>zxmtt)w&=nq|? zq1Pc_CMHi(gH<*0Y*6v$Qt1TOv?cjzwM@ATZGLxDdCzQ(RpmrV^_`3N{Ppz1Fv0<; zF(S&-a>Y-{^C6pHpB`ac&vwbj(|ZMa0_2FhzT##)rqI$?bwrY9JGd?R<)Se@;ZuP8 ze+Pr0Cv90A$yH)B^7Pa57;i?jYWKHuDg#p=6~o(OTku??hnml6pMZW&RA0~>x|{}R zr00q*r$<7R-^1Y@2le91^1`p}awb$w@^_)6cche{!j6943OnAEYGXgGD)&3=2+xt@ zSUkB%fHg|Nk?7SI(8u!^SNQ*Mg`oF{8od2c--dJA=#E{A9MY7@Q#59@5=icPLdm8( z31KN~{-k;yPlCX3oyr$Vw|Eh)Y+9OlOq1>>wfaYjwyFU`FcXh0`LTDxR8ys>;%m;V z)}5s|uKIk;08iT`a!$=?;pU9NWY8kEZ!RWbnsZX%t8Vm#{@k&e(Me$CLJ4A|8a{&k zY(vSD8;lHRK(lu+_f-osvu}J?X>AW_CSBmP2xLXW6<>&pJv{9*;n4am+>nX4yUX(& z&BSW%Zqe?C0r(|0)&W_F{PYzM{z_Ca=5A?g>XIQnt~gyQ06gOtnCT$rGP7CaUypE+ z!4Rw6xCVfl+qjz1k^hMT>f;FYkFow~3DXYXsEA7l!z)_@t2*utbQpjSjVZ!w+j_F^ z{0oN}zocblqKe&;+cj3}!{k9KgxqENrp?6_-86BMuLckv$BTd{{$@VsUzoq3Ca`42 zhP#!Qy*^axu)}UYE4;(bv&)K(s=k@I?GtTu*so~5l6KU4V*@PPQy|}zkr@=GjrG{= zvP~!};~3^&U`8vY{+>n;{aI5$gsui7V;S|Z9=G8ib2>cRXUM8>8e$kRHF&Lbt^6`v zeyFF3MGNGVgWHQXXE#kA6PE`3Hzv2$e3_H(W|O*Ds)CVCzirg|sXq$~R)@Iesp~#= zrxRKoE+twf@~d-f%AZ|pwz{}*`%kUm;=y2Bp>Vq(r1wE(bt#%9D zA9k zDqiK(IzX{@HNd7jYCtwu^3mjd5l3#d(tz>qtI`H<`*@!5x%<40Mur_$D}o%7{$H9&HQnzldPh&(2?3}N1i>;)@0 z5WxL5iY)xv0fg`gyCGkLM}T95 zEUD1eD%nh9tz8Kb36PA=`0Nc{HbI=FC0efkIiVV?vroX#9|8umv*9QFvfJ0@= zB%r`z{=Tvi=zY(|3VROZ^7TA zQ77S^%{YT>{P&zxzU_C5c<{RuZzH&NH(2uLuP%RnJ^QQcYYe|7G8X%@ql14yR|mpv zC}Zb%@_SS#gXFRX7Dq2`)V`awrJ{@m)c2cqn*Dp@eiKelMUmsPzo}-~C*am^N#)&t z_{DE22g-^A3VAB=S3f`o5deg%mwrP>wU5BP-^2sC+=1aY|3BBUT8%p{I$*%eud2(# z5L8A6`2+Dm`y_rAK$OXM-W<5&_rWRUHP(YXz6u20{3KTmgh7rBVV7EJ}Q8MELWMV8FN?{mw+w)Ym4!mQWd1|R!W!)1^&20xW@_lk4lF;R5ZtvmnI$d~lm(dyDujRIuxUH z&w^Mr?)zD4Y1z|1U|Ge8lI~`oN@Q6{g@4qNTY<;u+WIgoEAszS2ffnUT?4Z^Z02^J_S z^MAehdd$+`duFOr$5pS5k~ke{X#J_ZGOz7@bgu!L1WJrjQSGoE2vML^%cY{4Q=vT! zj2sX!s(0igk^t@06nghm|GoKNH2#&1|F<=TZ+LSTw+D{iFMLgPl|1epUWFvNOlV@M z0yzfbgCC1+8Qgf`p5+siTR~k~nw6F1KKh!**fb)~y{uoDBex_S*$WHO_;%Yd?$Fum zESLOKCF07#9$^Zq9aX4EFfGpFzAOV>*xGh#>TXVtF{6cPL|8ceW82RUFar%ikmp2` zWf?_DEd2O>!4RMf?HI5JEY{23D<%fAi2*_;D0M_AKR*C|J_}eu%HK7+>YiW3gNYo+ z5H$ORHEj1j$eAb91Tg_wF84F|OOm^I^0lzlp@5s2Eyeb{Ao*sVAw1uAY=3TEXxsJ8Lliew!;$vy1M~JOwb=i34A65v5%wXuS7A+mqgEs3XGvF} z0vo!E`Fr>dk@WjGjc#d224Qjk+&P z)cX}N+hE@=2Seg3uVMKtHmkJh9Us?JUB$A{y`_{J2Aa;ljvYH2MUR8D8WR>!KBBD(80$pz>%*q5c1-EQwASiw*-&l6!T(dKr_+eY-^l*IBKKClt`V@$sM&~D-;U=d+o^g%Tgzdm`bM@C1b}2Pg zAHnl`1Bq3Pv^c<3R}w1?tQdd-w)fcqIGlk&^FMXjSa-_dk!3+M-Q=upnK3>Ek~o40 zIgm-Icx$_-ntKExr*S42qF!#GY!8b9JZZ0ef4B_dfKvxUf@^pWUuLFEK5P8up#Y30 z7|_TT-%ZDS9^n1f6ghi~4*nRK5&m^=xEsbq)U1-6v_J4Sa=rWryqIZXyQLiPjlR|= zt(9({?=`#Oyte`DHt29E(@hz4@k5JYH>nAyP@TRs`*L8rSKo0C7^^%D!E8+Vdu*-8 zQ))uj*O}4G9n)$H%cQKO4{Dq&`$9!w@oRv#1t#`;2kY6+2yzk>G4EEL zAmZStY5e+FK)3J2oXOjd+0*moUE?&{;q+-iJvG^*U$bu!>Wf2IS$*k4!V4Z+1(shM zttatXnFgE>V+xYp9A9m@!++&B2Q97wEMBC?t^_1;IXEQ)qa;9GB*vJ zm8)0QetfTI7O`)}%wvs~trs8xGWuZLt!&%#yX0fcsqeuad{4^~RM2P)rF;$xj-}HPfbX`K*`E`x@cu7@epELKOqy0BN?hq~;iq13H;K$apZ!x1e z*=8&72EMNJ&|4}qNLE9P;vhz5(wqL59t~OpntVqBgn#at+U_GK4IJnPh%V&3v_KPX z)0RYHw4L1xjLZUQT{V^YZU>@Fitvt_cAmx)d}BX?f;MLBbq!+dP5XGq7J+S_m4?OM zPXPuAx2`Crm=H*i(9f_iaDW`>;a2qb}-fFeK7VHO+nYEu^IQ}zsm&6}s81x2PSGYjUYH+9*ULtX1&39Zwvd`*@V zY9NTPw%KxYnoP31*#=LLv_T$C)VGR6hyHRA|Sk5uK1f44>@UI$MUpWU%U$boQE?0ia*hk zsQYZzk;O>q;@U$W^#GXjp~MVAhc+e>qZNeZFGu&3@P~Wu`4^B@?pHQHwcbJiHXgLg+j953r`#J?n`Nf;*neizb3yb6d!2EpP5tXh$Qk6?EDh$CiOL@HP4T)sbR#> z$AjijMRCabab-xv#Q?nK!fD!OV{|<@NmRU+EV-iBmu)ev_LWT`gB};IX<@?wgA<>H zVw_qQ`*u@zLtApIVuFs1pb1$B_Y1p0`~wh|7Lgf#t;(LnyE7`sIasG;gMf-E zBm~!(AmL74S6Y{0*=HWYPgtqlm2y8c}BIlFqoS|># zc20Vg=6LFT;Tz)x20f91?L}X@OnjduD9^?nO)y$*yexhRnUo=D#Y>v>dk8`s_B~61Gi0|sH-RAMg{{EEy3Pd0|n}?AHg9l6~eoh zkY=LdVq)x!Y;3-r#%zWN)`uF~Mw{jx7fE3chH)+q=p#5~8lvZ9hbbz0IntHc@~CVm zu@uIo>oZ;`c{vwEuEiK6LmR3E1|q8u;dc`(wNIhttb!QxVvKV^y3*`+b)>H6C^1rT z{l}w5^!24>8fkOSE_?n8r3F@_B-Y*|Paro%%U8DE>XfbJ=clCHEZ*3gjJ|+Y%6DfN zRoE#Z*w?Y+Ej4D7>Z&|TcapB)*>Ta3YK~XWJ^0zwO;Q%8J(U+!RomCE+SOG#>D*t) zc*zu0#^}Ll8krI;hE~b3D1=!GxtB5!?in6EkCtF^7t>NN6n|;&*$^X5SdLHu5#;_m z&u%;d;ossn>5)Aelht?n+{T^|Elzi}n%F#YeR$GW3T_;xG_Jgi`eegdz0R3K$Qo5} z>}A7Q&1TqD#>FLvA0p^yX9O8!cL)`qv$}M`0oX|DvzY}3dl*FFd9hn z3=wg3M6ZdX1xE*UjIZoOxBN(2Z!Dj9E(}yIk=WIGxsnPZtMP>goEss{HC%r}gcQAB z%kdkH2x9O%Ll#MxWF)B9b<)s5^6HdojcAz&EGztUmGQPwfy+|ewO{_01!)#w*k+81 zyd{Go$7M3UyN`t;IhtH!k(bXr^=LYR`%ov-b1h&eUAWTyW(f#i9I5J5Up`Ig^Y!3& z{c)z1%aVtpVl9=@K^T^!TROVO#yt|B+m7!Qqx)Trp*0ctTIvhbKhqlg9OPxnAO+BZ zMnx|gtGtCnJ($usWxYkwX^nyUM5cl1DIwQu4>le3=+^K?c4}iUViNH4)rtk2w7bH3LTq=WF|P$Ka~X(aqdy3UAqwBX^tyM0R0 zK@MDdg(6ZK7hU|qX1qY{2kDztWEcZMc06e`=LhQg_?s=+at>UA*rXY|^=(!TT&9@V z1%Ktq(6J|%12V6qf(Gb|aV*GOuP4O&$HvD5%4Eb&T0wMSaEOK9SE@qF3l(tLl4+P3 z>Xgo$9UpV9)Uiajbs!|BO%a%Aav0<(2qR%t%>E|%tQmrA$KAxAQy0d`#DOD!`67+w z#0l1|gS9GoGU;YgKO324CxTGt$~KIS;2Q4~;6}yxF8yuh>VrX@4A&54d>2KID;%7x zeyNEu+-Aqgn{KasvwFfni1TSb>f0`u{Y69%VbO8h7kV_VlAeiB_WHHXRw#1kbL1ed zZrrcV3Uv|IX7ZuRq;53s>}=^-G{NYkN@aEU?0=wVMq!!+S|P@$@0(B*(yn|>5Y4H2 z3F4V1`qtUp4+^fgKV^ncd6Cpr7o;Z4%z+CjEy@i6K`QkML1hjhoKJ{)fMq^Dd5BOv zJq*d0(E-$T&hV%xI$?T7Z5+p&V^Q5_>RIq3@4$Yd1^~sHJ^B;$fSF>btJ+}|E0)G( zGZH4Av^DstJ`+OQ3KuX|fyW?;%|kg4 z1VXC~*>Q#(nLFZRdIF3Deq&O@LL6)7=nkNH{t)$v>c^rV+7~9No7~A^%@!bop&s9epML?8#GdnSt5Yhah2?Vny~ggadZ7=(Pc^O~>^HaQ&U z;KlILx~e|;9TF6o`Wgi8_3Ip#Cz~pc7qIv(bA9QXW83e<1Oc=23;4PDm}A5$tP zFt7L>^)W#TPmn}Ik&WY2=6!0G33(b!ssMm<#{zKk@72ge?aop0`?6xO( z(iSc}^erQy7Mj97mBmSV_c)V&x^)Z?pb^?4Z*?H!#1rI>en$O{+Ec(Tn~^jdGt z+FE;Za(=bRgR|%|V-}yX(Y7Od*VQ_k6O?!WHm8+F+6YS8Y~0O0MDXp~dL7tY$fJu` zw4pz*+Gxv2_-LqqW*qts8Q8!O^B?O@9f~E327zB6%kYv5Bo;hFsWx;5m9yhG*WV?# z{U9E>Nc;*A4|C=wKhF8l9FcJzZDBMCudnv#oNRCHe6Y=IdIW$y{brpNSy+E!h302I zpr32VLx6GqdJOlh8^KdOD%sl*iVI{UU@CbwQn+E+b*~pSOE_><_N!NWgZPsul!H^0 zgU)QlWz~&3n`(@cPjl$rs#BUb>eWPGjL4^JC;vlm*eH+-qS-!r$;q32E_=l@t~?)A zo{^4)EsbtluxU^?t~i~R>U&nmVtV}84KMwg%Zztw?L+8}vU}b0;yy&jb%Q(Fm|MS~ zs~J^&q}#MY{*(Q=l!vG^%#x;Yh2d%4z7h96mG%1i?to?Ud>U|q8k*CgGg5>Jo%U6e zZVH(+P!oil>dO=VMorK}UI&64oPR_t%BZ0ps8aphxC1ssLtM^);Kw|Jk%8QVMgvdV zf|_o9bblb0ny|(*b3x?`CwHegD&Dx#MS0ljWt)ivC;@&!>OE(;DE+I0xVzR+aK?|7 z4SyCiejZNNFxf$#XF`iCGpYp>YpikF*L&nWE3A4>X|?>^Or&fg2j0Y5pW~we$3`j8 z5DLB!7p2Z!-?;T1h@B8mazZ~Cv36YQ-8M4mi975H)70vv$B{m>mh=s-ZhU`WWQA4E zk%Q?Q*lDbtM8I!>v-+460FV3(tM@`671PUwxQE)Ox5aq=>C7dprb@Gt4riUT(M;2SQh=(0Z*Y-QbL0$_t~E(*BcQ*o`GXW%Nx4Gc$q_6*X1uegx;H#qfYidfZG7 z-Xc0(K~CBkYwc_*#E7>j}`2B0X;0UE&#}BT&0V zpDU{-$j`MlpaK58)pR3H*=clFJTZQ?!6XORCM{LSLCf-iY)bh|I1v%yji2%()Ff=0 z$+J(7#snkF@9z~)qz8ghKyEFwekd6gQxjx6PvTyj-i(pA`5=fgFUZ20D0kpaeE-NQYkCnh zz_BNk)8(?Rp4T2=X$ORKd>>{avWk}cdZnFtXp4GH*j@_6a3f5I*>hyI zW%dNWKFs}CXGOX~=79Depqvj-&Ohj(r$MGd>95-3;+$G@yWAimTGtAC{d={ssh3^X z)^PVd7X8z=1Yj?u?G&H$S`_ixTq##wNuGO6m*2;TUPC5`D}FXMlOA}7DPtEpjE*{J z7;O%5=W`!v!4%B}O~`;a`6D+2u9roA(8W!sC8!hwp&uekjDRbx_GF}7=1DlL?;~fy zN-@j+Sqc@^jLHwDVC3}@CbXEvCzpAHS$(-+$dv%)mZYtOmBWEOt*tw?fRm+Hlnq|g1J2dB;gdE-K@-V1{`7iYL_%G}WblKr-0(O6U7{S9KuF$EULDHQ6$ ziLk(2uv}1ld>qj^_PWe&$k2Cn9oyFTe)O4t(DsXn{Oh;h5SvP2$H05u2D#?JMBSYS z%0(!?lq6^ss>{{N^}LIxh67go=BP@Aul_YGw5++LYRUl+Q9Dxr5Q}_dxvYDq=Wc4! z8%XgGPjM=d54G?|;b|~O5F$p%nxH)*6B>y^loXu+=l6o&_TOA?lGSlB76Fm9Di^^D zDSH#=yj}vX#VHRWsJ;Jwc{#(HBSE3_=tht zs^a5gh?qbRU(YG~Op9-j&#KOzK;4ivq#WlOln`}-+q}}7=eD2DP z;Fp6r+;}K2rWO7AI6Y24#J{d`@*Yi(CN=nIl~6gMC_y5Q9>?w*T32KBbUO5y%}1i) z?nj#aoo9+^+P#4-&=XF)-Eq^=Nh8kS1&`YPs z%~tw;pG{XY?e6( zoD*EB%ED2#XY(zg;f#e2PmuLUjn!N7_O%H2gFE?IdFKGX|5&i=fbR9xuNzld$%hA} zWqmj9JMJz=?6NlrN@a#e)$iOIyktI-;w{pC^y|+5%LrK6OW6 z!!NtL06&-Hq@(0FIFKRZ=BO-6niEnwiSZ}y?sW_&AdLfvAI}_2%2#cv|X*B>O@`0CyA0fh=V{lfQxGyVal3RUB{h^@tTX z8Ti>_8|()ep#M#G`^_w9z5Xq%^}&rJ2!6$p&PYuyoak{Ke15_v$B0Vj^0$cd+jIy1 zu?5`0kgFMydP;o4!i>pwfp1wg*-Ey86LNBK!EDr!AmmZv?i#X#&wp}OO-ew*H>7wcF z1BSHZf1M6en6i2lL7#BW0^b~3CvdVu=c~*!hP1x2wV<9}*BKMU=99odGqM^H8NNx^ zF7fSyiG@Z-V5Z4`ZNRKCDW?f34P;+q+yY_)T`obsfYG<==y4@n;T9&9(wCjf?cy&D zK*{er6|1#S|Im&-5Da+{3OTnDpnCQ?wjdQBj2tZSb-C+p@8<9C)*ay1X$XlBE9H@8 z#pFpyNT6cwL~DOv{s(M7;6VKT_-$`}#8`Y$z6=mv{G1$&bjaqs0#}%VE{Tqgt+o09 zUUI)@LF*$3daKKK@8PW4qsk{$H*1u}fD*!2d4bGU(}~Ac{M>rIA^ejWtDB8X>+=6R zmU;vMqwk(~6G~_~0sA&@B+Skj`gv$+2=qq9Q)b~bh_mYnu=sZV^mx-m&T7QfUpwuu zAs!7@(2K5MKsSV1#z^zwd8>@?gdnTBHv{&Faup~4s0R%Y`4{}4R~;*U!y>ExXbi@0 zgPFNH0Dm9u346rykEYcqP=nu{+&G5dPYfs}W79a*1HOF1Rg;VC<;3(uy|}`i9iKC3 z1;mD=df$B0bNHN-on##1>0z6zpxEw5#kV-m)h)f+T@MPc=$rvr@neS+lgXqJ3rm&C z?M^~9K9E;@^Sni8Lf^+kI1aPpUPH-iX-od0OK}kU`TYpRpNxf~)WmQqz&{K`IkFs7 zp{2N!g#Zo*HG8Ki-e)H%m~XNk0KCbtl%1c_i;>hk8A3s3k;hKBoN%yK0?Y?*89)Mjb z?+XNPuaOF`0RQ89G(dnaPr6++2nj=uvrtXxn0%Pubu0%Gj{*N1-MD)tHM*ep=X1bM zH7Z;<-~&jeED6{d;5uasGzeT*YXDq;>(L{i5z2L-9>}Z#^vwy3cr8u{d>U>*MVlY$D>zc~Ewm4~m< ze78OI(}4c_`7aI>(fHpf2TyqwI4IO{O?fIkO9?#+?419a-~avmxz70)hyRs0=qWtB z4ajZ1oxBq_rTDbql14Pm9|KDDoS<7Ha8Lv^wluM + + + A gravity compensation PD controller developed by the Automatic Control Group of the University of Salerno, Italy. + + + diff --git a/gravity_compensation_pd_controller/include/gravity_compensation_pd_controller/gravity_compensation_pd_controller.hpp b/gravity_compensation_pd_controller/include/gravity_compensation_pd_controller/gravity_compensation_pd_controller.hpp new file mode 100644 index 0000000000..6e0b4fefce --- /dev/null +++ b/gravity_compensation_pd_controller/include/gravity_compensation_pd_controller/gravity_compensation_pd_controller.hpp @@ -0,0 +1,175 @@ +/* ------------------------------------------------------------------- + * + * This module has been developed by the Automatic Control Group + * of the University of Salerno, Italy. + * + * Title: gravity_compensation_pd_controller.hpp + * Author: Davide Risi + * Org.: UNISA + * Date: Sept 4, 2025 + * + * This module implements a PD controller with gravity compensation. + * + * ------------------------------------------------------------------- + */ + +#ifndef GRAVITY_COMPENSATION_PD_CONTROLLER__GRAVITY_COMPENSATION_PD_CONTROLLER_HPP_ +#define GRAVITY_COMPENSATION_PD_CONTROLLER__GRAVITY_COMPENSATION_PD_CONTROLLER_HPP_ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "gravity_compensation_pd_controller/gravity_compensation_pd_controller_parameters.hpp" +namespace gravity_compensation_pd_controller +{ + +struct RobotJointState +{ + std::vector positions; + std::vector velocities; +}; + +/** + * @class GravityCompensationPDController + * @brief A class representing a PD controller with gravity compensation. + * + * This class implements the \c controller_interface::ChainableControllerInterface interface. + * All of the public methods override the corresponding methods of the \c controller_interface::ChainableControllerInterface class. + * Please refer to the documentation of the base class for more details. + */ +class GravityCompensationPDController : public controller_interface::ChainableControllerInterface +{ +public: + + GravityCompensationPDController(); + + controller_interface::CallbackReturn on_init() override; + + controller_interface::InterfaceConfiguration command_interface_configuration() const override; + + controller_interface::InterfaceConfiguration state_interface_configuration() const override; + + controller_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) override; + + controller_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override; + + controller_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override; + + controller_interface::CallbackReturn on_error(const rclcpp_lifecycle::State& previous_state) override; + +protected: + // The following methods are overridden from the base class. Refer to the base class documentation for details. + std::vector on_export_reference_interfaces() override; + controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time& time, const rclcpp::Duration& period) override; + bool on_set_chained_mode(bool chained_mode) override; + controller_interface::return_type update_and_write_commands(const rclcpp::Time& time, const rclcpp::Duration& period) override; + + /** + * @brief Computes the joint effort command using a PD control law with optional gravity compensation. + * + * This method calculates the joint effort command according to the control law described in the README file. + * If \c compensate_gravity parameter is disabled, the control law reduces to a standard PD controller. + * The resulting effort command is stored in the \c joint_command_ attribute. + */ + void compute_control_law_(); + + /** + * @brief Reads the state interfaces and updates the internal joint state. + * + * @return True if successful, false otherwise. + */ + [[nodiscard]] bool read_state_interfaces_(); + + /** + * @brief Writes the command interfaces with the computed joint effort command. + * + * @return True if successful, false otherwise. + */ + [[nodiscard]] bool write_command_interfaces_(); + + /** + * @brief Reads the reference interfaces and updates the internal joint reference. + * + * @return True if successful, false otherwise. + */ + [[nodiscard]] bool read_reference_interfaces_(); + + /** + * @brief Reads the joint effort limits from the URDF file populating the torque_limits_ member. + * + * @return True if successful, false otherwise. + */ + bool read_joint_effort_limits_from_urdf(); + + /** + * @brief Plugin loader for the inverse dynamics solver. + */ + pluginlib::ClassLoader dynamics_solver_loader_; + + /** + * @brief Shared pointer to the inverse dynamics solver used for gravity compensation. + */ + std::shared_ptr dynamics_solver_; + + /** + * @brief Variables to store the joint command, reference, and last reference. + */ + std::vector joint_command_, joint_reference_, last_joint_reference_; + + /** + * @brief Shared pointer to the parameter listener responsible for handling the controller's parameters. + */ + std::shared_ptr parameter_handler_; + + /** + * @brief Vector to store the torque limits for each joint. + */ + Eigen::VectorXd torque_limits_; + + /** + * @brief Eigen vector to store the position error between the reference and current joint positions. + */ + Eigen::VectorXd position_error_; + + /** + * @brief Eigen vector to store the computed joint effort command. + */ + Eigen::VectorXd eigen_effort_command_; + + /** + * @brief Diagonal matrix for proportional gains (Kp) used in the PD control law. + */ + Eigen::DiagonalMatrix Kp_; + + /** + * @brief Diagonal matrix for derivative gains (Kd) used in the PD control law. + */ + Eigen::DiagonalMatrix Kd_; + + /** + * @brief Constant to store the duration of the throttle interval as an integral value in milliseconds. + */ + static constexpr unsigned short DURATION_MS_{ 1000 }; + + /** + * @brief Number of joints to control. + */ + std::size_t num_joints_{ 0 }; + + /** + * @brief Internal variable to store the current joint state of the robot. + */ + RobotJointState robot_joint_state_; + +}; + +} // namespace gravity_compensation_pd_controller + +#endif // GRAVITY_COMPENSATION_PD_CONTROLLER__GRAVITY_COMPENSATION_PD_CONTROLLER_HPP_ diff --git a/gravity_compensation_pd_controller/package.xml b/gravity_compensation_pd_controller/package.xml new file mode 100644 index 0000000000..678071d438 --- /dev/null +++ b/gravity_compensation_pd_controller/package.xml @@ -0,0 +1,26 @@ + + + + gravity_compensation_pd_controller + 0.1.0 + A ROS2 package implementing a PD controller with gravity compensation + Davide Risi + Enrico Ferrentino + BSD + + ament_cmake + + controller_interface + eigen + generate_parameter_library + hardware_interface + inverse_dynamics_solver + pluginlib + rclcpp + rclcpp_lifecycle + realtime_tools + + + ament_cmake + + diff --git a/gravity_compensation_pd_controller/src/gravity_compensation_pd_controller.cpp b/gravity_compensation_pd_controller/src/gravity_compensation_pd_controller.cpp new file mode 100644 index 0000000000..d59df15b0e --- /dev/null +++ b/gravity_compensation_pd_controller/src/gravity_compensation_pd_controller.cpp @@ -0,0 +1,393 @@ +/* ------------------------------------------------------------------- + * + * This module has been developed by the Automatic Control Group + * of the University of Salerno, Italy. + * + * Title: gravity_compensation_pd_controller.cpp + * Author: Davide Risi + * Org.: UNISA + * Date: Sept 4, 2025 + * + * Refer to the header file for a description of this module. + * + * ------------------------------------------------------------------- + */ + +#include + +// URDF +#include + +#include "gravity_compensation_pd_controller/gravity_compensation_pd_controller.hpp" + +namespace gravity_compensation_pd_controller +{ +GravityCompensationPDController::GravityCompensationPDController() + : controller_interface::ChainableControllerInterface() + , dynamics_solver_loader_("inverse_dynamics_solver", "inverse_dynamics_solver::InverseDynamicsSolver") + , dynamics_solver_(nullptr) +{} + +controller_interface::CallbackReturn GravityCompensationPDController::on_init() +{ + try + { + parameter_handler_ = std::make_shared(get_node()); + } + catch (const std::exception& e) + { + RCLCPP_ERROR(get_node()->get_logger(), "Exception thrown during init stage with message: %s \n", e.what()); + return controller_interface::CallbackReturn::ERROR; + } + + // Number of joints to control is fixed after initialization + num_joints_ = parameter_handler_->get_params().joints.size(); + + // Retrieve torque limits from URDF + if (!read_joint_effort_limits_from_urdf()) + { + RCLCPP_ERROR(get_node()->get_logger(), "Failed to read joint effort limits from URDF"); + return controller_interface::CallbackReturn::ERROR; + } + + // Allocate dynamic memory + robot_joint_state_.positions.assign(num_joints_, 0.0); + robot_joint_state_.velocities.assign(num_joints_, 0.0); + joint_command_.assign(num_joints_, 0.0); + joint_reference_.assign(num_joints_, 0.0); + last_joint_reference_ = joint_reference_; + + // Allocate Eigen vectors' dynamic memory for real-time safeness + position_error_.resize(num_joints_); + eigen_effort_command_.resize(num_joints_); + + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::InterfaceConfiguration GravityCompensationPDController::command_interface_configuration() const +{ + const auto params = parameter_handler_->get_params(); + controller_interface::InterfaceConfiguration command_interfaces_config; + command_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL; + + command_interfaces_config.names.reserve(params.joints.size()); + + if (params.command_interfaces_names_override.effort.size() == num_joints_) + { + command_interfaces_config.names.insert( + command_interfaces_config.names.end(), + params.command_interfaces_names_override.effort.begin(), + params.command_interfaces_names_override.effort.end()); + } + else + { + for (const auto & joint_name : params.joints) + { + command_interfaces_config.names.push_back(joint_name + "/effort"); + } + } + return command_interfaces_config; +} + +controller_interface::InterfaceConfiguration GravityCompensationPDController::state_interface_configuration() const +{ + const auto params = parameter_handler_->get_params(); + controller_interface::InterfaceConfiguration state_interfaces_config; + state_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL; + + state_interfaces_config.names.reserve(params.joints.size() * 2); + + if (params.state_interfaces_names_override.position.size() == num_joints_) + { + state_interfaces_config.names.insert( + state_interfaces_config.names.end(), + params.state_interfaces_names_override.position.begin(), + params.state_interfaces_names_override.position.end()); + } + else + { + for (const auto & joint_name : params.joints) + { + state_interfaces_config.names.push_back(joint_name + "/position"); + } + } + + if (params.state_interfaces_names_override.velocity.size() == num_joints_) + { + state_interfaces_config.names.insert( + state_interfaces_config.names.end(), + params.state_interfaces_names_override.velocity.begin(), + params.state_interfaces_names_override.velocity.end()); + } + else + { + for (const auto & joint_name : params.joints) + { + state_interfaces_config.names.push_back(joint_name + "/velocity"); + } + } + return state_interfaces_config; +} + +std::vector GravityCompensationPDController::on_export_reference_interfaces() +{ + const auto params = parameter_handler_->get_params(); + ChainableControllerInterface::reference_interfaces_.assign( + num_joints_, std::numeric_limits::quiet_NaN()); + + std::vector reference_interfaces; + reference_interfaces.reserve(num_joints_); + + for (std::size_t i = 0; i < params.joints.size(); ++i) + { + reference_interfaces.emplace_back( + hardware_interface::CommandInterface( + std::string(get_node()->get_name()) + "/" + params.joints[i], + "position", + &ChainableControllerInterface::reference_interfaces_[i])); + } + return reference_interfaces; +} + + +controller_interface::CallbackReturn GravityCompensationPDController::on_error(const rclcpp_lifecycle::State& /*previous_state*/) +{ + // Set the command to NaN values, to notify the hardware that the controller is unable to provide valid commands + std::fill(joint_command_.begin(), joint_command_.end(), std::numeric_limits::quiet_NaN()); + if (!write_command_interfaces_()) + { + RCLCPP_ERROR(get_node()->get_logger(), "Failed to write NaN values to command interfaces while in error state."); + return controller_interface::CallbackReturn::ERROR; + } + + RCLCPP_ERROR(get_node()->get_logger(), + "Controller is in error state. Writing NaN values to command interfaces. Restart the controller to recover."); + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::CallbackReturn GravityCompensationPDController::on_configure(const rclcpp_lifecycle::State& /*previous_state*/) +{ + gravity_compensation_pd_controller::Params params = parameter_handler_->get_params(); + + if (dynamics_solver_ == nullptr) + { + try + { + dynamics_solver_ = dynamics_solver_loader_.createSharedInstance(params.dynamics_solver.dynamics_solver_plugin); + } + catch (pluginlib::PluginlibException& ex) + { + RCLCPP_ERROR(get_node()->get_logger(), "Exception while loading the dynamics solver plugin '%s': '%s'", + params.dynamics_solver.dynamics_solver_plugin.c_str(), ex.what()); + return controller_interface::CallbackReturn::ERROR; + } + } + + // Set the robot description as node parameters + get_node()->declare_parameter("robot_description", get_robot_description()); + + // Initialize the dynamics solver + try + { + dynamics_solver_->initialize(get_node()->get_node_parameters_interface(), "dynamics_solver"); + } + catch (const std::exception& e) + { + RCLCPP_ERROR(get_node()->get_logger(), "Exception while initializing the dynamics solver plugin '%s': '%s'", + params.dynamics_solver.dynamics_solver_plugin.c_str(), e.what()); + return controller_interface::CallbackReturn::ERROR; + } + + if (params.p_gains.size() != num_joints_ || params.d_gains.size() != num_joints_) + { + RCLCPP_ERROR(get_node()->get_logger(), "Gains size does not match joints size"); + return controller_interface::CallbackReturn::ERROR; + } + + Kp_.diagonal() = Eigen::Map(params.p_gains.data(), params.p_gains.size()); + Kd_.diagonal() = Eigen::Map(params.d_gains.data(), params.d_gains.size()); + + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::CallbackReturn GravityCompensationPDController::on_activate(const rclcpp_lifecycle::State& /*previous_state*/) +{ + + // Read the current state of the robot from the hardware + if(!read_state_interfaces_()) + { + RCLCPP_ERROR(get_node()->get_logger(), "Failed to read joint positions from the hardware.\n"); + return controller_interface::CallbackReturn::ERROR; + } + + // Use current joint state as first valid reference + joint_reference_ = robot_joint_state_.positions; + last_joint_reference_ = joint_reference_; + std::fill(joint_command_.begin(), joint_command_.end(), std::numeric_limits::quiet_NaN()); + + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::return_type GravityCompensationPDController::update_reference_from_subscribers(const rclcpp::Time& /*time*/, + const rclcpp::Duration& /*period*/) +{ + return controller_interface::return_type::OK; +} + +controller_interface::return_type GravityCompensationPDController::update_and_write_commands(const rclcpp::Time& /*time*/, + const rclcpp::Duration& /*period*/) +{ + // Read the current state of the robot from the hardware + if(!read_state_interfaces_()) + { + RCLCPP_ERROR(get_node()->get_logger(), "Failed to read joint states from the hardware.\n"); + return controller_interface::return_type::ERROR; + } + + // Read the reference from the reference interfaces + if (!read_reference_interfaces_()) + { + RCLCPP_WARN_THROTTLE(get_node()->get_logger(), *get_node()->get_clock(), DURATION_MS_, + "Received NaN values in joint reference positions. Using last valid reference instead."); + // If NaN values are detected in the joint reference positions, use the last valid reference + joint_reference_ = last_joint_reference_; + } + + compute_control_law_(); + + // Write the command to the hardware + if (!write_command_interfaces_()) + { + RCLCPP_ERROR(get_node()->get_logger(), "Failed to write joint command to the hardware.\n"); + return controller_interface::return_type::ERROR; + } + + // Update the last command and reference + last_joint_reference_ = joint_reference_; + + return controller_interface::return_type::OK; +} + +controller_interface::CallbackReturn GravityCompensationPDController::on_deactivate(const rclcpp_lifecycle::State& /*previous_state*/) +{ + release_interfaces(); + return controller_interface::CallbackReturn::SUCCESS; +} + +bool GravityCompensationPDController::on_set_chained_mode(bool /* chained_mode */) +{ + return true; +} + +void GravityCompensationPDController::compute_control_law_() +{ + Eigen::VectorXd current_positions = Eigen::Map(robot_joint_state_.positions.data(), robot_joint_state_.positions.size()); + Eigen::VectorXd current_velocities = Eigen::Map(robot_joint_state_.velocities.data(), robot_joint_state_.velocities.size()); + + for (std::size_t i = 0; i < num_joints_; i++) + { + position_error_(i) = joint_reference_[i] - current_positions(i); + } + + // Compute the effort command using PD control law + if (parameter_handler_->get_params().compensate_gravity) + { + eigen_effort_command_ = dynamics_solver_->getGravityVector(current_positions); + } + + eigen_effort_command_ += Kp_ * position_error_ - Kd_ * current_velocities; + + // Apply torque limits using Eigen + eigen_effort_command_ = eigen_effort_command_.cwiseMax(-torque_limits_).cwiseMin(torque_limits_); + std::copy(eigen_effort_command_.data(), eigen_effort_command_.data() + num_joints_, joint_command_.begin()); +} + +bool GravityCompensationPDController::read_state_interfaces_() +{ + bool all_read{true}; + for (std::size_t i = 0; i < num_joints_; i++) + { + std::optional state_position_op = ControllerInterfaceBase::state_interfaces_[i].get_optional(); + std::optional state_velocity_op = ControllerInterfaceBase::state_interfaces_[i + num_joints_].get_optional(); + + if (!state_position_op.has_value() || !state_velocity_op.has_value()) + { + all_read = false; + } + robot_joint_state_.positions[i] = state_position_op.value(); + robot_joint_state_.velocities[i] = state_velocity_op.value(); + } + return all_read; +} + +bool GravityCompensationPDController::write_command_interfaces_() +{ + bool all_written{true}; + for (std::size_t i = 0; i < num_joints_; i++) + { + all_written &= ControllerInterfaceBase::command_interfaces_[i].set_value(joint_command_[i]); + } + return all_written; +} + +bool GravityCompensationPDController::read_reference_interfaces_() +{ + bool all_read{true}; + for (std::size_t i = 0; i < num_joints_; i++) + { + if(std::isnan(ChainableControllerInterface::reference_interfaces_[i])) + { + all_read = false; + } + joint_reference_[i] = ChainableControllerInterface::reference_interfaces_[i]; + } + return all_read; +} + +bool GravityCompensationPDController::read_joint_effort_limits_from_urdf() +{ + torque_limits_.resize(num_joints_); + const std::string& robot_description = get_robot_description(); + const std::vector& joint_names = parameter_handler_->get_params().joints; + + if (robot_description.empty()) + { + RCLCPP_ERROR(get_node()->get_logger(), "Robot description is empty."); + return false; + } + + urdf::Model robot_model; + if (!robot_model.initString(robot_description)) + { + RCLCPP_ERROR(get_node()->get_logger(), "Failed to parse URDF."); + return false; + } + + std::size_t num_joints{ joint_names.size() }; + std::vector joints_without_limits; + + for (std::size_t i = 0; i < num_joints; ++i) + { + const std::string& joint_name{ joint_names[i] }; + urdf::JointConstSharedPtr joint{ robot_model.getJoint(joint_name) }; + + if (!joint) + return false; + + if (joint->limits) + { + torque_limits_[i] = joint->limits->effort; + } + else + { + RCLCPP_WARN(get_node()->get_logger(), "Joint '%s' does not have effort limits specified in the URDF. Setting to infinity.", joint_name.c_str()); + torque_limits_[i] = std::numeric_limits::max(); + } + } + + return true; +} + +} // namespace gravity_compensation_pd_controller + +PLUGINLIB_EXPORT_CLASS(gravity_compensation_pd_controller::GravityCompensationPDController, controller_interface::ChainableControllerInterface) diff --git a/gravity_compensation_pd_controller/src/gravity_compensation_pd_controller_parameters.yaml b/gravity_compensation_pd_controller/src/gravity_compensation_pd_controller_parameters.yaml new file mode 100644 index 0000000000..832c2814f7 --- /dev/null +++ b/gravity_compensation_pd_controller/src/gravity_compensation_pd_controller_parameters.yaml @@ -0,0 +1,74 @@ +gravity_compensation_pd_controller: + joints: { + type: string_array, + description: "Specifies which joints will be used by the controller.", + default_value: [], + } + joint_space_reference_controller: { + type: string, + description: "Name of the joint space reference controller.", + default_value: "", + read_only: true, + } + state_interfaces_names_override: + position: { + type: string_array, + description: "If this parameter is set, it will override the default names for the position interface of the state interfaces.", + default_value: [], + read_only: true + } + velocity: { + type: string_array, + description: "If this parameter is set, it will override the default names for the velocity interface of the state interfaces.", + default_value: [], + read_only: true + } + command_interfaces_names_override: + effort: { + type: string_array, + description: "If this parameter is set, it will override the default names for the effort interface of the command interfaces.", + default_value: [], + read_only: true + } + + p_gains: { + type: double_array, + default_value: [], + } + d_gains: { + type: double_array, + default_value: [], + } + compensate_gravity: { + type: bool, + description: "If true, the controller will compensate for gravity.", + default_value: true, + } + dynamics_solver: + dynamics_solver_plugin: + { + type: string, + description: "Name of the dynamics solver to use.", + read_only: true, + validation: { + not_empty<>: null + } + } + root: + { + type: string, + description: "Specifies the base link of the robot description used by the inverse dynamics solver.", + read_only: true, + validation: { + not_empty<>: null + } + } + tip: + { + type: string, + description: "Specifies the end effector link of the robot description used by the inverse dynamics solver.", + read_only: true, + validation: { + not_empty<>: null + } + } From 3917dbd1a1254eeb1600be5903681e638f30c023 Mon Sep 17 00:00:00 2001 From: Davide Risi Date: Sun, 7 Sep 2025 16:20:53 +0200 Subject: [PATCH 2/9] [MAK] Remove unused dependencies from CMakeLists.txt --- gravity_compensation_pd_controller/CMakeLists.txt | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/gravity_compensation_pd_controller/CMakeLists.txt b/gravity_compensation_pd_controller/CMakeLists.txt index d245ad14d7..cdfd1fdd78 100644 --- a/gravity_compensation_pd_controller/CMakeLists.txt +++ b/gravity_compensation_pd_controller/CMakeLists.txt @@ -16,8 +16,6 @@ if(CMAKE_COMPILER_IS_GNUCXX endif() set(THIS_PACKAGE_INCLUDE_DEPENDS - acg_control_msgs - acg_hardware_interface_facade controller_interface Eigen3 generate_parameter_library @@ -64,9 +62,7 @@ target_link_libraries( target_link_libraries( gravity_compensation_pd_controller - PUBLIC ${acg_control_msgs_TARGETS} - acg_hardware_interface_facade::hardware_interface_facade - controller_interface::controller_interface + PUBLIC controller_interface::controller_interface hardware_interface::hardware_interface hardware_interface::mock_components inverse_dynamics_solver::inverse_dynamics_solver_lib From e12dffc464dbf5cf2774598970a4c45f998d6ad9 Mon Sep 17 00:00:00 2001 From: Davide Risi Date: Tue, 16 Sep 2025 14:58:18 +0200 Subject: [PATCH 3/9] [FIX] Fix pre-commit errors - [REF] Refactor CMakeLists.txt, update documentation, and improve code formatting across multiple files --- .../CMakeLists.txt | 28 +-- ...y_compensation_pd_controller_parameters.md | 3 - .../gravity_compensation_pd_controller.hpp | 92 +++++---- .../package.xml | 2 +- .../gravity_compensation_pd_controller.cpp | 177 ++++++++++-------- 5 files changed, 170 insertions(+), 132 deletions(-) diff --git a/gravity_compensation_pd_controller/CMakeLists.txt b/gravity_compensation_pd_controller/CMakeLists.txt index cdfd1fdd78..3bed7e8fad 100644 --- a/gravity_compensation_pd_controller/CMakeLists.txt +++ b/gravity_compensation_pd_controller/CMakeLists.txt @@ -4,9 +4,9 @@ project(gravity_compensation_pd_controller ) if(CMAKE_COMPILER_IS_GNUCXX - OR CMAKE_CXX_COMPILER_ID - MATCHES - "Clang" + OR CMAKE_CXX_COMPILER_ID + MATCHES + "Clang" ) add_compile_options( -Wall @@ -37,7 +37,7 @@ foreach(dependency IN endforeach() generate_parameter_library(gravity_compensation_pd_controller_parameters - src/gravity_compensation_pd_controller_parameters.yaml + src/gravity_compensation_pd_controller_parameters.yaml ) add_library(gravity_compensation_pd_controller SHARED @@ -52,7 +52,7 @@ target_compile_features( target_include_directories( gravity_compensation_pd_controller PUBLIC $ - $ + $ ) target_link_libraries( @@ -63,15 +63,15 @@ target_link_libraries( target_link_libraries( gravity_compensation_pd_controller PUBLIC controller_interface::controller_interface - hardware_interface::hardware_interface - hardware_interface::mock_components - inverse_dynamics_solver::inverse_dynamics_solver_lib - pluginlib::pluginlib - rclcpp::rclcpp - rclcpp_lifecycle::rclcpp_lifecycle - realtime_tools::realtime_tools - realtime_tools::thread_priority - urdf::urdf + hardware_interface::hardware_interface + hardware_interface::mock_components + inverse_dynamics_solver::inverse_dynamics_solver_lib + pluginlib::pluginlib + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle + realtime_tools::realtime_tools + realtime_tools::thread_priority + urdf::urdf ) # Causes the visibility macros to use dllexport rather than dllimport, which is appropriate when diff --git a/gravity_compensation_pd_controller/doc/gravity_compensation_pd_controller_parameters.md b/gravity_compensation_pd_controller/doc/gravity_compensation_pd_controller_parameters.md index 3336b056d3..e5d426bffb 100644 --- a/gravity_compensation_pd_controller/doc/gravity_compensation_pd_controller_parameters.md +++ b/gravity_compensation_pd_controller/doc/gravity_compensation_pd_controller_parameters.md @@ -125,6 +125,3 @@ Specifies the end effector link of the robot description used by the inverse dyn - parameter is not empty *Additional Constraints:* - - - diff --git a/gravity_compensation_pd_controller/include/gravity_compensation_pd_controller/gravity_compensation_pd_controller.hpp b/gravity_compensation_pd_controller/include/gravity_compensation_pd_controller/gravity_compensation_pd_controller.hpp index 6e0b4fefce..a706ac3fdf 100644 --- a/gravity_compensation_pd_controller/include/gravity_compensation_pd_controller/gravity_compensation_pd_controller.hpp +++ b/gravity_compensation_pd_controller/include/gravity_compensation_pd_controller/gravity_compensation_pd_controller.hpp @@ -1,32 +1,37 @@ -/* ------------------------------------------------------------------- - * - * This module has been developed by the Automatic Control Group - * of the University of Salerno, Italy. - * - * Title: gravity_compensation_pd_controller.hpp - * Author: Davide Risi - * Org.: UNISA - * Date: Sept 4, 2025 - * - * This module implements a PD controller with gravity compensation. - * - * ------------------------------------------------------------------- - */ +// Copyright (c) 2025, University of Salerno, Automatic Control Group +// +// 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. +// +// Authors: Davide Risi #ifndef GRAVITY_COMPENSATION_PD_CONTROLLER__GRAVITY_COMPENSATION_PD_CONTROLLER_HPP_ #define GRAVITY_COMPENSATION_PD_CONTROLLER__GRAVITY_COMPENSATION_PD_CONTROLLER_HPP_ +#include "gravity_compensation_pd_controller/gravity_compensation_pd_controller_parameters.hpp" + +#include + #include +#include +#include +#include +#include #include #include #include #include -#include -#include -#include -#include "gravity_compensation_pd_controller/gravity_compensation_pd_controller_parameters.hpp" namespace gravity_compensation_pd_controller { @@ -41,13 +46,13 @@ struct RobotJointState * @brief A class representing a PD controller with gravity compensation. * * This class implements the \c controller_interface::ChainableControllerInterface interface. - * All of the public methods override the corresponding methods of the \c controller_interface::ChainableControllerInterface class. - * Please refer to the documentation of the base class for more details. + * All of the public methods override the corresponding methods of the \c + * controller_interface::ChainableControllerInterface class. Please refer to the documentation of + * the base class for more details. */ class GravityCompensationPDController : public controller_interface::ChainableControllerInterface { public: - GravityCompensationPDController(); controller_interface::CallbackReturn on_init() override; @@ -56,27 +61,36 @@ class GravityCompensationPDController : public controller_interface::ChainableCo controller_interface::InterfaceConfiguration state_interface_configuration() const override; - controller_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) override; + controller_interface::CallbackReturn on_configure( + const rclcpp_lifecycle::State & previous_state) override; - controller_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override; + controller_interface::CallbackReturn on_activate( + const rclcpp_lifecycle::State & previous_state) override; - controller_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override; + controller_interface::CallbackReturn on_deactivate( + const rclcpp_lifecycle::State & previous_state) override; - controller_interface::CallbackReturn on_error(const rclcpp_lifecycle::State& previous_state) override; + controller_interface::CallbackReturn on_error( + const rclcpp_lifecycle::State & previous_state) override; protected: - // The following methods are overridden from the base class. Refer to the base class documentation for details. + // The following methods are overridden from the base class. Refer to the base class documentation + // for details. std::vector on_export_reference_interfaces() override; - controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time& time, const rclcpp::Duration& period) override; + controller_interface::return_type update_reference_from_subscribers( + const rclcpp::Time & time, const rclcpp::Duration & period) override; bool on_set_chained_mode(bool chained_mode) override; - controller_interface::return_type update_and_write_commands(const rclcpp::Time& time, const rclcpp::Duration& period) override; + controller_interface::return_type update_and_write_commands( + const rclcpp::Time & time, const rclcpp::Duration & period) override; /** - * @brief Computes the joint effort command using a PD control law with optional gravity compensation. + * @brief Computes the joint effort command using a PD control law with optional gravity + * compensation. * - * This method calculates the joint effort command according to the control law described in the README file. - * If \c compensate_gravity parameter is disabled, the control law reduces to a standard PD controller. - * The resulting effort command is stored in the \c joint_command_ attribute. + * This method calculates the joint effort command according to the control law described in the + * README file. If \c compensate_gravity parameter is disabled, the control law reduces to a + * standard PD controller. The resulting effort command is stored in the \c joint_command_ + * attribute. */ void compute_control_law_(); @@ -124,7 +138,8 @@ class GravityCompensationPDController : public controller_interface::ChainableCo std::vector joint_command_, joint_reference_, last_joint_reference_; /** - * @brief Shared pointer to the parameter listener responsible for handling the controller's parameters. + * @brief Shared pointer to the parameter listener responsible for handling the controller's + * parameters. */ std::shared_ptr parameter_handler_; @@ -134,7 +149,8 @@ class GravityCompensationPDController : public controller_interface::ChainableCo Eigen::VectorXd torque_limits_; /** - * @brief Eigen vector to store the position error between the reference and current joint positions. + * @brief Eigen vector to store the position error between the reference and current joint + * positions. */ Eigen::VectorXd position_error_; @@ -154,20 +170,20 @@ class GravityCompensationPDController : public controller_interface::ChainableCo Eigen::DiagonalMatrix Kd_; /** - * @brief Constant to store the duration of the throttle interval as an integral value in milliseconds. + * @brief Constant to store the duration of the throttle interval as an integral value in + * milliseconds. */ - static constexpr unsigned short DURATION_MS_{ 1000 }; + static constexpr int DURATION_MS_{1000}; /** * @brief Number of joints to control. */ - std::size_t num_joints_{ 0 }; + std::size_t num_joints_{0}; /** * @brief Internal variable to store the current joint state of the robot. */ RobotJointState robot_joint_state_; - }; } // namespace gravity_compensation_pd_controller diff --git a/gravity_compensation_pd_controller/package.xml b/gravity_compensation_pd_controller/package.xml index 678071d438..d37dc6f867 100644 --- a/gravity_compensation_pd_controller/package.xml +++ b/gravity_compensation_pd_controller/package.xml @@ -6,7 +6,7 @@ A ROS2 package implementing a PD controller with gravity compensation Davide Risi Enrico Ferrentino - BSD + Apache License 2.0 ament_cmake diff --git a/gravity_compensation_pd_controller/src/gravity_compensation_pd_controller.cpp b/gravity_compensation_pd_controller/src/gravity_compensation_pd_controller.cpp index d59df15b0e..3cd78ebcad 100644 --- a/gravity_compensation_pd_controller/src/gravity_compensation_pd_controller.cpp +++ b/gravity_compensation_pd_controller/src/gravity_compensation_pd_controller.cpp @@ -1,42 +1,47 @@ -/* ------------------------------------------------------------------- - * - * This module has been developed by the Automatic Control Group - * of the University of Salerno, Italy. - * - * Title: gravity_compensation_pd_controller.cpp - * Author: Davide Risi - * Org.: UNISA - * Date: Sept 4, 2025 - * - * Refer to the header file for a description of this module. - * - * ------------------------------------------------------------------- - */ +// Copyright (c) 2025, University of Salerno, Automatic Control Group +// +// 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. +// +// Authors: Davide Risi + +#include "gravity_compensation_pd_controller/gravity_compensation_pd_controller.hpp" #include // URDF #include -#include "gravity_compensation_pd_controller/gravity_compensation_pd_controller.hpp" - namespace gravity_compensation_pd_controller { GravityCompensationPDController::GravityCompensationPDController() - : controller_interface::ChainableControllerInterface() - , dynamics_solver_loader_("inverse_dynamics_solver", "inverse_dynamics_solver::InverseDynamicsSolver") - , dynamics_solver_(nullptr) -{} +: controller_interface::ChainableControllerInterface(), + dynamics_solver_loader_( + "inverse_dynamics_solver", "inverse_dynamics_solver::InverseDynamicsSolver"), + dynamics_solver_(nullptr) +{ +} controller_interface::CallbackReturn GravityCompensationPDController::on_init() { try { - parameter_handler_ = std::make_shared(get_node()); + parameter_handler_ = + std::make_shared(get_node()); } - catch (const std::exception& e) + catch (const std::exception & e) { - RCLCPP_ERROR(get_node()->get_logger(), "Exception thrown during init stage with message: %s \n", e.what()); + RCLCPP_ERROR( + get_node()->get_logger(), "Exception thrown during init stage with message: %s \n", e.what()); return controller_interface::CallbackReturn::ERROR; } @@ -64,7 +69,8 @@ controller_interface::CallbackReturn GravityCompensationPDController::on_init() return controller_interface::CallbackReturn::SUCCESS; } -controller_interface::InterfaceConfiguration GravityCompensationPDController::command_interface_configuration() const +controller_interface::InterfaceConfiguration +GravityCompensationPDController::command_interface_configuration() const { const auto params = parameter_handler_->get_params(); controller_interface::InterfaceConfiguration command_interfaces_config; @@ -89,7 +95,8 @@ controller_interface::InterfaceConfiguration GravityCompensationPDController::co return command_interfaces_config; } -controller_interface::InterfaceConfiguration GravityCompensationPDController::state_interface_configuration() const +controller_interface::InterfaceConfiguration +GravityCompensationPDController::state_interface_configuration() const { const auto params = parameter_handler_->get_params(); controller_interface::InterfaceConfiguration state_interfaces_config; @@ -100,8 +107,7 @@ controller_interface::InterfaceConfiguration GravityCompensationPDController::st if (params.state_interfaces_names_override.position.size() == num_joints_) { state_interfaces_config.names.insert( - state_interfaces_config.names.end(), - params.state_interfaces_names_override.position.begin(), + state_interfaces_config.names.end(), params.state_interfaces_names_override.position.begin(), params.state_interfaces_names_override.position.end()); } else @@ -115,8 +121,7 @@ controller_interface::InterfaceConfiguration GravityCompensationPDController::st if (params.state_interfaces_names_override.velocity.size() == num_joints_) { state_interfaces_config.names.insert( - state_interfaces_config.names.end(), - params.state_interfaces_names_override.velocity.begin(), + state_interfaces_config.names.end(), params.state_interfaces_names_override.velocity.begin(), params.state_interfaces_names_override.velocity.end()); } else @@ -129,7 +134,8 @@ controller_interface::InterfaceConfiguration GravityCompensationPDController::st return state_interfaces_config; } -std::vector GravityCompensationPDController::on_export_reference_interfaces() +std::vector +GravityCompensationPDController::on_export_reference_interfaces() { const auto params = parameter_handler_->get_params(); ChainableControllerInterface::reference_interfaces_.assign( @@ -142,30 +148,35 @@ std::vector GravityCompensationPDControlle { reference_interfaces.emplace_back( hardware_interface::CommandInterface( - std::string(get_node()->get_name()) + "/" + params.joints[i], - "position", + std::string(get_node()->get_name()) + "/" + params.joints[i], "position", &ChainableControllerInterface::reference_interfaces_[i])); } return reference_interfaces; } - -controller_interface::CallbackReturn GravityCompensationPDController::on_error(const rclcpp_lifecycle::State& /*previous_state*/) +controller_interface::CallbackReturn GravityCompensationPDController::on_error( + const rclcpp_lifecycle::State & /*previous_state*/) { - // Set the command to NaN values, to notify the hardware that the controller is unable to provide valid commands + // Set the command to NaN values, to notify the hardware that the controller is unable to provide + // valid commands std::fill(joint_command_.begin(), joint_command_.end(), std::numeric_limits::quiet_NaN()); if (!write_command_interfaces_()) { - RCLCPP_ERROR(get_node()->get_logger(), "Failed to write NaN values to command interfaces while in error state."); + RCLCPP_ERROR( + get_node()->get_logger(), + "Failed to write NaN values to command interfaces while in error state."); return controller_interface::CallbackReturn::ERROR; } - RCLCPP_ERROR(get_node()->get_logger(), - "Controller is in error state. Writing NaN values to command interfaces. Restart the controller to recover."); + RCLCPP_ERROR( + get_node()->get_logger(), + "Controller is in error state. Writing NaN values to command interfaces. Restart the " + "controller to recover."); return controller_interface::CallbackReturn::SUCCESS; } -controller_interface::CallbackReturn GravityCompensationPDController::on_configure(const rclcpp_lifecycle::State& /*previous_state*/) +controller_interface::CallbackReturn GravityCompensationPDController::on_configure( + const rclcpp_lifecycle::State & /*previous_state*/) { gravity_compensation_pd_controller::Params params = parameter_handler_->get_params(); @@ -173,12 +184,14 @@ controller_interface::CallbackReturn GravityCompensationPDController::on_configu { try { - dynamics_solver_ = dynamics_solver_loader_.createSharedInstance(params.dynamics_solver.dynamics_solver_plugin); + dynamics_solver_ = + dynamics_solver_loader_.createSharedInstance(params.dynamics_solver.dynamics_solver_plugin); } - catch (pluginlib::PluginlibException& ex) + catch (pluginlib::PluginlibException & ex) { - RCLCPP_ERROR(get_node()->get_logger(), "Exception while loading the dynamics solver plugin '%s': '%s'", - params.dynamics_solver.dynamics_solver_plugin.c_str(), ex.what()); + RCLCPP_ERROR( + get_node()->get_logger(), "Exception while loading the dynamics solver plugin '%s': '%s'", + params.dynamics_solver.dynamics_solver_plugin.c_str(), ex.what()); return controller_interface::CallbackReturn::ERROR; } } @@ -191,10 +204,12 @@ controller_interface::CallbackReturn GravityCompensationPDController::on_configu { dynamics_solver_->initialize(get_node()->get_node_parameters_interface(), "dynamics_solver"); } - catch (const std::exception& e) + catch (const std::exception & e) { - RCLCPP_ERROR(get_node()->get_logger(), "Exception while initializing the dynamics solver plugin '%s': '%s'", - params.dynamics_solver.dynamics_solver_plugin.c_str(), e.what()); + RCLCPP_ERROR( + get_node()->get_logger(), + "Exception while initializing the dynamics solver plugin '%s': '%s'", + params.dynamics_solver.dynamics_solver_plugin.c_str(), e.what()); return controller_interface::CallbackReturn::ERROR; } @@ -210,11 +225,11 @@ controller_interface::CallbackReturn GravityCompensationPDController::on_configu return controller_interface::CallbackReturn::SUCCESS; } -controller_interface::CallbackReturn GravityCompensationPDController::on_activate(const rclcpp_lifecycle::State& /*previous_state*/) +controller_interface::CallbackReturn GravityCompensationPDController::on_activate( + const rclcpp_lifecycle::State & /*previous_state*/) { - // Read the current state of the robot from the hardware - if(!read_state_interfaces_()) + if (!read_state_interfaces_()) { RCLCPP_ERROR(get_node()->get_logger(), "Failed to read joint positions from the hardware.\n"); return controller_interface::CallbackReturn::ERROR; @@ -228,17 +243,18 @@ controller_interface::CallbackReturn GravityCompensationPDController::on_activat return controller_interface::CallbackReturn::SUCCESS; } -controller_interface::return_type GravityCompensationPDController::update_reference_from_subscribers(const rclcpp::Time& /*time*/, - const rclcpp::Duration& /*period*/) +controller_interface::return_type +GravityCompensationPDController::update_reference_from_subscribers( + const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) { return controller_interface::return_type::OK; } -controller_interface::return_type GravityCompensationPDController::update_and_write_commands(const rclcpp::Time& /*time*/, - const rclcpp::Duration& /*period*/) +controller_interface::return_type GravityCompensationPDController::update_and_write_commands( + const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) { // Read the current state of the robot from the hardware - if(!read_state_interfaces_()) + if (!read_state_interfaces_()) { RCLCPP_ERROR(get_node()->get_logger(), "Failed to read joint states from the hardware.\n"); return controller_interface::return_type::ERROR; @@ -247,8 +263,9 @@ controller_interface::return_type GravityCompensationPDController::update_and_wr // Read the reference from the reference interfaces if (!read_reference_interfaces_()) { - RCLCPP_WARN_THROTTLE(get_node()->get_logger(), *get_node()->get_clock(), DURATION_MS_, - "Received NaN values in joint reference positions. Using last valid reference instead."); + RCLCPP_WARN_THROTTLE( + get_node()->get_logger(), *get_node()->get_clock(), DURATION_MS_, + "Received NaN values in joint reference positions. Using last valid reference instead."); // If NaN values are detected in the joint reference positions, use the last valid reference joint_reference_ = last_joint_reference_; } @@ -268,21 +285,21 @@ controller_interface::return_type GravityCompensationPDController::update_and_wr return controller_interface::return_type::OK; } -controller_interface::CallbackReturn GravityCompensationPDController::on_deactivate(const rclcpp_lifecycle::State& /*previous_state*/) +controller_interface::CallbackReturn GravityCompensationPDController::on_deactivate( + const rclcpp_lifecycle::State & /*previous_state*/) { release_interfaces(); return controller_interface::CallbackReturn::SUCCESS; } -bool GravityCompensationPDController::on_set_chained_mode(bool /* chained_mode */) -{ - return true; -} +bool GravityCompensationPDController::on_set_chained_mode(bool /* chained_mode */) { return true; } void GravityCompensationPDController::compute_control_law_() { - Eigen::VectorXd current_positions = Eigen::Map(robot_joint_state_.positions.data(), robot_joint_state_.positions.size()); - Eigen::VectorXd current_velocities = Eigen::Map(robot_joint_state_.velocities.data(), robot_joint_state_.velocities.size()); + Eigen::VectorXd current_positions = Eigen::Map( + robot_joint_state_.positions.data(), robot_joint_state_.positions.size()); + Eigen::VectorXd current_velocities = Eigen::Map( + robot_joint_state_.velocities.data(), robot_joint_state_.velocities.size()); for (std::size_t i = 0; i < num_joints_; i++) { @@ -299,7 +316,9 @@ void GravityCompensationPDController::compute_control_law_() // Apply torque limits using Eigen eigen_effort_command_ = eigen_effort_command_.cwiseMax(-torque_limits_).cwiseMin(torque_limits_); - std::copy(eigen_effort_command_.data(), eigen_effort_command_.data() + num_joints_, joint_command_.begin()); + std::copy( + eigen_effort_command_.data(), eigen_effort_command_.data() + num_joints_, + joint_command_.begin()); } bool GravityCompensationPDController::read_state_interfaces_() @@ -307,8 +326,10 @@ bool GravityCompensationPDController::read_state_interfaces_() bool all_read{true}; for (std::size_t i = 0; i < num_joints_; i++) { - std::optional state_position_op = ControllerInterfaceBase::state_interfaces_[i].get_optional(); - std::optional state_velocity_op = ControllerInterfaceBase::state_interfaces_[i + num_joints_].get_optional(); + std::optional state_position_op = + ControllerInterfaceBase::state_interfaces_[i].get_optional(); + std::optional state_velocity_op = + ControllerInterfaceBase::state_interfaces_[i + num_joints_].get_optional(); if (!state_position_op.has_value() || !state_velocity_op.has_value()) { @@ -335,7 +356,7 @@ bool GravityCompensationPDController::read_reference_interfaces_() bool all_read{true}; for (std::size_t i = 0; i < num_joints_; i++) { - if(std::isnan(ChainableControllerInterface::reference_interfaces_[i])) + if (std::isnan(ChainableControllerInterface::reference_interfaces_[i])) { all_read = false; } @@ -347,8 +368,8 @@ bool GravityCompensationPDController::read_reference_interfaces_() bool GravityCompensationPDController::read_joint_effort_limits_from_urdf() { torque_limits_.resize(num_joints_); - const std::string& robot_description = get_robot_description(); - const std::vector& joint_names = parameter_handler_->get_params().joints; + const std::string & robot_description = get_robot_description(); + const std::vector & joint_names = parameter_handler_->get_params().joints; if (robot_description.empty()) { @@ -363,16 +384,15 @@ bool GravityCompensationPDController::read_joint_effort_limits_from_urdf() return false; } - std::size_t num_joints{ joint_names.size() }; + std::size_t num_joints{joint_names.size()}; std::vector joints_without_limits; for (std::size_t i = 0; i < num_joints; ++i) { - const std::string& joint_name{ joint_names[i] }; - urdf::JointConstSharedPtr joint{ robot_model.getJoint(joint_name) }; + const std::string & joint_name{joint_names[i]}; + urdf::JointConstSharedPtr joint{robot_model.getJoint(joint_name)}; - if (!joint) - return false; + if (!joint) return false; if (joint->limits) { @@ -380,7 +400,10 @@ bool GravityCompensationPDController::read_joint_effort_limits_from_urdf() } else { - RCLCPP_WARN(get_node()->get_logger(), "Joint '%s' does not have effort limits specified in the URDF. Setting to infinity.", joint_name.c_str()); + RCLCPP_WARN( + get_node()->get_logger(), + "Joint '%s' does not have effort limits specified in the URDF. Setting to infinity.", + joint_name.c_str()); torque_limits_[i] = std::numeric_limits::max(); } } @@ -390,4 +413,6 @@ bool GravityCompensationPDController::read_joint_effort_limits_from_urdf() } // namespace gravity_compensation_pd_controller -PLUGINLIB_EXPORT_CLASS(gravity_compensation_pd_controller::GravityCompensationPDController, controller_interface::ChainableControllerInterface) +PLUGINLIB_EXPORT_CLASS( + gravity_compensation_pd_controller::GravityCompensationPDController, + controller_interface::ChainableControllerInterface) From 3b7d91d7819efdb86c64bfb84e64f489e220bc3e Mon Sep 17 00:00:00 2001 From: Davide Risi Date: Mon, 29 Sep 2025 15:46:55 +0200 Subject: [PATCH 4/9] [ADD] Add tests for gravity compensation PD controller - [ADD] Update CMakeLists.txt and package.xml for testing dependencies --- .../CMakeLists.txt | 28 ++- ...y_compensation_pd_controller_parameters.md | 9 - .../package.xml | 6 + ...st_gravity_compensation_pd_controller.yaml | 16 ++ .../test/test_asset_robot_description.hpp | 130 +++++++++++++ ...est_gravity_compensation_pd_controller.cpp | 171 ++++++++++++++++++ ...est_gravity_compensation_pd_controller.hpp | 66 +++++++ ...oad_gravity_compensation_pd_controller.cpp | 59 ++++++ 8 files changed, 471 insertions(+), 14 deletions(-) create mode 100644 gravity_compensation_pd_controller/test/config/test_gravity_compensation_pd_controller.yaml create mode 100644 gravity_compensation_pd_controller/test/test_asset_robot_description.hpp create mode 100644 gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp create mode 100644 gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.hpp create mode 100644 gravity_compensation_pd_controller/test/test_load_gravity_compensation_pd_controller.cpp diff --git a/gravity_compensation_pd_controller/CMakeLists.txt b/gravity_compensation_pd_controller/CMakeLists.txt index 3bed7e8fad..bbb9548498 100644 --- a/gravity_compensation_pd_controller/CMakeLists.txt +++ b/gravity_compensation_pd_controller/CMakeLists.txt @@ -1,7 +1,5 @@ -cmake_minimum_required(VERSION 3.8) -project(gravity_compensation_pd_controller - LANGUAGES CXX -) +cmake_minimum_required(VERSION 3.16) +project(gravity_compensation_pd_controller) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID @@ -96,7 +94,27 @@ install(TARGETS gravity_compensation_pd_controller gravity_compensation_pd_contr LIBRARY DESTINATION lib ) +if(BUILD_TESTING) + find_package(ament_cmake_gmock REQUIRED) + find_package(controller_manager REQUIRED) + find_package(ros2_control_test_assets REQUIRED) + + ament_add_gmock(test_gravity_compensation_pd_controller + test/test_gravity_compensation_pd_controller.cpp + ) + target_link_libraries(test_gravity_compensation_pd_controller + gravity_compensation_pd_controller + ros2_control_test_assets::ros2_control_test_assets + ) + + add_definitions(-DTEST_FILES_DIRECTORY="${CMAKE_CURRENT_SOURCE_DIR}/test") + ament_add_gmock(test_load_gravity_compensation_pd_controller test/test_load_gravity_compensation_pd_controller.cpp) + target_link_libraries(test_load_gravity_compensation_pd_controller + controller_manager::controller_manager + ros2_control_test_assets::ros2_control_test_assets + ) +endif() + ament_export_targets(export_gravity_compensation_pd_controller HAS_LIBRARY_TARGET) ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS}) - ament_package() diff --git a/gravity_compensation_pd_controller/doc/gravity_compensation_pd_controller_parameters.md b/gravity_compensation_pd_controller/doc/gravity_compensation_pd_controller_parameters.md index e5d426bffb..d4150c0123 100644 --- a/gravity_compensation_pd_controller/doc/gravity_compensation_pd_controller_parameters.md +++ b/gravity_compensation_pd_controller/doc/gravity_compensation_pd_controller_parameters.md @@ -15,7 +15,6 @@ gravity_compensation_pd_controller: joint_space_reference_controller: '' joints: '{}' p_gains: '{}' - robot_name: '' state_interfaces_names_override: position: '{}' velocity: '{}' @@ -29,14 +28,6 @@ Specifies which joints will be used by the controller. * Type: `string_array` * Default Value: {} -## robot_name - -Name of the robot to control. - -* Type: `string` -* Default Value: "" -* Read only: True - ## joint_space_reference_controller Name of the joint space reference controller. diff --git a/gravity_compensation_pd_controller/package.xml b/gravity_compensation_pd_controller/package.xml index d37dc6f867..df25a5453c 100644 --- a/gravity_compensation_pd_controller/package.xml +++ b/gravity_compensation_pd_controller/package.xml @@ -20,6 +20,12 @@ rclcpp_lifecycle realtime_tools + ament_cmake_gmock + controller_manager + hardware_interface_testing + ros2_control_test_assets + kdl_inverse_dynamics_solver + ament_cmake diff --git a/gravity_compensation_pd_controller/test/config/test_gravity_compensation_pd_controller.yaml b/gravity_compensation_pd_controller/test/config/test_gravity_compensation_pd_controller.yaml new file mode 100644 index 0000000000..938430a61d --- /dev/null +++ b/gravity_compensation_pd_controller/test/config/test_gravity_compensation_pd_controller.yaml @@ -0,0 +1,16 @@ +test_gravity_compensation_pd_controller: + ros__parameters: + joints: + - joint1 + - joint2 + - joint3 + + dynamics_solver: + dynamics_solver_plugin: kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL + tip: tool0 + root: world + + p_gains: [2000.0, 3000.0, 4000.0] + d_gains: [100.0, 100.0, 100.0] + + compensate_gravity: true diff --git a/gravity_compensation_pd_controller/test/test_asset_robot_description.hpp b/gravity_compensation_pd_controller/test/test_asset_robot_description.hpp new file mode 100644 index 0000000000..5438a68302 --- /dev/null +++ b/gravity_compensation_pd_controller/test/test_asset_robot_description.hpp @@ -0,0 +1,130 @@ +// Copyright (c) 2025, University of Salerno, Automatic Control Group +// +// 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. +// +// Authors: Davide Risi + +#ifndef TEST_ASSET_ROBOT_DESCRIPTION_HPP_ +#define TEST_ASSET_ROBOT_DESCRIPTION_HPP_ + +namespace ros2_control_test_assets +{ + +const auto valid_robot_urdf = + R"( + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + mock_components/GenericSystem + false + 0.0 + + + + + 0.0 + + + 0.0 + + + + + + 0.0 + + + 0.0 + + + + + + 0.0 + + + 0.0 + + + + +)"; + +} // namespace ros2_control_test_assets + +#endif // TEST_ASSET_ROBOT_DESCRIPTION_HPP_ diff --git a/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp new file mode 100644 index 0000000000..0a96620faf --- /dev/null +++ b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp @@ -0,0 +1,171 @@ +// Copyright (c) 2025, University of Salerno, Automatic Control Group +// +// 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. +// +// Authors: Davide Risi + +#include +#include +#include +#include + +#include "hardware_interface/loaned_command_interface.hpp" +#include "lifecycle_msgs/msg/state.hpp" +#include "rclcpp/utilities.hpp" +#include "test_gravity_compensation_pd_controller.hpp" + +#include "test_asset_robot_description.hpp" + +using CallbackReturn = controller_interface::CallbackReturn; +using hardware_interface::LoanedCommandInterface; + +void GravityCompensationPDControllerTest::SetUpTestCase() { rclcpp::init(0, nullptr); } + +void GravityCompensationPDControllerTest::TearDownTestCase() { rclcpp::shutdown(); } + +void GravityCompensationPDControllerTest::SetUp() +{ + controller_ = std::make_unique(); +} + +void GravityCompensationPDControllerTest::TearDown() +{ + controller_.reset(nullptr); + command_interfaces_.clear(); + state_interfaces_.clear(); +} + +void GravityCompensationPDControllerTest::assign_interfaces() +{ + std::vector command_ifs; + command_ifs.reserve(joint_command_values_.size()); + + for (auto i = 0u; i < joint_command_values_.size(); ++i) + { + auto cmd_interface = std::make_unique( + joint_names_[i], "effort", &joint_command_values_[i]); + command_ifs.emplace_back(*cmd_interface); + command_interfaces_.push_back(std::move(cmd_interface)); + } + + std::vector state_ifs; + + // Create position state interfaces + for (auto i = 0u; i < joint_position_values_.size(); ++i) + { + auto state_interface = std::make_unique( + joint_names_[i], "position", &joint_position_values_[i]); + state_ifs.emplace_back(*state_interface); + state_interfaces_.push_back(std::move(state_interface)); + } + + // Create velocity state interfaces + for (auto i = 0u; i < joint_velocity_values_.size(); ++i) + { + auto state_interface = std::make_unique( + joint_names_[i], "velocity", &joint_velocity_values_[i]); + state_ifs.emplace_back(*state_interface); + state_interfaces_.push_back(std::move(state_interface)); + } + + controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs)); +} + +void GravityCompensationPDControllerTest::SetUpController( + const std::vector & parameters) +{ + auto node_options = controller_->define_custom_node_options(); + node_options.parameter_overrides(parameters); + + const std::string robot_description = ros2_control_test_assets::valid_robot_urdf; + const auto result = controller_->init( + "test_gravity_compensation_pd_controller", robot_description, 0, "", node_options); + ASSERT_EQ(result, controller_interface::return_type::OK); + + assign_interfaces(); + executor_.add_node(controller_->get_node()->get_node_base_interface()); +} +TEST_F(GravityCompensationPDControllerTest, ConfigureAndActivateParamsSuccess) +{ + SetUpController( + {rclcpp::Parameter("joints", joint_names_), + rclcpp::Parameter("p_gains", std::vector{1000.0, 1000.0, 1000.0}), + rclcpp::Parameter("d_gains", std::vector{50.0, 50.0, 50.0}), + rclcpp::Parameter("compensate_gravity", false), + rclcpp::Parameter( + "dynamics_solver.dynamics_solver_plugin", + std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), + rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), + rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}); + + // configure successful + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); + ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); +} + +TEST_F(GravityCompensationPDControllerTest, NoCommandCheckTest) +{ + SetUpController( + {rclcpp::Parameter("joints", joint_names_), + rclcpp::Parameter("p_gains", std::vector{1000.0, 1000.0, 1000.0}), + rclcpp::Parameter("d_gains", std::vector{50.0, 50.0, 50.0}), + rclcpp::Parameter("compensate_gravity", false), + rclcpp::Parameter( + "dynamics_solver.dynamics_solver_plugin", + std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), + rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), + rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}); + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); + + controller_->on_export_reference_interfaces(); + + // update successful, no command received yet + ASSERT_EQ( + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), + controller_interface::return_type::OK); + + // check joint commands are still the default ones + EXPECT_NEAR(joint_command_values_[0], 0.0, 1e-6); + EXPECT_NEAR(joint_command_values_[1], 0.0, 1e-6); + EXPECT_NEAR(joint_command_values_[2], 0.0, 1e-6); +} + +TEST_F(GravityCompensationPDControllerTest, StopJointsOnDeactivateTest) +{ + SetUpController( + {rclcpp::Parameter("joints", joint_names_), + rclcpp::Parameter("p_gains", std::vector{1000.0, 1000.0, 1000.0}), + rclcpp::Parameter("d_gains", std::vector{50.0, 50.0, 50.0}), + rclcpp::Parameter("compensate_gravity", false), + rclcpp::Parameter( + "dynamics_solver.dynamics_solver_plugin", + std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), + rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), + rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}); + + // configure successful + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); + + // check joint commands are still the default ones + EXPECT_NEAR(joint_command_values_[0], 0.0, 1e-6); + EXPECT_NEAR(joint_command_values_[1], 0.0, 1e-6); + EXPECT_NEAR(joint_command_values_[2], 0.0, 1e-6); + + // stop the controller + ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); + + // check joint commands are now zero + EXPECT_NEAR(joint_command_values_[0], 0.0, 1e-6); + EXPECT_NEAR(joint_command_values_[1], 0.0, 1e-6); + EXPECT_NEAR(joint_command_values_[2], 0.0, 1e-6); +} diff --git a/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.hpp b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.hpp new file mode 100644 index 0000000000..c911d5b902 --- /dev/null +++ b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.hpp @@ -0,0 +1,66 @@ +// Copyright (c) 2025, University of Salerno, Automatic Control Group +// +// 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. +// +// Authors: Davide Risi + +#ifndef TEST_GRAVITY_COMPENSATION_PD_CONTROLLER_HPP_ +#define TEST_GRAVITY_COMPENSATION_PD_CONTROLLER_HPP_ + +#include + +#include +#include +#include + +#include "gravity_compensation_pd_controller/gravity_compensation_pd_controller.hpp" +#include "hardware_interface/handle.hpp" +#include "hardware_interface/types/hardware_interface_type_values.hpp" +#include "rclcpp/executors/single_threaded_executor.hpp" + +// Create a friend class to access private and protected members for testing +class FriendGravityCompensationPDController +: public gravity_compensation_pd_controller::GravityCompensationPDController +{ + FRIEND_TEST(GravityCompensationPDControllerTest, StopJointsOnDeactivateTest); + FRIEND_TEST(GravityCompensationPDControllerTest, ConfigureAndActivateParamsSuccess); + FRIEND_TEST(GravityCompensationPDControllerTest, NoCommandCheckTest); +}; + +class GravityCompensationPDControllerTest : public ::testing::Test +{ +public: + static void SetUpTestCase(); + static void TearDownTestCase(); + + void SetUp(); + void TearDown(); + + void SetUpController(const std::vector & parameters = {}); + void assign_interfaces(); + +protected: + std::unique_ptr controller_; + const std::vector joint_names_ = {"joint1", "joint2", "joint3"}; + std::vector joint_command_values_ = {0.0, 0.0, 0.0}; + std::vector joint_position_values_ = {0.0, 0.0, 0.0}; + std::vector joint_velocity_values_ = {0.0, 0.0, 0.0}; + + // Store the interfaces to keep them alive + std::vector> command_interfaces_; + std::vector> state_interfaces_; + + rclcpp::executors::SingleThreadedExecutor executor_; +}; + +#endif // TEST_GRAVITY_COMPENSATION_PD_CONTROLLER_HPP_ diff --git a/gravity_compensation_pd_controller/test/test_load_gravity_compensation_pd_controller.cpp b/gravity_compensation_pd_controller/test/test_load_gravity_compensation_pd_controller.cpp new file mode 100644 index 0000000000..2d550f0b8b --- /dev/null +++ b/gravity_compensation_pd_controller/test/test_load_gravity_compensation_pd_controller.cpp @@ -0,0 +1,59 @@ +// Copyright (c) 2025, University of Salerno, Automatic Control Group +// +// 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. +// +// Authors: Davide Risi + +#include +#include + +#include "controller_manager/controller_manager.hpp" +#include "hardware_interface/resource_manager.hpp" +#include "rclcpp/executor.hpp" +#include "rclcpp/executors/single_threaded_executor.hpp" +#include "rclcpp/utilities.hpp" + +#include "test_asset_robot_description.hpp" + +TEST(TestLoadGravityCompensationPDController, load_controller) +{ + std::shared_ptr executor = + std::make_shared(); + + // auto robot_description = std::string(ros2_control_test_assets::urdf_head) + + // std::string(ros2_control_test_assets::hardware_resources_with_exclusive_interface) + + // std::string(ros2_control_test_assets::urdf_tail); + + const std::string robot_description = ros2_control_test_assets::valid_robot_urdf; + + controller_manager::ControllerManager cm( + executor, robot_description, true, "test_controller_manager"); + const std::string test_file_path = + std::string(TEST_FILES_DIRECTORY) + "/config/test_gravity_compensation_pd_controller.yaml"; + + cm.set_parameter({"test_gravity_compensation_pd_controller.params_file", test_file_path}); + cm.set_parameter( + {"test_gravity_compensation_pd_controller.type", + "gravity_compensation_pd_controller/GravityCompensationPDController"}); + + ASSERT_NE(cm.load_controller("test_gravity_compensation_pd_controller"), nullptr); +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + rclcpp::init(argc, argv); + int result = RUN_ALL_TESTS(); + rclcpp::shutdown(); + return result; +} From df9caa74f509c38b11660e19dca83f8722ec83ae Mon Sep 17 00:00:00 2001 From: Davide Risi Date: Mon, 29 Sep 2025 16:23:02 +0200 Subject: [PATCH 5/9] [REF] Refactor GravityCompensationPDController tests for clarity --- ...est_gravity_compensation_pd_controller.cpp | 52 ++++++------------- ...est_gravity_compensation_pd_controller.hpp | 4 +- ...oad_gravity_compensation_pd_controller.cpp | 8 +-- 3 files changed, 20 insertions(+), 44 deletions(-) diff --git a/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp index 0a96620faf..26eb988971 100644 --- a/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp +++ b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp @@ -36,6 +36,17 @@ void GravityCompensationPDControllerTest::TearDownTestCase() { rclcpp::shutdown( void GravityCompensationPDControllerTest::SetUp() { controller_ = std::make_unique(); + std::vector default_parameters = { + rclcpp::Parameter("joints", joint_names_), + rclcpp::Parameter("p_gains", std::vector{100.0, 100.0, 100.0}), + rclcpp::Parameter("d_gains", std::vector{5.0, 5.0, 5.0}), + rclcpp::Parameter("compensate_gravity", false), + rclcpp::Parameter( + "dynamics_solver.dynamics_solver_plugin", + std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), + rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), + rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}; + SetUpController(default_parameters); } void GravityCompensationPDControllerTest::TearDown() @@ -45,7 +56,7 @@ void GravityCompensationPDControllerTest::TearDown() state_interfaces_.clear(); } -void GravityCompensationPDControllerTest::assign_interfaces() +void GravityCompensationPDControllerTest::assign_interfaces_() { std::vector command_ifs; command_ifs.reserve(joint_command_values_.size()); @@ -87,27 +98,17 @@ void GravityCompensationPDControllerTest::SetUpController( auto node_options = controller_->define_custom_node_options(); node_options.parameter_overrides(parameters); - const std::string robot_description = ros2_control_test_assets::valid_robot_urdf; const auto result = controller_->init( - "test_gravity_compensation_pd_controller", robot_description, 0, "", node_options); + "test_gravity_compensation_pd_controller", ros2_control_test_assets::valid_robot_urdf, 0, "", + node_options); ASSERT_EQ(result, controller_interface::return_type::OK); - assign_interfaces(); + assign_interfaces_(); executor_.add_node(controller_->get_node()->get_node_base_interface()); } + TEST_F(GravityCompensationPDControllerTest, ConfigureAndActivateParamsSuccess) { - SetUpController( - {rclcpp::Parameter("joints", joint_names_), - rclcpp::Parameter("p_gains", std::vector{1000.0, 1000.0, 1000.0}), - rclcpp::Parameter("d_gains", std::vector{50.0, 50.0, 50.0}), - rclcpp::Parameter("compensate_gravity", false), - rclcpp::Parameter( - "dynamics_solver.dynamics_solver_plugin", - std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), - rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), - rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}); - // configure successful ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); @@ -115,16 +116,6 @@ TEST_F(GravityCompensationPDControllerTest, ConfigureAndActivateParamsSuccess) TEST_F(GravityCompensationPDControllerTest, NoCommandCheckTest) { - SetUpController( - {rclcpp::Parameter("joints", joint_names_), - rclcpp::Parameter("p_gains", std::vector{1000.0, 1000.0, 1000.0}), - rclcpp::Parameter("d_gains", std::vector{50.0, 50.0, 50.0}), - rclcpp::Parameter("compensate_gravity", false), - rclcpp::Parameter( - "dynamics_solver.dynamics_solver_plugin", - std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), - rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), - rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}); ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); controller_->on_export_reference_interfaces(); @@ -142,17 +133,6 @@ TEST_F(GravityCompensationPDControllerTest, NoCommandCheckTest) TEST_F(GravityCompensationPDControllerTest, StopJointsOnDeactivateTest) { - SetUpController( - {rclcpp::Parameter("joints", joint_names_), - rclcpp::Parameter("p_gains", std::vector{1000.0, 1000.0, 1000.0}), - rclcpp::Parameter("d_gains", std::vector{50.0, 50.0, 50.0}), - rclcpp::Parameter("compensate_gravity", false), - rclcpp::Parameter( - "dynamics_solver.dynamics_solver_plugin", - std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), - rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), - rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}); - // configure successful ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); diff --git a/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.hpp b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.hpp index c911d5b902..968612dc96 100644 --- a/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.hpp +++ b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.hpp @@ -47,7 +47,9 @@ class GravityCompensationPDControllerTest : public ::testing::Test void TearDown(); void SetUpController(const std::vector & parameters = {}); - void assign_interfaces(); + +protected: + void assign_interfaces_(); protected: std::unique_ptr controller_; diff --git a/gravity_compensation_pd_controller/test/test_load_gravity_compensation_pd_controller.cpp b/gravity_compensation_pd_controller/test/test_load_gravity_compensation_pd_controller.cpp index 2d550f0b8b..ee372b8da3 100644 --- a/gravity_compensation_pd_controller/test/test_load_gravity_compensation_pd_controller.cpp +++ b/gravity_compensation_pd_controller/test/test_load_gravity_compensation_pd_controller.cpp @@ -30,14 +30,8 @@ TEST(TestLoadGravityCompensationPDController, load_controller) std::shared_ptr executor = std::make_shared(); - // auto robot_description = std::string(ros2_control_test_assets::urdf_head) + - // std::string(ros2_control_test_assets::hardware_resources_with_exclusive_interface) + - // std::string(ros2_control_test_assets::urdf_tail); - - const std::string robot_description = ros2_control_test_assets::valid_robot_urdf; - controller_manager::ControllerManager cm( - executor, robot_description, true, "test_controller_manager"); + executor, ros2_control_test_assets::valid_robot_urdf, true, "test_controller_manager"); const std::string test_file_path = std::string(TEST_FILES_DIRECTORY) + "/config/test_gravity_compensation_pd_controller.yaml"; From 04c26b63507eb4818ae1c155d01788d3a73cc65a Mon Sep 17 00:00:00 2001 From: Davide Risi Date: Mon, 29 Sep 2025 18:49:16 +0200 Subject: [PATCH 6/9] [TST] Add gravity compensation PD controller tests for parameter validation --- ...est_gravity_compensation_pd_controller.cpp | 136 +++++++++++++++++- ...est_gravity_compensation_pd_controller.hpp | 34 +++-- 2 files changed, 154 insertions(+), 16 deletions(-) diff --git a/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp index 26eb988971..90cc83b504 100644 --- a/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp +++ b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp @@ -21,6 +21,7 @@ #include "hardware_interface/loaned_command_interface.hpp" #include "lifecycle_msgs/msg/state.hpp" +#include "rclcpp/rclcpp.hpp" #include "rclcpp/utilities.hpp" #include "test_gravity_compensation_pd_controller.hpp" @@ -29,10 +30,6 @@ using CallbackReturn = controller_interface::CallbackReturn; using hardware_interface::LoanedCommandInterface; -void GravityCompensationPDControllerTest::SetUpTestCase() { rclcpp::init(0, nullptr); } - -void GravityCompensationPDControllerTest::TearDownTestCase() { rclcpp::shutdown(); } - void GravityCompensationPDControllerTest::SetUp() { controller_ = std::make_unique(); @@ -40,7 +37,7 @@ void GravityCompensationPDControllerTest::SetUp() rclcpp::Parameter("joints", joint_names_), rclcpp::Parameter("p_gains", std::vector{100.0, 100.0, 100.0}), rclcpp::Parameter("d_gains", std::vector{5.0, 5.0, 5.0}), - rclcpp::Parameter("compensate_gravity", false), + rclcpp::Parameter("compensate_gravity", true), rclcpp::Parameter( "dynamics_solver.dynamics_solver_plugin", std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), @@ -56,7 +53,7 @@ void GravityCompensationPDControllerTest::TearDown() state_interfaces_.clear(); } -void GravityCompensationPDControllerTest::assign_interfaces_() +void GravityCompensationPDControllerTestBase::assign_interfaces_() { std::vector command_ifs; command_ifs.reserve(joint_command_values_.size()); @@ -92,7 +89,7 @@ void GravityCompensationPDControllerTest::assign_interfaces_() controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs)); } -void GravityCompensationPDControllerTest::SetUpController( +void GravityCompensationPDControllerTestBase::SetUpController( const std::vector & parameters) { auto node_options = controller_->define_custom_node_options(); @@ -149,3 +146,128 @@ TEST_F(GravityCompensationPDControllerTest, StopJointsOnDeactivateTest) EXPECT_NEAR(joint_command_values_[1], 0.0, 1e-6); EXPECT_NEAR(joint_command_values_[2], 0.0, 1e-6); } + +void GravityCompensationPDControllerInvalidParameterTest::SetUp() +{ + controller_ = std::make_unique(); + // Parameters are set in each test case + const std::vector parameters = WithParamInterface::GetParam(); + SetUpController(parameters); +} + +void GravityCompensationPDControllerInvalidParameterTest::TearDown() +{ + controller_.reset(nullptr); + command_interfaces_.clear(); + state_interfaces_.clear(); +} + +TEST_P(GravityCompensationPDControllerInvalidParameterTest, ConfigureFail) +{ + // configure should fail + ASSERT_EQ(controller_->on_init(), CallbackReturn::SUCCESS); + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::ERROR); +} + +INSTANTIATE_TEST_SUITE_P( + InvalidConfigParameters, GravityCompensationPDControllerInvalidParameterTest, + testing::Values( + // Empty joint names + std::vector{ + rclcpp::Parameter("joints", std::vector{}), + rclcpp::Parameter("p_gains", std::vector{100.0, 100.0, 100.0}), + rclcpp::Parameter("d_gains", std::vector{5.0, 5.0, 5.0}), + rclcpp::Parameter("compensate_gravity", true), + rclcpp::Parameter( + "dynamics_solver.dynamics_solver_plugin", + std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), + rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), + rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}, + + // Mismatched p_gains size + std::vector{ + rclcpp::Parameter("joints", std::vector{"joint1", "joint2", "joint3"}), + rclcpp::Parameter("p_gains", std::vector{100.0, 100.0}), + rclcpp::Parameter("d_gains", std::vector{5.0, 5.0, 5.0}), + rclcpp::Parameter("compensate_gravity", true), + rclcpp::Parameter( + "dynamics_solver.dynamics_solver_plugin", + std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), + rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), + rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}, + + // Mismatched d_gains size + std::vector{ + rclcpp::Parameter("joints", std::vector{"joint1", "joint2", "joint3"}), + rclcpp::Parameter("p_gains", std::vector{100.0, 100.0, 100.0}), + rclcpp::Parameter("d_gains", std::vector{5.0, 5.0}), + rclcpp::Parameter("compensate_gravity", true), + rclcpp::Parameter( + "dynamics_solver.dynamics_solver_plugin", + std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), + rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), + rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))})); + +void GravityCompensationPDControllerMissingParameterTest::SetUp() +{ + controller_ = std::make_unique(); + // Parameters are set in each test case + const std::vector parameters = WithParamInterface::GetParam(); + auto node_options = controller_->define_custom_node_options(); + node_options.parameter_overrides(parameters); + + controller_->init( + "test_gravity_compensation_pd_controller", ros2_control_test_assets::valid_robot_urdf, 0, "", + node_options); + + executor_.add_node(controller_->get_node()->get_node_base_interface()); +} + +TEST_P(GravityCompensationPDControllerMissingParameterTest, InitFail) +{ + // init should fail + ASSERT_EQ(controller_->on_init(), CallbackReturn::ERROR); +} + +INSTANTIATE_TEST_SUITE_P( + InvalidInitParameters, GravityCompensationPDControllerMissingParameterTest, + testing::Values( + // Missing dynamics solver plugin + std::vector{ + rclcpp::Parameter("joints", std::vector{"joint1", "joint2", "joint3"}), + rclcpp::Parameter("p_gains", std::vector{100.0, 100.0, 100.0}), + rclcpp::Parameter("d_gains", std::vector{5.0, 5.0, 5.0}), + rclcpp::Parameter("compensate_gravity", true), + rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), + rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}, + // Missing dynamics solver tip + std::vector{ + rclcpp::Parameter("joints", std::vector{"joint1", "joint2", "joint3"}), + rclcpp::Parameter("p_gains", std::vector{100.0, 100.0, 100.0}), + rclcpp::Parameter("d_gains", std::vector{5.0, 5.0, 5.0}), + rclcpp::Parameter("compensate_gravity", true), + rclcpp::Parameter( + "dynamics_solver.dynamics_solver_plugin", + std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), + rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}, + // Missing dynamics solver root + std::vector{ + rclcpp::Parameter("joints", std::vector{"joint1", "joint2", "joint3"}), + rclcpp::Parameter("p_gains", std::vector{100.0, 100.0, 100.0}), + rclcpp::Parameter("d_gains", std::vector{5.0, 5.0, 5.0}), + rclcpp::Parameter("compensate_gravity", true), + rclcpp::Parameter( + "dynamics_solver.dynamics_solver_plugin", + std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), + rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link"))})); + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + rclcpp::init(argc, argv); + + int result = RUN_ALL_TESTS(); + + rclcpp::shutdown(); + return result; +} diff --git a/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.hpp b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.hpp index 968612dc96..fdd909d404 100644 --- a/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.hpp +++ b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.hpp @@ -32,20 +32,12 @@ class FriendGravityCompensationPDController : public gravity_compensation_pd_controller::GravityCompensationPDController { - FRIEND_TEST(GravityCompensationPDControllerTest, StopJointsOnDeactivateTest); - FRIEND_TEST(GravityCompensationPDControllerTest, ConfigureAndActivateParamsSuccess); FRIEND_TEST(GravityCompensationPDControllerTest, NoCommandCheckTest); }; -class GravityCompensationPDControllerTest : public ::testing::Test +class GravityCompensationPDControllerTestBase { public: - static void SetUpTestCase(); - static void TearDownTestCase(); - - void SetUp(); - void TearDown(); - void SetUpController(const std::vector & parameters = {}); protected: @@ -65,4 +57,28 @@ class GravityCompensationPDControllerTest : public ::testing::Test rclcpp::executors::SingleThreadedExecutor executor_; }; +class GravityCompensationPDControllerTest : public GravityCompensationPDControllerTestBase, + public testing::Test +{ +public: + void SetUp() override; + void TearDown() override; +}; + +class GravityCompensationPDControllerInvalidParameterTest +: public testing::TestWithParam>, + public GravityCompensationPDControllerTestBase +{ +public: + void SetUp() override; + void TearDown() override; +}; + +class GravityCompensationPDControllerMissingParameterTest +: public GravityCompensationPDControllerInvalidParameterTest +{ +public: + void SetUp() override; +}; + #endif // TEST_GRAVITY_COMPENSATION_PD_CONTROLLER_HPP_ From fae54e4902f9dfeaa1234c0578ae019f9a31e717 Mon Sep 17 00:00:00 2001 From: Davide Risi Date: Tue, 30 Sep 2025 18:57:40 +0200 Subject: [PATCH 7/9] [REF] Update robot description and dynamics solver parameters in test configurations --- ...st_gravity_compensation_pd_controller.yaml | 4 +- .../test/test_asset_robot_description.hpp | 77 ++----------------- ...est_gravity_compensation_pd_controller.cpp | 67 +++++++++++----- 3 files changed, 59 insertions(+), 89 deletions(-) diff --git a/gravity_compensation_pd_controller/test/config/test_gravity_compensation_pd_controller.yaml b/gravity_compensation_pd_controller/test/config/test_gravity_compensation_pd_controller.yaml index 938430a61d..eea00c9ebf 100644 --- a/gravity_compensation_pd_controller/test/config/test_gravity_compensation_pd_controller.yaml +++ b/gravity_compensation_pd_controller/test/config/test_gravity_compensation_pd_controller.yaml @@ -7,8 +7,8 @@ test_gravity_compensation_pd_controller: dynamics_solver: dynamics_solver_plugin: kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL - tip: tool0 - root: world + tip: link3 + root: base_link p_gains: [2000.0, 3000.0, 4000.0] d_gains: [100.0, 100.0, 100.0] diff --git a/gravity_compensation_pd_controller/test/test_asset_robot_description.hpp b/gravity_compensation_pd_controller/test/test_asset_robot_description.hpp index 5438a68302..89c811fcc1 100644 --- a/gravity_compensation_pd_controller/test/test_asset_robot_description.hpp +++ b/gravity_compensation_pd_controller/test/test_asset_robot_description.hpp @@ -17,77 +17,14 @@ #ifndef TEST_ASSET_ROBOT_DESCRIPTION_HPP_ #define TEST_ASSET_ROBOT_DESCRIPTION_HPP_ +#include +#include "ros2_control_test_assets/descriptions.hpp" + namespace ros2_control_test_assets { -const auto valid_robot_urdf = +const std::string system_hardware_resources = R"( - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - mock_components/GenericSystem @@ -122,9 +59,11 @@ const auto valid_robot_urdf = - )"; +const std::string valid_robot_urdf = + std::string(urdf_head) + std::string(system_hardware_resources) + std::string(urdf_tail); + } // namespace ros2_control_test_assets -#endif // TEST_ASSET_ROBOT_DESCRIPTION_HPP_ +#endif // TEST_ASSET_ROBOT_DESCRIPTION_HPP_ \ No newline at end of file diff --git a/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp index 90cc83b504..ae73dfd4ab 100644 --- a/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp +++ b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp @@ -30,6 +30,8 @@ using CallbackReturn = controller_interface::CallbackReturn; using hardware_interface::LoanedCommandInterface; +// ****** Definitions of the test cases for GravityCompensationPDController public API ****** + void GravityCompensationPDControllerTest::SetUp() { controller_ = std::make_unique(); @@ -41,7 +43,7 @@ void GravityCompensationPDControllerTest::SetUp() rclcpp::Parameter( "dynamics_solver.dynamics_solver_plugin", std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), - rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), + rclcpp::Parameter("dynamics_solver.tip", std::string("link3")), rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}; SetUpController(default_parameters); } @@ -106,47 +108,74 @@ void GravityCompensationPDControllerTestBase::SetUpController( TEST_F(GravityCompensationPDControllerTest, ConfigureAndActivateParamsSuccess) { - // configure successful + ASSERT_EQ(controller_->on_init(), CallbackReturn::SUCCESS); ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); } TEST_F(GravityCompensationPDControllerTest, NoCommandCheckTest) { + ASSERT_EQ(controller_->on_init(), CallbackReturn::SUCCESS); ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); + // This method is protected, so we need the friend class controller_->on_export_reference_interfaces(); - // update successful, no command received yet + // Update successful, no command received yet ASSERT_EQ( controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - // check joint commands are still the default ones - EXPECT_NEAR(joint_command_values_[0], 0.0, 1e-6); - EXPECT_NEAR(joint_command_values_[1], 0.0, 1e-6); - EXPECT_NEAR(joint_command_values_[2], 0.0, 1e-6); + // Check joint commands with gravity compensation only and no PD action + EXPECT_NEAR(joint_command_values_[0], 0.1, 1e-9); + EXPECT_NEAR(joint_command_values_[1], 0.0, 1e-9); + EXPECT_NEAR(joint_command_values_[2], 0.0, 1e-9); } TEST_F(GravityCompensationPDControllerTest, StopJointsOnDeactivateTest) { + ASSERT_EQ(controller_->on_init(), CallbackReturn::SUCCESS); + // configure successful ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); // check joint commands are still the default ones - EXPECT_NEAR(joint_command_values_[0], 0.0, 1e-6); - EXPECT_NEAR(joint_command_values_[1], 0.0, 1e-6); - EXPECT_NEAR(joint_command_values_[2], 0.0, 1e-6); + EXPECT_NEAR(joint_command_values_[0], 0.0, 1e-9); + EXPECT_NEAR(joint_command_values_[1], 0.0, 1e-9); + EXPECT_NEAR(joint_command_values_[2], 0.0, 1e-9); // stop the controller ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); // check joint commands are now zero - EXPECT_NEAR(joint_command_values_[0], 0.0, 1e-6); - EXPECT_NEAR(joint_command_values_[1], 0.0, 1e-6); - EXPECT_NEAR(joint_command_values_[2], 0.0, 1e-6); + EXPECT_NEAR(joint_command_values_[0], 0.0, 1e-9); + EXPECT_NEAR(joint_command_values_[1], 0.0, 1e-9); + EXPECT_NEAR(joint_command_values_[2], 0.0, 1e-9); } +TEST_F(GravityCompensationPDControllerTest, CommandNanOnErrorTest) +{ + ASSERT_EQ(controller_->on_init(), CallbackReturn::SUCCESS); + + // configure successful + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); + + // check joint commands are still the default ones + EXPECT_NEAR(joint_command_values_[0], 0.0, 1e-9); + EXPECT_NEAR(joint_command_values_[1], 0.0, 1e-9); + EXPECT_NEAR(joint_command_values_[2], 0.0, 1e-9); + + // stop the controller + ASSERT_EQ(controller_->on_error(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); + + // check joint commands are now NaN + EXPECT_TRUE(std::isnan(joint_command_values_[0])); + EXPECT_TRUE(std::isnan(joint_command_values_[1])); + EXPECT_TRUE(std::isnan(joint_command_values_[2])); +} + +// ****** Definitions of the test cases for invalid parameters ****** + void GravityCompensationPDControllerInvalidParameterTest::SetUp() { controller_ = std::make_unique(); @@ -181,7 +210,7 @@ INSTANTIATE_TEST_SUITE_P( rclcpp::Parameter( "dynamics_solver.dynamics_solver_plugin", std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), - rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), + rclcpp::Parameter("dynamics_solver.tip", std::string("link3")), rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}, // Mismatched p_gains size @@ -193,7 +222,7 @@ INSTANTIATE_TEST_SUITE_P( rclcpp::Parameter( "dynamics_solver.dynamics_solver_plugin", std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), - rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), + rclcpp::Parameter("dynamics_solver.tip", std::string("link3")), rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}, // Mismatched d_gains size @@ -205,9 +234,11 @@ INSTANTIATE_TEST_SUITE_P( rclcpp::Parameter( "dynamics_solver.dynamics_solver_plugin", std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), - rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), + rclcpp::Parameter("dynamics_solver.tip", std::string("link3")), rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))})); +// ****** Definitions of the test cases for missing parameters ****** + void GravityCompensationPDControllerMissingParameterTest::SetUp() { controller_ = std::make_unique(); @@ -238,7 +269,7 @@ INSTANTIATE_TEST_SUITE_P( rclcpp::Parameter("p_gains", std::vector{100.0, 100.0, 100.0}), rclcpp::Parameter("d_gains", std::vector{5.0, 5.0, 5.0}), rclcpp::Parameter("compensate_gravity", true), - rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link")), + rclcpp::Parameter("dynamics_solver.tip", std::string("link3")), rclcpp::Parameter("dynamics_solver.root", std::string("base_link"))}, // Missing dynamics solver tip std::vector{ @@ -259,7 +290,7 @@ INSTANTIATE_TEST_SUITE_P( rclcpp::Parameter( "dynamics_solver.dynamics_solver_plugin", std::string("kdl_inverse_dynamics_solver/InverseDynamicsSolverKDL")), - rclcpp::Parameter("dynamics_solver.tip", std::string("tool_link"))})); + rclcpp::Parameter("dynamics_solver.tip", std::string("link3"))})); int main(int argc, char ** argv) { From 6e3725e8795e0962c7188ba7b13d349d4e61bf06 Mon Sep 17 00:00:00 2001 From: Davide Risi Date: Wed, 1 Oct 2025 10:12:54 +0200 Subject: [PATCH 8/9] [FMT] Fix pre-commit errors --- .../test/test_asset_robot_description.hpp | 6 +++--- .../test/test_gravity_compensation_pd_controller.cpp | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/gravity_compensation_pd_controller/test/test_asset_robot_description.hpp b/gravity_compensation_pd_controller/test/test_asset_robot_description.hpp index 89c811fcc1..238f7bf5d6 100644 --- a/gravity_compensation_pd_controller/test/test_asset_robot_description.hpp +++ b/gravity_compensation_pd_controller/test/test_asset_robot_description.hpp @@ -23,7 +23,7 @@ namespace ros2_control_test_assets { -const std::string system_hardware_resources = +const auto system_hardware_resources = R"( @@ -61,9 +61,9 @@ const std::string system_hardware_resources = )"; -const std::string valid_robot_urdf = +const auto valid_robot_urdf = std::string(urdf_head) + std::string(system_hardware_resources) + std::string(urdf_tail); } // namespace ros2_control_test_assets -#endif // TEST_ASSET_ROBOT_DESCRIPTION_HPP_ \ No newline at end of file +#endif // TEST_ASSET_ROBOT_DESCRIPTION_HPP_ diff --git a/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp index ae73dfd4ab..431a07d3bf 100644 --- a/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp +++ b/gravity_compensation_pd_controller/test/test_gravity_compensation_pd_controller.cpp @@ -135,7 +135,7 @@ TEST_F(GravityCompensationPDControllerTest, NoCommandCheckTest) TEST_F(GravityCompensationPDControllerTest, StopJointsOnDeactivateTest) { ASSERT_EQ(controller_->on_init(), CallbackReturn::SUCCESS); - + // configure successful ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); @@ -156,7 +156,7 @@ TEST_F(GravityCompensationPDControllerTest, StopJointsOnDeactivateTest) TEST_F(GravityCompensationPDControllerTest, CommandNanOnErrorTest) { ASSERT_EQ(controller_->on_init(), CallbackReturn::SUCCESS); - + // configure successful ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS); From c0a31b2fe65cffcc25eb84d04249de836a0140fa Mon Sep 17 00:00:00 2001 From: Davide Risi Date: Thu, 2 Oct 2025 14:44:43 +0200 Subject: [PATCH 9/9] [DOC] Add Gravity Compensation Controller documentation and update test configuration parameters - [REF] Remove redundant README.md for gravity_compensation_pd_controller --- doc/controllers_index.rst | 1 + gravity_compensation_pd_controller/README.md | 27 -------- .../doc/userdoc.rst | 62 +++++++++++++++++++ ...st_gravity_compensation_pd_controller.yaml | 4 +- 4 files changed, 65 insertions(+), 29 deletions(-) delete mode 100644 gravity_compensation_pd_controller/README.md create mode 100644 gravity_compensation_pd_controller/doc/userdoc.rst diff --git a/doc/controllers_index.rst b/doc/controllers_index.rst index 4bbe6eb673..2fb8bc3993 100644 --- a/doc/controllers_index.rst +++ b/doc/controllers_index.rst @@ -59,6 +59,7 @@ The controllers are using `common hardware interface definitions`_, and may use Velocity Controllers <../velocity_controllers/doc/userdoc.rst> Gpio Command Controller <../gpio_controllers/doc/userdoc.rst> Motion Primitive Controller <../motion_primitives_controllers/userdoc.rst> + Gravity Compensation Controller <../gravity_compensation_controller/doc/userdoc.rst> Broadcasters ********************** diff --git a/gravity_compensation_pd_controller/README.md b/gravity_compensation_pd_controller/README.md deleted file mode 100644 index b051094acf..0000000000 --- a/gravity_compensation_pd_controller/README.md +++ /dev/null @@ -1,27 +0,0 @@ -# gravity_compensation_pd_controller - -This package provides a PD controller with gravity compensation that converts joint position references to joint effort commands for a robotic manipulator. -It is a chainable controller; therefore, it requires another controller to provide joint position references via chaining. - -## Control Law - -The implemented control law follows the scheme shown in the figure, based on the formulation presented in _B. Siciliano, L. Sciavicco, L. Villani, G. Oriolo, "Robotics: Modelling, Planning and Control"_. - -![gravity_compensation_pd_controller_scheme](./doc/media/gravity_compensation_pd_controller_scheme.png) - -## Controller Configuration - -The controller uses the robot's dynamic model to compute the control action. -In particular, it relies on the [InverseDynamicsSolver](https://index.ros.org/p/inverse_dynamics_solver/) interface to estimate the gravity torque vector. -Control parameters for the PD controller with gravity compensation are defined in the file [gravity_compensation_pd_controller_parameters.yaml](./src/gravity_compensation_pd_controller_parameters.yaml). -Please refer to [`gravity_compensation_pd_controller_parameters.md`](./doc/gravity_compensation_pd_controller_parameters.md) for the documentation. - -## Behavior in Edge Cases - -The controller is designed to handle the following edge cases: - -- **Computed torque exceeding joint limits**. If the computed torque exceeds the joint limits, the controller will saturate the output to remain within the range specified in the robot description. - -- **Invalid joint position reference**. If the joint position reference is `NaN`, the controller will fall back to the last valid reference to compute the control action. Initially, the first valid reference is set to the robot's starting joint positions. - -- **Invalid joint position state**. If the controller detects a `NaN` value in the joint position state reported by the robot, it will return an error to the controller manager. In this case, the controller cannot compute a valid control action and will output `NaN` values. It is assumed that the hardware interface is capable of handling `NaN` values appropriately. diff --git a/gravity_compensation_pd_controller/doc/userdoc.rst b/gravity_compensation_pd_controller/doc/userdoc.rst new file mode 100644 index 0000000000..7a7a4a77fb --- /dev/null +++ b/gravity_compensation_pd_controller/doc/userdoc.rst @@ -0,0 +1,62 @@ +:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/gravity_compensation_pd_controller/doc/userdoc.rst + +.. _gravity_compensation_pd_controller_userdoc: + +Gravity Compensation PD Controller +================================== + +This controller provides a PD controller with gravity compensation that converts joint position references to joint effort commands for a robotic manipulator. +It is a chainable controller; therefore, it requires another controller to provide joint position references via chaining. + +The controller uses the robot's dynamic model to compute the control action. +In particular, it relies on the `InverseDynamicsSolver `_ interface to estimate the gravity torque vector. + +Control Law +----------- + +The implemented control law follows the scheme shown in the figure, based on the formulation presented in *B. Siciliano, L. Sciavicco, L. Villani, G. Oriolo, "Robotics: Modelling, Planning and Control"*. + +.. image:: ../doc/media/gravity_compensation_pd_controller_scheme.png + :alt: Gravity Compensation PD Controller Scheme + + +Description of controller's interfaces +-------------------------------------- + +References (from a preceding controller) +,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,, +- ``/position`` [double] + +Commands +,,,,,,,, +- ``/effort`` [double] + +States +,,,,,, +- ``/position`` [double] +- ``/velocity`` [double] + + +Behavior in Edge Cases +---------------------- + +The controller is designed to handle the following edge cases: + +- **Computed torque exceeding joint limits**. If the computed torque exceeds the joint limits, the controller will saturate the output to remain within the range specified in the robot description. + +- **Invalid joint position reference**. If the joint position reference is ``NaN``, the controller will fall back to the last valid reference to compute the control action. Initially, the first valid reference is set to the robot's starting joint positions. + +- **Invalid joint position state**. If the controller detects a ``NaN`` value in the joint position state reported by the robot, it will return an error to the controller manager. In this case, the controller cannot compute a valid control action and will output ``NaN`` values. It is assumed that the hardware interface is capable of handling ``NaN`` values appropriately. + + +Parameters +---------- + +This controller uses the `generate_parameter_library `_ to handle its parameters. The parameter `definition file located in the src folder `_ contains descriptions for all the parameters used by the controller. + +.. generate_parameter_library_details:: ../src/gravity_compensation_pd_controller_parameters.yaml + +An example parameter file for this controller can be found in `the test directory `_: + +.. literalinclude:: ../test/config/test_gravity_compensation_pd_controller.yaml + :language: yaml diff --git a/gravity_compensation_pd_controller/test/config/test_gravity_compensation_pd_controller.yaml b/gravity_compensation_pd_controller/test/config/test_gravity_compensation_pd_controller.yaml index eea00c9ebf..7ab999667e 100644 --- a/gravity_compensation_pd_controller/test/config/test_gravity_compensation_pd_controller.yaml +++ b/gravity_compensation_pd_controller/test/config/test_gravity_compensation_pd_controller.yaml @@ -10,7 +10,7 @@ test_gravity_compensation_pd_controller: tip: link3 root: base_link - p_gains: [2000.0, 3000.0, 4000.0] - d_gains: [100.0, 100.0, 100.0] + p_gains: [200.0, 300.0, 400.0] + d_gains: [10.0, 10.0, 10.0] compensate_gravity: true