From d3e67576f024ef09103c6e53bfba59653cedb2f8 Mon Sep 17 00:00:00 2001 From: Yamato Ando Date: Wed, 20 Sep 2023 11:34:41 +0900 Subject: [PATCH 1/3] feat(ekf_localizer): add diagnostics (#4914) * feat(ekf_localizer): add diagnostics Signed-off-by: yamato-ando * update readme Signed-off-by: yamato-ando * style(pre-commit): autofix * update diag message Signed-off-by: yamato-ando * refactor Signed-off-by: yamato-ando * style(pre-commit): autofix * add OK message Signed-off-by: yamato-ando * fix typo Signed-off-by: yamato-ando * fix typo Signed-off-by: yamato-ando * Update localization/ekf_localizer/src/diagnostics.cpp Co-authored-by: Kento Yabuuchi --------- Signed-off-by: yamato-ando Co-authored-by: yamato-ando Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Kento Yabuuchi --- localization/ekf_localizer/CMakeLists.txt | 1 + localization/ekf_localizer/README.md | 30 +++ .../config/ekf_localizer.param.yaml | 6 + .../include/ekf_localizer/diagnostics.hpp | 40 ++++ .../include/ekf_localizer/ekf_localizer.hpp | 29 ++- .../ekf_localizer/hyper_parameters.hpp | 14 +- .../ekf_localizer/media/ekf_diagnostics.png | Bin 0 -> 103904 bytes localization/ekf_localizer/package.xml | 1 + .../ekf_localizer/src/diagnostics.cpp | 169 +++++++++++++++ .../ekf_localizer/src/ekf_localizer.cpp | 107 +++++++++- .../ekf_localizer/test/test_diagnostics.cpp | 192 ++++++++++++++++++ 11 files changed, 576 insertions(+), 13 deletions(-) create mode 100644 localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp create mode 100644 localization/ekf_localizer/media/ekf_diagnostics.png create mode 100644 localization/ekf_localizer/src/diagnostics.cpp create mode 100644 localization/ekf_localizer/test/test_diagnostics.cpp diff --git a/localization/ekf_localizer/CMakeLists.txt b/localization/ekf_localizer/CMakeLists.txt index 6e7e194f7cf72..8e29bfed14a28 100644 --- a/localization/ekf_localizer/CMakeLists.txt +++ b/localization/ekf_localizer/CMakeLists.txt @@ -16,6 +16,7 @@ ament_auto_find_build_dependencies() ament_auto_add_library(ekf_localizer_lib SHARED src/ekf_localizer.cpp src/covariance.cpp + src/diagnostics.cpp src/mahalanobis.cpp src/measurement.cpp src/state_transition.cpp diff --git a/localization/ekf_localizer/README.md b/localization/ekf_localizer/README.md index 748b5ee5becc0..977e0fceafd9e 100644 --- a/localization/ekf_localizer/README.md +++ b/localization/ekf_localizer/README.md @@ -88,6 +88,10 @@ The parameters and input topic names can be set in the `ekf_localizer.launch` fi The estimated twist with covariance. +- diagnostics (diagnostic_msgs/DiagnosticArray) + + The diagnostic information. + ### Published TF - base_link @@ -148,6 +152,15 @@ The parameters are set in `launch/ekf_localizer.launch` . note: process noise for positions x & y are calculated automatically from nonlinear dynamics. +### For diagnostics + +| Name | Type | Description | Default value | +| :------------------------------------ | :----- | :----------------------------------------------------------------------------------------------------------------------------------------- | :------------ | +| pose_no_update_count_threshold_warn | size_t | The threshold at which a WARN state is triggered due to the Pose Topic update not happening continuously for a certain number of times. | 50 | +| pose_no_update_count_threshold_error | size_t | The threshold at which an ERROR state is triggered due to the Pose Topic update not happening continuously for a certain number of times. | 250 | +| twist_no_update_count_threshold_warn | size_t | The threshold at which a WARN state is triggered due to the Twist Topic update not happening continuously for a certain number of times. | 50 | +| twist_no_update_count_threshold_error | size_t | The threshold at which an ERROR state is triggered due to the Twist Topic update not happening continuously for a certain number of times. | 250 | + ## How to tune EKF parameters ### 0. Preliminaries @@ -194,6 +207,23 @@ Note that, although the dimension gets larger since the analytical expansion can

+## Diagnostics + +

+ +

+ +### The conditions that result in a WARN state + +- The node is not in the activate state. +- The number of consecutive no measurement update via the Pose/Twist topic exceeds the `pose_no_update_count_threshold_warn`/`twist_no_update_count_threshold_warn`. +- The timestamp of the Pose/Twist topic is beyond the delay compensation range. +- The Pose/Twist topic is beyond the range of Mahalanobis distance for covariance estimation. + +### The conditions that result in an ERROR state + +- The number of consecutive no measurement update via the Pose/Twist topic exceeds the `pose_no_update_count_threshold_error`/`twist_no_update_count_threshold_error`. + ## Known issues - In the presence of multiple inputs with yaw estimation, yaw bias `b_k` in the current EKF state would not make any sense, since it is intended to capture the extrinsic parameter's calibration error of a sensor. Thus, future work includes introducing yaw bias for each sensor with yaw estimation. diff --git a/localization/ekf_localizer/config/ekf_localizer.param.yaml b/localization/ekf_localizer/config/ekf_localizer.param.yaml index 4d3f5b9643462..8b24b79e71829 100644 --- a/localization/ekf_localizer/config/ekf_localizer.param.yaml +++ b/localization/ekf_localizer/config/ekf_localizer.param.yaml @@ -21,3 +21,9 @@ proc_stddev_yaw_c: 0.005 proc_stddev_vx_c: 10.0 proc_stddev_wz_c: 5.0 + + # for diagnostics + pose_no_update_count_threshold_warn: 50 + pose_no_update_count_threshold_error: 250 + twist_no_update_count_threshold_warn: 50 + twist_no_update_count_threshold_error: 250 diff --git a/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp b/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp new file mode 100644 index 0000000000000..f4dc6436f6a40 --- /dev/null +++ b/localization/ekf_localizer/include/ekf_localizer/diagnostics.hpp @@ -0,0 +1,40 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef EKF_LOCALIZER__DIAGNOSTICS_HPP_ +#define EKF_LOCALIZER__DIAGNOSTICS_HPP_ + +#include + +#include +#include + +diagnostic_msgs::msg::DiagnosticStatus checkProcessActivated(const bool is_activated); + +diagnostic_msgs::msg::DiagnosticStatus checkMeasurementUpdated( + const std::string & measurement_type, const size_t no_update_count, + const size_t no_update_count_threshold_warn, const size_t no_update_count_threshold_error); +diagnostic_msgs::msg::DiagnosticStatus checkMeasurementQueueSize( + const std::string & measurement_type, const size_t queue_size); +diagnostic_msgs::msg::DiagnosticStatus checkMeasurementDelayGate( + const std::string & measurement_type, const bool is_passed_delay_gate, const double delay_time, + const double delay_time_threshold); +diagnostic_msgs::msg::DiagnosticStatus checkMeasurementMahalanobisGate( + const std::string & measurement_type, const bool is_passed_mahalanobis_gate, + const double mahalanobis_distance, const double mahalanobis_distance_threshold); + +diagnostic_msgs::msg::DiagnosticStatus mergeDiagnosticStatus( + const std::vector & stat_array); + +#endif // EKF_LOCALIZER__DIAGNOSTICS_HPP_ diff --git a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp index a4ae47b670897..4fc2305cc7adc 100644 --- a/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp @@ -25,6 +25,7 @@ #include #include +#include #include #include #include @@ -126,6 +127,8 @@ class EKFLocalizer : public rclcpp::Node rclcpp::Publisher::SharedPtr pub_biased_pose_; //!< @brief ekf estimated yaw bias publisher rclcpp::Publisher::SharedPtr pub_biased_pose_cov_; + //!< @brief diagnostics publisher + rclcpp::Publisher::SharedPtr pub_diag_; //!< @brief initial pose subscriber rclcpp::Subscription::SharedPtr sub_initialpose_; //!< @brief measurement pose with covariance subscriber @@ -144,6 +147,7 @@ class EKFLocalizer : public rclcpp::Node rclcpp::TimerBase::SharedPtr timer_tf_; //!< @brief tf broadcaster std::shared_ptr tf_br_; + //!< @brief extended kalman filter instance. TimeDelayKalmanFilter ekf_; Simple1DFilter z_filter_; @@ -167,6 +171,22 @@ class EKFLocalizer : public rclcpp::Node bool is_activated_; + size_t pose_no_update_count_; + size_t pose_queue_size_; + bool pose_is_passed_delay_gate_; + double pose_delay_time_; + double pose_delay_time_threshold_; + bool pose_is_passed_mahalanobis_gate_; + double pose_mahalanobis_distance_; + + size_t twist_no_update_count_; + size_t twist_queue_size_; + bool twist_is_passed_delay_gate_; + double twist_delay_time_; + double twist_delay_time_threshold_; + bool twist_is_passed_mahalanobis_gate_; + double twist_mahalanobis_distance_; + AgedObjectQueue pose_queue_; AgedObjectQueue twist_queue_; @@ -221,13 +241,13 @@ class EKFLocalizer : public rclcpp::Node * @brief compute EKF update with pose measurement * @param pose measurement value */ - void measurementUpdatePose(const geometry_msgs::msg::PoseWithCovarianceStamped & pose); + bool measurementUpdatePose(const geometry_msgs::msg::PoseWithCovarianceStamped & pose); /** * @brief compute EKF update with pose measurement * @param twist measurement value */ - void measurementUpdateTwist(const geometry_msgs::msg::TwistWithCovarianceStamped & twist); + bool measurementUpdateTwist(const geometry_msgs::msg::TwistWithCovarianceStamped & twist); /** * @brief get transform from frame_id @@ -246,6 +266,11 @@ class EKFLocalizer : public rclcpp::Node */ void publishEstimateResult(); + /** + * @brief publish diagnostics message + */ + void publishDiagnostics(); + /** * @brief for debug */ diff --git a/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp b/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp index c74fa9be79525..9fa877c8fd2f6 100644 --- a/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp @@ -39,7 +39,15 @@ class HyperParameters twist_smoothing_steps(node->declare_parameter("twist_smoothing_steps", 2)), proc_stddev_vx_c(node->declare_parameter("proc_stddev_vx_c", 5.0)), proc_stddev_wz_c(node->declare_parameter("proc_stddev_wz_c", 1.0)), - proc_stddev_yaw_c(node->declare_parameter("proc_stddev_yaw_c", 0.005)) + proc_stddev_yaw_c(node->declare_parameter("proc_stddev_yaw_c", 0.005)), + pose_no_update_count_threshold_warn( + node->declare_parameter("pose_no_update_count_threshold_warn", 50)), + pose_no_update_count_threshold_error( + node->declare_parameter("pose_no_update_count_threshold_error", 250)), + twist_no_update_count_threshold_warn( + node->declare_parameter("twist_no_update_count_threshold_warn", 50)), + twist_no_update_count_threshold_error( + node->declare_parameter("twist_no_update_count_threshold_error", 250)) { } @@ -59,6 +67,10 @@ class HyperParameters const double proc_stddev_vx_c; //!< @brief vx process noise const double proc_stddev_wz_c; //!< @brief wz process noise const double proc_stddev_yaw_c; //!< @brief yaw process noise + const size_t pose_no_update_count_threshold_warn; + const size_t pose_no_update_count_threshold_error; + const size_t twist_no_update_count_threshold_warn; + const size_t twist_no_update_count_threshold_error; }; #endif // EKF_LOCALIZER__HYPER_PARAMETERS_HPP_ diff --git a/localization/ekf_localizer/media/ekf_diagnostics.png b/localization/ekf_localizer/media/ekf_diagnostics.png new file mode 100644 index 0000000000000000000000000000000000000000..2580d6d973290235f1d131251b815db319c07af8 GIT binary patch literal 103904 zcmdqI^LHjuv@IH^)3I&a?AW$#+fF*RZQEaL+jcr;$L39+an2j(y?5^Y1MdE%zFJka zzpAmT_L^(Xxx?jU#bAG8{R9F6f|U>#Rs;e9E&~Drk^cel9ofjdru^Q3ISEQA|M+g+ zKa9h^_c5JC)SZ>=Or6~f98G}CZ0&4JXq}84O-yW^%vDWG14j009vI zNeBxlyJuZ&xj8EjZS>w;ZFQe^2@oKFP95y&JF{Xhdl6jqQ|5cued@TVY( zkVK8&PA2MlqT{(o5dVRo==#Kag%5?`$v+!*$4P$NYkHO4M*6gt?%^sbB`Jx7BBFpo zn#%aTfGYp}Gf7JUSW*E+WGq?PU-5h2krXxWUsziLoZ{b!YD`bQbiBVek~KvjNd*)U3Do64#ozG*Nh*HI?|56nPx=2mtZeIO z!7B8td2jzPrl*+W_;Idt^%d7N_YHmqod#<199`;Sq|!s*OlMEyTHzO$PZ#QO;QDd) z`_xl(!Ml#Kzo+a;F*_|zINp5P&#!W;VS&_fHq`Y=clx(2s3yDCoa_zfLOvrXx3 zOZ5PGIcQTaAd?*(r(^vR@&=EiTAFpQ&*nGpINMG;ZAh_s0+J}Q9sJ#^wnUV}-PRVM zWY4gj5a&XPVnHwuO-8M*F{KMA&HML|C9|)A+HTWT8+5DNKraJ{QnEnXo$1l6w} z5yI$XlS*%qUgP?Qc_oeS_JrXpJcKgOLFi=d_PU+X-#6D2=^Hhtv%!38P0O3!o|GKv zXY%YcWcLByuPx{VP1Yce_!FYzMyQt=<^GnN*ccZicM)p!;tWl|t z`{Pnd*@Hsmo!xQQ@nZv|ImE5{_q*=7L5e}K_LWA}*$2afd++?p-N+eC4hFA3oXf{2 zD!jLlIdiw>@=pD51pB?sam?GFzY_161ZbL13=25~dJ z5JYk>hM(9MQ>A{T&vqa(8sw~AYzLuPjjwcQ6C9^+06@S&HtW-Do>ASi;Pk4G-)#)d zh6AR-)^qev3~)(u6dtV2GhDY~%k}A1Ie|tjd8^Pw>{X?>I<=)BXk&V6q$rJEtPa>s zZOy#SAg3b|VeQ0>s2}05YguRxajbeSC8zp6owwxMG zu8us(^k36_Ku95hGbu{AlrTPd_`zg^l&o2B?Ha<>Y(^)yPB?&w6PV z{B?bsBhfim#0~zj)`j0wuo+ua zL^AdX(C-6ji}!WS8uT;=A)~yRhLGqu#ZA{9Arp^eC^R=Wta}UVDb-*>nCj~6?D=d6 zYdyH0B_9MSNZ%afW0B{U&Hw_*z~BKP=^aRFi`G(kG0eR?vgsEbnlVLy9sHxC@@c2_ z>XYJQ!#CWSZDM=dWMqzMiXy`tA*OCXiE~6K3d;z_M~f`mDtu5NZElG?JE(sbA6EzD zz-|cwabtCxm}MV6TAW+l1}gvv)9WTuED}eg)O557{&7Y#Cm^H_BM;ZQ@9!6&Im~ zgGQG@-xHHVgiRk7#&P&3L4wKYMpC20Gd}8EN9BDoe%?yuh*K(aTa~-I=`a(yJuIwf z=86P(xq|5+PD(f{!QD9ZVzpk#^lq@o=Xe=wn*O2n7`MsOR=}kv0VUQ9|W2YrdJ+hk?8;6MKwBf@qHZqk~ zF#|S>0vc^9<;qhfk-({}G0R?Cn~10;km=c>(tXKOuH>s*7;Pq#0yGm1AyNzV#k*EX zIIF?SoEGY~mI9QW)3%#3`|aSI%Xd$sq7WvxOLCbGkC+Gl4%Mo@yMgWR`X{KKI>Bj8 zB2%SRW2+c9F>+S!Zip!(9(+CSnQGIdNw z*Lj17g2;{vwoG<4Qb!MUn2KUzF=hulUcfjj^`McCB)<~*vfBsctO-9MgaOORc5gKqtakcP1Jr z4$m?VX3Bp2w2Qz@4j1A^WfPbK1FOTdBk~>U8AFx}QAN^>jZ4U~IYz=g1IZ0tgP%mdv z5JfNpxjDvD-cFi6mC59=tm4l;+g=&w<*txFX8Z+}$&PqD&)MYw>M;CsvF6CDQdUOB0^A@jnbM@+!Nyvs8y{Eda(gs#&RV!5u zI^4cw4M>=0zUALFP5lk9^O)B)Syw56t{Fp;rpY=d?f$N$$|swT2#$NU50Jtuz<)L4 zS9}LfZ*~C^rJ>vRKy!yZ?K^?f}x?MJRK>?tgKQ0U1i9n7jyz8tP27$u16p)6qgy!>wHNbjM=x~AUj~kJYpCnye z!`T#U&WayT?t)z)dN3Xx{E*&$_Qd$JiRt<`N~|^med@H=gz5Ms$PB_1l+a`%VTCoF zl$!3^TBvqXucXRkY+d>NJc+Pp&Ocw7Qc!zAqmw(m85Y3zJNsgzF*#|px${L6c{~$n zMC7)^>U)wa0p@D|(em@>Yq{RZ%PWm{2mL`J7w^jUF4y=GEz~pb1J_k!MGUz8TER8r zyQ_;wICuYA043jJCX-dZw7ZchfY89~wa|KE>Y zaG;6rNPf1Mo0u*Y>r;!$SclIf(w;2RB*l^9-vvE=q}E!buP6XH!Nn{Xhvyf0AyKDV z6IR<6pKB^i>twDT(F}-vbSU!m0~H~sjzqcMh6uH7l@hM_c6+?=u%VpKRJ2SO^t?j< zB9%n{9jwK9p^@gfduA0cd6@wCH6IuHD8yIlkOrmrbbEIWOM!YB8!Jb!J5)K>;AH2! znXgdq<(C0w#qsDZvULpv5@2-FM1fhKTCkxt_2W5m274sssT?6IwKJd86I$*OBESDuU&-mdx*rwpol)(4i!9f^p5>GmGFpT896gNnM*0;Jexck< z#ww81lG^Eq@J}PXu)~M=1&u~)N@(AYaPT+624jUP$WjLPL2XsL?eS&W4$gE>T0@L? zkn0sUMzj8(dy2MUBngA>pLUE}DygX%FZRaAvaXk#W7AtB;%q@mooVdhccFJ{ji}b^ z?a9>}`>pOS=%x`Vw817TvEJ8*G@t5Bp$^Du2!8u_3jkodd#aHe`i;3uKPB}}Yha_- z=7JFx;^^0I;dC4y@AmJfDz;?zRFOGev6VT!SyJ}ZYmN$D@cR>~*SvLaq9tVS)1CH7 z+9V5CvSq~_-m`;87f28Mi3LSn!eDgFsm;kLTN~2(X$iF#(wr~yg`eJKj45>_W4JfJ zj}ehXqPfw(D(83bwt^I2m`zrJNGz;Sk0-xq7|7F5u_R&OVM90sOX^8(u z)^2vt2+GIk*WF7IIE_wo+S+~yqv=#|&!N$8Xzf%m213g*FEE)>R?VUj^$U z$(?oV&-~@st?b0OB15l?v?!qUMNItE^J@GmynR$g0*RaHUgl+&oteXgn&5$YZ`WQ@G?j#~5-08NA$Y9hKLsz|jcGzn3tzWG5?CC_=v z@F;HT_}i!_>Remk_E|Ya?vbNbE9~A6V)&`7>bLPYtG79qq#xR zsp@&g>`F>Nr1GI(7lOcp**Jkab-Sml#Njm9(2)6@ww?#j{J$h4$#;H zAu1luYf2!bY;dw>FUQ5Duq6vjtI9z_&=sb7$Rd__rM=8NKl4@~V*_k?ZHt--`Zkk1}l)T9*fINLlFO~1(|mRj$mu(2mOH6aB&kBUgS z|IR=a<3N^8C~f?)n4OhYxYza_;Qn$% z9D$}`dmF`!&TY0T+wLGym7=>K;uC*7_ISEjRIqnQ&S&e$v+sBg;fD=JIIC5dVw=LQ8f@Hsd*LT6!++%+m| zUPK!*WE9y|CMw^9bTLf7hT`jOfs&{_EAy*CSc63XASIt~K6Y$_1S`{N36tCP!Uf&+$X2s6t4J6r#Bp17rpj?_Q+P?|JIPSwV2JL(iPn$$`FCw8#lCEDmv zYcXR2Yzi9bFUSn!U=yoTZR_*@eHs98Xc0bA;@rlcX~q4&^u$NFA?9dI4hwP7O@_{c z2g}xq*Gu(AnRPStX(+l>O~W|8lD;af5oG{U$#QOz8DS@8zVU2*5Pizh+iNEX$1(85 zQJhYA-SEvi(=-#OqgjP?M&-^kW+*If<-hjCkNWM}g>cl!>zpDM%B6;fm>n;!1vKsy zQ0pzjiq8-@50D&izf{lKEdu)VGNNLTL&LN&@Tr@vfzReIVvvmaqjqtPMFZ%F${Sqx zIT;JX#Q;$0PEA{Vhk9D!ndNbv^+#-xNV;hRGB#wCx67Um+EDVt{7|rLkzMaVYtAn@ zwWXO+=YJyh<+GrTltD9+?1h}H_4$L}2L~VbHdvw3sR`1?XImA( zOckHIv{(?6H5csqT@wJNq&=NZFgle%yQiqa?!U$Hyxdq%K^#wsC_$!mu-7uk%$qG6 zzriw^-m_za-4+Cri#;y3&;mbbhH2@&zYGV$d@RnMaLlsfykq;T0+|qp%6V#k^MjP` zDPO3ON4h%wj80G=9z0eTgP1iY=gt`-)aqVli&!`79K(Dw8!R_4s2vBA1=1Mub5Q zPHSv_KJdkRQ2od@ZF1zV8I#LCHyaF`*<$3@vqM)P_rp%UUq^!a3jF>d{mPyoQzB9g zow0l6&^uF`b~@r{S_>R~b8V1a^An~}C6asUwM|R}S%QZ3I!>%E=ameo=jjGp-IhhM z`W%QhkEapXR8L0l$b)YF7&L8}$Ez3G`!i1PWg|$@zwuLuX@8zSmO2Is)W1$WJ}!wA zZ9l9PjP!%D;ccP9a0$WacTU6Jyr2i;B7yn# z?d0MlV|nAL&5)ANWHDddUs=SJc>3aYT0mrN-)wb4lBce#cShUha57!@T~9Nb9_-wO zNzrkqQ34qeQF~Dq2MM{79XC|VpLZn)zDu$rK^>FJbnI8q1=opGxz}*YdyRBY)zr!f zA7ffI!o37$XfG)Z_(&9Uc8!>=&c~2{&#pNQvUvDC6f(##9tVd*>4XFI``8vcdEJAL zJq75vPPnBF_#CQ9@{TaX{FHMQ%w>L4w;^n?N{Bh9OD ztNzzhk(^98Y7Hdm1d6G{37FApvk`52i6nec=2n3eevW@OYVQc0=C`gYBNlP-(-{n+ z!}w)>6X|Hryv+)hxF?*Kg0;^|%`*r)`|{+mF!se8If53z4FUs6-7Y6n2QR z$rah@Gom>*`10#ZO9kr7Z-quXv5=8MqHUBk)!%f;cH#n(IoUm&@$QIuztA&X$0!5a z_HmMQke)=3e}vzB0$+pIir{aB2%@>f{$|@mT43ajdJ%a!2wf?U z;B4J-?EAZ^MHD51IulmzJ@R{-5jr_3JgVmX@$sBaIK$!Li$bFN)v4pbTui<1m|)7K z6fs2wH>(xOOobd!v?z_yHu{!@Mhn-HCHrApdoUw##!!R^sI|!{yC3DwleKiZJ^ewy zMuLkS(RdQUqB|+;yQFppt5v;PTD<|`m)H1UgaMB^@ip_S?KfeJo~p{+ zXhhAc``H`AuaM-|wuzgEQ~6w^@eM5weM-uKT)Z6PyC!^%rgkG+WR%>7rw*z^NPj#u z>Ni8mKW?$Q!I^pzWtx4C7jzwer7XI&b!LJm9@WtjI=RBH^u@FMfGQk&N(Zb^N8Iit z4zxYP-H51AXP6fBo>K#ORqTfj_Z1{9BkT;D^D#Q(`4Sgb5sKHYr8{*l>wi=;%o zxPU(YKK*aKNL;x5tnq>~>IL$1cnRvkDC%-OC*I8JW^A#zO8cF9AeTC)5|V(mMV}}V z3vJuP19)uGs&#`0sm=Sg5a_KCO9mqL*R&Q}S zrCJZ1fG8pDC&BR)u(0sY@1jRm-o;p(jKtynn90KRipC~di>v3=3p$+>2OGdI@J9-$8sJ&eAO z7V9psd$LMYr=?^IFJrRSW%qcwGi4IJryelg)!6l(c&^@GDBCMN>1$g?r)`B0JG383 zn!Z>hpz7rhr%WNN&X6$f!5uqBhs*@80OkMk0<7L>&^&DO$^88sNY`CUG`iz0)a%g1 zaj?->+~CHz=kT@G%0y>J*M(dwa$fk5?XgVmd#T8`s>nq?1Kuc+YmVo|LqB~)6aP@%M12Z-=gev6T z<;UC(W@D!L#sG8brNLr@S|ZEG(52!_lbUctVbV3SuZD7Hms&Vxr~_$oy`PdvrZe^F zR*OVN(gLRTyL^{}%*t&EVg@shRL@Oe2;lX*g^8Ack zLMabxpSCQ--|4ETg;OLo&4w&qPxZ&CE6O36Fw@xNn`04@kM9g@jliO3!S~CF&PmL& zg2SUpKRyo^88OX`>2FkMAA?4hp9i(ZVg;l8~%%nzC-uHHN`;8r`e zz)+bbU#oqMR_zRF%oEPi%=xHJEb*K}F_oM6r%82EXW|lJTD^)VaZ2ap`siLZEEkHu z{)0zUDiHVxsbMEKI}$vVI+`*P9Y)y?MMLw2WilYSud0u~goXJCca~kydr}e)Hj@P( zoS5jAbuM5bzQA3@|laJ_UZp_EOVXb8!i!J{;YHtCK{#n0PQHWs z3k7g%Rn1}smBc%4g!>Ku=NVPx~?7V^#Y7HfD?QHo#~_re+}F%BahoGlJ*naLhHEx zBn_H{{U>^4=Y$A?Gp;nL7n74A`K=i~>*6L9RQIjJWq&koB}@qiWfL9!R;O=j4Q1$b-D!r9abnsecJ&wtnLnwnVt`MCMZA8!F|K)t_`n zmsMiSXbI~Rh6sHc+3n}we%(4Uri?mGM$Nk%>_Raql$qSjnEr-Y7Hh{QhMll~ z#P_Z#!$#fwN@eC}>W^db-Jh1|R}aC2%$;=2zYCw`z-*-A$lm^HoJShzu4}EVq^jk# z^8bmAKfbWQI? z*fIUp=gN>1*~WMSm-%45%o;K)axY~!->VPmuFrn)o(D;x)0(_+7{CA=^~+Ra{r`Aw zyEQCtsOuGRb;e-KUo*S6*1gzW;|}i=u8nUyC}{Lry=mRmCyZ0#h28WD!(b^DwexS` zD8ty5?S%d4awyN#U2zg9Bq43*i?*cW>{gK(|J(dEHl6)zt?dnCOcPJ@$yTmAJ9mCB9Uk-76MV`CW2^+R zX#GjiYea3qd*zl^LXZNHXU!;E*;Sm(N2D1Uh_=ocn+997r-CIaEE+sOfTd7`8{}3h zykg4ux*euXC1H@&!qI$MZ2s|v0?L^^a?Tk2Do#+bL=_UVX8F@CX&soYJ7GI>Ob20{kLl>KHxOPPw@TMmuvv_(3hl}rb2 z2Akw>1!@Wbd?bbp+s&Akwx#QrN=*9!89TWIhsnw;#D8$-SOu8UhEG3JMjhqG0d_G- z#bSWe#{dGh9}ptsdQW7kCgfaJp=2{Go_2g!s%XlN3rE+d`2 zQf_LG$^3cKTZ_3XY60P!h z$)~a?`c|ixl`TOrAJ32tV`%S^+#q;dBD7wtp++sj z8gE-s65?f4X=g-F@0fb!bod~vvJ$y;Vz&)nJaZg;XvY>UaZ2qr*@BeV&BUanj08&L zMa?q^oksazsWavHr2Wr4IPRD7Q~pZ=ZuvgE-+5pXM$I=0I6E!%Ms7vny9D53Mc?sD zNKacat3O@4*D8szBJ=xMVa@T~fdLi&hge%MDk<5wVJ-N(qrc^Jy#L`^RQx}i8vn05 zJeHKmPOH^?VXz|fO{IGTsnqIz7gX@5r*{t!Y^_&@FVedR!Z*PI@! zDYRO{^Tkq2%v9*@jy9K}Sb_he1GK%Ak>U_oD%@zRfz_H%zvMPjPHFyCPEGvV9{SYU zgQk4u$y=Tdc{OY4-O6;)RtSHFZ+)Dh z1XrHZ#j&k3R%+;z>EkgJbDqW+ve9R$Rrx{hhszD;GIPb%2+T(-yk70}J4u3rJ(o{r z5?O5vY-J{Wz5?ng_wEn3D-9{LhrISdVX!|2j7B#RQ-meT%-`r zEQSo9$Qvx}j!3kj(Gs|0$k7}>rxmUb@3-MyJFmHw1t z)D&$SXA^tlOCU`ZO6j;z+?}v-?zfkpNO+?R0SQ}y5(%^Lj13D;?>o23G{1u>QU8kG z#v2u_gE%4pNB{2&LWG3WZi(vBZhbQ<3~OF6PcBZE`QVmVR~Pz>xyZUvd2SY1uQc-Y z=wcKr>B6$uwR$u79(wM6FUDX3Tg09#*MM^FXlzmaTTPk%Z7`M|dm>PJ`-^MWBRHQN zj#%?%Z}mqw6R2=#-9pt1@yB1*U?OOP%)3AnqCKL4fn4Y4U80CWAPagGaw9h*bM<@3 z#st1!3UuWV=>_i}^G^-t>r~R&zWSb(@9K1<`wHVf$*-F8<2qZ}A2el&{c2~PO~ifa zYB2iGKQiY?&3`Sdhn6p%K%VqvNv$x#;Yf(Fuvhq9V^^-&nC_e!McJIi2S&>z;kQN? zExfJOITKE(eF%5h6MN1xrC7WA`=;UVyk+Q=V+p|a7;E)&%H~S!T{H_Qk8Mjng&k)8 z^;+w2gV%!K3qLF|G&El)K|+>gn|X^yZl508IcgXqOp_X#CmH|IZIkZF7T=0nsorSL z8p-DlLydXyX2dyi|10TmedYvS)T!5?aGV^Qqumc)>`^YyrEWMlxe%jcDctu0z5D$E zjE*)4ZU52f=pJ*L=1ic^uhCCg;d3JDpb|-{>r74_U_eX-cKpYIqV)Oj%lE*#kUs5R zLCaFrGmETC>_*^&#W%On-{}nW81z9OB&i%G8e2r4EO@6w1X-b+^@Gfs{AJj5vihV{ z<6ePAFu^@P!Lm6C855$Bk!4UU_)Z=($Hji36$)jraPz_>3uS*kpGOZ|Txo z9I>!MR=XadGD>Log&$&0;coOoBQtu1wxbp$_va&vg#kb(bk4xD3|MwIEGvzZm)vt# zT-zp8OCe^4yv1Kf$gFvI7Xa_w|4hGWlh56ZvbJ~omE+kG+U{o2sb zHC)#M$`AWq>43gs1&AY}&hS@L#!9X5It1O~<3 z-|8n%k)5_cl>y+2{10K=^6+IHEYU&CrsHleQ5ITofQQ5ib&2ENsx>!>tL6V!QDC#q zl5fr5Y}uAtAl(Rc517PdjR!4Hr~gGyl1QX~{W!D%l+d2~_l+6ai7TsxZW=?T1HEE@ z*d)dK9m=mL!0ltYaoP+>4d)Hsj35J2&e#-5(~@VreL3 z@|MfMQS*Yr+7FcQ>mCntffp$}X@5yQ*&fII=TKqAPG?jszvdj6xjIqdgr}HX3K+0t zN-14pj%IJ^El1X}w?*jpRz5Au%z6&`&ZR7F(QITTF2uiAV&Zl9x`c9!w{bD$?lzVo zn0@u>z{$69eB5!pp2QrU6GutEJFE4G*!Tz1b7B_aQkUsjN##MM=aM2F#1f(3*V|}R z&K67O{7H@F{(NU4O^5c*g#`P=>2i%NO5_76`!GJd%TE+94~Szh7=xK>*%k9DZGDfP zh#-hiduM}S3KtMB>WOT!BV1z$v?pSE?0*n#)N{=K3+VW)rc+?10HUG z-(RO97b70``Y%ywG&|!LQtTzUb#oe$o4v07B8@ER5lKfjI$3JKbII|HY3bIR?7OSbIuKY$NJyypRrzg(DAeupT;T$sT% z*va*CoFEj_a-gfQ)%pgchiG_?{!EHh-+1JeXY(J*N)n6BNdAY_#*#0~!JDkt8bVdz zzr#J!JcW3)PbhgQbULqb72n<7u9TZC79Qq+BuVZnqmZ&IS{${lBwIQ0En@tSD{kh6 zz6xp_znElgOin9kFQn*)0XEbo(~xD~UE$|z%D1IV*N4~6wwjQ8`T-(}vZjSj+ok*a zY%VxFUoNjc)R34GVgX(YyweqJoZrBp1Z1&Lm~VJR?iE?P421sOJ4(!fG&YK~R&kaO zpVSiGSZ0_{2b)wa5m1HoPJ?>qVc-T|VE)0L=1B07Ta)Yv|Gjdj=m%ZuH1SrQJ*UGM zu}{!AXugyCq7%zyOG;;Ll<6>iU|BXxhO5kLJ<(xqO=g196MCL@2j+)2?l|gnU~UIE z;Cr!%VbkgR8c~c%E~+Zu$hw_wzU>VHx3#M`v~t128#8B`tBY8cCQI0IGSM|atIi8j zDbLxdd)>k0(g|_|-FMt6R&39#We-t1D1#ox>|rfyl7X6p?ltacNfJ4k{RcifG};qE zfmP37natQ4-kz*1&1Y215;XE3(;?bChNWM=!+Xdr8p%(hl!@-^HTmg3=e(LgXaB=$ z@~wZoe61dXe4Lad^ftAP zZTeg8e?o|puoGLq)OXmOrl_YBQ-1$q-cT%mE1ml~y*;>VHn@W+6b{6DZ~QAb4XSy@ zTk>EhQ4HeSszKu(l3cK+w!wVv-eQ$qc*l~w9bGBkppOUAX`NP`6O?Q%ekI{m`%4b! zzvIlsW5YwP7}%(HL#XEFf#-5NsWaBI{yIh)PUC~ul+BM}@zW-%{dUKxGD2RoIerE(seOF7 zNGaiiJthwxt~-~hJyLKF3*7qP@5WpU6lze%){yZS{V@qtUe;A@a=0 zf4bxH!g=caQ79FKBT($fh#xtJT&x2cVVEOIFo%e%>QLbB5DG&u0&-KJ$hF=0WRHPg zY7F8q8fr?#`0JkAJjA!`a$A}rE1v>%Lp>1WIO>8`O%WqwkK^O>AC!`)f z(c_6k3W}X;cSt`j#qzlOZM{X?;Cu*GXl>`M4R4#+IhUn&%mG2&jq+RceubHPBRtQM zI^MjEcz!|1H)gAx4N!dJziJKQUEouxb*W((2iW0a3tw_5=g`?i;zB?vFHPPqBq6X}_a< z3SZ1G5b;hd2~x;k9IqT?vpGkTV!#>CZYJN%DJq%%yl?KlUz;vQPy41c3|&t!&}K!K z1q>0ZDBhV$x2g4u6mJ$IDY_rGeU4<-pTn)*_l^{2W2KHzWY&7gVyF8D8w}X;CBHQ= zF$a8utq({@83YUEZphJUum8`N@bJGwEmlZO_$mKeJbK9k-ixD<{?h(@A<2KoO5&4+Pl52v6F5_=XwYcnSJ)^=#TF7VcgZG-B#qN)SgN)ZC|!KbkEg9T17hWA6z)WX;xcSYKjl9@t@w`Fy1}v*&WWMD)o>ET7M7AaEwG3W|+Q8PjTG* z_fJrUX`}^LXa<$3e4en^Pz2TEfJuJCR(^I$MNSBaLh%3GD48~>MTY4fqR1H$RBoGh z$Ly_lpdn7l?HC$RBft40faJm;!dmJ!1J`J=5Yzy?Mwj1*tY=4zMYrdAL8Jk+^;_sx zzTNqUXwU&zb^`A9ZsBiGOpa?EPv^^VDOhOxV|%*-`E*5h%Rj3eIq{X#Ce5uR(FX_j zSvu!lTyiaD|E&t>V9k#4x)4;x^9bpTy;1jtJV&ekW4LTpBP6BnxGFnTQEYd@rRG@O zlSBeskj_I&!Y#}#lRgHn%i5FVBa0X>)$sZkquvagqXnAn_5gKJ#bIt+n*d3 zmZDf3DPE_8%mPUAwu|H#Bqb+rNxrW7FeQU~4)4%F-caHb@7K9Qx5W!WAA#`b_!elX zqJ1S%beuVVl}4hlSZP4vuOyI6f_IE=0yxDJ;wBmz#fs8cgcq#$uv63mxTOoWEU)op zq%VIburG?yd?&ud`77Hv7R30*DWP$s!mqC7L`~(T@V6 z2t^cdROqvFtG)n~iO90mI%bS;Pt0fl04- zcJ4OegSOI{k0+6R^>$`A|#=nd#cNGIFtN_ zECV9R(jzVr6&n|4B|1ijzsC(jrz5))<~GsnR-1^R1>0sa*uvzuTzYE{kgqR>NeUjJ zPfPovZ?hLb8W*&V7H%YNhgXi}oPz@Y?RhonOmR zEOU%6ZA<}G(y$9nd#4?bkd)OrqR7()(xZ*MZn(%{ACQ>->TPsIGqoI7>Zjfd3Gb38 zkd@pS2+1M%1Ii`C>7&U7N>RVVkYOk4a;B+V0B55y&Erlj(LyF~8+B!YMF5ng;^`}> zKDMRMwJ7~P5RwxSA$TA;HpQDy2~F-#y6sdMT1mXys1*Q0ro!+^Bt3?#vzI&N_kVc- z7_5K`@h|u_QTepnIJ4@85^*XL$xSxewLQ78eXB7)AH*-MGx+n!Q$Ipc=YX+BqFN0C zl^7KEyKkg%=Yw$V9*YK|VIeHQ7M*6x!NK@d^NjLqFG>tlY*$N)I(1 zrt|d-y?DoemaH^_Mx7d0o#eniWe60pdWFlBzvp5jkFSlT zM8Rkmf0TC7jnIe7GqH<3+7c2M-p_(tIoqDXt@rl!{=qLYgd1N^foJCNcFzf>L~pK% z;;Ui)#IGI{&K9t;hvRBdoQw_u%(1?|huzEN6`Znn#QCCY!hwQ<1|nfZvO)Z7$q9~A zd1$nn_i|$f`uh6z(-=mJ#UgDui~YgSUxbV>-)$P#D5|}YA~ldnkOLM5hKg7;&ExQ} z$c8GQ9@6Cd8hv?6Mx3PI-%X%+&|dyOyN!Gj+WLazfUh#zo$0A7E`xKsHC3$=83c;C+)yn51v9D}WGtN;w2!u^!np+o<0x2MWjHQSeI ziv?$$@@9YN{V(RuIl8iLYxA+HV%xTD+qP}HDyXnx+xCfVqhco&SDc*Ko%eq1ukUSs z-J{o^XY8}~+WU+%)||iRnR5va!f#$2&U#`b-qhxNb?H7?;(i=Zy70aAHppy^DYT>- z>AL3kac|2GP>eD6Hx@r-VS0RE!doZ~=??Q;4?)!jz&`jjl}6LGVNy;*BC7E7#rsr; z)t||w0S1CLtMVV@`&odBLoUp7{VQa~g@>a97iceCD7_g!7< zP3W%mRbX;dSs)FAyf(aw!04;~d`>{`@`^RmWOIuz7!PfWNr+n=8mH#h3UJ+|-EfvUmWGt&>cTl$D&k^on(ocyWx)i(?*?mayxPeL&`3D=@y?k zmY-ZvebH4*;2Csn=_hgT1yQ4pYI_e;@_8TwqZb#GBiCjo1@d9tE=){`&a-?cU}t}} zh~a+PKa{t&OgL>oLdXqndEOG#!a5cDZ+rBtYOnDk#72C~}M;*+5MWkZh{PwU1e@1N;2F}yyCW@@h+;B@jUbhMt6SoI%w0gNH z9u4{1lnG^#3=ZN9*I}YT_Il4j`SkH1^m_eMC`zUuxBtjF-;jl64KB@wq@vyagyfns zdC|3k*y$|cW&8*8nDeoXDiHl!6U&hH>2dA%7-3l9d(r6j&ZbGu+V)E~B zuX5$e6f(5b!q9D!J%AhX3^U_00+2J`$mm$)UeBq4+XpobcPFb1g*Er6p(wg$k!;@RgoJa zezr`i_h0hy1&#Jsh}>xe7a9jV)?j7Ap;xn2NKstilPD2&&D$n(im zL{oVSjIbLQ?JK9Lo)l-ldSC81k)L^K_OF)}IAYLYDsLIkk7vt!Tj}LTM9>XHJRB8+ zEC~^1X;NgTAkd5vY&@8PN7PdN3e{WSfAGqQFMd|(Wrm$Dn^%ovCUuc_`4k&Tk~X+I zwyUvz_vNM4uqY&NDRt!+OtM7}&Qv3>o-p;Rqg#LJMXxe{^1&p5r1P&J@F@OO(9XJ( zhmfQHT3`99o1Ri+!4@$uBsktz1xBSc&~T?97FFb*TQjKJo8a}OYwbs#G;$A}?&-~( z@)JZv=}mA;yb07y_hQx7soDDT&;2i2IPM22Ivzp;7A;OPjdeL=o%#AwuwRJyYG@Wu z?v2g}5Tyi0WT&Fsf!*L$I&EJNdBRG!Mb)E3v=gwH7!i>XJDM+POifqhhZBm;j*YBc zIAfb5?sybrLB4zVHMoa*1mamYNmb+rHSL^ZQXs6JR%Csn zS3Lmk;ZhKA8=ITfvnDQN1!Hl96QJ`9Ey%bUDGBLpf20AiYckUEk?*d;^gUi(s$we+ z+H${ubRU0)cJqDwM^__f)Qy?vsXM9m!-# z`=CrNtA_}7DsrkqNNBkWKaWi{w?Wa~cJk&XHSTp7X6xyeS3}M>_$Bc1$B<$5VN^2# z9~hP3T)UuLDGs^8TT=3KIr?aFWz~uu9MY|75UdOwd6F&LA{$$=5F9lf@J+%TV5$zn z)BcU8oX!&25{_jemp$A-)Y9o!53#?2Z%8w9x*QH$_*h41B95STOiij^6~7lB2+q!w z@BHOjD~clpPTv&DgrDjYfUo$o;YNCMO=-G?pkue_+rYMS@>3Vhrn6uuW%aEknhD=u%%5>vjj>e%4^8=%h zI0B!s7-y!crKU<(-?Dzame1{b82EDrd&_Sb&FzY`dqk3O;8+lHX%z^1jgC)Bh!3Hd z4{~b4P0xPiVJO8#a=}!zxBx{=ODxmm1(6N5U<0a3?T`$|OywbEpFNqTHP3?|+ORpG zMYs@B%%{u567Ol>k5~wF5~Ce#jWk}S?A#mvZ{j(4b#Wva8U!<43({j%OMDc-LYy`c-xv`a$8~g0q+|V_Hw`19kV#i1%b(# zkO7a2RMy+{EW7o=J;J+}AQD4B51d*$n43?Z4HAW25`yEnIn}rvJ@rWLf>E1&nKme6 z^r0u?oe57plrU+zH#Gv3FA;`m8q0GBio!xtJ4%zDBqr@lCz|X0Yt>r_Q z$3M?}kT6`2zDMwr<+tiN{uWAm)JP_kxE6X) zgY2_wWs#CtkyG_oM~pw4cuROF1_!k+3Q*E$3;}8tnMg^ZyK_1+na%V?7I73*VH-T< zN@9EsZ`B$@eQ+AE5wb}uabm}UrBWNZTZzp(LmcyGC@A>k#0UT@<1RCu?~GG=)QoKR z4^W;|Q4kUmvSNAiB$v;^aQ=1fZMSBpM7allNL0uG7ZGUi*KX7R-16fru==6x@d%UDCtdPhKLpscK6zZp!I;noXf)({` zUXI;9ZBKOgpG5S09I)7BJATK8>UQ13X%`@?nh38o!+EZ9ss z{D&3if6U&Tn2}V6?(b*yqUeVmvV&1`G3GW>_49U5#Hxll>CThAM#k*iDi*Asi>5vA zb+}y}Z(u{yhXqcIfUl|WuF1Xk$;DJCp`14TeqOqZ6xE4h7FX$N5ANJR)iRxHy`EgnjwLqOe-giJ_@1S&A3kKB9P&iJ5+~jV zBL9H=G&N_>FL+4)UjDU9MnG&yk-W%?5F3}H!LZ`jev0MONn!xm(}KnJb6NG`7eD4# z4ID~{{C<*fcIerYCdkQvF2-tG$$}UHBGwr>FBR~b6EAjlf4)O0anEAK5hgbCLhDq7 zK^qDi_hT9GFILQ)v!$YCo(d=%>C2RFu{rb=#uM+Mp{{{u1Mx%^#fIXiKW0DPBS2iT zM0*&2XG^xbzPX>b-p$6Y8k`bSO!}tc_D8yVtg_0bKf>QSS~#1P_kFCM8rmIMB0my{>8GIl9h0L}cdgY1A}g{p@M5-ywODRNtb4 zLD1Y2NUOiKq2*InSq)E`+9NMH!maMI6OTu+l0=(+TuF{Y-+%scjwG+lcBL3Z_;C5dm3d>4!nGIYrmVD$rb%w5K4c< zOFh#Yiax$4)}gt;3qyRdnA*L<08LfWNyMJIjKAI2W-8pEUjtW*cgk4CPbE#dYu)I8MFNxM(1_?S-Uje-pmuR7}wj@h>4uE zK1u#a05RHvxHC;_gLGJjjFjEa{?Iu!C)!;V3KMn&zf)2Xi0^l-hCQAiHu z%=vN{o2NLTBlfs@6;&oaAwZheGc!`iazp6^5Y3-t_x3CQ@@tj*#Kum>*#2Iy*-L1f zKjQm&rV1}{5J)CuWgyv@=DpFCr!F;>a+2$a8q{W*Lb4EUbKHp=cGr_5v?YZX%Z52mzL4*FECR z)3a$eZ(|U>oOd&>d}Zj4WfKb4^0%7H*OTOWI^CC|(lNdO(Jv>OwIX71_)+w6tN^N_0r6xlXA>Q?E>Z4#CVQ#iZFd=L z2_#^3+GinZ(tA7DBYtz0t}iWoi`?0dM!Xz7N+yYnrI)SQr7LHX?xLYDeqvxlZ*ih4&0gn0r@i+r3v0W!aD)&^Pygn7y@oK)#~iEn@t-NvYZ_HlXI>j%dzj*=Vq(uP;3jb{-F7czCIaO z_+njZ8u` ziCU^+K_)&aNliM?E+#1%{BH8$jU0NM?j4yK{;+NI2xWy`te~wK*6*TT!pt+|i}au^Pz1DUVa+ z&&H!zUEfpYvYxbajFs7nii<{Yb1AFXN<@hgkL$@l&+w4=j9JQQlM#`qh`iy=`3-7N zKhLLRtOSvek*qL)az@AFZH9FNEr%V*DJ09pBp@RBPZ-jjQzmE3E$#U!<}V}BZM%-l zsw*EAL$}B9`}$n=pfk-B6~4c|QIEbgL_KQPCUAPb-wEcN*G`~o1h#qiGZUg&5xF>E zyU)xDhsxAmei1JcViEX5H;Yq1_tR`eqUBF|u5_soxs|cY8*gT@5MKiOjX=4%1k-Z7 zu&v(i7Lyo`4icUG{?Hv|r+J6|?q}7E<>*I-wm5ZIqt^i^H5xMiscjp*4(g=)e)?j~ z{61guJfY4}O1w+5KCDjT25(1MD?%nGy?ZQd!wB{6#$E9SjwMQxevQvf>^#r8b&}<8 z{`9%EHc5(yas~<{)h5aPQj+)$*cPce5j7=S@4W{wWaqJARC6D(aYtNMfA=;RHi!c&o>F$1-HNibmVX z6ux;gYv58BN-6QUh9W^m({|?lhPPe}dbr|WdA&kaTW^N(@D7soV`Y zrWdni_odw%nacAt9SSx1L5G1FQ78f7?TH>0B6$YH0i*r)`tf4s1xo7rNW1?@VQK2# z>RoeV1FdjWyo2EdMrt@3osU>Wrk|&h_x3|P6+AQfZOUbXJ2G{gdoXSUBsr-5$e3{# z+lUqwq4TY1V<j*?QiEUDmw2!g0d>R<6)WY2^>-u?SryidLF+ui10xMk zv?}9OAIbvpxo$U1q0rd_ z^OyM*;`wyaU(-^mZPQ9t5=j8u%P=?3P_wPYjX6)ZU*+%s1 z-v?zHpP+2UIQghM;Z1Bgp7qfDUbvPfoTD(Mj>(^_wu>_byOIK^Qd=%(@CIJFWp^OD zNm*`0h)yY9Y_U#<8#_`-t@`SId+C1S=~c2q3jy2f`7d68hy^Zt$6uJ^XS7G~oE;Qf zqM5z{yA3Tz%q5=mG9R}Sa!O5=tq+^a+MF*wC2|G>m74nEW_D;4Gr|aF$4ZN~+WfSM zcAFw@a;?Zcvr+N@5@o&K^4FqS9We-M+cPGhlQ2c7VQfK_t zcgOj8>jkN0i5szdaW>q-8Y3wnJUusX!T__?L(yb%L(k2eyxRI1o5u}y^8bHEhW|_D z|Adjb@Pe?8rFz@f9PJx*0R?jYf`|h@fRo_~ zodQwymTn5yL~(#Cm48H!l(+OP9|P@rxJW%P3)# zf4nm8qQsu%u85*UPTWBughcd+M|2I8Cg@wdicp{K)u;pA>;d28dHe&k+-47c-TD@{ zi=#vPy*7c`mj`@CPy3>AAz5*uh|5R-k)#G$E4@xJ$Tacf=9VB7Kw#0}$d7P!VyccJ z!ItrkL;Y5bADmxqp&+dgU~7Sz+>{S_aF~K8o1#hx5wf<__G`^?8NwNPcrK?!BFNXH z_boc;jzYTRWDLqCqA0~5StQPm-im8KFxTY(vQlnIAzYIMp?3+^maBg6mFctxp~LT6 zzY+e@M6DuV8m0I31*P&oL#5Q5_l*{+1nmd0$R7!H0`pxyQql+>!Vp@4%etSAUE%~T$1YZcNB8aVQR@BZ)s8KVFR%s|W@I9t9fF`qKp7=f!BES^6Y zgMEE8S43gEY85HdX2f~>%@MF(msk+a#)I%0UHhIHgZ*>GA@_Q|(fGELCtb>xn46oj zPHZ{f`==1x^hClplFq%3S1xy$7Iyjm+CNwdA7mMu0wLvs-LlZR0&Y&fTpnBe`10tR z3a9o7C-=+X$mgaAZto^VIQlOvoj`VD1WbM(ujNbWJmut{O(>`%)PJR6Ib=IoBY_!$gSW3L zrU6oa-v?IxKk|W9R(16M8;HWJ4NllQ+fERcDBoGMm<)rPnTQt@=jL5ah!-w@S-o$^ z>md`M@^m%3#9(2OLDa94I7+$5qlN#M8Ip4&xv6Y*1txE=cDyl4^j6wg-dm?10~=9L z-Jz=cxc_X(FmvKeODtdAkj@Eyk1W|f6M5FR;-(oNV)zK{{gvJ){*C!N=Re`ABwMH^ ztJ#7;nZG&4T!*m=8R*9k@-P_m9uXt{W){2nXR}xma=-Pb4Gf#Pf0CAw(q0ugnxE>^ zWd0u40~j;NpC!Xa!p?Po|o-}K1T+R=%zGMsOi zA~%_rYQ$igk`7i^>4$rqMc)!NpRcPaO7Qs#_+HuayRm>_;G{26b$4cq&YIG=%)BP+ z)o=NF<>dmU`xw7~*2fi{Hze8ZW69G6s#m*!kYy|3*wn+ijYlv3-@QY*C#C!xo=KhOQd@12ma0NXJU(G z3P$%F82&(*^On=9tOpos^ILBJOD~_Mv!Nn?f;uQv`~$`Je1AKG^oXh{kxPxC(!&$q zk@*gFMhbk8j};s>bHPl@9{FvV4A_*pmxaC$Ur@TtO)5d6C~spnRhHgTH~NN#&}=mcOl4 zjFhh%4#7PLoiQtz?$b0$@bl5P^jcC7{=i`5CYZ624+?z;?;%g*&-;PGJ^tiw%L6ZJ zwcgpQ3k>1gg)oAG*-BCi;wO4psIhXcOkgVj(yIU$ROzIN?1gGM)d8ubgG z)uIoxvn~hpz4?_w2e2j(Jr!UGbN&d5>uLUJkKx?1!T)CFKl8GEHk|sjk^9WFxKsbc z`?&WY__!Aay08GZdUZYWs^+s4+;eqiygp4L_B0C|TBXykPoYou#qu>3qQ=ZD|5!n^ z+vrT6!nM4XGv#fkdS&zts+I5{y3#XeW@^P!!jZ7~6_t5|MrK^9aS7@cvw-vkrLGWpwVhMHBE7dO8=V#~o3K9LmP0t+6xkxLzgHxG*pvnTo;pQh3m!F1QQ3m?lNtBFS`rNONn5o^aB#LvLJIl| z=1|E`2x>`LDd)X^S1&Mf$FnZ~X8B;*x>NhdE`*9C+>pXA(9R=KvSWb7y?SRtSIdN_ z*U^7|h!_N!kpnkyjem6sl>g-tFk!`c@*j*wjl$yP2(AH7;1&q{I`83AYrR2*av(4X zYDvTYBl;-D((~q;{`mGIfN;KBHwIw)R}#ePu8*uuxqEy+_*MjI`+MAc1XN0fPSlM) zW+4fwF&8kF#vFR5STs926FRRw=bsiH6E$4a+jMQ2aty73GW7%)@TXY=K0rMq-idfQLpbdyf^|~A@=j#mT%!2gCFNMW9eh4{@aJ1pJmvc zEHOLPBJZE=s6Dm+l5XB1U0hv@_Z^q2w1J+V+Z3f_B`d%m z8#=~ROk6iSc&UYsvje*-efq^c8Sv(yv-EY?zY0WFk4HZzt2fs0o=g}#mNq2gu3#3? zVXp@D7*kOy*1ni-D%dIUzqmaY8Q1FQKp zM9%S2w2d*2cUb4S{jVaLdoWP69nP)+PsgpPMfQQ;qX7tqy5VIh!;9HE33i%!B35tD zv6J2aLi>}UT_=2EN=4+HjgX|P2G4pjLXy)`6qUx_N>b?1FvTv+y>~H^0$2=ET#Z6?x|BhDMuGRgOzkg-A{`P%Keq2@d z>HL6VICUHfDi!2kixlv4vu_?1Z^F`Y4A<1g<$!OfPZ#k#dUUx*ZJIq|9b2ZWnrjde zQF$*Tff3NnSTaPpJm#q$H*E@0iG~~o$;mR?Ad;ZYh!bvu)(sbO;j#)&J(p!-Y{+ufO!iKJJ6HP~pmqAhpPr?$Gu{$HMoCPptM z3ku;xy%v2ZgwnudeyrC`4LAjZ{r8^_?d$~-Zb%$a=sj09Y+VQ5C6_$qNr0B+wm03J zlPm?lI{ZvSs`|0idCv_6h300XQ?#6}Hs**vkF)R23$`CjxwV4#%lWMd6XOpT`Q}qj zcp8ExbA*=D*TA2x|FOEjVk59aBBt7MvJk(V5ck^@frv?ACKj7HuBB>Ww=LfTN3FPB z9eC7`u$2f;HUaL;C1r2dh4+ar+IYfrR1e1Tp}~-9IYyGjQHH07YV%O`S;iepmu?9X zzR`fm7qSK$eVq-a@bpzMm^RkjJo9Xb{@1F%1jVJcnD@)t!_jRuH8ucae1-@$uf4#i z7|n`B@R!i!*2YTf#R~Llou+-@iLg}()rtP*_)AO5lyr0L&N**QzOV^bfCg;zgD`6iY>h>=e6lhKiCOqto`rD$(!=?t54b62h)Ng8a|M!LEcgqd0_s#|;b{Kjkj z#n=~?H+_+lPon>Aa)?D@bdxn|++qJ(9B5V1qQCWZxX)xh3B;t!q{!|eJlr-hx}8If zEh#M+mAuKKkqfP0ajw`~qIIC?B$KPRu|r zuwS=%{Xm}kVmj`F9T2I4V0}IAs6s{Jv$X7@+endiI?7t9Z_ajp30}DYAj00ntj!TX^dM0uP>v#U*%uf}ly>DdAl zK(@`P+Q9!=C=z)Kqb|T(_TLJSKZjKMg%A9hZupd8 zcdT4g&Qa^tQ8!*GXRG!4De(5h9HCmZexmPJXk!VIw&Aek_e+;!2C)n;f>yL1#e+Ui zwB|k0t$~U8soG-32^F65$#nXIHzT+%#dm7ZgM@bt_(|Q00#>Jt#+wvU)6yNM+(2>6 zKo6GYuku9-DLVj1YDtt z5*8YHgNNV7l_CE?Yc;uG61X8K_Jmbngf@^d8yOIg5O~;chn5BZ-)_?B5!)whleq#CxMKCv$c`TQn;sBWjRH``6+c?+@D6!HH|TN z_`MM7P(q?&X@?e_z#EG~o_WP)%9Yh?4JKI`LZn%pS;EhY7h`Z(`Du3Ay(;jw1=blXQd1HC#G^Qhl>o*#JbI;d37lErLZ znN#s|^?jw|4()`-#ixvg!Zv*ye{@Er8naULyo^W-QZR~lp&=(vsewwog zmIV#9m{V$X%4R;%L}HHrWlJ}oE5&OLqJA$`p-)HM$%rz2Jv;Y*U+bgpaZD~u$BVk0 zoX>q7T{=%Z&bAVn(H`~u;yNDhzZ^Ob8#nVjHotlXMc;_vUfH@@?~X~pW>OpY=VOKU z@`@(%60yhE*XJ@cL;5_&xl9jX2sq&S3_P=yq$}vqJW!Fu-R>Dz@BXe1R!a}dBROtf!XJWnRGYlZ6s=aFT^inF zVX&!blAojZe>(4BabBSR5LnDD)eSB5 zjL!FI1Qq9>m{YWHy85Ac2`{D*)u#@kz8o72~NML z!FaAOnM7mOzbv_rXW|X=R%NNhM4$*liz`K|SWha{N9rp~of8v>9%FnSpB|a0j4V6B zSgS=!mD5ujx*oR>WhXuGi|sDF#ZpZe3AB>)%6^48txcn#7WacW{1f06YkJzZKIfGISH}> zg|gCMeP39D5oSI9qgI9wx`Au9_{N*x&}JVI&&*Z>m!z0ja?w*4S>u%tw*DI#*)LH# znX%vO-P%oDQ#}O|1({evC zw9@Q+E!WJZmc@h)h0NLE2_%AvTSl#P`QWtJ*8FYFoaLpkyn#mfOFUIfM+;Oj7Hl|- zcxsMBw<(izZ1+UMB@}Wwv{S(nF0D56j`T^g^FT^^Ff-E+57NUr2Mb0KH=~wz)sh0j zlXTIuP1hv8OPWR;j_g&&VIv_)q15BoPA|MJf{4M9Bv~694v8Ks8}ZgS*8zZ*NV6)H zy6D#|*_9DOXjW(H?Ql@l!y5}x*|Egg7p3+_aBb_=wAadC0k?h_Kg(mV`O)7UDGUXd zBV`1<@zxqM)O!fT!6sAz*8@q;ogUtIn7ySc+#5G25!--RRTMG3quI�zqS*Uy=xB zeZ$<*XDW$Kiul@=UuwJ$T2-`MAe62yAF)p{V~R%x%$-_t_tab%EP7x}PFo5roM0WA zxKmOC^(GdG>C5q~NKWNYj$2Vt^rH^pX@6IMq*O%fbmz>3H4$?RqL1;({y34)vJ(fp zh2$L4`%v%p2GA~w>M8Se!7@SJ3^sB{AFKT&I)GSTsxf){uIEQuIiD90DywP{X^ETT zUqA;XM7WR)itiVhP4Q02Bl0q7vKPd8yq(V+%Qu&#uz7-90F8!9kqG8spU!m2@3V+7 zlGTuSSGiPAxtV;G*3K4rCkl;aBFSW{6L^w*9WqI#0_1mMKQv+#PG=`T($l@_c|x_e z)S4c3n6jShWGxKv$g>#Gdc6aIBbcHDJcl6SxThnk!29b^jO$3^WwpTWaH1 z_Cpl-2;ZG={kbw|fg0Z_%F>ja`Ufp>u)AAU2E$PMTZWGsLa_nf)c(XQ<9b93!t4_t zgDl|k+ZfIRTFad5aw}kCysItHGhx(l>Pyp)x?2(FE)4K^@S}#S)jy|LDot}h%$ zleI%(P*{5s^>%-%v3wDgf>>%E+cCd;8ux9#FZ(W(vqlsqNW1tDw5#}Ia~1)MA+6S9 zTCA2Vp(2JL9Zour@1Jm%)bJAPwv?7m{k2%P)X zD%i#iZEiE(IPX!iX<_OB;|gt&t(or5JE!vcr-vl9L;jZVCO3!hGzdp;f82ABSW!Ph2TX-SNu$7r9tQ$P{ z>vObH&f+Eg_#DIh5r>}#M0}15>5FYlcSks0%a4uTVf^c?FV+*N@If-a^Ut$ZxT3^y z9})@f$QV5%sa7x0aQ+%CgMoGs?m2{pHsT`!qS!q^HD(u-q4LZ^PD1-C1Z`hkZ znth?8JDF`N=rZI_M-Rt0PS$*QlUz?Jh1YqEtNz_mlGp9tYb)#}C=%krZMV!S*U8%- z&5K$bk{Sw!s|xNB2*5$WRBDmlz~oCy>-82r3`!rdn}CstuyA&*Fgh2?=xqyAbiqu59z2TXE}z;I9EykX#YXz zo*l_e>MA%P;2otoGGnaRj~CB8t^vuqVe(r!V#WEvHX|R2093?@33dl z8?X0mR%gfz&HB@M;)khLhr*xc*U2b!f;x(~l6?-lm;KM|N_ufr=-P=bvTvX6{Q!47 z@v=H$PyBBE%+ma31iVD~H-oOHBuNcxl0y0ujb9*!MrN*(DF~w%SJfKy z5-BsU8=uMe;AjH8ua6tnFV_n=JlT$ON)`|hx85LgUatN?6@i-%MZD0tnOs-~3 zL3dq%S+$_I&S`5XOYQLD@0N>9MQR#*kGLCbIf-i6(PM59SfXd)n{aZuJ63>m%JA|!~7W}a+d&*WLw*m4Oq%hSQK4pIHD1o~U z;1Xholq-Wc_43V`;We=$yKlm3X-)HP(eJV%=RZm4sd;lDz5}aowrL!#sEoD$g}b*3 zj;m?6G;P^pvY46KVrH_Knb~4yCQB+YGcz-j#mvl7iJ7@1wZ8NJXU;^QnU3h_h`E@{ zU9~GRB6IJo%qQ1c?+8(eJB=Z{K7VIYqVMt-BIiC$7mc1DGjWS#=lhi8Ji_^*06?Bq z5JA*H>EnuAoyoC969LBncs>Q+B%ACNTI##^B+|rNPG=hrI&5`g7=Vv)22I^2IFJ+`ljNUf!8t&;H~Iq3b@| z%MQ5U3V5YE7`}9LZ`3i~87`uPsVXG7YP2yrzUe(?IaO$~lIy+A)f73AN+~vu%g6|+ ze+L_qHHrCn42$cClum7czF}u-NF%_{5>&Qg3#xwS(94<3F^$QBuF}m)7S~Q1RW2`y zX>lbeMO?1CqpK2ZowGhrK%OG4f1GQ2qEd~T#2qv9U5RCO#9}w6z(AEt^KA*)t1rdX zWAm%?;10VTyt$^wIXUhlHHOAC#A@2cXgYfeR~i{R!pZS_Bh>472M?)0x9IN7+=cuA z9`)EB9~8$tkFl7ZwQasg;q&|6AgwX@wXRb7@H+n~n9ui`?bqJJq*){H9t=_w0=?95$8>#tqICnIPS?lO=PW@iv@Vt4H?`|UlCjQRV8%qGGAeKCqHN}5;cq%t%`FnkC zd5Y9tj0ft9CNHV-mh7(@5#2G|fU3Qys|>iARNzv|yCIe8T|}YjlHi^7OlWiE$Iw}r zwY{2TN^x4)0?~Jk)not>e#^_y^nPR_DLR{3)7$BC%${Vc={L8-HMEM4Ymzpq+v6=D z7J3%iPt{x-na^ZcIm3&0=`%wTnrp%#=IQ>`+B$mpXFSRz^kc!q03OQb zFYHrLX-XSj*e;gvoe$QEGnZkf39L&pVbDlEx+%*aaBYcvi!#K#KNf7I!xQVz?=v;H!u?cKir4-HK%&wHU+63n+Z>IGk~o^U zZCxPr?dArc7E1>u_GNlUr5y1M2Lkv7#S5Q z(kZ9{DzF*d77TVBe}1hZoJtnv1xgBkSIMkeh@PKrd7OC#-!A`*1|`R!bie_R zOL*+_ny3#K-k+v;d+w&Yf413rZEymI;FG$r=S=>vXGDD82>m_2!8~c ziX-TAQpX7t6ci+5-JwiXgl+B@#vMWbIXG*%r|T#{{G zNG{BFsX67~bqGVd^7pI{Z5d=bYMI_a`Ce_}w3SkJb)bC~s-y6u6vMbiyvD!?B+d!7 z3>F4BYX5(OD#Ww@Yp6m^u6BKYi%OACoRp*|DarVi-gn65 zcUi*~eZ$-t{nws%ps8Y2D6sxt`~yF~KD0f%x`i84L4v6RDnxgo4SSW`rhfhcfE2T(Ag%daeX3Y&L@DutJ7R}wT6VgVSx zI3wfwF|bYio+}7EUXU;~K}8vGz1F3~pY@ce3f&tiEB+=DLR`g*@y}J|8N)l5i2W&9 zxTC0uO#FiISeS;O08)N^^OJjPsDxQU$Y$hc&Q8VWD`WO#R*)it;61OtK7lmr4nnLu zC}uGEErZA?4j+GiDBAC%XzBuw{&@5e&-z)aG{w2NLs1%4Z+1KiXbqQ?WILX$=Xx27 zN5hxc#Yk^h#iHr5mrN*!G_v;4+Hvy^r_o{2S)s?N$LHP^`yDH@@WJyHCX1U@@aG0a>8;yWNK)1m-VfGPgN#M&%P*SxZg9- zmmhFR42bm$m3KNe-{Xcrc|2;TeYW`#>+yxcqO&#*4JE5U7mM90l@s%u(QkG`gj3T8 zVi8D}a&8mqm)tDQ{!L!-k=rVva)Y_lH$ylGr|(XwlT+bCGpDh?yrf$TicF2}!i!Xc zU^&Uu$!Emx4qxH7nDUHp3o~whNk|Ty;EE_~8>Okx9Yr3IK-TH+;)=PHO0*P5Rn&u< zl;WzvNJV{tpyq!hizlcSHh29dtJ}rV)@ah(@pz=djq5lnyI8F`l;xz>YjiS8xp=9_ zFqk{}BdgRvOt7bOVD64qr+2K}A_Sf;|9?HnIEfIE`B!f3zX zouw4hFOW5Jo))}%m?N(PzklhC<=yir%*_Kmd~h)KXDJ5V8sZ^E@=$8+9^MHj1}>4} zmE4G`HX6v&YjReCZa9@Qrf9*)y=6`7431#b6;_Wb1FKaxOUU#E+Qs*gORmXUdY4V^ zY7hpma`PjMAS;@FSxDwOcei-#sUbWIe2OJctj|mxI2*kpHK;h2`!_BFt*>;g21S^> z>OiP+hIZ`@_QUeTbK*<%D;gQy`6$|TrB?H7g+@IM!b`}a2&7~EURQD(H2=4tHXkUfX!{%G?bO)0-lAp#4}l|mHqM3a_G6-J$La( zk}hS{hY_K}wl+E+jyDFI3)-Z#t<>FEcfN749lh3-^#>QpiH?)33xe-zqD%Y(8o{%X zP4BA~UqNDD_wTy@*oY7R&y<30XZp>>h~nA`J*k7`Q*Wtwi1B2sDHjkvez9MOzc1kB z#mE2)mIRaW(d<&N@XxM3}(1AzNwEtuct-gBmom6KTZ;sz^T>BmA3+Uunps4*rnj8&x zY0<6MrnTjngBDKhek$2XZ0FWnzGgdbpW18aQxW+&FLLl`IWnfDLhH*dQpeP~Jrf(9 z+$~huE3SQrEB$w1Cn$qrwl4sBS;r?6+nQfm!%B{2kV#hZACiLtV+xf(6^zN-@kV1ajPU z5LEQ>Z~`xeIE1Qfl}AVxqWJc){@@A&0K%K!cy1+5wq%*J^8pXPQUS&_9P4nqt)ulm z+q)zq5EgTzlq=T;otEBT*@`it+Qm#a|10`z5@NBg6I50dd4#DNSRM}Z_8eY8_~d4GtPloqs zG%T(m;DJ~sP?`u381zN-uLI z84OXT;vK{mbGwy^86CNTsfpGMiG4YgltpC`Yg$gUi6gxfLUwFgcCb-}Z^Oa3RA<|z zW{X#wN|mKpXrb+a(DC(%v6U3{Q@UX7d$?MBUUA~Yo%SpmcGu8_hP&)ftjWmx@Pvnt zKW~Fw`XSm4Yg>?T*P<{?FLpqzyfz~zaf6)!qote-KkwSLS7qLk%*OQ0cxT%(6#7?EO{6rHJFZF>9+j^j@=3DSjs`O+!31?(s&osO(B2gPB z9!?#AJ7+}8c0FLqbFeq^(|&jRVEpsG60AYs`u7wDk}QKi`Oic-oQjcAXc*O#GX1W% zMy#65u6CM`{=lj-9f-F`5!)tAmIHz04fZ6p~3Hj)NBG)93lxbQN4kmz4IZHQ@tSNA} zun4I~URHP26b(rwuG@+%3dS%Ln`o_KiIK;$$*F;mlKdJjGOnbAl4?so!>V3aN>9wrC#Ze&>B^P76M|g9(XvUfs zUFpgFd0S0h_xIx;qKCw}jI5+phM{f)okX5iig_IaFUelh)A{n1%Mv_1xUeTdlSPJ$)i|g+s7(#YU`Yk zLsE3{?M_*l9vTyiF6u>%a4|5#OT(P6=Bcam#C+bq)DEA5+tciLz}JcW_;1f~-3BEI zb@Q=d;`C+KYkO18W#Ph!J9Q^^amMIob{9hK;}bHga&Jnq1qZ*No!c(4UF8%oT-zpi zB!Q{M4?e5t`~#yisYcId4BQT;^tLg&rRj-YKlT;3mw2W!FPNiaoh(rDX>h*s?g*1e*Ucc#h_we zeAqFU!RH+yDi@rWjO#+LVegKQ_jf)+4kb=PVv5-0BHxWvZ;GCXWCzMjWm^2s;N@k) zYRxf&IbAo;a0cOq^`@%^$h)bT{fA?5Z(%~BposkXwB$tnvq1fpM|LCUKw>?qv&3$e z@Jyn*$)XQ=7&B1NFMIzcnM)7M3vD)T@+w-K*bFf~+dcWMQS8=2e5%*$jMR%SR8985 za8(Qbnv(wZ76+5rj;(MjP4Z(HShN=eTZZCasyCCXO?Y9`Gk4T@sf-N(a4Wm zOI*1yp_yiLU+WqO68>no{<_TuE}>4jX7Q@K?qt-1f=YjDYFKM&D`-JhD+hxR;Pw0iG&8$bryWFI2JeDjQy9_-Io}p%fu)g~^GDHe zY;+&--Lod~xm8tE`KjugKvC9~Ls_MKITwlft%PcA*`p&CI?R}fS+3sE z#g}KXL!ewY+p*$mMWLgO>8(0HLy}u=b%(X%)s8s(?)ShLPJOt{wa>u=xWv(a;iL6k z8qqaAN9Vzc=iuS6-PD_Xp(gsQ;lBjkX1iy2UUTzNI$s82sW<-2a^?NLTo);HAaffk zoc8PJC>L#Bu3h`;wopY}|D5LiexhR))Sw9Uxa)yiJ+G-&2uZmlN%t9GEO~5I`|#!@!}znEI2- zuMC~TcR_dC4L-I3Z!u9)6cX$YR2i2}^^OXCYKiWW0C@dM5LjrLL*jCDZ-13-@}}<( zSa!(UohQU6tBa|M_dCu-ukL{8CfeQO=|sa$`v24doE}y(DAF*b5|h~tFI7rmKQeoC zfALCWiJRO53&t0h*>S4dR@jUVS5aVUzEVwR>&V{94yGAYxSR!xi+R{(r{(j8^VHJo z`V41i+&9XH&+3joSkg;lI$h)c#r;B@m?4ImWlFL|-J!l2U&$PwvhnOt6Kr^0=+Hjn zmDQ3pJ2hb>DyjGKissD*-|}ava7!FzxiOCu_TXc%-T8EL1>vfD{Qs9^s+1RkohQRN zCT+Z{(@g&Kd;W68GJJFK2^O_-VV#D7j4ljT6`k9|e#kYWAMY(C#f=b@W2-C}7Y5Jz z9p#?A)f6970Z*3U0QI1j2Zy9#vT+7Ea|<1V?@SiPmhP{umPs#XFJ9QCVy2u&XGg*^ zQ{1dJ?}D?G3AJwio)nATsOrPIF$k{ilYY^o9lzXd6RTH=DBSu0Gw9Eins+393wooZ zMrxx6$svJtFswd*T~Z@70uKvyQI2kTamrdZ^JSKAhG;o}i{cA-GeUM!v1`v|etLs~4SuN2-%6UNiRqD2_tcC{Z)3pV**+AKjn z{EkwB$b^6yQIIfbU_idc?`&1S4!0&O)Oe&Qxja-jmJk{;lQ;+E1A%$3rBk1=tz$&6 zqi zV3)KFGQwrOb?H$w*tMo_1X4=Xy+%&x_K&w{u8@I8Jf34fTqLCOGml1x9m94Fuov2x zyE}q{;%ZrWC!jX9EH;}pv3)MO!nD-zwsSJNVf_+f;_OR+ANYWxI5{r$jzduzaXq&u z8vR~-sPFF>HxK7H4Xh=YxT}~=DF;zfIaOXfLM~MM^VVOVSGFd;*GohIEe4GY8e)sI z3Vco3aTqWFW@hKW)R?F=S3b|3O@}uBdp~^$#S#OYA7hxOe#!TikWs%x_km@SIL`V^ zb%DFsJ`+cuYe6XR{jMw>7l{;gHEB~sXeuoUL+bBg^|DBJL`-(hvSBw#AaADJthGWy zXgRs!UP5U0Qg(yvz3@Zyp}%j4g&eM&;Y+ojx35SLV>Ry`!l17gor zlreA#5OBtT;~f61lalG>bvDkVqm=rWO6aHjb1OqC$PG`j9mnqGW?-h04&|Uzyn1yf zMaiYkXMyXXpdA@sDOs%6C%Fh5?*#6%TB#{2>be$>%+xGd$2x#rhhpkr0fF&5$6j1q zfLdgFwWcN^A}XDi}{4}v~} zQ@E*~0bvog`N3x1`5d_}Q>YZ%a9g{V@0}whOzK$-E`=$Z9S42u6$Cl>`wyMwSVPZ5 z=!5F;sNz+m&EU4Vr3MQvHc5_~lQAeF*<5FY0J5E;%m3w{=iwDLHozC=q#`S{*sS)q z6)tqV$4uRuosWZi2A0%jZWgoO=&|)0N1AUys@x(W8{5NdvBwbNifj62YI1}l?#cr= ziAPhOef$FtuRZrBFTdFWyEoL#*S&am4+g1CJb|I2Nb?m(QpY)q>(RVyw_AgdQ!?MJ z+=4=#R^l$_Q`Iz9OP2w`k7>;jJ&BKLbg!f{vC9DouMN#`(>Abnymnp0VvH-1$SSXR z%+YNX&*vKd-Hj$`;az``xxhBp)!>9S2{QA<45dRt9~OQqDgF&GUZ?(K#7m5R9L8!ICH0rzGi{*3EPswh6*{q52Tl^B>a)_h%Y0eU7r~JY9YMU3+Sy@vZqXEKXE8ibv zmurF_xtb4a{f$ywx5-`S8_o?^V+14IZj}~sKbps4CjbhSN7H6dm+ww>ZeOK1hst*B zpV~rZJVrNxu29cQwXum#ep?^XZQ^G$(=GP+`j93@mw>`EIjO_Hv)Rj)yoK1VFs}xS z^c$j*gZ7J{mdLyIE|i4GjcS!XW=g;+11-gF)!HpXKKYG32{RxM^ z7rE=y-z+bdoA!EvnjctcmN-?G>r`+Hm~76-bw3lAi`#&Xh?GMs=MTux;QTR1UcdPb z&}Pi3a~upG2(v)sp^V{TN=s0brU7NY)A6PFn0ae&D|GEe#_upGS-rB5aqcgd33&#XoGe0YDJKt$)e2u#-Q_ffc$&fN!@YW1d{Q!&xc>-Vkkaq(`P?eCC(T1umiElO6&En>xML3$c-Ws!}4! zaXWiUXWZeWqIEhbm*{QZcL>}{t>JoX(8r_jzl-qoD{bL-7EGr)+I`LER-u@m2pAxX z0nq)qS-2P{p4~UMdTn92A9dT&cj)Ioa97P@aHlE6&z^Fuv{b5{A7FY>>^j!p#QX4V z2!kJ7uFuy* z!(!xoMb>D>*j=K)(5>cal06gavrq_nao;v(0&b)A^mV=uO;L%SMo0FuenzqCYINXD zaCjsaZtm`C#6LYA|4N+Odd!dOhD8@=7@a>ID&}T_srF{GB=7p$jxxmbQqBvmWYH|Y z^rh}`%E)OcE#bkT-`MHz1VhHCGxzmo^@?9ilNZN*p750u%jZ}k|JX?Rntky!bVO(S ztn_q*iaH<^Us?=%rZQD$F6oP%csnq27OEyd%11n5#qiuz{x) zoT_=4&7sN8AJfgZJg+VvP>S+bha^yoG>J z>e4Yt$pQ%^RLE;OC0U^jxV+Ef%r}X;kG8t%&!vj8nl#}c_N8Qp%w8|x9l1alH8VVD za6YC5Kma(F03du5lRGQeX_nV^*FiyGGFxx_@99>jVhDm>uLaUtm zBQ%l2C5bMX28;w(P1x&sB1$g%yBiD!apBy^&6~ZOa&r&e!icV~!2J>$4gwLzHb8W8 z{t@c;%n+xigN70^%3G6r6HzBq*Xwp=HQa(h?pK(3PpLF9q(W_^ax2f$fEIU1DUp>r zWJNcAC*4dF)jDe8f3#~!0bX<$K!PJW*%vTTv#BOMi98*clV!PJXE;&mDqWz*^<{}* z-HrB)6HHZjeRQ^4N@75V7x&1xh-a+PU9z&4ZDG|4f-iZc7fe-Zpl?Gzud*&^9N?#+ z>FX@3j5MP2p76cxS>kspWf+_jQeZ$1Vq&qHNm!_g4~~u?93j`?7b+AqG6jXiy)aIy zJal(@wEE+$90jp!m`uZxKEnE)y#l5i5lDIC9ngnO41oHf@#6~TjSkYZ> z3G@2ohF2~H$&%E!Y@jNtv+azaj@3^GQXdPg>p3DoZCb>d8Or^gllgfb6qlSipGo&# zs7_omKb;9Y)Sus2_vtEDo`aGVNIjSo)tB@MG))??*mPPQ9cpu=03c!G)(TB4aUQuZ z#m1Xc0FkEHMN8K3!xmlwbuphct?3WpJ$;S%Ds)pdrrHbN;e^BNnCIwZbly-tkjAH> z_N{s4%y4QVW^M>&@9&L)Vvips!nv_&n|6E0^Qpg5x1^*n(1(a&=grgo!>9 z(P&v7EnoVf3SvWEY64albWui$4GCz&=8FWzL^v>rFfWhRf@RS?5ZLif?s`igHEsU= zu(A1e2^656r)|3<^gdMDMt)m_*MlJ`eCoAv6cpW-S2PywEi8&?=;0QCO0Bb{jvZXW zmR{0?%jtTOLVA`?)+u}!Fe(1>o4=f<)qRK0m@Y#&~YgR*w5zesbxcSVHL!?;-5e4mI5PVs&J+>j2KGfvkPgL?09 zlAI+a+`#i8RTLU(T!BSvau+(;on0|ZH(BJFo$e@)ZqCkJKb(AWkC%`}sg%wYW|qtu z=W*RuR(d1DO=180I+zrrbrBnUop>i?9VDY0;N*PAq>#p1GcDkFvG<=mbRW-wDP zN81;u*XCK~Zm-qgIj=h}Blw8a*W9q+eO6Fq=dLz@D>~o45W)JJ)e?wDp+f2n8}He_ zeF}{7{mo&bC2g1uFERo2YRc(Wb%(EQFvt573tNG!994t8fq8#UU`*+k*8gBVRFm&u zW3DHOg@$T`8K`PTWO%r|W3=q}Q2UyL=j6k3G5f<7PoK$XaRU?(O0-7=47excG&bEM z`J)dkgUl5kmX+BLu-jnzxMlk%k&=SJoLtCkfsK82hHQ>ZV=uc*kSkr z)ZC6zK6$Li4=oroMU~;_$cgq_q)bFQ{7Zovq=?+iin0t3CzY0Gl$yL<@g1lx2x*}CI|TB7vTJ()5{lbqt_R#~>J_x}yr zz)^(CH04LaEwQWBTUgc1#?$mdGdQxS^yrOGfnji(+|pTV%1RPI z2Y-G_iSotZR`HBDg5l1AJ|FJK*X)V6)P-!mp|nf2tC=Jd9&eOOC@ND}a&Q4rG@P|9 z_Y90fd;z^ClwIAkU&kFP9nWV@4}v`+D~+RTE79Zxpx&31$LFmfX7wg-dfR*5eh?mi zowpE&3%4IawWjyc*3X(@VD2Zw%RS=Ic=Dxrer_(0Wi(<#1DQ0heFcwSQMS`lK}$qV zc+OUXcQnAxD_fRw*Z}PG%H)!94}f+Z79cbkQ(-TXml+mj zz}_Doof)ztL7;%7U&SFw3iXJ4l-q&)W0quOvghhFcK43 z_3EEW@Zffos}BMVxrdHH4tJQ`;S=Hy%$1Rl0J_)#*yfl^< zcqjZBWvIGXyDLl=r|&ETy;sHfg`S72-!Up{mZ%w83rKNFH*I-fUC3)r&$&`YcBg@4 zXHAeuD7(@4L?ohxirKLpj5fHtgPpz8#V@x`<#u;bjLOk$IVENqFC%aWNp_6yi^JVM zskTzs9&jFhR#6lgf};EDJAD~SJwH}r4@2&AJs+Et@4I?V&g3K0R3a!(G?IMpzfn}` z^YTSks}<%_lb6kh=C*84Rp?}2t+e5a)c$ytFEsRYXV+PB@>ec9ibUYP=Jy&Yi(fIO z$ZioDSk7__C0PL*RQHI)m7coTFxTyA4dtHOIoSDwP=mMHm(BUbr9u@=IJiuijV7n) zU&6D`&a>ZjdmHGw!<$cUF%-A@z{B-=v#TfAn+jCBmj83pugYR)vGg^RQoPk6nP0&` zH|1T&k-*JnLQn$2u?_Oa5A0v1rUXc~N_Lg6aB`}wIZw_e^D(0w!<;_YiqLwt43dp$ zqhHezKG;ayi_*TXT|AoOo&?*vxtGoV9z9w(E&=%0geo50qaCr=!4g3v77Pf7-rxV7 z+JZHsV90}{C%yjz2~9mzmOfoFs%*=V;!dG5{i?{deoyVaU^uKbk;CK@^c_O! z^xk^UFxTOu*j%4csn$bO8jxv}?LyvUqonDSJ{(1S4@%pgcuiGU0K2-0&JmKfUX9oi z>!M8QBZgW`FX6r;!*-`yM)006+V8l!d+h6*N%cF)SI>q#%0K2V<0gXG83%qG(W`-WZ`uKTUpaDlqsIDsnOd_G))p%NpL!zHip5KraS5A8N5ws%96_y)wOR!^^&& zkhoho5%fk{oc@Z!VeFU>Sq(Sn&w!py)A$X63)D*HWLOOLS9iEO%PV7?ncoxC9(8TDb zTIhA=R)eL8%k)n9sXNu{O`C@LdC&g$oQ3L}2P!nJ+{7TF(%|*#{(|0@Y{`AQDJfE) zDLz?=ANHBz%&+0^LC60Mv9%l|?n)YrAPMwz@0wNUaU|g*CiiUkL@AB5ro0h{R&D{( zdR&2-XaDgm9D09u?;v5OyVw4#U{ju>V9vCH{2#0l2+U6Nc;SZqkBB}2g3PuE>BC`!tGQ*;b&R|<^Qe;Pi@_t#Q=|n z;=Wj7;0tcWae*n7o9H0Y{=J^7oS!A^JG(FOIouf5N+qXEnycyj6vDg}W_UNgKu`X& zvFgXqfaU&b_bMr7?B=tP(5WT6r;F~~w{3gRyeE9Gccg*hT>Ii-eiHF0)8T>8yR**A z5fWKIPISUf`t4FfCmvY z*~rD_^ZT#qFaD&Yl)yJ$xy>Qhl}t|8i*@GWao+rU1y}S!7`@S+?oW= zW(s9rSnYxRS_}U+p61&K({Ftm^49(>lB1ge`p>z%C+&Vd@gMM#cU7RLJXqAhx)q^{$>05)XD0|f?%m<_S=`ydX6@8JT1hG-pY+% z9)CW*-G3#GUyeLo@wj5i!V{Z*BbUtlr%#@LGnXhD^51br-(e45VRRX&9m`dK|Fu8k z9^`%IiRaTCja~14_LI5EzR=;V#lU-TOpTzV~}?H%K4<7bCQ1N z8e10AGRo`~&rLP;a}cTo)l4Yo__F`jSC8wzTwTTCwP>NkMY=uQns?l-pL*S1ygi|* zWsDgN5v|Tk?246Sq&)xN)e9qk8mU$Xy`?)1KLL6=bq)HQ(ZS~{FnzpV4bs^0``Jas zf_RYgx(=SJ;E#VAz*DhPemEJtYTaRRB#RW6XFP*62k&uv*;g{%PhSVTo<+Xk4BZH-m$rtome9?7KAuXXd0J}k8_6&Z=-9*yedg_3? zSDuS!j;j0B76V1B9><@R`|7BjhEvCFIJXFicUOXI3FhwtFi7o}5`?sNZ!Q02XJAmG zEmMv;T1Tcdhx-$X;s@V*^W{xtjXk*oHR1*ypgA5(?E`9+mo2koJ`NQEWtN1(-uBc( z`QCNNkOjD>6v@`Nx%YPcIM)E6K>uv9vHiL?&&W5*ZeHmYYm+BK0Ffd>jG}{jv3Mxu z8MnjM&c4s8VO!&v{zXQ6uvBpc#B`|f4AlAV$+5Giky;eEX`tiauVby1%6ajT z^5DyGC86wZLVsp9c{Di>V>e*z(nHb0MK?rGqp|aAME|rndZs81QI^~c>?GPm)MbZ2 z*LWdh>h>WdKJ{v%3#4EPeJ63yd{;+F2|!qa^dZI|+I__MtyE9EIr%C3a|N?>G43~8 zgEch~dKn#AUuxqs=uzd#lu6O9P`?g=FEPc_Z^&op1!QCRuU9&=>GDG>*326ZDxVW zNIMpGkV&y=sMcr?x-p0*E~oqUYnFkB_s9`cM88+q7To+CyeI1RGx|TZ0HT+-3#AYp zJg>s|r!&E?LsL8X{$j*i*(3Dam?vHRt0Xv2z`~H@g-Z5l+2@SfiEX?2B%0*<^Py+c zWqBXV8_q4bYKI|+5~jsK#r`uSLP1q_MrtU4g3urOSkiy^p-A_tyfzHqXZR&*xGWNC zr!r=Xz$BN*e1f|}b}}&~#5IgHr3{WrvcTo!jYbDGaaq9|pJJ~xAcrHYQPa6}&)^5R z==z#$JmxFwL@frvpQ3EqXs?S28_){S9_yT|=`2LrI>y#4Y`U>ab1+%7m$Zymi^`0ezKXHOAqV8 zvntehtb^~<(5mdoCwT*yNp1()Lr)U{Hg%|j#D9s1IG6I92JZoWOM}Y*1CaJ{4Wf@w`sutY)Ya(XX$iDop_Au^Zi-(B| z6s$IAYL5z0y9B?a;_KJB`ERQkR+>gzPQ;+Sh!q{ek@L7j(2#1+41;RH(=habs)xaOv^4}ZY$q6(%m&(ps@wb z+%E1?6BWCrZiP+UHU;tiY&OBc@WqEE(fh<^3?7EHgTAD2?Yx^t(@NFb^SOY=iC`k* zl?Rjlg~TK|S^Y=7?h_50>}2LRMhNb&S)n57wE^&f^s2eX*o-u>^*W@WQ@o5fd#3D* zrhIbz-G2A4!r!vq%t>a}5RtMwB8I@w?D}sO3aU9Q>ZgH~*8KzcK;ttWh$k9j>x_|% z4Kh7DR+hA1^T(u76UX7v2&j$}e33Hb&&yU9w=+b^O-QXoB)-b~tf8W%#~G{5VTm;P z>a3-lrZ*gQro6?lh;cHHS1Z>d$h%9-RZ(AS3CvciJ#UM5$PyJWbyTu6;$=r`H!7mF z`wp_RbCU#HT1?Q=>#G}{|GF1*q+<>N4HBovM4K2iCe0I(S3q*8h!-F9Ve>)8Kpz5$ z7Qx}oJFI#abQ3l1;;5{CdajDj;#!Ye^aory;Ph)HWfNDdH$#1qcw7}W6i#h~(g<_` zIo;mZYMjd5MEPt>Thp^hBJzVD?VFcD&_7+@Gg=~;aRItAdxQ7Vrw754NK*tPeNW;>E zBDg{A1UZGiebI8w8ftQ7UZaNs6v89&SHGxSpN9RaR(XSaNGaX&9Fw~_Z zrG-iMSezIWLxCqo&bOpFicmX`(z||mBD``B1H?WBZqo&#bZ~xY8NUFMVOHs z=I!G8Ydq-H2l-}tzrt~Sd+SsJ^iS6VFH^SuTVjG$0(DqFg`q((u3m^08R(Q_8kgV& zO>bk;_n<9uC^eFF}WtYR7n)r7BAYjRhw6r4C z4zbgei`nMd3cpHwTBUsG*wP0&_x@kv;!Jk{TPK_cOg8uZsL{*o6kVkJZsL&Q$j zH`!DgeFf|#IqG|5+8=l=Ny8aQpBe{#k-v*Z9XCaRA++$Xr1YN%7n&epmlOD^6YDQb zWVda__S&$$fyi&P35Xoes)-eqBCogE{f?b<#914gtTx;K2j{fBlJa?piaK~GBMyW& zh432ceCYj~(}J2r(+&Cd9&-~g-r`S&MXn5|htsk{+_$&XLJ}dVrjYC%%gZu+tGNy(yxP|1Vxx z6oo`E3^?PVq9SrCAo1_m9JPe$z;e~y$7FQa7zSfe?rF9r?hrbot1#CqdsF{zXFxT# z)$)Aj`gv!jIb~vq=L7 zc?k{HbUj(Fzdw3)B0=(J$D{`;X48AmR($w<<5{|t5A~orjx?U+HkJyTFC%2nhCko* zQpOXglv0@NX`>McCf-K7`wH=3DQHLa+WtAKrRnY4IbFc{$S5elv6`>{ZG;->eJ*g~ zS>x^d@ZlaFX*4Re{xNx}+ePdlz#g0(NvK77E$`PFYGmUuTiv{(V>Ez*2At?G>BURh( z9rAP1Dw+moFLpP<(NeY9zJY1oeX>x^w#$ddY^-1d36*qpf7XkY2H zM5|_F-f_Mx7WsH0U4R$EZn6q^KKlGk3uxWA)?h&uS4C@@M;>yS^X51ZF715s$wUo; z;*0mbxJJz-;p-#n(Q;>Cw%Ed7RHg{`8NC~UznLf*ITg&5BgQ>{1s1=z*bxzhS+xgv zwo_m&PW$C`XRC?%_Men`s`IrWEQZl9Gc&aooItg>^2o6<>2KZh;c0pOl9V?I;0Z41 zJCsNJrXoa>zqDld^z`nUy#)e@8CpFgLTq05E3b))OUs$8tVi;)mS z>*LlyM8RJPkUGJqR|Ndh1;cugY%JL+s$no9_*klfpFCZhy{%eJ@!6a#oqCzkH}j^( zo~+w|D0GiQ{Qz3OFNuwFqVs7dvL4)$lA9Rx3G542Gj$YYS?awH?**5a49E#9k=Dr1v|Qdjg9DK~kn;{MXH<@K`EBjasu@aI20=0b90 z&k}rHo#oYFm$Ps8=X;1dILLEth0}$53)g3{jHy8pNLDRp;+kjxni<0QOj_%JOk=e0 z^+mUS_InVG9Fq*&BuTN079#kC{7w(!F$D+;c`^j6@Xp?iWpBS;Bw^To)I?l=^y$6b z+Mj*j-C<$*a`>Ttl5qdT-{Ke5mVdUXLnw79X?Jh&l-5y-yQA|f?AyXpgyBuDq#GH} zWeua^N^hkh>CXn_Hb<;IPRO|@|K{iW*J7x-Z!OcHNHoxO&(Brm+rL@P&_?p!9^DOo ztd5XM3Xllt6blxw`Q&&eA6@Z#FN^uF_4Q8|1234l{ z{Nnp?EMvknrzT7uQZDAN$M%2EOA@nZiUe3pSL|*mJJKJ6quM&&q5Yn1q=OgwRV3szj*}^>RQk{gB6QIG3%@OCkZx{SVsSGAfS0&-R57AV?s%ySux)LvV-S!D-w* zNaODA?rtHtySux)-_HMe=G=2;&73v&#jTgUx~scuRdxTqyFPpGgH=C{E}yL6RJGo* z7$MJA|E{t~+6O()%N-tg8zg@&6AVj|h3boR9-=$#sT@Bam<(Ns$=^%mA5TtD4dp>i z=e*`A2<>H0MxBEj7jf7ep_!8u`*p_lM)I;avQ7L9)vISn`>)&y?2z4(q#r)-^DF!F zelAJgJwJ*H!jEPmf(0V;j?!cvon60h|Hg0oWnJQio9<2E!uC@zV8kaPnEBz<=Ry^V zjD%zd_)=#wg5K(QWZ#!mS<(>O$*16T?2UW!Xi9Sf~>#_z4a zdQb$q(YSR!{Y*qpK{q3`+7(6@P`;VZ^1mb)=zRM)WHv@H3tI+GKQV8Pu*q5|zSF#e zxGWd`k99DzrCtKA(XAUXXi5=_@eLlQk0@e{I8NtBMln;36K1J)J-v>ZiZ{nS<&J$_;X#)JE*Ja*1+wk zvo{D4-|UvgmW7A=skLZu1<`Z3r-NYg3e+Q0B)X^0`d;=ETzUt4wpWfe3`jx4lxl+W z9yC4;2%nR2iHpS=DBWnZuT0L4YjQ_b^`cg6>p^8dSUc`dpm4r#U;lCei&XFW?!x@x z)P1)hbskE9r8g2$jlm8|U#WI5eG+}1{n|S>lWu z8Krw?nZsUh>jxS=SEJgzNq{?q8~F|I_NFSra4BX1zNw5NZ?>D?w_>!<%>vJT3X@*5 z$kX|+#yZ^_`E{qvD)OVAA(>U8D6hNfwD0e7+{T`Ln|f8%IlLIU%*@RBmmAl6BYPI} zmAW)lUGLBO1dE7+Nl}i`K?XwGdse6cL#m%F>XQsEM5T4~atOGUOm2!u3Y6u108HAw zbx6@hvr2O{4)s6gGSIuxkK$CQW`@`^UN29;bMBEI`dMvcI3K~P0lur59 z^!-$ni862}m0d54+MGr&iNE4lI%H066e>WYU8LY{lInVWTd8@9A+Sz0o@IN-XHSnj!#x+`-Oq-yC4ENiCD7Sn>SR~j-W z_vIOq9K9?nacN?w9lR6uyn(=u_-yQk0{=EKTKt6kAqd-%WzqrFjjPyTpRu8j(^vi! zzS6kaTNk9fAH3fh#*^;M9@=@p4r3L{nB=7kwYmP+H+ghSQOuqKrbkMP&j z^28|$>sljWI;QW`PW+IX6PsAs*U>uWrn}DrR#Kai)BTWh}iP&mpOj@4#T4Tf8rGy&p zLrn+LKN^wk{`9sI&Z3gnpCS1E;h zl13nrY6d!K#>UR4jnstwY>SaUOgI2_^|6RiJi}7`AjF+}L`Yn(z8%vh{&!B7^!{EW zK`OP}=(+vHstVOAosNgC^!ONLu>cRF*eE_Yvau6No_{tbneidA6v#SCFL_(`wXa~) zfrCJy<`7kAO6Hdz+-|vus9XxggBumdY+5xLG+nRg1ao^%o7GoFoGZP2K|(ePGMmO} zl&L03*67cSme~!4npgCG&c#gcqnK3C`8u41m-;_e#!z)o#bnRbt{zwq zMi>J}7Uj4K;uJXr|FbX_yK&X{rV+_iS>H0W))hULQPAhX6ua>ZT0Rz~k2u3z4%rd_ zn;TNdgU^&ieQSsA)h$95g-{O&OV;v3XTM%0SSVB_@KPawR6MsR*OPCk8JsVlL!uly z*FZimoAL{LU!~h~B_dv7kfbH^#zaG^E^6=XqvFr|TAatwO&I!>JfUhjY=E=OR`B_T0`}5K9I-*HHf=5abdT*(W?B+mD{#cnh4Ce0|L>B!gNGKgu!Qfe~>I6gPcD(6RN=R5Q*1 zp{v4^TQAb0LZl|E&s*-$WWo+$8lSWO%=X0rz;_Q$Z_lRt?Si{d!hix~L1zmH}-va+Y_8r8K- zNCfLFi|+=7zh2|&1!%;lj+c0)X|yl{RpU~P$fHOs=N(!vE31z1`FS!W4PV{+=a>lZ zcW7UnY`w+qVuvZiE2$^Sr6~3mZRRB^4Q?hTzK;;sUp5Js~GJh*MtqNg4k_e#Y@|(^7#cS7d-Agumu$+eF0djam^39T3V>MS2CKo8PLZtrXBY%(DYOqZ9b!! z@vO*kERt(Ci@YPRi;!uzTE8fmJB z13(HydRam)vanO-tm!2U&o-OK@&rMb63?=4$43`WkHK}E@nFwhI5PHz%tJI;g~uB) z%_WD;l^}3VQWEMz&@#shfo~p6fRxLRbWX@Z7}>c)Kxn?JGp7#f$J~;nw4?|fB9=P) z@x|Yh$w~@_G!(<{9Ua!oPq0i_To`$;0Yz2b<2(AFU|ul>0X##2-}4yk z<~==#5Um!Qg$G&j*7N;1SmQnJ{{X{Q>RveNX5rm{a&l=mI z^S5(oQeq;F->(vnp&>k|YiX^I$pw?Y`>D4937IgvJF7I(9G)Jwzaw;4)9Qx&ohtCs zqY&^LAvcra#SlqAiTCGpE;^K;oII&mfhhZjOe_K@SMl)Dd?9Px&%HX!_#-FR*>;Te zVkQHuBf9-=_Dzw|$Nl3mSR7W}xp-HHrWd>X>nkr_ zsq5yxx*xSF4x@!86!o8{(;KmQXcjed@f||E;uKOceg81+rD{Hmsi$d&Sv!k1YF`91 z4vgEq^SA{e@X4)(d@KX^ZyvBiM`BS{@aS+s$n`Qld1e)#TV)QkeGCNZg9F?^$62b2 zAB_nNDhx{mM(02+t_#D}NhBWU<3;tOiPspF<^uhY_QH9Cdia8mG6SYg3LIQ@%w;aO z@&NeN@J6@2(SpQ)pmXG-Q*Sg;pWk@bR-k&T?aXs!$xj5VFU1`qvryt^4pEX}uKZmZ zrhm%lZkK(|w%zUsQwpl!cU3gpno-Ov)Vjvy;z=i76sU#n_B#@BZ`=ro7I|<{5ZV@~ zL?~h-9h70MOt97WOJXwk!DKk>L6MCkmLn^r4?O#jfGT;6993}kleXfgG>l)V5;mE> zpIV6_f`vDKFInB2cefFE_qU_rr0^M#geA(FuJyyPvZ9d?fZ@2gk&PiV*K{reV|_Am z^`^R|uU&X~PD$o79&+}IOTvF{NsTTTxzaH2K$XfSk3sTpen*<~)4H@fzEfWkrfXB6 zmiCiXrEAPCG-Qsu$UM%PP>G4p*X3}Zf7X2=)>CY?9d3GmHNk_zp$Z0}8MD!sg zMY|?~9tx$RoEI$T=JWPbyNx78j#VvA7f75SfXBWuMHO72{sG-Ip zCEWvq#PdxRHmu!L?a8`!Z>R`op+wWp#QVm~PD{+(4IV^2Te$_Sv0=gHqLCcu-XGZ@&EqqP4|V~1fD)-tm;V>LE>P1a{(2t?|WSTSDmnE+H?i! zfx0!8*NdirbRC|=WvH#!bFx=Jd9r4JgV%YfxuBx5Cbtnn4VnAJUjMTrzMku$Abnpo z2Yc5--O4HFIR4(F7`PDxR1`s<2n6(WL!#vol=purz0sE`9A92u3qmhOo$qXtfkCsc z+|7H*tnVAHIQ_i}sHOL{x#6Ke7kNDj#Sk*%Y-gA|I^>Y%ND_;4tXG>cBesRT3k$>a ze3jwC-d*u(M)`8GpTZ2fDCX}9DVgKiv;<3r34~v}4P}dEvj^wo^m`T*bocLEurClr21F{J0A2!rtVHk!axPRIj^3|Y}<=GoheJ@2a5 zlW7muxF+X=!S|0gnNir>=ic9HoF-)q zjzU|b-9O*Z*F&iGmk>4LlP0n%m9Toy=*bQ>`2%5zT3hFA$tjULwikO=VGqT6I7@diksiQx-1I}8n z>eN21kzLW%44sEM!MzUA`iXeQI#?8zyEO(Sqk$q>=)Jp@x(76Gn|Q;js;9yvW530u zU{0E)dZtQYVH=PrIbdS_Z2}rWCk=MO-S+9WQm|TJH_KYojuwNE5@$r%J17 zhLlF=S&IIp3$cV8b;)Zq(mT-WF-}9jlqk-mYTtVdrpZUu)5A>xh&F^B`dXC1u+tR| z>|G>$IBH0?6aj~~rdQ<}`mF*S>i1b6$}#DWXL4Ap+&blz%MtH6n|{qm z97x%sz35G{Z_(KJlQb=W{Xg;J2Eg68!<0C~m*)<7K%{ zX*DtWzCr(*wE`PR7p5cBDXfe>p5`FdllN3n(|A@vG+T$7izJ4i`Xs2iPkl2(gzkA^ zkH3N|cMJZ51!#)xwtc6kU?^JGsTcuBqw~*+TYPQ}l`2BX3(E>@!lt#Yl8=rhRS(-8 zyehCA%x>%Ho#>-<4~TR9tP%%x7CboW^=l>_j(gDXt|Ye8EtPk+KGrq)tD)U}TuA1O zN!A+C(8)$zw@WZEs!qreC`5a%R-)Ba!FxR?RFgz0xYzWs$Pj1zedP5Xd-Pl>XM8XI zwDvJSWYBGi!!oeGWS;~*K#x|BXxd_0e27ZfHx~38vtw343SRoTlZ@D6-#LY;zCh*9 zKE}d`eINR>hkyCorQ*?d7C{|3_o=kCK5Qj*tvfFTcKulUEz?i&A#(C`USjU^jljAg z&DWFL#075wx?gcjbEA0IOL;CbXoz*me8TyAmnpS0GIRo1ku2BNA3v_jugc3u-_slu zli($4%RM}@SxYymO~axBUEJk61?(I26X^u0u&}VyWm}u9mV}e&bt{uibd@d1Y$2o6 zTZ0*5`CK29KAS#FBFuo&)*lZh|ChRm7&fLobTcMVS3g+K30lQs)IO%9Hoc<;esJEO zeMlq`IdE#vs>P2df$LWqD23T;$8>f~c`AwI={!9^Q4W#64;mn3F|@KU=I^7XkrgO9 z?;0Y5l0gaw;VpH^Ll;KMx={Z0^p+MdljG4*QD~Nt7N&wfo(wm2s{0>t)|0;%pGoAG z1)hu203O*-`9b0>xp?Sh|I!7OO0i~Jolb02dH$-7!{PH1Ynt)Yf)%=L_vmbY)7|n; ze|pVkh?RVbPyAB?GPCmJ7Nl%+>U45&1T;ebXK@jkPViqY)5KQ~{nK#+SRI~K+%4_gZ+n1q*>zLnri}!0DN9z6UH3$#DNM-DMEbIx)09M zD|;o+!&kRd7xi9!ZR1MG!1hrV+*Lr}EYF-uWLQ4#N>3-KfX`6|^to-oIWV&6Uw;eg z>kA)0?8HHkF*tb9Ip2TO#3zG%%bKm}e0^xFG#ni+{BC6uigQKC4Lq_24pOl1uPfgb zZlov(Ud!0_YcAxK_aE~dKB?{ z>{0N@M@>r)sAn4$rW+PTrbc8ge87V7Btl0r-f@s{Be%<@End|XxtMN<+&htFRu;Op zBbE;y?;ydgW|1edH~^w=j=I@utCELb@V*3NNBf|+!*fT@*=+N za|%f13n;g}()Qp|&#{&A+^8a|nJdXXOJuf8TW=3;PQy{@j$pC!x3>oM2seF8#@%C8 zpfA_iU6_t@NY@ze2oi*F1z*IGRIVTX^cnXKQN*`FcMUwp3&WXOU{A4R<~vk?>Cnl$ z{$e%x-Ajf`qll)#!=qmjp{Q8x_`>a@Ne4Q?p$`=u*Woo&;l3Qjpd5L*SeI(7)nNX^ zX+5rEJUT0=<&4h@Z6BBLPS!JLqO(+XSGYQiBw&G+^c4Qmx_V>mNM; z-J;fweWL52g$3sJ-1%h<5(q4FqHrYypCk0G4275Zd_KcZlUK1AqG?-}uljKu%`U2; z%b225t#B7Dewy!l#mRB|QNOshtsg6(UE#|mH-GJi5 zBZg-)ryS1Ws|=;Kuac~*I*^c<*#GjoPkKh`R6_*?_mIKBzV7Z8A-e_3P^t8BB4s2e zp^G|e+x6#+1`^#1W?hnN!`+cv4`+0osDmx_GJdvCgiJEsJ+2TPee<`C0IN5K@+GX1 zC0e_O8__H`|Kb(~z=hEUa@8jtH2Gi0FlpFds`+cg4$f{~zn#JuSPL z0tZTaCBF))s;D*t&9nsu&+q`;vd+qG* zXjs{srwg@lbkGuJE2eN8$ZEaEgid|=Od%A9+t&v~ zeuR?jG96So95BigE3Rb-dl0*Dsq;0#nn1x2&<@P$r+nwk5Vx4N;XgbKwKssCDSVgJ zq6)4I5=RN;##7i{cQH3twCiOs0XS~Su|YWXzmNMRV;bIn^bRssEXP7|#v)51Gkki3 zb7JPE@l*R19!OfBQS1Y~mtIl6Iafkak&bp6%#H+#pDAlxvAetOjcy9KQyf^TXF?C& zmVeQ+2GDFj%-?sIAC>grzrg60&Su{XB5FDnwxbX`KC)ShC*${K3M-`otuIU)bwMFo zIQZV2pWwJ(x#4qMLhw%q7Hiq|5^3QMJ+)XYexihf3Jw>Cx7t77pD755DTqdSvpOmZ zg6vxQTypKrKI~CVU;d1(N%uv6Pwm1MtMpBu*bgF0ravQfkNO%TBN|Z_A*MK~30+Mn z1vx+!iJ`ez^38%*F)h+?KyVRaVp@Q-3u3aZb&K@MYRMj%$NkR>zc47?opbKTpa>lk zar#DM${U9pO@wOd6sIJ#1-aA^Sw<-6|LirbrG*q`&)%#gSFho=;L)kTMTWv#yXM!% zx&y_rKaXx&EHBKd@1)dWF@j158y*?WfnlGX4+1-jKU1}iDY z1NV{3e+%584t~Gx3voBmYCZl<3k!lYQ_4q*9)CgCTTasIrM_QyG{ zEZkMuSxFXBNb5Tuwf}VyPN|6#R0Iz~hYz6|SwLVuZuSovAvq!@&CAlQs7B=1i_Lx0 z?@);CI!@W-4nKU5sR^C6-`9hY1*1AE?6z@bx}HK&W#C%*7PHRpoO(YP!}gXo*GmL+ zJAmt)v7@53{vKD?>XspVjUhw{x5c1nl6Lm5EivoNhUF{a;^VNfb&*^S2yp?@!=+2F z_S4`&-_9*|)s4Yk;P~E!-Vf2L2^K{i#hLi3=n&Ju+y)-qt`Mv!H7sU{W-po9)< z92~cbUfml*=IjTk3>9{XfHW0BU85mF5N_Gls<5^*N4)KqlYTlt16!+3__i?w(6ptGx`e0Nmb^ko-cS#T8`b~*`Ri2oN` zA#B@Z8MvA&=id^IOT4RcRb#c$x1krry2v%sW^lCkOUScS%CTqc1V_9SLH89FoOm%m z`Q+RNA#;=IcwZ$xv3|$6c(#bf(28&%W^_;&yjwrpNcV= zqivOe=f2i$|4SeWKY89V^Tpb`;Yp>iP{3Dhm&07AG z@U0j8zTb39Ef0d^y(xraMH@J$&93wFy&v}d@du`LsoRf<)4>ak4}krWr}%e z{}$k_!4Z{oZYgV$q@#p9UEQKamc#f`?--BD z562Z&X<%#&U=MpFkxu(?x?luNf7+rV9)p@fz(S_C4kx(`-9Aur* zAGWtW59u*HTlt8h7umOKEPjK|V1Ve<>B&bo(Qz98j~NS<>py0!*OQ$wpFQrsXoSak z2pHLafEkj1!3=|SC#eKu6rWwj;0cU10FIKwd3Zs=$FS4i*qr-SB=F&X4Na{L(xVT| z0@^0tDS?N@*Q4(CSyV;rYp}!r?3i^pQcX?rpAhWEd=-{rr<3`$(tql@;<5e>XK1xK zpV3)>5RM@6rGGOVlytxTCTTm1%CK~KwRrwb(nkDOCQqX%=>GlRt%*#__g}4DbS)(7 z0j)QHXm>k2oJIoj4nu~Z#|6l=~mr`3?DryOxJxd_Kz?2 zj;Zm2l6&SrfK2Np1ca9tOvy%+0z&+rP-ERkR6(zC`p)3=-YHe??Nr5-$HD*3R&0c# zQO?eIP7gtUSVXv;w#~%1!^davRdM`j6aGw>`H}H4%X!e%-*<6zkT0Sb-}RpUT)X*a zk71Fk&Xd^d7;5`?SNccCOL9GNCu(OtpsZzxj2{|7!i{%{oEs!st4ydCTW954)|k-$ z$82Xl4E}NQ4Hx0Aa2(Q+6Str=zWnM!w6<<={@3N<>#y)q#cJcyn|z@1yU+f==?SH- zrsM}3G5K+iUsoVAP^i{`j8lDVP!oj7%CH^oPC%O+sC*^odZv6N(pVId4>SbxLEh}*~zO(LpvHTezwGv8;h|yJz>6teE!2)Ly4gi z$o8{!iXyz@p})Dpr}>Lp8#=VC=vr`Q*i~z^8LDY}j80uI-`#@0CoLG|a4T@?Fi^ek z`4*EUOGLfG`Ty|Lbe-lzu*4|49iD%0&lqifmY6)RIT9^MY_Ci_yM--8Fc%4&gNz%3 zw7f%Tuh~Kd;~Ge01PCe%x2H3Rq!N4_cA6fm`H7sxs zrbuofxhc&yHaclO#zcken~kP=k>P(IdwWxSb%X^P=FA*~{@OLIas4T#GltIVk27iZ zY8a`X`Ky#d^ZNJ)HwSFr#+d)qsl4D=H^}MdpDI23fnOxzL^Ez`<|(Yrc=(}aw|{Ni zMcU~_vSv5KpXy==Q*~RS0Lj5(I#GI?iKP5TdKMH}ViO=%^y7<9%uk%`%&nPwbjSTh z*(haj9Gt8&pwQIT>Kz<1SyC|vk8%}|p^}`0T%E?C0_x^`dG`}RHQ>j2-RedqzN)7# z6AqoLTJgZl2(t`eLuT^Y!Q6OL;jaH{v3{5LyZ#!r>oFMpx2LO*MZ8y1eNX<>b=~L7 z(NP9Wton?oB7MzQ<(;fND{yJ1EnO=AkdQBbMBV_-7UBzynTMpocxf&%!2yfKW29x& zCEB^1+rF#1Q>Viyj`NX@9V3nrgJCfYGZ#ymR=kuc1pB-Uweo*#tr-+Wed(BEDk=p@sFY#vNp;F-B9!4k!nmN>8=qOie%+c=a-%h|y2 zEGqw^3B6FwdkhA^LeQz`|XgSFbqU`x9y zu2Tugq01diY<8(KP$|3aT(axTT^(zJb8km`^a)Bqe|45Mviv=r;w60VfrgrrhV$vy zHzXt>QCBojqvtP-+8j&5InaO`@}(%(ET`|YB3G7m&)iIJ!Q&cj3U`PQ0sg4|a}9yP z62?vFs+&J+FpJ)Kbc$*33P&(ql}paejDGcgzO>*RSbW`-Cr1tkAGtMIF!J+#gyTke zRHpt!v(3ZJd@LX7uI6QZ`p#jf1KH}xEYfNXT*KE*&V~eQ7;2rx;r=zZ5NnRKMm?}Q zR_&&Yz8p;R*#;6dv8XFg-XeNVq;ERvzC3>B`#d{H}<@89GGTQi zyY~MMe6X9?`Tu)X*YS_N7F#@W2< z;my*R`e$E+skirZ?*#nUurEy}@2wGWXlRk<^-r=}`%vAkcOe~vHtI~?W=6l=c-mS8 zFX^JuPajhY#-pVuxB`ypJ6(KYY`O?9ov*QXEo8T6IES5@1bj_a-1-FL5Dy5R)fA!m zy(-S~Hlk7(HMd*3hsdU2EBLvM`lK!|7VM@lgKq3q8&Z1r?78>LzrP22w5kXP`?VFG z5|J<^T3eE6b{*kBsn6z_mK)uT|DgeQ7tYd^GPK8DN@+{cITWIQ@5G4OJ+wpQ9OkJI zzIwRKwP>SAY2e`TA>WrICc=7!sQAS#^luy@-ySR4B0j->Tutrrcs5RL9QIx$Erh!> zQ+36<+1<@>aHadXc*klPGfV_fTjD43MPpB?T^rfAaaP83;n{>XeHM|<`nJ7UxCF|4|(WNr}ydQz9>7FB3D8HyOkM0>uy2nijIh{O&*q@E_7^R3Ra|i zsfc>8Xu#yx)t%P_-9lxSs|7k)O_)IG34(8|L zGvOdW>T;3JQdj3-x}Tn*eD8e>U6x&d>{D4xQ=^pItlVY57VhiJpZV%67@dY&L~kQSSqY^IqMfj+g89oJRnxnn^Ls9J9Rw!Rza2eHelyZPh*fN4{4s z=gA6efwlDh;=Kv?Gi)>*GGe73^Wtd2?rH3ykZMmJ4!u)8G)x=w4bC)r-_ulzB)EQ7 zo7_3OAeBZZ&CzKI#a?zotk}kolQp71r&}A${b;Q_kL9tJ=<01jA_-07Nvx+^+MJIZ zuizz&8W{S<6!LT;l5#oZ`fht~k?3dq>^fzflppne(`;&{SnDf~;>6uR;kjCruEQ2VmH0->NP#PI?jaqW1|UxAmLS2NHj3ebnCF zz|{;visR9y!gnxQE|jd3Cp)`yt4~0mZ|~1xK`x)k+P;c|)FIW$@fr{H@vrD@bOR4L zpQpFB$T?&F_}d=D{IC{n8)%*3m)^TgFQM%OJFjR%$(Tsxfb!o^K~paXCxEutAS+ZOGdY)9_ZRZ8q`nxkuhrsN9)Fs&T81)IqrqqH>17mKC*>kP+vB-V?oOBC5T7S1cC|gfmkvpt4*v?xq^{xTFf_~9EAz<^$+s^7JpQqF*vfob zY!AW-GPDFb3DL|sk5K%7(pkZN{f^}OdHz?avh0bhhbfjENY=tUb3O%PO!4L2xH;(V zEY4=e-`tV$){@_8@q)_m*ccy`JJWfj{p@9ektYMT0xY*lrD*YWAbj)*hU>Hbc(+Oa z7~pWNv@zgQ>+Z5vPi>|8c~y6)${t;9-|Cu8;??QS+N`E-uO>Y?j*3Vq(H?;mn@+w_!NYC<7WNEUl0=2iXgJx_3``N(v#RFQi?h6qbmNb zTJ^<8?6^tC)z{mB8Ir(t2YMx+%P-uJl#B0~l4*?ko)8vS+t(_+CFB8mC;nAR?aspl zF4zqgzIC}Vmpw)*U+6@t6~v&bXssf$k=NTHW5^)~a$rP*e<9%?%DlNWC0OL<1@Zo= zevi>0{ngx*`fYnpBD;!bTrc5}>+W0RpJ!(zW7Lu;Y?5NVC4XYg-VTjm`41QPh5M?@ zX)l}ThKw4zo=ZeJk-QimrJt9UHlq(y9Wq=hW9N-iZ2!RmL}q-$KmHCqVVYrnQen^p z*Ke_Qq&M@W_;I09q!`>vTOeC*ZNJ|9fmIoCb-yXB9_96Uh_djtK3Nq|rop)*l6lAy z$>*ngG&c*|Jn4Q(Xn~*A>w7?6XSer>-^UazPGR13auc0%L(kgjI>#7F`l?{Stj@Jf z231Htg*08N5BC(97|X(;{HgU))WcS#PdFgi`Ev;rb)RESA5~?C@*CPb3CtIz7loX5g_EEEb;Q0Sl5c?Y`LGu>?f0rCkY3d*6RsGAVven{L^>B+bOC)_nui>QXzh8J53cvvlDK)&bX}or40c7*^%5 z3Ot0Auk!a6RcYTG!79q2w~S?ou5$eqM7@Z;a8Z|=!bFjti?QXqr1Y;mMLua}wV6xA z|9Aq5BtYHtTuV9Lj+ayyjN^=^@dYxciBIq3WVW{zd}4TGO4 z1?-3~H(Gm)iMdxMr2Xojx*7|`eTJUiByq0rN?37QO^Y1w0P>5kwZ!kQucGi&+>a4V zHeNW&@3BFuc^y5?QLme;40H6lD4*43p5ipQ8uQ^Y1#zR5pLX~HL_P4~mcZ{_;+@G#z&hwNTi;_r5V z4Q%iShK04Mx*vkJcxehnU4b58?m&p=l9LCr8I~(ObqFo+O%wLefKi zN<7e(!GpXec=Y$Ft1*XA(*Nu=ayQcz@pyfp`-u969E2P-8y;_|(=Vla=Zwu)So~h}7mx^HNuOy_om)nyXz? z;$WkocPBkDrFTkqg)?0%wP}=1e*8#+&6a`sA#3|!Ye_NfkUT~^n9ddt12?FtnC`FzSirdL>& zjm!8&8re!`1OqhUcEdy0kG`wd$gVj~rW-D9=ZgWExCN!@a0+hjrqo!hVi||Sy%U+1 zVjJ0I-BjqM@k%nd#kBN4?~q|jdW%mV9CGI!3irbYR2L}ncZqo#`n9x9F6_%N%;wW$2oj9OD<6ndrS26hvkM@r$3Bj;&MQXgjes;v(<3e?tSp0; z%4j_J&Yok9rSUJraE0ZrP?4Ew;a1FGZ zEwlVIQPs;}OoBFM%W8jxKV$J)WM_jS@Y23bROVI>+WBTgz?eq~+t1AK&BXuJ zZTH96{tpc;5P@NQ_u|C4jr5L(TN4dctnV(yZ8x8<9$>%p6W=HM)4Dvm4g|5=;!*%sYMZ82zKV&5(zWF<7+QA;$XolCQm-hIuOt&j{3RBxN($p4tt1Gbwc%e?#<(OUcmi@OWy($XK~X)|7|hrs85`R=X5qpssU=y0$D~VX=#GurBG& zLs753*lhNDEoTpr1iv-0={MzoDB~>M-RW3xr5R1F`-#_#LOq8EWU0t5l4$p;;V#>*;1q9Jh8IEqW3qy1&stg^`vo;B@8cTD1i}54&cFr`3 ziDNt7Aj~&&zfc-F-o*(rlwqQN4o7}^Ca(z%A(czQ1SJ+x;}FH5ed^Uz{oF@8x3Nmh zjx?mjE%-@Ql&M)pvH)}p%4roD=o4tCNUt8u$o`arj9`!I<+NM);(v``Perv0dK!FU z^(;5}wwiI2Nhe!)n>3a3PJ3@_&Vcksy;evZQ6Z$cA!W~1di?_>h4uA#y;^73)@Avi z$s%Ke(h$zbp~pf~aIy5)VJTzdd{MO%;;ajX@=xk}WtBooOw3BeB$k750;D0%Vu+}U zbeYJT7v$uSLV#GPJeM$C`y(JR6bSvjaY8Bkh^uAXvG`D=RzjZCbntF0nwLa8eN1k5CQrQ!fQwCom<-~x2&Q2zSu;jZy=||H z9HEB43+d^kWt>RMA)7fOxj-__c`G=ZWW`TtYuIyVG$eQexMdnUHFd*_w{I3FV#yb9 zDCOjRrle^J`$G;)#H8gJ>Q}6O4bp|vKn)Y3>FZG}ZAY`rfDCCs%JB>nabSqEbE%`9 z^5;42T#EAqc)(!GMplfp_-7+ktj+>P8jW_p2cVF1x;`1h9Eh`~=8qbSQyGfin+Oa6 z5+}Bj7#pRM=Vl}@tY}oSeK*8t(~UcYJJ{`w5vhIe5I0o(=CA{>UyK0)jAKa3y7y`pb34AewV4W$D)i|<#4Y; z?XKMS$*Q#Lz}EuOx^wHm6YfLz4{v$G`_hq!)K=XR7^%9M%Z+a)v~IhV{1lx1{a#C2 z7u~7*c}eUz&+RbjRfOZ}`?tQ1g76m}5mBpJ4;4Npv^hbvf{EQ3`bOUKf}bg|F{<&M zu_J<-%R{rGa-yf8JHk74`j>=<(RFZHF~js|yGI-2LkZfI86S$7#X92tycN0BBCgl2})rZJ1taQ|XVtt4_FjLE0U zWNmA%e9@|BZUn{X9$l@9XLOkj+K%$P{%{tziP!sLgE*)^llmSa?x%JmtaT>d05Fb& zhfuh$s{2h8Q}7g~m%?Jvx%^;4#^2CdJc~a@L-ERTDJj_=s+z!Xr!Y`ERzmX5eE3FT zJs2ipmM(2E$tx(M4SACB+fojW(<J~2R% zcaH@o_?ai~)0r=Jg_`jI6uUlh^@V|~kqfAtHg8W9fm=|9|4)oDaG~iYTDO+p;$ZWB zO$V8A?o7BzT1~LekWJATLmK8Ke9B^MWvD`<8e3*r9bTiNPb%~0!7jtZ%=6SQ75o<* z6z<12W!t_YXyp(7;iFwRQUa}R3B+{6>%23pdx>#=x5%vPR<-Fj`KE+eP$QK3d2EpL znn>BB7|P6IsF(~#?P1q>dE2i1$`k{@rdM)%Ka$K^hP}BV&w&PUa0kFF3UB!S{GHsB zIrAf}BXv)|eGteclU#2=H1YX>p=nW-QJay*mvgcnm+$)6qYqGs1J89)DXB)TDFz~| z`V7ZoDs-Kn_0>peXtFMO2EfS?aeHUw*oAX9eu!RRYp_QgEKRU)3eqR#?4pt^Hy9kH z{u7GS;NB@14BN8aq&PZTth4yS@&8@PlPAsjx02`bJF4cBlMX7pALQ-XW$qBY6v5j8 zU~D{B6g;EgoCQ+(yFL{jXjSf=I|Xc<7f@2D{AVd;yez=(QOEv{L&y zx;Dee=T~p8xRGk$Or6)9*GDOF@tIMFG5C6%oQodZm}ci^lF`+p^mOX=`H46j;n)bu zgqwI<5i3QnDjAl#2{>h-k+MV{fzsSU#s2`!U)^WH`|W4TPSgkgAKKnAyt3|1_pMY^ zsiSa zWBm;b^t^4UHm5pC+aIzLzelYA3`wGAz62{Ah#gSYI%!pO8~n`%bFVwb zT)?J4^h+1Yy&ffsfkyh$rQmcYAn0doO%fKk?P&Gd`Lby>_DX3m|&nK(Aiv8(rbW(ykNd(?PvP`A*m7odaE-o}QYFHoM*dMvO+jKZO5ZD|9!Uts3!-Q~LpG@ttz- zdUkO&E{GeMYC;P&VJVqaHlqRGP8USI*E}LhMwk+Zv{X}m9_cAp^M~yEylIFPrAy6_ z#=we+N2_kQ3xNJDe?rB^-{gWF8=oK3&U#T>Z8>Cl$xxF_jDu-Af5A1H!dOrTc*k4Y zVckDI>-i(Y&F~GwlKd4*@njeH`V|#H_>(!>IPzp#UhFzx#rkcW(;1iuk}s2_VE|1o za?3H4#M5nAvoq$?c|yCX=MJ3Vn9{L?NyN>bD0-kj;nB|>Rzf`TtUv{kNUnZC+%$&f z;)d3=bF?uCGQic~q~pWBlztD^yNS=9=DGPzq3j_OiEwLBpGHcmcOM=dNVO(brskt3 zQwf$gTwri(-i$YNa(Pa&lhe8TvhB=zXgz$g5+#;QD?Ei+)Y82 z|I8%HU^AREm8uPc`a8_Xx*5bJaICvPHQ?-PDNU{~o?z<~i(D5dQ_id(x#nO;STqfe zKnuVUF(p{*11&S^wf9vOwGL+qQ;w{$=fB|E&Qo40!#@v=RBOqV62ER6+R@}?(New*e25`j+$+;5dhK%K`YxV$$vW?!&5^B~Lhy&l z;{54LlKnJiwq|@+h@x@H>}~78nKc)8^+qp_Au8%^LMKEFE0YjZ8^Q) z4*NZ(%rwvB2Z_S`=|h$^_=C&0LK_|4Wfx>J-*3S;U7M-#Mj@CgG=$DSCEf{6Z*=ZV zS%(%`n)W|%hOV9cey?MWq)W;DuvQdBNXWjFSN%96b!Cp|o=O+h(_<_2E@dd+77~Ih zyd4yqqNTZH*Sb*4qPs*l2|;fJ{D3tz@@rXmj2k!M4}%oJca8(Jn3cd5z| zuURYcUMzg?u1fioQ!jl+YeB@3ZY|@MY7`Hs6bf(9{&ScFY^*ecF*_L@eG$+`mWN97 zcIdM!I#yGr@_O=3O&PX#B$01d5Hu_JRp6C{6tMga!M~SfO!tffeAp9Xp4AZDzrV{; zHJ~*b6Ul=$aTXg z*gG47rC^cNY~N8opL7>}CiJguIXVogcKXTmOc< zg^Hnvzd1KQge@7>w6eNp; zZSDHS^{6@SwoMP{4M(JV+?3JQk?GX-`Src&;ALip4Cu+AO(fN zFtPMkLM^{i9OFLmi9JO#*~2?Z%i6;iN;B0|RHPKdH2(`gD+8!yBLDx$YXZzNY=4In zArX^|njyTflf|C3smUhY5({e)&O&=f@wyxFP^k6c*+h&REP*JcTLIT+roqW?8x$A9 zv+0?cnHCDt6rWaxAg#{M_^{K#{EdQ{`I8e;^qR;;BL9FntP>HDffp?-?92Z%LIA&4k8+ilX{9mcY>bGH2qLT;5jW}lcd z0fvZes(>qmJD{;0$m@IJH)NgW6oF2^WC@C|jrES;TtAXfJ0CDhD=yh`RbHm@aJ`KpHmL>f#AQ8W~9hNYdF4C;{f%F zT>AaVwC${?B#~_2MD_aoJsBdd2Ug4n0L{`)D>naF7y{XbF;Laoxh|+=S}I21GD8yA z(QDx)6tA6%cCK20U$A5`)@73#qPy3_g6nM2rJE9i4ynwXnroeLl=CUDxHKFfF4c5yyXdY-;<``&!8yfHxgC3^NOSQtS+5w&#~kw) zp4muqoyB0(NB#bqosPFq!M84sdENK7 zwx7b8S2x6Wa!}3*Riac=_K`R({v*s)LDT+D&P4cAN6CZd`F}7ahXoXv`S>|y#Y(~= zCo@9CjK8#5Id}wXtoABmz8bmMh;r;HNEyRP3@`MrHapH$S<_#Ilv5kb0?Tr3Jm^724J6^Jbt!1Ony>f>^73a`?0h2P=){CinWQ+%irB zefN=bi}t>0cilmQ*CM^MyH8F&J4<1wjpS_(V7L-_GUah?j1uuHYH8T`_j%zQUgz>E zDA2FGEGU;xlB=;MA$yI#)r^qpdOV+O%YJfM$3Ivt4H$EeKFK2^pEA!*V($(E>fkK` zC)N7`C%o)l*ZDGGM)SB#QKiSnP0G5yQ28mO!ATAAGt)=oxq9^D2Fvxt3FMgBi@W%(}@;39F^c`(~FQR0OBu zIXLl5qdC$l2YVzEi8$J?n3{lxwK}+kAebpm-hBCy(3*?o?nCkKkDTEq=aIRj&h_cT zyx_(o!Yr{G@iXg_pAlZM`96F73~X;Dq@f711b~I~Fq><#e1HHwIzD!;yn_+qT2^?u zcAy$94V{6OJ1>c8_4CWmNP+EWK!8@-y<+}GU6jfRyh&U$7{gmzZ1LWX7AAXSEe;W3U;uN94zTr{O zQ(WacrV&7krYIInFL@oq5NoCfk3VFYW|tWhOV6L{D-)fOrO zA-Frn&g=>SaY0X&8zGN!!(%+6r>e7j?6l`+lkKlN?wOTa5mr${blglaJ{~`#)uTJ9 zV-(2#>@RuTP-Zoy=7X#6SWFSCj}d7<5VK4}1Tervkr5buK+ok^T5ChEDaEJLoq#%yxymlzn zYgj56j`@;2f^38Hy~a&{l-q+Z(L5$3KFHCB3Lo>+t7vv&7)zFRT|C)Je0s8O57uRW z#;boDWV`oh1)>hk_{b8LCngQg?#3Q(Hx!=?DTHn6(?+7E_J}0+(T%rwBYU$g=uzUw z)>Ziup^W8QSC{;8b4xJ2gk@AEcAxJ016(KgTqFq{8SxE>xE_Ltl+yPIS@SIY_V}8d zX7lJLn)*w7|IO1L9I zeyF2dAD@1KPm~QQUH>GcNXZavA{=d+Ehm9un#uzW@WEcR-`Z&XJfYs1hoFzO*Joyj z$=^{bAOa?tJorFfZc!uMP!Cvja4$n{&XwfzjKy*Z}QVol3#hBL*C$PMnpmz|DrCCw93`o^LD1+Y*6tmORH>_%gTl1gbfyVM5QBP5zMt73Pyr%^bAU+kG(2C3E5=neZoR+E0i z%l_q_mOGihWn!_Xay;Hx5{rDq4$ceO%*x0qZb;vrF2>&0f15Ed9>^=dm!Jx`A8w~WIxa&6Gp+CS{{z3telD zpyML}V-jnG^9DO!3a;5cJi_K|#b&zy0~n{1Nl_%m+S*eZ)60BQSWbl`)BSh;k2(x+ zlF#H38n1IAqFS6j>`LoB-NwHY@QchYQv81)RC#oU|BO(hW$;^K`)id?_pVeEVGx`S zJox%JBR!su?n7MsfvO~p+zds89FvIGDl#<1k*k?m13n;;>pFgq z$;!1v@|SB=NBGb0m8;Z?O8=>p|NXy$Qr~u|>Dd;)8L1l=aR33`|Dg4!Ggf@;swj|x zBi%vH0uI_U48Jv0i%cFgoYAn1Dop50Q4@qv;y^c;IOQ$$#)-R z6^u!W8e?J)R-t=s#Mg|65SEM6$KlA%BDdhma4@=20ouCfd|y0)#B1NaChRr(y)!b>i@*Nxjc;qen`8!J$c17si~Ea7EyH4U0MR?Two2N-OCn z(4~rmVYA+;@iS%9~gVfU1MS3A@jw zay+<2DhcOvUemxgKwSIYxq3j(*sN&gB3#*A-@EmRm@3Sp$NV?5VY~8oqnU(>nE-;5 znPT|QN-1Z6Dn0c11`gr0fc?0^d*VxoNWZCjaBcUUk>#6F(OZb+<%lx9{4&6Sv*LlX zzuo$fKF6@!9QhHcBw)VLy=cx0Z7gWdNpIfLIDBu=cg$o@USva1Ziooz?dCpzV>!dO1Q{tb)jHX^jp8yO(O_>H2U4|z6LR5H)Vs^4o}T^r zDMB@%up$4OKSuuUKT* z9KmrE%xcw}DjDo1f4_bYPX8bn6LU2#e-TEXtgMj35HymR>g|&%c&}|1lrUP~RY!M; zBdNX>XNd61&gVj$eVI_dbxk35*0|1zx9d4HYlu=FG^skL5s=JPSM)pWIu{0(s#r+N zw2+yL5{qzyzLf;Z4M3UID;WHqQtbrTpxDK+Ohq&`g-L(MYV5I1+lU+|seB#G=7`%$ z>L?T{uvIn#NcfDWj1^=CUw2MR)8s)!F|4#ChZ9wCmv^gK2kNRAX{O zf`c~7#ENAIa$avye==={{tubV88N|d=5rk2u zb&7==KyZUG@DHGWEK1#Kis?Fx|5q^Y-!QOfW4RX*A5`(~#tsFmAp+c*Y|8woBH{q0 zBo`-sB*y9~9cV*@N0htF6yZrm^=H;5903qvc^spPTUS<>kZh za2N3sCVTjs8(z@@7o$_~2W_Y*Hm=8JtVJP{4*OnKKaYqp+(4@qu}pT$b-vuF&S0tx z2MjSPwK7rbnyOtlbQddGy#XeD!J@fwfvi3EXOtSO)HSe7Eh^;3?aZe%Ia*q+1)_Ub=-!&5YKwdLTJo_O(8 z+G$59#Cdoc?bdK)e;;4;4GKo%+OH9vjkARs@}H$%(w@Of-8SKULzv57o0FO5yfsXP z>PNrBy=P2&ROU}jjFwv{fS`e6uv%q@B!LEe2XZy+CbH5ZcX$X)dgkH*!5M|MP->oV zaNt8QSYss3+0l)(0<#^;9^;`A8(p7+pJ8S%9*X38q|!%0XR^sh-JNdqYjgnBB3^5w z?`|DGIv(2n(HQa5G7}^)DQ}iPt9A`0S971w6=-Z6eo6Hxv!^kr%h53U)(*!vqg_#jdh|Sr zFa5UYM?d_$rM58>k||nV*_u$HWNp-9fM#V5%lQ~YaGD7koQg8kA&`Fbyu-(#7N<^q z_g(GY`X``JjZ-_DKS09@nat2sfvG!W%uAd}l_;X5Ykgi-^+k}K)tcp-f;;-70Z-Vv zItDrRQ_xY%f~@meas1UMOT?Di)ab?C^GzE9C1;Ut`EtVLL+JMMVkHPOsdC#1EdA+1W&D)d;2WTj8-vf=5<3s?2+T2Js~gq(52>$vG=kCE7|D3HiRT{DuDeUe0hZNlZw-- za7lV5eZl}rcZY*hZpUrrr1-yY2Nf|{7?L`7!0P)|4u^>GK}V>Ndk3BgIdCw0`vu)t z(BI$}B6=tJ=qkW%E!U9>qBpynb_*qSGo>2~(B%>JQ#7>~}TG zXk2xmOJuC}pjO*iKOVh1l1CLOLgSH>{{rSS^%aWfw7T8|IM&f0h-o+&y^U6r`n*GD zinFt0ocBphzDM${fz4NELLF~M=)Hy2^chgK-YMaee(cpOnFKvtai3CJ(MuWE{m zO&P6;6K&b-89f~K`NJXu5sE!dA8BwocKl19lWoc#sjUZa}=3d?C8n6mPeb+!s$GQ!`Vxc>TR)6D5{% z%gGU`&aGOZ9Gi%7)H#@!SK;dNmS0adZCH7f4{-oLvnOZws66z0E|`5>N)Z-58TZ)U zXK8lvu3BMdz44sdX^^^L53cT16}doX$2QZip!Cd-Vt+KdRb|??FfZ?aBT+)|3~)1Y z1`E^V09yv4U-NT-Sa4JwYJBc%w!k@f(J+6fsT3!`K!b=*ifu@g1fXl3Uv?&Yb}#4) zH zw`=kTw)(agBtzf^Nt!tG2w}dYhTJ8q%?Nh--f z+N05JZq*4=zOOLJ;O9MU2S!3)Y<0r2LD_Q3u2f4gaeX80;OxGjs#tPb1pb6ihDAkVZz`= zDgyjY0~qq>&rDd(zP*F6Wkn=yHh1iy+#0`=%|bLub;rXSri9<$LsxuNX=N_B>60Jz z+)SShY^*nI6Dv4FL6mnsm0)FN(0B^|EAmtvu&8=eIrxG1$?k+nJGkYNXT(sE*GB8! zfbi5*ESU|&(?jt}pZN8T-XJZxH*jfTvT$jm^=1khbdT`Ol8Z=<_d_~PT0eDiqQ?@Y zEqHlqJYjPOtVc#FQ`@Bk71TJ^bvL?STXkZ2?_kN(V89!H6037URrhq=?)cAqhPcV) z1gDKkxyK!N{RMl5yh}@zg0`z?L#Puv(#6D0@7Qa^u$+k-cyvd45(bQ6PeHq(yAXb6 z#>6|G;uok_=r3+SXmQX-Kx`(DTZhp_z(5LN?Wyp-ub>z7C2q*87 zD%2ob@6R8r81#P*3IE%nP0zOr^@1RP<{%Xk5*9`PFi!%0!c)1P7MuN+{a4@vfGvCA z0)T3hXD6JC@ozTpShroyVtBj~OqIG+NjItO6{U31fmdws`;UM*MV%=XP)x{{&IwIwo5_mBBu36Py6q7!&Q9jugg}gOgvLXNP5*+3*K@uhSaP z9rnEh{)3JiYn=S!A$EK)YW3IlI)E14x?cOwb8^$arbMo5ll`djCV6J0saXL}Uaf#4 z7DwRXj9of^hxdvw3FztxncUJIe(+)^LFtk_O66^4Yk^lNqqw5v^pG~Rqu#+z_(#qN z{?Bp-!!Ks>OHKd2NdDX6x*BT!BKOd7>HJ4|&g(hYl)0IafWa6VoT9yJUL{Wvia3(Qe zo%&j-BbQ7OFJ#W!0^tkRnpwnK)vCn7P`Fg|<`PG}brfaN3;LRl1OcX2q$$zhQnBf7 zgIF^B)s?TfMkT@D@o_m``Wi{qG6MAis$VN{v-!DEEGd+`rx?TwYMm5jbN~rFJ{?6Z z);#?_o}pr!N+~W5M4^Nd&rndtqhRYwHHl_45kZ_geh57Qg{DkZO2PkG=`5Zfb{ z6=X8^CWhe(95)gC+d4yLk1-*I-*! z+&l$JKdM2z$8$l?apHnd=5qtjKvP7Q_{AS}7Q)k=1m^kr1M?2CLrw_I&_2FjNpDMd2j zW{bAIaIRsh^}}khQo6TI)$CMb#in+#KoLQDvPygG({21tmJPTd@TR{!<9wqniIXBo ze(PAQ&T+z8kzvwmwVQWMRjF##53Bm>!_VQUcBRddKr}T}In0rvRo5C>E(-Io9W3yt zM+$mdrX+h5Lf553DaOxO_2A4$EQyTjaKZ_Z{_X%wcBjC*n>v?%ilquC%bRJv%8%!d4rhKU12IVD{67waHL?qVH4OQ^(G%VV1zUUd!$;?E z9G8k1oRoNO@|U8DSezVDvY4ENX5@l38$-;^&0oz4@1!8LE{dw(mbo6W)&`8IG-K?# zZUz7;6vSdjmi=&EfzCJhq_|7Cd9MijRnhLmnP-}Of*o42kjc<%jn%hNkRbD?y^woe zdV=RP?(?@C+FY}dOUgw@8g_V*Uq)B$ePyJbVDFa~Cmpf=AV2)Eqp3TD*u;!y^C|Fu z6#sn{lal5Z;|iwY2G`^K@R{bj%HY9`zvpwcwY!>p66OK+Cj|L5-gI@h&LMrdkzwcP z=r}o^QfJ5I?g4th^%0}{3EI3Tfaw*EG0~Z5_k4&n1%7&eYlf)#mrcFNgdp5 ztS7z#{N}&q7i(=i7ebr}UwHTSBWzi6I7Xu!>wE?^s+OJ7*Tb!kR=lzPd>u3G`=pb_ zO2FVFxx|j0$&q?WW7QP?{^1`O$l6I;x^*aWW;O7pepS%p`{O(2#_~UyEGc2XRQ)B3 z19@X*S|0Tc%Ao)m2tOr$fezD}XDtSZMJ}?qBo0)W;v}yB_8Z2f(!_0X%5kE=AiSeu zs^XS7JgG2mGZ8vi_t{2XjB?Tx%)Y4<)}&z!rj(Np{}F-Wa2C%SfJ;vs17*h$1S_Z~ zL~OG6Yt)p8u!4r5sffToWtbwSz;;KGcc&y8YodY>Vv7m*c%~Ga5g23ctxgr{u5EDC z;O)2G{N9y*JSyrROC&kz@*KTrX z>clf%tHgR0rnJ_F#;dJE*Khfv@yP>(3Z5UY~<{VVoLFCDv#2etIh; zqN8T6eAGSWLQ$WS3S;I>!0>Dx)Kwg+LWAKeP}#jDJKq8u#<}(6b(gZYgG6|DT!b$U zeahk`?9G|hADD-4`uia;$=htaI2QA;wQhlb>)U>q zQqs|hDpy7m`VD>=3`U^wRB2_DT%>oY5n-~yb>JQDqJVoH&#l(`#p`t=o{~xatcgLX94(4(qG<9V6cA#z`Km1A2oS* zZe(2;^L1A=U@W)#HojTd^}{%7G-PY-@mxApa-QCR=2l5OgjyeLK)2>il`Z9k|mM}!F^r9WUD=5Lo}8VxQ&e5$rrMv z#+Y9|3ZYDuM_*R(k;t2V%`2kPm7r{*^Pa!%C^*;+4OP)l+;;V4SB_4H^f;U8=PpI% zCYAwPUP`H`v&tSkI1v8i*^_Sg#u+=TyR^J&|M>zo*RkA^K^_`|9Ts~dwf?y`TKY9s z|C(k-%)UD1*+~TdLe04d&EU;IOi86!7aY~JMON?h6tnGfzgA*6)>Q0%E0kLWj2fji zm2!x;w|5tJf;;B47;DPcJ$xm?c#e0A^}{qc}6cei$?Eul#14u;`c4v3t?7p2zi!~T`=VMs7ZQcsUq zt%;n0(uzOvn*tY9Dti{Qx?-;?&CdQ|=s=jf%158I8rX8It0n9jf8?*cyTa8l-ub6a z^$zq>7>_VqbqGR8bQmmwirvmiot02&&$rOdhmIOr5`+Z89m5Lz2Z#=s!bh)+1~(-- z+GZfnNb*^PSXwn#**r^CC{;id468h;U@;lD9;=sB#n{5ihw;_}R^u|1{zxDiL))Gj z3jS3T>EVrFUa!?L-J;h_Y(CE0OupwY1Q-RKUYsua#@o2G)nhYh{fp9>cus}@Y?=rC z(;1^SG4Ox)0^Ekbc|aqWBBQfCWC@5#Np%*XusL7jUaU5>9pMr!iH*>vO%yMXTVA0H z?=jV}UQNd(7$qURS0l-Qf(8f+o#bU|V;^nC|BNa)87`{FsP|Z5=eaIA=1<~C`wpsDgw#1ZbW%)Zm}V1uDK37CD(XelAWC` zgDDo^1D{f((c&EQouEgNtY4plKsf=E-#r!k#qm3Fn^-%89`fCg!ld#EvE^2K|3DZh z&ExTUY#7WpSs57_(t`M(zy%hs&`T0q9A=Ez0*aA2UK$3+eV$3{sEv$ix?hD-KLO(l z4)G|)7chG5MhGUd9WPcN>hA&P%Q&0IbCufPh=7qZFx-=s6_F6JQ@CSL zFk|6rR8Ac?t?eqwuo9Vw1MXc=ZWk>+J)^&Yo+MbrC0!F;-?9?$Muow@zfzIZqO#j_ zqqXo{a&et4CUjc4_pgo(NQ@b=^+@Ll-ENZH{b>2LD!4^JmAACLJSKv_9FfWDZ*)4{ zHN6rax|-yO?tR_b!+XU;cvvH41BKnaxO$9!t}=Xem#a03RAx?_BTkJ;Si8Vj|cJx zck`NR+XCBZXV0$pDJFgV148kwGa)P-H_CgaW<|@9>#Rt*YZcXK#8<9|bB1P^4Kbgn zK-%ken#OQo4u2;jY&p18d&K@VK`=@v65>C|4ihE9PqI=mC z+O#ZzsN%eZ{ekgnSYFFdFkZpJ3U@i%FaBi7WI>>%au*+3?n$9?@%+VY>}HO#i5Z;2 zEZ<&wA*qh;LL9DxJQ_gzxyJ4$j~rpUhoVmVR79yeGRS153nq-h4)LzZZAWKf$#VV5 zFQypSrWN|_yZ{M@vF+#H5(&3GBnG5O`lf;b&H@9>m+;DtMEE~9(cto(1F1O|E??Q< zJDvOjuH`V)>+s8PB;2 znlAT6KxPwP2OhdnUj4u_qh@ZJ$i50Yu&JN^bDwx%`5{s zqk-a6^7Y2R7_(Ny(4d-=Tr|LAYGMCC5s~n771S)jfA9^O@8{^Hdh{z<*X#-|o+x>_ zTNP1|1fOBV(VeP%O8YTGi?_Q6^dEMnTs2jr@&`40rAh_MH{vX>7p4qT7u_;uouiNM zRT3Xz#qOEK<<|`oo&_*mj$lwsnF?+vRLB_;2eRXney<;XC-X-PHnlufC%#^FfY`@m z_o8!+Nop+qC}hSPhen|)Mjh=!Vk-+Vszj|p3a{TecDP!OVE2hI&d*DKu4~PP2V$Xh zc9n*cpv;xvjKnz;Cy`8;uEqH*k!aazl+@*%8;1odFsIbJ4CW4o48kil`df7_bq_r{ zfcdkmR2cA*9kGILCw3v`gP&7W&*0&TN!jhOP++O{@_IImw`yqOkljV1sY5?>;r5-* zLzf@g7mkEA49j;rzAu&3u|6!6wL4HJA8a|bS$QZ#C&q`5lzeY61BFLTekzgedC4m8 zw51arfzMn(mwlVO@?k97HPC#OdoD(2G*!5*Bf^U0N+?z+fkzr^(>0m#&OUrB7GM&7 z!Wjxqxvu``AEAQ)?`zf%Oy2`%u|zD^P)ATW;_XXrx$tO>QXSs>K|rktTyhRWTLSO6 z%D0c~qOD&!;gygiM5W`@Z=ulWn2b+@V9;(P800KlUh`_dp&bF9p(u9DZ1^ z&8p#kJnM^Y;fff8hTQy?(5IQ!o6sSiGVMXwMYKFq`Ujz$kazX6!ruT$zlK|%Ta_=s zZcU1TQcF*huz|{e{7|#5t4PuZ0_WiQkNHMxRvojP>`I%CI6g|#gh6jx-HJUEv|mK( zz50;Kn+?sT23**;{j@Q(>2~m}Pa9wTv)cFu$-Ul1Rwzs6U?kZA?RGK=?wAa*z(s7c z*yh?dl+DveCJakR+@Lr!Pko1DvdW?#QWwE2Rt+3!Jfj{f2CJ!Fbis;PEJSx!@_NmV zUGXC;cJrt|1r1XZtODU2CB^-iBx^eEGFth>)m{y3bgphVma_8&)223uA!z$kDoC|^ z_Oh6aB6U8q;V|7z@b2D{_}{wy$VE07LzInFuX}EzO!S<-faq>&Zhk=Wu0Ej7{zP{l zgXkwVozWMzqbE!Aa&URl7BXN!r$rY(Zc}ifw;nK|)@bf-!HO#`t0`1{GgJ|$g9w7L zW@QfCV4u?cE`jp+3)yI&Z<#k%9|?wP?M`RWj(2q72fV&a5>9vT^am!JN5*nBgn~Q@ zanlb@$s!dNBMi}6u&o5(>EpUS4Os4}hHHa+`#6z} zHw1Ah4s(TyoXPt*!XbY<7JH1gC#u}6CUjO86!ypzYsYmP*C zW$DIC4Wc*l4C+ohLGmcg);kP z`)mG|?EWztFdpmy4YJ>ZV7P6WZt+nFrmih0%mmiK4l6pf-UqdVJy%_`tSO08ljF2! zmvQliEDb+=-la2BZ~rtRAS8*XjY1SIA_<-uboLyWvHlo|HN>$ZI^U+H9$42AU2>bt z;!jPGoH$ zsH!S^y@;D`ybCue9hbkcm)-_$<2y%9(_LZ5J92C_5rFuMbo z_O`=YKeoj0*i!>f-{4^^*k=0WdhI=Nbm7_{SYyK){5a9~WF3P9tF5e93`Y_ZGt&OZ zcfV9pwM{Q;1(3N@U$|4uJwB-Vue*J=L;Na%Tf#rH^_|egXC>cRBc7kjzemN`gWV(Y(@0XW zIou11gLy?jbvJoR6H~DZj`F+agXWG87mKqoY^I$V2eJY%=i30p#DBx1blTh z;!eKwMmZBdJV3JHfoib-7MKz%{!0^Gz51of&pgvaTqTg|!Z4h`@)pst;w5!HPpH~N zdTG&7rkgxy)r;`#(T(n1Xe4XtfTjfzS_EyLUAg?HB0pyjwKTK&r5E)uY%9)e|e+JFLWOnAQzxAoP z9=aJTEHgSU^DFRu5MsG@fc(%`6}ql=@X+lEj92mb!sy?|U=eqbJF^e=m zygol1i1tWw+h`xqcBaUuB6~lQX>-{oCqlqVgLXRlvgM$)`5rWCxgN0vUjqJIFHh1* z2lHoR@r2>c4M;S){Y80kNI>uMd^DGRYZQ>K%(mlfPWSfMXz)@iPpIvdbgFcNpkVjBfss`rH0;DSa8ef0a@A zrCk(3OukrPM8h4O9kW~!cgW^Zf|3pwpw_Ht|DV*FX?_iSe4;>ws>${)9g-d8#oyh+ z5$UL-t3rn%hk_ql8h4S&aEQZVPA5*~j9b+ZZ0mTEf{n(C}5xBBWM1`%Oqxv zAC@vz@e<4Ls=1^*6~=P*tRiUriNW_l2%g@`H4dpv_P!E;$YZk$LJ}Et%?peLv(b6f zeP#7aM>fu>F>~kqB+jKPi=`(9)Z==3LGQf~c-&n1+V_3~cO__Y1~i*||LN;Dk=>2S z*>r0QFnLVRqpTvS{34{$(`LC8Xted!yx*ac4qXZ@!?}QZ(@*8 zcLE&;#Xu>jL3ILz4o}1e4J>Orr{2}k5b~-j0@-iqUZtSNF#<4cgNucCQ_R+tiWoGE z``BOcjWi5J7H@czP+e2BhBNVS{HD1GCi(dz#^evW-F}ePpt&Whp~#u0!<>WhuLh)N z7rx?cS6?n9yEW4@`xOxNwz0o8wZ_YUq*z+pc63Z4gfm3_k^4$M?C&W8wOHFy?tQ_f zE)Po3mxHCWv3p4g?>i4}$R~whOufLQvAwgD4hKUw6|8LrSGu^%@<7zOJ|)hzVUWl* zN)-kqp%2fvXB!rs`6dR8#eYt5-%=$$+z;lQsyOBY|4;If_j+I5%QY;LrV!|!^&Sp^ z-7O!3s`u(-SSSz>$oof$cUpq~>SkJ~=j3rscY{WOdl$IO$PiG4zK>Z;Xnak~uO=tD zqr5AX78md~zNT8!M+^|@l?chTO^_B5@02@0M(9hg!#h%ISoA~JwQki8C7>xMOS4o- zDkraK-ZP<*t9zSoR4eGNZj7Y6{ZBS&v;8%fj@bRh2p=p=Sy9(hCzGfkG06eyjp7{8 zgtsv$^Q-G$W;Da~w>gbXf%#=dtVo%mk_SpqUzX5W^$dt)O}_$cyk3m>mLvQ1k}w6B!H zPr5>oFe_7PrT3oV1kTZQC(hfsEo0mIqh>HKXhG$6K5eAL2bS`0;SVc)AMp+32bV2t zrW&b5%6fl9@;Gz*^GAx9T(oyWP4E=q6n5dWs?Kprj2Mi$drDT&m5)wHoW^vXDh#g- zl`k{aQ}Bd{uDihX+aqgJv-2yZY%Y{To3!D8ukJJQ*@GQK5scl+%aMZX!qWg92~u7H z4YaHD!BmEwiI+h(Ikvgm@rtzxH*MYjut z&VoHUXsj^Va>6f*#klRsQh(kT49gAun!+O@*}{-^yWZwqZ7_41;uWh*hy{Gz$d)Ot zZ!$&>S{T}G=8#ZKQIjmUFh~s}A!b60;XJ(GvOEdd?GMBKv(1sYJNh;kBW=R01JU&J zC#yW`oZY7sm*qVraaW4DbH#VRrj*~rgwd9bIU{a3vlo>%@FC^sv%auTNE%P8t#Qk( z%{ZA;rZS)HXGH*ws+3F>amy}nIQ(FAAPf-|qEZZxcn_@tc9^!m=p@F9M5nf_U!1^@ z)=T2R{Y^Zj+2al#g$B8OInPdL;NRs zVt}OWT}WtX57$&uz~CSj!%=K?&L`y}@|WiYpbY^CdN0owH!HE;y@IuWt|H?s79UE= z1-Jlcz--WMXu-b(EK%8#Ped_Dv>43whAjD{1_sp6p9>FyS-1To?UOs2Z>%n=f*W`} z^OQY{y1S2POqH9XGh>PMAJ-2-`x`D|!3xw@YXdoTG0XMN8B$1LbrcljRvdO-kl+$Nt(E*|s)$OZpZQbw13#22>6wOt%cuLEtVxA(<3EwB zH;wh@OwL9Z5{yKct1Y!07jui6oM; znr<1Xud#=wDUp;{9XD|z17o^H56DyxISsfv0wMF{5yGM+mf+f5O&%`gAZqGxJoP2|&A| zL%V2RduJa_aL*y@76lbu8UeERQoix`ZQHtb;k=f?6`tfrbx;nx%~;%y`GE642Q znSSB6VbGwizfuijh=EUT4b+A>=i+MV&-fGw>|4Xa)g5@}?&X5dC6RCDHC3a4PguL5 z2b*!%EhH*8(|>8l%|!ASPmFhN&hRC#Wikn=HNB;Axvpn1sJr>K zCSzBBY;x-NH~-|iYBl+AGHbregXJ`(QLNatSZn^!V~fo?ymyDvNzX{~t#B4DCI?cc9@I zkQ8m}z|-UH<8CoCTd%xJV|0`d_)Rtt2Np5p1Zu<5klqi}r}6IwtqBoDc@IV-e;dHHi^?&o5Oti%w0KABWkROK8-tbPa?n|`m1=N61_GG(RfoFL&{_P2g>lq5%6o%#V#u3u zpjcT`;5uUs+?J-VO2&;X z$-alUlS60wi#Ogj+e!zIky30qFBCL z^zY7=U7h|CS9?D)L~a)ilh{7~8A5#t5vC@auacZgLR3`l-fR2sXlq0BSch7f>W0tq||Z-==cZznF$%%`I#i@IA%14A(8q&`|l zr%5tO8T4`q0W>)qvH%mZwGU^ReKd0vaxQff(!VIn#IaFV+?-Ho*h()S{lu+`FJcP; zCxy?20rHZGAr`EA(Ie=>BM!Y0dbZR7C6Vdwr0VG;N8yJMQu&S;e`IQ-bcjTkYGw%SkpC4S6mY=tMB6K%(Im?j}d#azAw9p;TnQtPKqzO+3WngzhboSX`6TD0c%L;|^ z?HGKe;zLGwDK~3tkn@p&Q4u1#Xjq|>q|k?&I34y*(dzxQND9)BI))lWgI_k8(aFdB ztba0RgmCeQ4e0bz(|_1SmsJQ!qU#RKtqX@|R~waONfUB~f8sQR#3v1w{NWdd7hX1L zX|qBn_Sv)UlM9Kb#R;bhQwgCh4F^p+g9-{(^guw>X1Pls#Uw6@v$n z^G~;@d=kX(wI=ILokXy(={}CxcN_%z6m@8bK5OMSnpI zN4W5L75?Fd54>uE(m*9cDkc_LX`UAKxoH(JCI+{fND|DY>^%>l5TrSsY$NdcNQnpRx?(vvJUR~Rd7=dM{L+56<(eRM`lDgi~bg(A?>j1v2Y<~vVHLHgJN4;*j84dN8gZMUx6G&riOI-)D;P>5eJckW4&vggfZ{fWgXPx1^h7W>Rf}9 z(@z-At!7gU?Da~+)!Pf?Hcrfnsc%CTRE)fQSQD*=>|?R zLzOr9(AFkF6ir+{cNo-moeyK)YVV6W2dW^ucCD`V??7`QPc81kf99Fc5)(r9gjhIj zA330(P^wJFtASY!!if|)!A$l@!EuT*9xmo&a}ftVpXqou+5JMUuU!w6+DdSQ>U&`- zDgR)xT?;{!l${>^J*T$R3&AuNei`PYp)f-`K#vF>W(>kv??=Q`(`@=4SUwA3a)F3? zVk63&k=YV#uk#1At*z``?nw-$nK>HPgJLBnct z@x0Tr!66+@OnS^yV@A$5IGop-bx{yh{ z+Dfu!?BR8R|4j*O^@!Q|jRB)F;T z0_`%Wp8k0`o;ni8{*2`-thjAr0M zs=emjm^SmfHvQ!Tg&j|Cu=L~0WHMnAH+Q4KUr6h-;R=F7@{8B;DWTpJ<)hSwc&P#% z)I7GN+6%5%A#)(}Y&XE^zzZMSY12nEM5P}X&N^d@t+=lyVERi$JtbJWT9`QPZx}xZ z2+@N3lYZZjo7LugfHVZgd#(>aw!F~9M$tGds2OITb1FAN3?i6{gQ2rxUw&9U)8LN{ zJH3`nR{`>cK75Hteq`Aq>}n!Ji%lT3Bjs}hDizZ&PnW|Fa31L1hEQOBtNj7Rr4Vvr zn4~vJs5#@LIyjGQNE~KzwB!Dz*L)iN?~bbeG6O+RD;%lv5~k2Og)j`rvN1ic~kdsLrm_+l%9au z{POPv5eVo6ys>wJShTv4uYD#AkI6wQ(!}dZ@n93Vq=GA!E(Hcp4u)aA8#Qb>J(KJg za^!?||Afk&gmk4HWY$PGh^G?uCvkT^Wr>0U<)9AE3c{xm7<4=tk#ImPt==FsYFYNF zVym|hxS5m33F6Q2v;-^ROpO$%7BWY%%|2Lt9Yvq}924>*zD)xs+6GY&L?)VVf{uXX8|Q@ zZ174H^g=H{ARwPFfLj;g(W)mCs*HfSr2-cxNC0urMNx%fNfpM_Ww&My4B^gZIpk#Z zZxd!?i;=mg^4_gvp$lm)0qtMH z2mCNpRRl`V>ZQ!j>a}u7JpxXfaMU;gW9?|I(i5UnmQh|~IV*W8NgrpE&YU2M#=XA(-|i@+Ri6jjyPWw)=~ zDBxwhUMvn8K%UC0eC7D~wwuo_U$GK(-Eq++Bi8itM8I8&^Dt7s8a(Z7u$vJI_mc7U z5w}&|0L2Y4U?ub3YlT=W@)hN3rP$n~vin_^3s!TfX`WNNBP3I})ob1T!Q`%z8IaFy z1&~uyxn0jE$PHvXnO$$})t9ReyX=*(Y5l|fG1MZ<$Rw=K_b>hhsxZfMPOdB`;E36O z$5q(skaK!?gOwzYea0~?MOFE`vA!x8v=T6-ry`GQY@zHAjZ*A?xu8A&2 zYk62XF+%@^`k;Gk_XH52#FIa&jcRc~YS_`0t`3@Q@9ft9XAV1#I|*viqv@4~?iky- zxM}-)b3TsDrMyYA>J$@P{n_Ps$mocINcoKTEZc z^A!!S%F?V%C)nBE)-%6ERH%7lY+@rj4tJ9aZg-pW)NXfZ7!<`j{uJP?Lv<&|eCLp8 zvDQWgfhG2jd$;fVaI3iu_nn7Vmc~}tF__-0AOPG(cN|w-TP`|7ud8H(mKc=(G^D>; zS27+>UR1b2w#QfVGmZzP-e3*bA3tHNM&k_MPXb zJ1ebeLz{6Hg=hmH{^mbI$56;4lTI$MeHyLOV1(N$q!x25*?a0-d4He`TxTz`tgN}W z$-BT~{@MwUkQ*O8I~RrRGHyhf&3p`$sy{?CQQMi0Z)B;rnF1L$v5iGMTS)DZD`CBIX9 zFS#T~n-lY#Q{9|)7G2r_n7v_6`s|_}2MRkUgp%DJDL;=K+pvM0aB)HxOV=3^j(O-w z9Y27wQ_`k@i{m_VJ+i%2sM({~@LrN#K~wE32{BT~GIHZxOVro@uH%INtgSWLIHvw$SSI}Bo6yNv4x(?IM(+x(uv0RisPtt zc@qPag*nl_ojHkQ#=E1m&hLm5N^8Y`j)9pbiwyX$ik(#Xcf^UNVKkT2@uqRGIpoaQ zVkntsqriXC<TOExWn8oj`mH_T*AOq<_nKia#@FtQG+jeri!zvyVgoSMc9$m z6cwMpBqPif9bHkDr?Lr&4;&tGUppIL!M~u#2UQPD-p-l>Xal}fug}OdA z@KI!%66$5o4=tnJ-$cx6xP``gyRaHg-s9lT|3(#D(e6HrutT!xJ}1;1oI8~Bg?^Fo zo^YqN*T2JmTXjZ%5#J=y$r8+o`Cd_mr^GP2NP@mqM8DMUnz`u3dq>wHhB_XnX@2<@ zZB+9X+kN3%8+x0+$|kCd;EI@Pu1OR3R~|- z=ZoVz6t@YFgOMRdHYv2OEBfnD(aU9yqegMA;X#vB^l44O?n`@6*M^-pYEJQ)0Gx{f;c(}fN z$(PSm&xws_OoM!%bS1JD4Te&IgZ|Cnl!hU?FqGk^w%cf*Qrj9<@Km2Bz=B)S+l^3a zL>P+5B%#Tp%R*~ahEu~LMBJR@FHI{-zb_|k;(^!r^V@3((xLVEKs>}}-^LOlD|S%b zQw0@wSGR2Tc-x)V{*}?s;n2d&yi)syS=g8*&#Jo&i*n>la~jLb~m171iOiJXO=hYB;&uD`w(*<&MS9JZ6Qb_~;H@ zYw5A1l?p?SK+k1x6gVL|=Skj;pKx%AGnSO85``^2=)=zaA%BC~Hv)w|+16~a5v zw}J$wyo8(8WoY=dHb_)%J$}sR zm%{2Eg`A0RCS!~tepJ|}He$mevwlxRN_Xq9I3lP_G<~!%#6GHZb#vX6Jw3|TSJRo0 zmy;yd?n>T?2oibHfC@lFwBW>J~1QQa6uI+&U8Spi^_c`FqMZEn<>sd*6ic zY>3D=i#;~ZcVn3DXB{IMO3$4{=)>o}Ji8j(+C3#P3$6VVO;{&;2#r@7bHSUWZ&a__ z2z`Uf=**h29E!T@SD*IArdhuYu%w3cs7~zIV2Lc(dp6OIFqA;|3(QrR2`@l9r8?so z_C_*xGnv6UjOp}8mRYZO9M&)+u;cr84D0H2hV{)pX109`BZ`w5OXF+r#4zODZS@#O z+I;N^jjXmy`WY9*Pk>bR)*~p1HYC%7{Zco`R5Jc}sl z`%o4izro^;wqgl4+XvogdqTicJLV|YoEuAl4oCDvPg&5qcx zo*XYFTM_Dv95J|ky~EE7twnaIh_~QK&NEXXY%-0!j(A)`Qk(9_cYkm0Ay%oQ`*_n2 zKj9OXdedm7bgnO5Sge)cpVAnf$ED^;Vp&2yIVvywa)Dju>0Fd)YqpSsf5G%Z+}JWt zmx_ZscoXxQUAz*<$(zGS{%}|Sb!)aAIj_@ZAK=78uB2`(*Z4SDmuiB7fVb^v3)ktE z+Ygpbe@;X@H4;)6L^?{1tJPAPu=5E5PNhyF884*k3j{0jk8J-tr^DuNO8TZj^na+Ku^6KSpY+9H1Ss7y$5 ztKVDcp48U9LX901MRmHB!NwuoUzw~Dh5+MoB1rs`v52BqHDtjZ2W>adRT^v#YW0&xYlQh~4b>T4W3VYtLRK5EG$; z;P=LKR%pVSvSo4>BZ^|AaP4C4^((q)BKKyv+tkBxvh&ZjxxgPxqT5A5pSFl&tKD zMGw5XNZrBv)!|V^b;F+{s>D+gNcA41Xn@u1T!FleF9nqn0fuzrq6jnu_qKyG6F`l7 zn>4A!FhAon^{sn?kgP0BVitw%i>I6nhucpvTBZ71R7#Sx;A0J0D-K>=)t5;7Vbv6w zpU%5mL0k#%G`cqTE3eHayC)FdH}hElnh>T{g_V72&ZZMlR2k^`7oT9UbMk#j`Xz)% zi)e{eJoG<3-8<=I+FGu*v2wsioh|3W#$IS8*X>Pr)w1i$=E#nBQVdh;%B_ZMP5#-A zS*%2cDy>4B@TuQH-Kj#chHp*u0LP}G(MDQd)wjC+(C@tyOYlP_kZL>7Q_l)Pc@lnp z*pY)%f<4Ov>#!IZtnXHvyOVOGBT#ema|9h_86IX#{n#Ex#%GbO`X1Q6NaC?T3Ay3{ z<<+!SbCfeM&>3y%?j~H3L6EhE!g7P^5OaT}z|m8%W?GrFz)r%RoDOrT7Y%1*{Mnj2 z+(-pM9dEg&Ha+caiyr+VrWR=v91&THZ8fc2vBu-x_F(hCfem(VM;lF`W_o5~F46Ah zme1hV`tGnTt!B%M7_^w5txbS>9=w<>SE-aE>%w*)fqO1c!z*L>F8O@{-j?jcdReSzOhqB^ejDbl=?Gs>*oWmeyG%qj#@;OhnK8DhCV5%_jx~W|%-O3PYLQF~ z)~&p1`w7AILam;Z5>l@$k*l%~jDIp2PCPcEt&jrq$@Hb}n)BlN1uVS$HSt^_fwkDh z14|4eZS=HN@}1Y&p>523>%*7yuTsuBI2?C;+AJ6WHFoXsru@)hRQfceKZ@m zQ;7W%4cCgi^cUpJcB?Sxv9|s@v9{pjssGSOD3ew1X{HxYC{dDRhqVUfipCR06F)PQXf9H(^!}HZ8bkJeyHsEzLb`EW#tnb} z?M7iZ+_Xi1{-}R>&8=F|P$vDZ2L&kP!_m>>*OX1xiw=J{32ypJMP+r)e{T>)P zSgbiP=2hp)DBNH)qUU=d??veyNM1U77ek}}HQOs} z9>Bq#{aiHQ2CE3y>W-(gG*~B3&kyTLpi(w^?tPr%p^a>`-g}y0A5%`<1V>X+5~|1_ z(le^9ClxoI#qVk8x) z*p5IJTi^#MHuR$arACi0V}qFldN=S-?5pHRJZX%^mc-HCGFPLbs_}rFn?;a)+Xi`1>4yZR*4Dv zSy1(?Ca8vV(gRV7nuWp;74Z+Pk&JS_3c*?^1_ui)?WOAl$4o&G1BvuOXZJt@i61|N zNX9AzAQS8G^hPdA!1ew1O}KXd?Y2Vm5j3Mg;vd5F?7O41KS$cTt%bi$5KN8@9M9~q z@v7Oy?!<03og1TR7d)`fKg+`;RG-?<6=7F#SfJh_%db1I9ku zLLP4JWwEDRU`1>=MksD){FxVi9tcTEO%jPyy}H*#Fv@Jj^6MPF;bI#vo$K}vN~C6V@y%@KaUa3 z!410VfVwl~#iIcPe}Gew(xdbxz=#@r%$>8^;W_Xn8(|D?Zge4RpIXNK> zj22vGx}fzu8aZ&KTm2k<483{%*{Emt{ECMvIu4&w(HFV%veq!*e56|QTJ0Y#1qSKk z+07}ljt3*_I$IDn{oLv}J4^pz2L1!Dzsoh({*# zyRwVuQ-Hfu8^gkc&^^u{`#G-u!9NfPlV*EmcZ6MhV~E&#BIoz1_RCy-gMYBmJ3KM# zIFS{$jK;q(D-@&gwqQ6?dqa2fs`^_dqnI3yb#Nc>W1+io2_@6&z5OYiKT+%HdSQk| z{8hG~F%La33E;f&1Z+1$xA=XbYpZF6*S|MMe^udQ!E9kL)yI*s%V9-o_KFgn9${fJ zo5EJTDh$B#6Z`87`0|13SN-)rUcn3h{D71tc-OCL+XVV}gWz}32IbpF$pg)OGa@s) zM+mO;AYxXj6}c!0ah}}w1V7ruTv|jZ%olQ>rng5!D_d^l$SebzEk+D=ncXnoNNqDb z2_aMyXfaDUt(Iqlu2N3GB?0pWkWD`7QLrB)Ohod z&YhvpnT(v9T`cUe;M!@qFFqwQnwYMu|IK)8ny1dn>}^BPN@um|}ZB;*Qc0 zN^toms{S^HS{6Z0rR!svoz}e>HnXifAul)5x-P`LAIjPG4DrlyDhAx&c<;52t|PjU zLVgEk19|NVuj<{GwM$HJ^@bPc$@e1vxCkCrM}FZB5J-aw7Txkhj>pVCUl z8}IQF(BvA2gl<$tGZ7dbw|5U7jsSi@3w(BdPe#l+F`ZSrWkK4{S=&w5pD*65+^miv z?Vs2Ux8N&pp?%YO2nt`kFbi0nAicdfk^9qO`7*W3^`lmpsWo{~YGe;=zfK6$ZrnAR z`-gE-4Z>d_WX~7D8GIdpcdou-^Tc10Ip?h6i8zbC0^y%;SH0gkOK>`3bVK_t^^N;E zx_2mn;vEy5K9N%8@j@>z)(g&NET1pLwI^PzNz6i3UkOjXaE0aNSASl9e!R_=tCTWB zj$UacBqWrNj__9;-ctJ90sbOmBTRlr0?0VDcfqR90)wL43|EZ|_rmt|Vw)K*j%l&^GeVSdhd& zMxbVAe{@*=ex2lQWQ70pWH$f=AS*jz%q$`%ouYrB~J@)oU877O2#S2ARk)9;otu|{Bw9v+4MgB$nLm3x7p0fb6*<*wQD zUJVkZ=KYqs^TK__HN#sJEhUlaAiP5#s*}LJCvPS(Yw-wEZvk|D@6K>|q+=v2SSg%5tEDOzoJZM98~q)>Mz-$suvvlnq%LO^swH|(@1`i zuc)|Io$}o?b(2pyULAkxXEabe+-=kqMEyL^WN4G$qmwvDX-@D*>_7YJ$9QF%Pg2UM zU&7dp&R)*iJiYk}bNw5=8GRsdv#{WJ+yq4BH^cqjGY^E~>37c%9_?#zA`@sB#%hn; zqkoXq4pI8iJoofG)kI-}(%WPP=*j66ur2qo&7s+#>*=^31E8(*6BvwELAx7o63Zg^z2jW+m+=?PhEsP@wm}GE#wZut z5v6*#|N6^W^>r;K8jLWM*ckHUt>^7b|9b!SBSJ`}&U=Ho3(X##;Nc=nK|VQ{$;{wl zrN-T~8zQJjCx}h|KFnxC!x`_1r$NJqdF(panZE-LdK6Y)@TvT5`zG(I{xa=pmj1{K z?t}@A2R6^P-wz1rN0F4M5TK&yNqS^-)bJ!vE{pxf*2u_+)9G-6$8SV`l;4cd{zziy zf!f%y)xIf95(@piWuKZXQEc|Bpp$aWWkL--F?sGYE@uKvc&Gn{$By~sE)@U@2=N3Q4x;#2?;h9XpqbJ3jvIAT8u7V%ZIp{=(6yN;SGKa)LmL8~ z=Rc^z&~B*7!CFK|xVK?R6~Gyi*CUOKIb;%Qou;|&TYsU(P8h9 zDmwR@M%(!L{aZzdJuEGA#&Fvg2z zagAw`f`M1#;aZk2&8+do^KE^`M2L~;D@5&v^>;FN<3EN)PtG3Qb_!Uzeh0F_n;b|q1UcrstBA?NREd=;PvIDUMOpoH-GwI?T_mZ2O2^w_uK9g05AZ2 zYS#hO!)XtSJ0ky>J2K05^DG~hJ+7n^3Z@XP8>Am=Z6xWj;OZv0fVev)#|%I1iJ62@ zk#&A{a5dDbV1NpWc=7_*vIrdt3c&821sNr!JPm61GC%Yu$mMjgsI)p0L~yo;K;1-= z7Egze((+_mn8#_>Ir>cT(>79&_Ah6kE&J4c#hHXY2Mski5)4D^M&|SzIHehbse-n4 zhv(Z|Z7d6&XaLf}Pu2^@2U@llaJ1%FTjzSFRq`_I>q#GS2BWUF?2o@cetdtc*5dAz zG3RJgD05uKkot8;LPf)pqQ;^nle~Pxq;g1&5ih)$+M(P=ChIS zl+~)_E)DrIeWS{?O!+DHg>VohC4Xje$4?gY@AK{*569P)+`BmL1r-d z$NBokyv$8!Bu7WQHxM|&Y|B}yD4UQBj7!!k<^K;baQn&E2Vkx z0*Gwp?`)W_ukZcc)ui223XCEWrPa?9?{#*k&}lv~kqjn6W#bD$NE{Zc&aV;La>q{U zY-80Kxeu%xom8?r*)vIuoQxB%I5NS6 zHY!l3+!}^f5z;1P&-Vd$^$Y(VlG~HoaIwsYDW{bsQw5Gt|O2|hdp}bJMb%lPQ-$<>fUd)lmt>yv^WXK&Yx=5C;t%AFr zjwm(K{)JPDw6UvEpcM3kKGWJ3zse--QsBie9Q<~L*T8>b?!kitsm^qArsu}Oo(=!j z7Q);uLe4P(%NHFvHy)9S8vc`By;AQ59qLX^crakJzGbT3plW!vchv;=h4+R@HvuMj z;E87W2`sqciYgGgKbg%w14wX?bE=Yf(uY(398Ggv{Zje?-P9W0b z!iMMv?$D8wA5CXhzGYZ#Vhu4J37S`FNFSUSXS)S(%T^~f2o)Xj=nGh~9Fy+_{W*^_ zggW!*faLPn_*Kov3z;vcHk?Llf0yxzq(Wz8?-smx2&~6Ylq9D<7!0}vn>EYh`4`U7 z9KDexgH1+1fX>|bDuZ)i5N{X}6qhi(`DX3$rwKX!U~Khz{Zs4mb}gyxdEC%u*W6aq z;O_&fwrp46vrsRgKRBHCZ{#}3Kzh1CZbz3w^i?z7L$*4j@)Dl%2#LLCFyr^C=^ro1 zKPa({jGUPhr$~uTYSk6hX$K<2qUwsqWNxHcbDNM$cXyH89O?8P>DXq#wY%!L;VmsO zZr-36DBV#dmh6T?n2qyUdSs>q51YMBYOuj{#Z6sR9b#4UI}Pq6(ovH@wOIS3yURz$ zqz5m{i5QL9TP9zAtlOr#<%+G`Tr6{H09gc<8a<^r|1!%NZpFjj(>4IV;kUblFp!n7 zg4jMk1yD~H_$Nh?q$fl=kA_#4pDW5fW##;57~9ts|8z!lgM6CMz;+>w7b z*YeAXcHLyJb9DZ814=NT%n?YDUOZl&CI$X-zL1DZbo?1xgU;o5L1MB&jD%toKs@MK z8{-8^2uMXDBqE_hO>_o-d&&y~hFLh{fvdg{``rZ`+A{+}jr0Qf^t~TPuG%k40yI-- z*=t)?3-&8}p3~)Jvx7S1s_}Ss1SIg2&@6OGSa3Q*qmH8y22BHk6qhFi1f*hn^H_Zv z&L1i!0gW{j{IQ8>oa{AoeU}Ktyjni~$0&Z*&ZuUXQ=*>HLV( z6o~SGJ$BelH?kdoNCv<;s*<46DE=V*_jzzdBENRVrEuBy%GYMW&Cu^zJ0#= zF_H+RIzrg>!vtKYPJCnr7zzNQd1nvoKrgb>D5MCa^YPazoukeK?S(L+|_Cpod@{_$jUA zMpLq8p-6y)ssprufP@qM1Lah1cD?+F1LPRblgKpMf6~7$DFbbPpsojYnDikhk_wG! zMBMZrkvt}X6A$|Yi)%Mpa z3jIELv}r7ruHbKK0BT(u)F2oTvXMuql`tcpCx&k(JJe3>3+K(SxqG`Drk+-go@L*c z>k}GA!TZx?>Jyo@b9yf<6D)a=n?G9(zD@`igLvV~fXxUf;a?Q$6naj^?d`vY?#7E! z`)~Jy=VCNI4{B>@d3k#{AKKDd+z|_qN zN!Yp<22+r+EHjX@b#_Rpw~tT3LYVN%vD{)Ab-%;O&W#Z3xlNMUPDhWcAh4*-)j6TL zB;^>ICx}gn>4Ik3Ig2_jqX_5)sciD+BmI*DR4C*qq=Gh^Ovu{uwYO3khuMB=G@xgg zB^=*+`#Hn^a5z{VTuFx1a668hdh#GnTAq(Tn+3J=>&3f?ux4D40j8pXI5TSa9eJ-t zgVKPCnm`9Ey~Ur->PrcMa2`My25C*dcK}AZL6~n9Nu)Bg6A}PAyQ;5!C@fmeT3snw zJ}OBCW*{r%?Z`xFG3&Unj>+Oq2+>@ld&9i45pD|wTL}&x9j@OAR2VN8?G#HiB z2NfuK<_tCgHxGnFw9VBQtu_ubIN*bL=f;0JoBIC)6`LYg=Qk<|`Xf_O$Y)6Jlkwfh zY1q|N{o4&6WBXmJNqH{%jkC#8-*X_DF~WRxLW&>+n-GO8@WAr{!oWa7GLq7>poKVr znH@sFpeSlSK@VwPJEcp>@UvYR2%0>F4*N^rlJQpfW(w%rwd6AuaAh63#drR5?oZfmPg z2i4vg$*+8!7ILGCcaK}QiL<}worKH2BO|yC7OSaSJEOp&Wk0LP7P0a8&e+WIdwH4* z1u1!792X{~A2#!}#ZV&GBjy70-sZlWd76W`q20*?hZZ7GT+*BEOhH#wGm?dEfN0f= z3`;IGqeK76p01{+9d^x3jDt@GV?A#n&6;c8dJasIgd%Qk7G7;Jh79%0Q1TDV-D_z~ zH`!@XKQ3oPqtHT1BU{vy)qZ-QnVo27YMhhSUB2&bcAP#b1Mf6b{gVn zNY16-l6Y-NyJnqT{*X$CyuRQoksjoUaAmX6;XO91EC50(Bz34QXUn@cBV`m}Hv91s-+7Lj3IHHgYRf3n0W5GYoAvtx zE!C^5_zOm{>oc!Po_^&H4N=c)ur%J~mp0OYZgPzne_upoL7|J0P&)29m9x+$3?YlP zoAq(!a$;yaeH}Y$(=pwpc~)|7{i98zL}m8YF6C)}B1!nd3g_(VW}=y|oxPs}LeZyo z9`>IFH|lE8oQvu*bXB;wYg%};Rxl|N)LsiYnLi7kEw*~j%@4cjbYiLv)$i0?iOS!P z9n8ZObM%9yoV6*F7sSv!JmZPP&^RrbZjmJ=Zz0nsvLA(YmP3fKrPPLGttK ziz~xqq#WjqsT148Jj75)VG*Z|>OxZGLjC&TXU|?9>cpFx;P%do$f$g&VtV16i^r-_ z&ELCHwAJN}y)e)=^fmh7$}>$c85~xf@SAKn178Oh}5wnqmpz z=cM6Q9y=EkRS=U?o^g07JYBzlL3Y4`{&Nz`YiM2SR5XmxueraeH4nlo4)0caw5>nh zHi5(v!OhifCUfOZ466&)`Vt*74oh>vl~v~ zWT@A!W>wpsNL&$bOLE#13x!3rrv+WV`%qKdX_Eaq57K$I!hmpJQ7i%|R=eb@_d`9V zw?t$pbEyVtW^omZ7<;Z*l_90Dw%!?P^jg02ov7s~@+;8d_p7;FSe5{0WRLn&8(r(K z&2as47gFT@R+poLM^eMCd9WHZ*37rFl|}+bl0KwieT+i2*c=PfG$&G5vwW;|jq8Sx z!k0(q2xQ`6x6f)7{ZclTQ}2~T&~)yA0gg0LB3_og9DtBV2T-v#-9YU;3p7&kN&6f9 zYrd_}&o%e!u-2e{=r#c=o1Gu71{|Ug?$&Hn?qxLvLN>5Fl`Aj$u4H(PKg(0R8x<(K zFDA+XWfq1Jl-1uDMk&F1kg8YkV-3l?m-j;2;6$4PHc{s^b(y2FqCe~jgEpEM(pMYx!l2&| zbcn9LZH46cBo+3oPQNc-=hKDq3EkB98Z<1djLhisA}jj1ISz$Ev-(gGry0v*WgU9E z4?XAK{$lG)G`BZbf!DR6ni^~k@FiFD0;t6>IgyhB2m$N8CLD?$vSTB>+zMj;yD`qB zxqMN{jyZo^ex+z<(W!J}+F#6ZW%Fr&q9R!xWe+P(C_5z#|B9X{x&wewF0$M?Y%+f3 zvF~lgY)8*#!7{z(wG@RC#z|piNF3=mY!iQDagw{!J#33dY*rfH$K*?1fMRi zqJLyWgomuzKO~)(yCKfAqfFV~YOwA#8(*OVf literal 0 HcmV?d00001 diff --git a/localization/ekf_localizer/package.xml b/localization/ekf_localizer/package.xml index 5bc9c5e42712d..005bddd3eb22b 100644 --- a/localization/ekf_localizer/package.xml +++ b/localization/ekf_localizer/package.xml @@ -18,6 +18,7 @@ eigen + diagnostic_msgs fmt geometry_msgs kalman_filter diff --git a/localization/ekf_localizer/src/diagnostics.cpp b/localization/ekf_localizer/src/diagnostics.cpp new file mode 100644 index 0000000000000..9ff36561abaa9 --- /dev/null +++ b/localization/ekf_localizer/src/diagnostics.cpp @@ -0,0 +1,169 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "ekf_localizer/diagnostics.hpp" + +#include + +#include +#include + +diagnostic_msgs::msg::DiagnosticStatus checkProcessActivated(const bool is_activated) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = "is_activated"; + key_value.value = is_activated ? "True" : "False"; + stat.values.push_back(key_value); + + stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat.message = "OK"; + if (!is_activated) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat.message = "[WARN]process is not activated"; + } + + return stat; +} + +diagnostic_msgs::msg::DiagnosticStatus checkMeasurementUpdated( + const std::string & measurement_type, const size_t no_update_count, + const size_t no_update_count_threshold_warn, const size_t no_update_count_threshold_error) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = measurement_type + "_no_update_count"; + key_value.value = std::to_string(no_update_count); + stat.values.push_back(key_value); + key_value.key = measurement_type + "_no_update_count_threshold_warn"; + key_value.value = std::to_string(no_update_count_threshold_warn); + stat.values.push_back(key_value); + key_value.key = measurement_type + "_no_update_count_threshold_error"; + key_value.value = std::to_string(no_update_count_threshold_error); + stat.values.push_back(key_value); + + stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat.message = "OK"; + if (no_update_count >= no_update_count_threshold_warn) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat.message = "[WARN]" + measurement_type + " is not updated"; + } + if (no_update_count >= no_update_count_threshold_error) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + stat.message = "[ERROR]" + measurement_type + " is not updated"; + } + + return stat; +} + +diagnostic_msgs::msg::DiagnosticStatus checkMeasurementQueueSize( + const std::string & measurement_type, const size_t queue_size) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = measurement_type + "_queue_size"; + key_value.value = std::to_string(queue_size); + stat.values.push_back(key_value); + + stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat.message = "OK"; + + return stat; +} + +diagnostic_msgs::msg::DiagnosticStatus checkMeasurementDelayGate( + const std::string & measurement_type, const bool is_passed_delay_gate, const double delay_time, + const double delay_time_threshold) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = measurement_type + "_is_passed_delay_gate"; + key_value.value = is_passed_delay_gate ? "True" : "False"; + stat.values.push_back(key_value); + key_value.key = measurement_type + "_delay_time"; + key_value.value = std::to_string(delay_time); + stat.values.push_back(key_value); + key_value.key = measurement_type + "_delay_time_threshold"; + key_value.value = std::to_string(delay_time_threshold); + stat.values.push_back(key_value); + + stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat.message = "OK"; + if (!is_passed_delay_gate) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat.message = "[WARN]" + measurement_type + " topic is delay"; + } + + return stat; +} + +diagnostic_msgs::msg::DiagnosticStatus checkMeasurementMahalanobisGate( + const std::string & measurement_type, const bool is_passed_mahalanobis_gate, + const double mahalanobis_distance, const double mahalanobis_distance_threshold) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = measurement_type + "_is_passed_mahalanobis_gate"; + key_value.value = is_passed_mahalanobis_gate ? "True" : "False"; + stat.values.push_back(key_value); + key_value.key = measurement_type + "_mahalanobis_distance"; + key_value.value = std::to_string(mahalanobis_distance); + stat.values.push_back(key_value); + key_value.key = measurement_type + "_mahalanobis_distance_threshold"; + key_value.value = std::to_string(mahalanobis_distance_threshold); + stat.values.push_back(key_value); + + stat.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat.message = "OK"; + if (!is_passed_mahalanobis_gate) { + stat.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat.message = "[WARN]mahalanobis distance of " + measurement_type + " topic is large"; + } + + return stat; +} + +// The highest level within the stat_array will be reflected in the merged_stat. +// When all stat_array entries are 'OK,' the message of merged_stat will be "OK" +diagnostic_msgs::msg::DiagnosticStatus mergeDiagnosticStatus( + const std::vector & stat_array) +{ + diagnostic_msgs::msg::DiagnosticStatus merged_stat; + + for (const auto & stat : stat_array) { + if ((stat.level > diagnostic_msgs::msg::DiagnosticStatus::OK)) { + if (!merged_stat.message.empty()) { + merged_stat.message += "; "; + } + merged_stat.message += stat.message; + } + if (stat.level > merged_stat.level) { + merged_stat.level = stat.level; + } + for (const auto & value : stat.values) { + merged_stat.values.push_back(value); + } + } + + if (merged_stat.level == diagnostic_msgs::msg::DiagnosticStatus::OK) { + merged_stat.message = "OK"; + } + + return merged_stat; +} diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 0e46a26add852..68a31bcdded1a 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -15,6 +15,7 @@ #include "ekf_localizer/ekf_localizer.hpp" #include "ekf_localizer/covariance.hpp" +#include "ekf_localizer/diagnostics.hpp" #include "ekf_localizer/mahalanobis.hpp" #include "ekf_localizer/matrix_types.hpp" #include "ekf_localizer/measurement.hpp" @@ -87,6 +88,7 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti pub_biased_pose_ = create_publisher("ekf_biased_pose", 1); pub_biased_pose_cov_ = create_publisher( "ekf_biased_pose_with_covariance", 1); + pub_diag_ = this->create_publisher("/diagnostics", 10); sub_initialpose_ = create_subscription( "initialpose", 1, std::bind(&EKFLocalizer::callbackInitialPose, this, _1)); sub_pose_with_cov_ = create_subscription( @@ -143,6 +145,7 @@ void EKFLocalizer::timerCallback() if (!is_activated_) { warning_.warnThrottle( "The node is not activated. Provide initial pose to pose_initializer", 2000); + publishDiagnostics(); return; } @@ -176,6 +179,16 @@ void EKFLocalizer::timerCallback() DEBUG_INFO(get_logger(), "------------------------- end prediction -------------------------\n"); /* pose measurement update */ + + pose_queue_size_ = pose_queue_.size(); + pose_is_passed_delay_gate_ = true; + pose_delay_time_ = 0.0; + pose_delay_time_threshold_ = 0.0; + pose_is_passed_mahalanobis_gate_ = true; + pose_mahalanobis_distance_ = 0.0; + + bool pose_is_updated = false; + if (!pose_queue_.empty()) { DEBUG_INFO(get_logger(), "------------------------- start Pose -------------------------"); stop_watch_.tic(); @@ -184,13 +197,27 @@ void EKFLocalizer::timerCallback() const size_t n = pose_queue_.size(); for (size_t i = 0; i < n; ++i) { const auto pose = pose_queue_.pop_increment_age(); - measurementUpdatePose(*pose); + bool is_updated = measurementUpdatePose(*pose); + if (is_updated) { + pose_is_updated = true; + } } DEBUG_INFO(get_logger(), "[EKF] measurementUpdatePose calc time = %f [ms]", stop_watch_.toc()); DEBUG_INFO(get_logger(), "------------------------- end Pose -------------------------\n"); } + pose_no_update_count_ = pose_is_updated ? 0 : (pose_no_update_count_ + 1); /* twist measurement update */ + + twist_queue_size_ = twist_queue_.size(); + twist_is_passed_delay_gate_ = true; + twist_delay_time_ = 0.0; + twist_delay_time_threshold_ = 0.0; + twist_is_passed_mahalanobis_gate_ = true; + twist_mahalanobis_distance_ = 0.0; + + bool twist_is_updated = false; + if (!twist_queue_.empty()) { DEBUG_INFO(get_logger(), "------------------------- start Twist -------------------------"); stop_watch_.tic(); @@ -199,11 +226,15 @@ void EKFLocalizer::timerCallback() const size_t n = twist_queue_.size(); for (size_t i = 0; i < n; ++i) { const auto twist = twist_queue_.pop_increment_age(); - measurementUpdateTwist(*twist); + bool is_updated = measurementUpdateTwist(*twist); + if (is_updated) { + twist_is_updated = true; + } } DEBUG_INFO(get_logger(), "[EKF] measurementUpdateTwist calc time = %f [ms]", stop_watch_.toc()); DEBUG_INFO(get_logger(), "------------------------- end Twist -------------------------\n"); } + twist_no_update_count_ = twist_is_updated ? 0 : (twist_no_update_count_ + 1); const double x = ekf_.getXelement(IDX::X); const double y = ekf_.getXelement(IDX::Y); @@ -235,6 +266,7 @@ void EKFLocalizer::timerCallback() /* publish ekf result */ publishEstimateResult(); + publishDiagnostics(); } void EKFLocalizer::showCurrentX() @@ -376,7 +408,7 @@ void EKFLocalizer::initEKF() /* * measurementUpdatePose */ -void EKFLocalizer::measurementUpdatePose(const geometry_msgs::msg::PoseWithCovarianceStamped & pose) +bool EKFLocalizer::measurementUpdatePose(const geometry_msgs::msg::PoseWithCovarianceStamped & pose) { if (pose.header.frame_id != params_.pose_frame_id) { warning_.warnThrottle( @@ -400,10 +432,14 @@ void EKFLocalizer::measurementUpdatePose(const geometry_msgs::msg::PoseWithCovar delay_time = std::max(delay_time, 0.0); int delay_step = std::roundf(delay_time / ekf_dt_); + + pose_delay_time_ = std::max(delay_time, pose_delay_time_); + pose_delay_time_threshold_ = params_.extend_state_step * ekf_dt_; if (delay_step >= params_.extend_state_step) { + pose_is_passed_delay_gate_ = false; warning_.warnThrottle( poseDelayStepWarningMessage(delay_time, params_.extend_state_step, ekf_dt_), 2000); - return; + return false; } DEBUG_INFO(get_logger(), "delay_time: %f [s]", delay_time); @@ -420,7 +456,7 @@ void EKFLocalizer::measurementUpdatePose(const geometry_msgs::msg::PoseWithCovar if (hasNan(y) || hasInf(y)) { warning_.warn( "[EKF] pose measurement matrix includes NaN of Inf. ignore update. check pose message."); - return; + return false; } /* Gate */ @@ -431,10 +467,12 @@ void EKFLocalizer::measurementUpdatePose(const geometry_msgs::msg::PoseWithCovar const Eigen::MatrixXd P_y = P_curr.block(0, 0, dim_y, dim_y); const double distance = mahalanobis(y_ekf, y, P_y); + pose_mahalanobis_distance_ = std::max(distance, pose_mahalanobis_distance_); if (distance > params_.pose_gate_dist) { + pose_is_passed_mahalanobis_gate_ = false; warning_.warnThrottle(mahalanobisWarningMessage(distance, params_.pose_gate_dist), 2000); warning_.warnThrottle("Ignore the measurement data.", 2000); - return; + return false; } DEBUG_PRINT_MAT(y.transpose()); @@ -460,12 +498,14 @@ void EKFLocalizer::measurementUpdatePose(const geometry_msgs::msg::PoseWithCovar const Eigen::MatrixXd X_result = ekf_.getLatestX(); DEBUG_PRINT_MAT(X_result.transpose()); DEBUG_PRINT_MAT((X_result - X_curr).transpose()); + + return true; } /* * measurementUpdateTwist */ -void EKFLocalizer::measurementUpdateTwist( +bool EKFLocalizer::measurementUpdateTwist( const geometry_msgs::msg::TwistWithCovarianceStamped & twist) { if (twist.header.frame_id != "base_link") { @@ -488,10 +528,14 @@ void EKFLocalizer::measurementUpdateTwist( delay_time = std::max(delay_time, 0.0); int delay_step = std::roundf(delay_time / ekf_dt_); + + twist_delay_time_ = std::max(delay_time, twist_delay_time_); + twist_delay_time_threshold_ = params_.extend_state_step * ekf_dt_; if (delay_step >= params_.extend_state_step) { + twist_is_passed_delay_gate_ = false; warning_.warnThrottle( twistDelayStepWarningMessage(delay_time, params_.extend_state_step, ekf_dt_), 2000); - return; + return false; } DEBUG_INFO(get_logger(), "delay_time: %f [s]", delay_time); @@ -502,7 +546,7 @@ void EKFLocalizer::measurementUpdateTwist( if (hasNan(y) || hasInf(y)) { warning_.warn( "[EKF] twist measurement matrix includes NaN of Inf. ignore update. check twist message."); - return; + return false; } const Eigen::Vector2d y_ekf( @@ -512,10 +556,12 @@ void EKFLocalizer::measurementUpdateTwist( const Eigen::MatrixXd P_y = P_curr.block(4, 4, dim_y, dim_y); const double distance = mahalanobis(y_ekf, y, P_y); + twist_mahalanobis_distance_ = std::max(distance, twist_mahalanobis_distance_); if (distance > params_.twist_gate_dist) { + twist_is_passed_mahalanobis_gate_ = false; warning_.warnThrottle(mahalanobisWarningMessage(distance, params_.twist_gate_dist), 2000); warning_.warnThrottle("Ignore the measurement data.", 2000); - return; + return false; } DEBUG_PRINT_MAT(y.transpose()); @@ -532,6 +578,8 @@ void EKFLocalizer::measurementUpdateTwist( const Eigen::MatrixXd X_result = ekf_.getLatestX(); DEBUG_PRINT_MAT(X_result.transpose()); DEBUG_PRINT_MAT((X_result - X_curr).transpose()); + + return true; } /* @@ -607,6 +655,45 @@ void EKFLocalizer::publishEstimateResult() pub_debug_->publish(msg); } +void EKFLocalizer::publishDiagnostics() +{ + std::vector diag_status_array; + + diag_status_array.push_back(checkProcessActivated(is_activated_)); + + if (is_activated_) { + diag_status_array.push_back(checkMeasurementUpdated( + "pose", pose_no_update_count_, params_.pose_no_update_count_threshold_warn, + params_.pose_no_update_count_threshold_error)); + diag_status_array.push_back(checkMeasurementQueueSize("pose", pose_queue_size_)); + diag_status_array.push_back(checkMeasurementDelayGate( + "pose", pose_is_passed_delay_gate_, pose_delay_time_, pose_delay_time_threshold_)); + diag_status_array.push_back(checkMeasurementMahalanobisGate( + "pose", pose_is_passed_mahalanobis_gate_, pose_mahalanobis_distance_, + params_.pose_gate_dist)); + + diag_status_array.push_back(checkMeasurementUpdated( + "twist", twist_no_update_count_, params_.twist_no_update_count_threshold_warn, + params_.twist_no_update_count_threshold_error)); + diag_status_array.push_back(checkMeasurementQueueSize("twist", twist_queue_size_)); + diag_status_array.push_back(checkMeasurementDelayGate( + "twist", twist_is_passed_delay_gate_, twist_delay_time_, twist_delay_time_threshold_)); + diag_status_array.push_back(checkMeasurementMahalanobisGate( + "twist", twist_is_passed_mahalanobis_gate_, twist_mahalanobis_distance_, + params_.twist_gate_dist)); + } + + diagnostic_msgs::msg::DiagnosticStatus diag_merged_status; + diag_merged_status = mergeDiagnosticStatus(diag_status_array); + diag_merged_status.name = "localization: " + std::string(this->get_name()); + diag_merged_status.hardware_id = this->get_name(); + + diagnostic_msgs::msg::DiagnosticArray diag_msg; + diag_msg.header.stamp = this->now(); + diag_msg.status.push_back(diag_merged_status); + pub_diag_->publish(diag_msg); +} + void EKFLocalizer::updateSimple1DFilters( const geometry_msgs::msg::PoseWithCovarianceStamped & pose, const size_t smoothing_step) { diff --git a/localization/ekf_localizer/test/test_diagnostics.cpp b/localization/ekf_localizer/test/test_diagnostics.cpp new file mode 100644 index 0000000000000..f506dca1cb230 --- /dev/null +++ b/localization/ekf_localizer/test/test_diagnostics.cpp @@ -0,0 +1,192 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "ekf_localizer/diagnostics.hpp" + +#include + +TEST(TestEkfDiagnostics, CheckProcessActivated) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + bool is_activated = true; + stat = checkProcessActivated(is_activated); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + is_activated = false; + stat = checkProcessActivated(is_activated); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); +} + +TEST(TestEkfDiagnostics, checkMeasurementUpdated) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + const std::string measurement_type = "pose"; // not effect for stat.level + const size_t no_update_count_threshold_warn = 50; + const size_t no_update_count_threshold_error = 250; + + size_t no_update_count = 0; + stat = checkMeasurementUpdated( + measurement_type, no_update_count, no_update_count_threshold_warn, + no_update_count_threshold_error); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + no_update_count = 1; + stat = checkMeasurementUpdated( + measurement_type, no_update_count, no_update_count_threshold_warn, + no_update_count_threshold_error); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + no_update_count = 49; + stat = checkMeasurementUpdated( + measurement_type, no_update_count, no_update_count_threshold_warn, + no_update_count_threshold_error); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + no_update_count = 50; + stat = checkMeasurementUpdated( + measurement_type, no_update_count, no_update_count_threshold_warn, + no_update_count_threshold_error); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); + + no_update_count = 249; + stat = checkMeasurementUpdated( + measurement_type, no_update_count, no_update_count_threshold_warn, + no_update_count_threshold_error); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); + + no_update_count = 250; + stat = checkMeasurementUpdated( + measurement_type, no_update_count, no_update_count_threshold_warn, + no_update_count_threshold_error); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); +} + +TEST(TestEkfDiagnostics, CheckMeasurementQueueSize) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + const std::string measurement_type = "pose"; // not effect for stat.level + + size_t queue_size = 0; // not effect for stat.level + stat = checkMeasurementQueueSize(measurement_type, queue_size); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + queue_size = 1; // not effect for stat.level + stat = checkMeasurementQueueSize(measurement_type, queue_size); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); +} + +TEST(TestEkfDiagnostics, CheckMeasurementDelayGate) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + const std::string measurement_type = "pose"; // not effect for stat.level + const double delay_time = 0.1; // not effect for stat.level + const double delay_time_threshold = 1.0; // not effect for stat.level + + bool is_passed_delay_gate = true; + stat = checkMeasurementDelayGate( + measurement_type, is_passed_delay_gate, delay_time, delay_time_threshold); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + is_passed_delay_gate = false; + stat = checkMeasurementDelayGate( + measurement_type, is_passed_delay_gate, delay_time, delay_time_threshold); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); +} + +TEST(TestEkfDiagnostics, CheckMeasurementMahalanobisGate) +{ + diagnostic_msgs::msg::DiagnosticStatus stat; + + const std::string measurement_type = "pose"; // not effect for stat.level + const double mahalanobis_distance = 0.1; // not effect for stat.level + const double mahalanobis_distance_threshold = 1.0; // not effect for stat.level + + bool is_passed_mahalanobis_gate = true; + stat = checkMeasurementMahalanobisGate( + measurement_type, is_passed_mahalanobis_gate, mahalanobis_distance, + mahalanobis_distance_threshold); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + + is_passed_mahalanobis_gate = false; + stat = checkMeasurementMahalanobisGate( + measurement_type, is_passed_mahalanobis_gate, mahalanobis_distance, + mahalanobis_distance_threshold); + EXPECT_EQ(stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); +} + +TEST(TestLocalizationErrorMonitorDiagnostics, MergeDiagnosticStatus) +{ + diagnostic_msgs::msg::DiagnosticStatus merged_stat; + std::vector stat_array(2); + + stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat_array.at(0).message = "OK"; + stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat_array.at(1).message = "OK"; + merged_stat = mergeDiagnosticStatus(stat_array); + EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::OK); + EXPECT_EQ(merged_stat.message, "OK"); + + stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat_array.at(0).message = "WARN0"; + stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat_array.at(1).message = "OK"; + merged_stat = mergeDiagnosticStatus(stat_array); + EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); + EXPECT_EQ(merged_stat.message, "WARN0"); + + stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat_array.at(0).message = "OK"; + stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat_array.at(1).message = "WARN1"; + merged_stat = mergeDiagnosticStatus(stat_array); + EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); + EXPECT_EQ(merged_stat.message, "WARN1"); + + stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat_array.at(0).message = "WARN0"; + stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat_array.at(1).message = "WARN1"; + merged_stat = mergeDiagnosticStatus(stat_array); + EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::WARN); + EXPECT_EQ(merged_stat.message, "WARN0; WARN1"); + + stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::OK; + stat_array.at(0).message = "OK"; + stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + stat_array.at(1).message = "ERROR1"; + merged_stat = mergeDiagnosticStatus(stat_array); + EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); + EXPECT_EQ(merged_stat.message, "ERROR1"); + + stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::WARN; + stat_array.at(0).message = "WARN0"; + stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + stat_array.at(1).message = "ERROR1"; + merged_stat = mergeDiagnosticStatus(stat_array); + EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); + EXPECT_EQ(merged_stat.message, "WARN0; ERROR1"); + + stat_array.at(0).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + stat_array.at(0).message = "ERROR0"; + stat_array.at(1).level = diagnostic_msgs::msg::DiagnosticStatus::ERROR; + stat_array.at(1).message = "ERROR1"; + merged_stat = mergeDiagnosticStatus(stat_array); + EXPECT_EQ(merged_stat.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); + EXPECT_EQ(merged_stat.message, "ERROR0; ERROR1"); +} From 6a81ed5520477390c432663785e647f3da75363a Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Wed, 20 Sep 2023 16:21:45 +0900 Subject: [PATCH 2/3] feat(ekf_localizer): ignore dead band of velocity sensor (#5042) * feat(ekf_localizer): ignore dead band of velocity sensor Signed-off-by: kminoda * update Signed-off-by: kminoda * update readme Signed-off-by: kminoda * style(pre-commit): autofix * update stop_filter as well Signed-off-by: kminoda * style(pre-commit): autofix --------- Signed-off-by: kminoda Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- localization/ekf_localizer/README.md | 6 ++++++ localization/ekf_localizer/config/ekf_localizer.param.yaml | 3 +++ .../include/ekf_localizer/hyper_parameters.hpp | 5 ++++- localization/ekf_localizer/src/ekf_localizer.cpp | 5 +++++ localization/stop_filter/CMakeLists.txt | 1 + localization/stop_filter/config/stop_filter.param.yaml | 4 ++++ localization/stop_filter/launch/stop_filter.launch.xml | 6 ++---- localization/stop_filter/src/stop_filter.cpp | 4 ++-- 8 files changed, 27 insertions(+), 7 deletions(-) create mode 100644 localization/stop_filter/config/stop_filter.param.yaml diff --git a/localization/ekf_localizer/README.md b/localization/ekf_localizer/README.md index 977e0fceafd9e..6492f20331a66 100644 --- a/localization/ekf_localizer/README.md +++ b/localization/ekf_localizer/README.md @@ -161,6 +161,12 @@ note: process noise for positions x & y are calculated automatically from nonlin | twist_no_update_count_threshold_warn | size_t | The threshold at which a WARN state is triggered due to the Twist Topic update not happening continuously for a certain number of times. | 50 | | twist_no_update_count_threshold_error | size_t | The threshold at which an ERROR state is triggered due to the Twist Topic update not happening continuously for a certain number of times. | 250 | +### Misc + +| Name | Type | Description | Default value | +| :-------------------------------- | :----- | :------------------------------------------------------------------------------------------------- | :------------- | +| threshold_observable_velocity_mps | double | Minimum value for velocity that will be used for EKF. Mainly used for dead zone in velocity sensor | 0.0 (disabled) | + ## How to tune EKF parameters ### 0. Preliminaries diff --git a/localization/ekf_localizer/config/ekf_localizer.param.yaml b/localization/ekf_localizer/config/ekf_localizer.param.yaml index 8b24b79e71829..667217d2591dc 100644 --- a/localization/ekf_localizer/config/ekf_localizer.param.yaml +++ b/localization/ekf_localizer/config/ekf_localizer.param.yaml @@ -27,3 +27,6 @@ pose_no_update_count_threshold_error: 250 twist_no_update_count_threshold_warn: 50 twist_no_update_count_threshold_error: 250 + + # for velocity measurement limitation (Set 0.0 if you want to ignore) + threshold_observable_velocity_mps: 0.0 # [m/s] diff --git a/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp b/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp index 9fa877c8fd2f6..01ef658cf445d 100644 --- a/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp +++ b/localization/ekf_localizer/include/ekf_localizer/hyper_parameters.hpp @@ -47,7 +47,9 @@ class HyperParameters twist_no_update_count_threshold_warn( node->declare_parameter("twist_no_update_count_threshold_warn", 50)), twist_no_update_count_threshold_error( - node->declare_parameter("twist_no_update_count_threshold_error", 250)) + node->declare_parameter("twist_no_update_count_threshold_error", 250)), + threshold_observable_velocity_mps( + node->declare_parameter("threshold_observable_velocity_mps", 0.5)) { } @@ -71,6 +73,7 @@ class HyperParameters const size_t pose_no_update_count_threshold_error; const size_t twist_no_update_count_threshold_warn; const size_t twist_no_update_count_threshold_error; + const double threshold_observable_velocity_mps; }; #endif // EKF_LOCALIZER__HYPER_PARAMETERS_HPP_ diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 68a31bcdded1a..3c3c38dcb1561 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -385,6 +385,11 @@ void EKFLocalizer::callbackPoseWithCovariance( void EKFLocalizer::callbackTwistWithCovariance( geometry_msgs::msg::TwistWithCovarianceStamped::SharedPtr msg) { + // Ignore twist if velocity is too small. + // Note that this inequality must not include "equal". + if (msg->twist.twist.linear.x < params_.threshold_observable_velocity_mps) { + msg->twist.covariance[0 * 6 + 0] = 10000.0; + } twist_queue_.push(msg); } diff --git a/localization/stop_filter/CMakeLists.txt b/localization/stop_filter/CMakeLists.txt index 2d1867b8cd0bc..97a0443195ae5 100644 --- a/localization/stop_filter/CMakeLists.txt +++ b/localization/stop_filter/CMakeLists.txt @@ -13,4 +13,5 @@ ament_target_dependencies(stop_filter) ament_auto_package( INSTALL_TO_SHARE launch + config ) diff --git a/localization/stop_filter/config/stop_filter.param.yaml b/localization/stop_filter/config/stop_filter.param.yaml new file mode 100644 index 0000000000000..ded090b75b5bd --- /dev/null +++ b/localization/stop_filter/config/stop_filter.param.yaml @@ -0,0 +1,4 @@ +/**: + ros__parameters: + vx_threshold: 0.1 # [m/s] + wz_threshold: 0.02 # [rad/s] diff --git a/localization/stop_filter/launch/stop_filter.launch.xml b/localization/stop_filter/launch/stop_filter.launch.xml index 36a66a2c143c0..0ea92d26c9677 100644 --- a/localization/stop_filter/launch/stop_filter.launch.xml +++ b/localization/stop_filter/launch/stop_filter.launch.xml @@ -1,6 +1,5 @@ - - + @@ -10,7 +9,6 @@ - - + diff --git a/localization/stop_filter/src/stop_filter.cpp b/localization/stop_filter/src/stop_filter.cpp index 111d460be737e..ac0960b8cb67b 100644 --- a/localization/stop_filter/src/stop_filter.cpp +++ b/localization/stop_filter/src/stop_filter.cpp @@ -27,8 +27,8 @@ using std::placeholders::_1; StopFilter::StopFilter(const std::string & node_name, const rclcpp::NodeOptions & node_options) : rclcpp::Node(node_name, node_options) { - vx_threshold_ = declare_parameter("vx_threshold", 0.01); - wz_threshold_ = declare_parameter("wz_threshold", 0.01); + vx_threshold_ = declare_parameter("vx_threshold"); + wz_threshold_ = declare_parameter("wz_threshold"); sub_odom_ = create_subscription( "input/odom", 1, std::bind(&StopFilter::callbackOdometry, this, _1)); From c6001e9731916a59a504dde86c8c50ebea53867a Mon Sep 17 00:00:00 2001 From: kminoda <44218668+kminoda@users.noreply.github.com> Date: Thu, 21 Sep 2023 18:48:45 +0900 Subject: [PATCH 3/3] fix(ekf_localizer): fix bug in #5054 (#5066) * fix(ekf_localizer): fix bug in #5054 Signed-off-by: kminoda * fix bug Signed-off-by: kminoda --------- Signed-off-by: kminoda --- localization/ekf_localizer/src/ekf_localizer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/localization/ekf_localizer/src/ekf_localizer.cpp b/localization/ekf_localizer/src/ekf_localizer.cpp index 3c3c38dcb1561..b39112b1d8d62 100644 --- a/localization/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/ekf_localizer/src/ekf_localizer.cpp @@ -387,7 +387,7 @@ void EKFLocalizer::callbackTwistWithCovariance( { // Ignore twist if velocity is too small. // Note that this inequality must not include "equal". - if (msg->twist.twist.linear.x < params_.threshold_observable_velocity_mps) { + if (std::abs(msg->twist.twist.linear.x) < params_.threshold_observable_velocity_mps) { msg->twist.covariance[0 * 6 + 0] = 10000.0; } twist_queue_.push(msg);