From d32dc463e5e716287d0e78bb4640122d4e9616bf Mon Sep 17 00:00:00 2001 From: Takamasa Horibe Date: Fri, 24 Feb 2023 12:53:09 +0900 Subject: [PATCH] refactor(planning_error_monitor): remove pkg (#2604) * remove planning_error_monitor Signed-off-by: Takamasa Horibe * remove launch Signed-off-by: Takamasa Horibe --------- Signed-off-by: Takamasa Horibe --- .../planning_error_monitor.launch.xml | 6 - .../planning_error_monitor/CMakeLists.txt | 45 --- planning/planning_error_monitor/README.md | 80 ----- .../config/planning_error_monitor.param.yaml | 7 - .../planning_error_monitor/debug_marker.hpp | 56 ---- .../invalid_trajectory_publisher.hpp | 46 --- .../planning_error_monitor_node.hpp | 81 ----- .../invalid_trajectory_publisher.launch.xml | 9 - .../launch/planning_error_monitor.launch.xml | 15 - .../media/curvature_calculation_diagram.svg | 44 --- .../media/flowchart.png | Bin 74808 -> 0 bytes planning/planning_error_monitor/package.xml | 33 -- .../src/debug_marker.cpp | 88 ----- .../src/invalid_trajectory_publisher.cpp | 78 ----- .../src/planning_error_monitor_node.cpp | 312 ------------------ .../test/src/test_main.cpp | 26 -- .../test_planning_error_monitor_functions.cpp | 157 --------- .../test_planning_error_monitor_helper.hpp | 67 ---- .../test_planning_error_monitor_pubsub.cpp | 129 -------- 19 files changed, 1279 deletions(-) delete mode 100644 launch/tier4_planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml delete mode 100644 planning/planning_error_monitor/CMakeLists.txt delete mode 100644 planning/planning_error_monitor/README.md delete mode 100644 planning/planning_error_monitor/config/planning_error_monitor.param.yaml delete mode 100644 planning/planning_error_monitor/include/planning_error_monitor/debug_marker.hpp delete mode 100644 planning/planning_error_monitor/include/planning_error_monitor/invalid_trajectory_publisher.hpp delete mode 100644 planning/planning_error_monitor/include/planning_error_monitor/planning_error_monitor_node.hpp delete mode 100644 planning/planning_error_monitor/launch/invalid_trajectory_publisher.launch.xml delete mode 100644 planning/planning_error_monitor/launch/planning_error_monitor.launch.xml delete mode 100644 planning/planning_error_monitor/media/curvature_calculation_diagram.svg delete mode 100644 planning/planning_error_monitor/media/flowchart.png delete mode 100644 planning/planning_error_monitor/package.xml delete mode 100644 planning/planning_error_monitor/src/debug_marker.cpp delete mode 100644 planning/planning_error_monitor/src/invalid_trajectory_publisher.cpp delete mode 100644 planning/planning_error_monitor/src/planning_error_monitor_node.cpp delete mode 100644 planning/planning_error_monitor/test/src/test_main.cpp delete mode 100644 planning/planning_error_monitor/test/src/test_planning_error_monitor_functions.cpp delete mode 100644 planning/planning_error_monitor/test/src/test_planning_error_monitor_helper.hpp delete mode 100644 planning/planning_error_monitor/test/src/test_planning_error_monitor_pubsub.cpp diff --git a/launch/tier4_planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml b/launch/tier4_planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml deleted file mode 100644 index 31f5820ce5a16..0000000000000 --- a/launch/tier4_planning_launch/launch/planning_diagnostics/planning_error_monitor.launch.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - diff --git a/planning/planning_error_monitor/CMakeLists.txt b/planning/planning_error_monitor/CMakeLists.txt deleted file mode 100644 index 66932c63e8990..0000000000000 --- a/planning/planning_error_monitor/CMakeLists.txt +++ /dev/null @@ -1,45 +0,0 @@ -cmake_minimum_required(VERSION 3.14) -project(planning_error_monitor) - -find_package(autoware_cmake REQUIRED) -autoware_package() - -ament_auto_add_library(planning_error_monitor_node SHARED - src/planning_error_monitor_node.cpp - src/debug_marker.cpp -) - -rclcpp_components_register_node(planning_error_monitor_node - PLUGIN "planning_diagnostics::PlanningErrorMonitorNode" - EXECUTABLE planning_error_monitor -) - -ament_auto_add_library(invalid_trajectory_publisher_node SHARED - src/invalid_trajectory_publisher.cpp -) -rclcpp_components_register_node(invalid_trajectory_publisher_node - PLUGIN "planning_diagnostics::InvalidTrajectoryPublisherNode" - EXECUTABLE invalid_trajectory_publisher -) - -if(BUILD_TESTING) - ament_add_ros_isolated_gtest(test_planning_error_monitor - test/src/test_main.cpp - test/src/test_planning_error_monitor_functions.cpp - test/src/test_planning_error_monitor_helper.hpp - test/src/test_planning_error_monitor_pubsub.cpp - ) - ament_target_dependencies(test_planning_error_monitor - rclcpp - autoware_auto_planning_msgs - ) - target_link_libraries(test_planning_error_monitor - planning_error_monitor_node - ) -endif() - -ament_auto_package( - INSTALL_TO_SHARE - config - launch -) diff --git a/planning/planning_error_monitor/README.md b/planning/planning_error_monitor/README.md deleted file mode 100644 index 0890b32da6330..0000000000000 --- a/planning/planning_error_monitor/README.md +++ /dev/null @@ -1,80 +0,0 @@ -# Planning Error Monitor - -## Purpose - -`planning_error_monitor` checks a trajectory that if it has any invalid numerical values in its positions, twist and accel values. In addition, it also checks the distance between any two consecutive points and curvature value at a certain point. This package basically monitors if a trajectory, which is generated by planning module, has any unexpected errors. - -## Inner-workings / Algorithms - -![flow_chart_image](./media/flowchart.png) - -### Point Value Checker (onTrajectoryPointValueChecker) - -This function checks position, twist and accel values of all points on a trajectory. If they have `Nan` or `Infinity`, this function outputs error status. - -### Interval Checker (onTrajectoryIntervalChecker) - -This function computes interval distance between two consecutive points, and will output error messages if the distance is over the `interval_threshold`. - -### Curvature Checker (onTrajectoryCurvatureChecker) - -This function checks if the curvature at each point on a trajectory has an appropriate value. Calculation details are described in the following picture. First, we choose one point(green point in the picture) that are 1.0[m] behind the current point. Then we get a point(blue point in the picture) 1.0[m] ahead of the current point. Using these three points, we calculate the curvature by [this method](https://en.wikipedia.org/wiki/Menger_curvature). - -### Relative Angle Checker (onTrajectoryRelativeAngleChecker) - -This function checks if the relative angle at point1 generated from point2 and 3 on a trajectory has an appropriate value. - -![curvature_calculation_diagram](./media/curvature_calculation_diagram.svg) - -## Inputs / Outputs - -### Input - -| Name | Type | Description | -| -------------------- | ---------------------------------------- | -------------------------------------- | -| `~/input/trajectory` | `autoware_auto_planning_msgs/Trajectory` | Planned Trajectory by planning modules | - -### Output - -| Name | Type | Description | -| ---------------- | --------------------------------- | --------------------- | -| `/diagnostics` | `diagnostic_msgs/DiagnosticArray` | diagnostics outputs | -| `~/debug/marker` | `visualization_msgs/MarkerArray` | visualization markers | - -## Parameters - -| Name | Type | Description | Default value | -| :------------------------ | :------- | :------------------------------------ | :------------ | -| `error_interval` | `double` | Error Interval Distance Threshold [m] | 100.0 | -| `error_curvature` | `double` | Error Curvature Threshold | 1.0 | -| `error_sharp_angle` | `double` | Error Sharp Angle Threshold | $\pi$/4 | -| `ignore_too_close_points` | `double` | Ignore Too Close Distance Threshold | 0.005 | - -## Visualization - -When the trajectory error occurs, markers for visualization are published at the topic `~/debug/marker`. - -- trajectory_interval: An error occurs when the distance between two points exceeds a certain large value. The two points where the error occurred will be visualized. -- trajectory_curvature: An error occurs when the curvature exceeds a certain large value. The three points used to calculate the curvature will be visualized. -- trajectory_relative_angle: An error occurs when the angle in the direction of the path point changes significantly. The three points used to calculate the relative angle will be visualized. - -## Assumptions / Known limits - -- It cannot compute curvature values at start and end points of the trajectory. -- If trajectory points are too close, curvature calculation might output incorrect values. - -## Future extensions / Unimplemented parts - -- Collision checker with obstacles may be implemented in the future. - -## Error detection and handling - -For the onsite validation, you can use the `invalid_trajectory_publisher` node. Please launch the node with the following command when the target trajectory is being published. - -```bash -ros2 launch planning_error_monitor invalid_trajectory_publisher.launch.xml -``` - -This node subscribes the target trajectory, inserts the invalid point, and publishes it with the same name. The invalid trajectory is supposed to be detected by the `planning_error_monitor`. - -Limitation: Once the `invalid_trajectory_publisher` receives the trajectory, it will turn off the subscriber. This is to prevent the trajectory from looping in the same node, therefore, only the one pattern of invalid trajectory is generated. diff --git a/planning/planning_error_monitor/config/planning_error_monitor.param.yaml b/planning/planning_error_monitor/config/planning_error_monitor.param.yaml deleted file mode 100644 index d52f24553b9c2..0000000000000 --- a/planning/planning_error_monitor/config/planning_error_monitor.param.yaml +++ /dev/null @@ -1,7 +0,0 @@ -/**: - ros__parameters: - # trajectory check - error_interval: 100.0 # error interval distance threshold [m] - error_curvature: 2.0 # error curvature threshold [rad/m] - error_sharp_angle: 0.785398 # error sharp angle threshold [rad] - ignore_too_close_points: 0.01 # ignore too close distance threshold [m] diff --git a/planning/planning_error_monitor/include/planning_error_monitor/debug_marker.hpp b/planning/planning_error_monitor/include/planning_error_monitor/debug_marker.hpp deleted file mode 100644 index 0462cf359db69..0000000000000 --- a/planning/planning_error_monitor/include/planning_error_monitor/debug_marker.hpp +++ /dev/null @@ -1,56 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// 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 PLANNING_ERROR_MONITOR__DEBUG_MARKER_HPP_ -#define PLANNING_ERROR_MONITOR__DEBUG_MARKER_HPP_ - -#include - -#include -#include - -#include -#include -#include -#include - -class PlanningErrorMonitorDebugNode -{ -public: - PlanningErrorMonitorDebugNode(); - - void initialize(rclcpp::Node * node); - void pushPoseMarker(const geometry_msgs::msg::Pose & pose, const std::string & ns, int id = 0); - void clearPoseMarker(const std::string & ns); - void publish(); - -private: - rclcpp::Node * node_; - visualization_msgs::msg::MarkerArray marker_array_; - rclcpp::Publisher::SharedPtr debug_viz_pub_; - std::map marker_id_; - bool initialized = false; - - int getMarkerId(const std::string & ns) - { - if (marker_id_.count(ns) == 0) { - marker_id_[ns] = 0.0; - } - return marker_id_[ns]++; - } - - void clearMarkerId(const std::string & ns) { marker_id_[ns] = 0; } -}; - -#endif // PLANNING_ERROR_MONITOR__DEBUG_MARKER_HPP_ diff --git a/planning/planning_error_monitor/include/planning_error_monitor/invalid_trajectory_publisher.hpp b/planning/planning_error_monitor/include/planning_error_monitor/invalid_trajectory_publisher.hpp deleted file mode 100644 index 33ed7f606b4a3..0000000000000 --- a/planning/planning_error_monitor/include/planning_error_monitor/invalid_trajectory_publisher.hpp +++ /dev/null @@ -1,46 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// 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 PLANNING_ERROR_MONITOR__INVALID_TRAJECTORY_PUBLISHER_HPP_ -#define PLANNING_ERROR_MONITOR__INVALID_TRAJECTORY_PUBLISHER_HPP_ - -#include - -#include - -#include - -namespace planning_diagnostics -{ -using autoware_auto_planning_msgs::msg::Trajectory; -using autoware_auto_planning_msgs::msg::TrajectoryPoint; - -class InvalidTrajectoryPublisherNode : public rclcpp::Node -{ -public: - explicit InvalidTrajectoryPublisherNode(const rclcpp::NodeOptions & node_options); - void onCurrentTrajectory(const Trajectory::ConstSharedPtr msg); - void onTimer(); - -private: - // ROS - rclcpp::Subscription::SharedPtr traj_sub_; - rclcpp::Publisher::SharedPtr traj_pub_; - rclcpp::TimerBase::SharedPtr timer_; - - Trajectory::ConstSharedPtr current_trajectory_ = nullptr; -}; -} // namespace planning_diagnostics - -#endif // PLANNING_ERROR_MONITOR__INVALID_TRAJECTORY_PUBLISHER_HPP_ diff --git a/planning/planning_error_monitor/include/planning_error_monitor/planning_error_monitor_node.hpp b/planning/planning_error_monitor/include/planning_error_monitor/planning_error_monitor_node.hpp deleted file mode 100644 index b38a95f61d5c0..0000000000000 --- a/planning/planning_error_monitor/include/planning_error_monitor/planning_error_monitor_node.hpp +++ /dev/null @@ -1,81 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// 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 PLANNING_ERROR_MONITOR__PLANNING_ERROR_MONITOR_NODE_HPP_ -#define PLANNING_ERROR_MONITOR__PLANNING_ERROR_MONITOR_NODE_HPP_ - -#include "planning_error_monitor/debug_marker.hpp" - -#include -#include - -#include -#include - -#include - -namespace planning_diagnostics -{ -using autoware_auto_planning_msgs::msg::Trajectory; -using autoware_auto_planning_msgs::msg::TrajectoryPoint; -using diagnostic_updater::DiagnosticStatusWrapper; -using diagnostic_updater::Updater; - -class PlanningErrorMonitorNode : public rclcpp::Node -{ -public: - explicit PlanningErrorMonitorNode(const rclcpp::NodeOptions & node_options); - - void onCurrentTrajectory(const Trajectory::ConstSharedPtr msg); - void onTimer(); - - void onTrajectoryPointValueChecker(DiagnosticStatusWrapper & stat); - void onTrajectoryIntervalChecker(DiagnosticStatusWrapper & stat); - void onTrajectoryCurvatureChecker(DiagnosticStatusWrapper & stat); - void onTrajectoryRelativeAngleChecker(DiagnosticStatusWrapper & stat); - static bool checkTrajectoryRelativeAngle( - const Trajectory & traj, const double relative_angle_threshold, const double min_dist_threshold, - std::string & error_msg, PlanningErrorMonitorDebugNode & debug_marker); - - static bool checkTrajectoryPointValue(const Trajectory & traj, std::string & error_msg); - static bool checkTrajectoryInterval( - const Trajectory & traj, const double & interval_threshold, std::string & error_msg, - PlanningErrorMonitorDebugNode & debug_marker); - static bool checkTrajectoryCurvature( - const Trajectory & traj, const double & curvature_threshold, std::string & error_msg, - PlanningErrorMonitorDebugNode & debug_marker); - -private: - static bool checkFinite(const TrajectoryPoint & p); - static size_t getIndexAfterDistance( - const Trajectory & traj, const size_t curr_id, const double distance); - - // ROS - rclcpp::Subscription::SharedPtr traj_sub_; - rclcpp::TimerBase::SharedPtr timer_; - Updater updater_{this}; - - Trajectory::ConstSharedPtr current_trajectory_; - - // Parameter - double error_interval_; - double error_curvature_; - double error_sharp_angle_; - double ignore_too_close_points_; - - PlanningErrorMonitorDebugNode debug_marker_; -}; -} // namespace planning_diagnostics - -#endif // PLANNING_ERROR_MONITOR__PLANNING_ERROR_MONITOR_NODE_HPP_ diff --git a/planning/planning_error_monitor/launch/invalid_trajectory_publisher.launch.xml b/planning/planning_error_monitor/launch/invalid_trajectory_publisher.launch.xml deleted file mode 100644 index 2a55b62191017..0000000000000 --- a/planning/planning_error_monitor/launch/invalid_trajectory_publisher.launch.xml +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/planning/planning_error_monitor/launch/planning_error_monitor.launch.xml b/planning/planning_error_monitor/launch/planning_error_monitor.launch.xml deleted file mode 100644 index 438583840a8e7..0000000000000 --- a/planning/planning_error_monitor/launch/planning_error_monitor.launch.xml +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/planning/planning_error_monitor/media/curvature_calculation_diagram.svg b/planning/planning_error_monitor/media/curvature_calculation_diagram.svg deleted file mode 100644 index b1d69058c8dab..0000000000000 --- a/planning/planning_error_monitor/media/curvature_calculation_diagram.svg +++ /dev/null @@ -1,44 +0,0 @@ - - - - - - - - - - - - - - - -
-
-
- - Current Point - -
-
-
-
- Current Point -
-
-
- - - - Viewer does not support full SVG 1.1 - - -
diff --git a/planning/planning_error_monitor/media/flowchart.png b/planning/planning_error_monitor/media/flowchart.png deleted file mode 100644 index 4b594e126e0f37c9707eb4034e70c8f5e897961c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 74808 zcmeEu_g~L{`!)$Ft29MX?}{cVX{V(-8Mx^E{99IFIw`tD$yc8~JYXb?eq`Q&f;Wxo+LY zo9ouCUm_#HZ?>jzG^|^?f!1Tqgxvr z&b^&H8c(G^ta-dlI$lSLQZtxco|-~FU2dZmx6T3M;~RrJo}6tT>*`yQnEE!n*L>@~ zo@`ITQ2X%kCwto5Ywg3lrN&))Sv!{Ynq z`2Y2do!6zBx9syhAbNRt%m4nQwTBWYk8S$DU$gUo=z0RB>Balv$N!Jl|Nhc-0?EgJ z1Nz^`#&MkxKl~z{YG{<6W*g0rOmbE5c2AlaS`|33MjVFX97 z3%rw&`Qh<@8MYLa*MVW$coo(sXS6w(GwvsRE15)_*|F3P%bw{tZwl@77D{=RE zjm1`Hnt!LpJph)+XIv`(XM4Rk_w8h0I2fXI*1+Jolu@1BU%USwX5e*~O)8M=;>EtZ zUoEp}*PiBO$BWYvwPR<*=0BD+Z$Xlto_;dR-DZ-+|-0`s0n{U%QGWA^6%jI6O%^xAEWbmz;>Zh735r;-hUQGiv(}v*3EcAHNEldU)K`5 zLFenMC3nX{Igsd zavL%9I!nUpzk2=pb$WX8UGWn! zYv0^?KoIMmDDQW7?H4pgZ+g23s5R=h}+6kcM*WvVQC66VSzz1Rm-iEwv;4eF!rBN-S)~H+eERe$ zqj~Qv$sZHCE_He*-bf?QaP8KgEq0H)UQ|@1#i^>OxbSWyo#CJJuEhuAj^CjByPNZp zM9b#zT3uV1eHz3?P`XD&vvy`UW3DG8B;ZLZDlgp6$~^q{MLm43I8Zal{B*O>>C*l2<-YZp>aV{1u9BL#zjHL2iK(6LXL(oah9KL<^CQe zHkKd5!`vZCtgNicPmaQ3|E`%%s2r77>EB4@#j?@Bz`$RYI{Bv1zmc(EN=EN}?yvpg zw9It^C4NpP6!f$G9hK>RoI>v4^c`#Fw~@xi$qCl}^XE^RtY!0~e?Qlwfzb=^p%z#} z02+p*V&dWfvcX|*r9{_W5F&@qm@+6%Z&=$ha<~w(En5zH=WG6Z;b|>=h-R;|!`d+! z7bcOAkidHVni+~YMQ{3d^w;0?;ULcMVGCX}UM)?pT^wpK-}nm;t^S&?Djt?x7jL{a z`ZBtGin2B~Hf3Yvu74w?lnW(n!cd-MWbKFt%XqzcBbBVRo0?i{d+TgkL~u+D^J1d1 zwDh}@mZmTo?Ub+99ffgM+*g(s!oJ>2T^mu45#F`H%$l`k&EsE5Z``=Sd4kGzZuIOF z-&spb%gS@>sL8!ULTIjBc*rDPc`hlYgd#+VX7Ap;*ye@ESi+yxj6Hyjk*oM|_1|6w z%93u{r0w9Bawd)6D2t5r#>(`6P%rjBjt;AW>JZ!IPU(&Zrw1 zl~C>3V$^&6&-7wVV0XbUI4o|ixkgT}p{6ue-)9;2EY##>UK=*6sHn)YP?jEo&-+?) zRD}52A1R0{^Us&Q39rq|ox-2+?&HTKccH0Eu{N%O_8r zKYu=^Y0@F5pm3WRl&i_|mi}20#386u5u#+;Jk2jED%!Og z`rAcZI_wruVUnVq8ZYr^m*zd1j^B{X%aiRoq0`7V?$FuNl%Zy z&oC;+!Gx5Qf@_Pjn|CmYxzCSRM+z0HmP=AlP?WxVCnhGg2d1}Y&+Krs{jcc(W2T$W zPbM1{Iv;maeO$disDjt9F!#d82hpNVkA>}f+Y6ks-rU^0gN2nfdsHv+WZB1$4S{eM z2;6$goqv$Y{2UC06-+WaQ+Xf(X9)dU`A0)kGXeT0+iTCnXKzJ-b`f(en28y?E};hkmjwmzrL- z`|p>5N6I$a^MnbDyEH!$z5zxM67Z;!H`YbMB7M+hDf5{fx|;luLc+yE2S=wi*| z_Bff_t}}ym1nGS{=@}WFhQHOdwJqg*_ek)rQ1b97#vY9SEN#uPwzjlvi#>jmI6|wo zTsc2lELTourrWRSgVwu3O{b=&`f6g-U9Xs#9lh}3-isG67N+`gtlIO>m---~v-tY_ z>l?2PZqxn8P4T*r;NT~^rwt7|?lBxOPk$`#X7NELLjNbtZ+|e)NnB%cQAhGWC;J&a z36>K!UsjfAEHG#EdU7i0j@#U5-7dR0jegjpl@%{F`GB8s`g}|FWdipxmr0Y>*H>ny zr~3;E;d`QAUum6u>9Wv$N-RXFXSBTlxHL7}EI{E))}@Ax6tpm#<3am5I4&+s_F#<~ z>gs+9`Ybin*1l2>m^{rlOC zd^^c3umeSIPM)5g`82u}RaK0KjY*pW6bOUOnSB`6<*(1>oOo#cN)|^8uorb_o}W%} z9R7CLP~0M0gqQb$)d6bEc=%b!jhy`}TYgX62+`#Ine!jj*5W;l%sNHVJgXa#vha^b zue8`)AoG%{%`mNMYct5!Tb}HxYE0E{Xy}dCCM7wJlb-v1gf2$*K!_3_U)qQJjC7~> zyA-KKi&Ta3bnVr*%X6O@{Cah$k;g+nPQ%>7LdlHR-GeGlJLS}=Q#?F8+qP|!)b)%! zdSz*8DYv?dosz`sO?mkpQHq=A={IcHKu1SsZEdZW_u#<;c>5fxP*YR>W;lRL4C3NN zG+f%_l|N#BpAZcXA}otZms0*4Mb!2kJ*v$a5_-GuSn#Imuxj6P^gi!*ZrZe|J^$+E zrkBwV9()dDQ`QMR%^AXV<|Q>5X?L*B0qX60Md0(MI?MdLyu9>ZTmF1(Hq_s5W38;I zLUo+vK`4)Y{gEr_I%3y;Ie2=m0;*bmFD}B#>gK^3!ES&2I9Hi?G8r-9{=IwsuUP`h z>+9{tI*Lv_*t0N_^F2byTJ3v%U0wLmE4zi$jS3t`?ohJkiqepKpDl3QD`*j%nAig| zE$21iZ^mwJ+q%`9jV0ijdW-}jRtNSVO4xq)QA>sIROH?xtvQ}c^M|i63Hippl8$?& zn`wrrrNHV+eYWkAZxi-rv5z z@+M&6ioDQcS&uVBL|8baVRkvk?3yjr{+(n5s*2{!i!l<{c2iRR92!!# zQjFE&1ki56ik>}t)=TP~nHlY_T|r@CNm`seb}kkcgD{AJ<_sO~j@MThM~)v>yd@p? z?bZ1W+m6Yy1Vl%-M+#Y!lao`E%elJ#D)Xbe{N>qk3tC^kgdD+tfRKW#MzV zxVfLWy(Ry>fWbn*9X(fMYnj&Ik}wrOu*=m=rH5b;6&1c6O#G6PF)xBDDB$<;oau>) zJm(1(C+@EnGv7T|Rn?Q^SnASBR+K2HgJh{`X&7Rug#C|&+cav7Z>N^N{Nk? zN<4X~d8JD^D{y*xy2kyLw&v+;?Zn_~W@ct#Vd3cbS~_k%|NcRbF}pl5e52pCVMPto zV_R%_^6HiUR)&G`z8z6|sl7}K*gB=e4CkqOk27%^{)ekSeR>izuk4oejG1KT4{`!K zyHeuG6DLlL`h}P+`}N7v)6>^BTut4LRl^j~5-gno4OMwDGFUy>= zz3>@9I#v7QhY$6l$H~3l9lyCL`Kv|#eqqhIsi_3Pp}|4JTpO=KCVF}WBRXH%Q%_ZX zS}E9t=2(C4DDjkJXJ-en78j3R$y+s{3J42p%DkwqSAxYc@?0)Ui7{>7!7QN?A>d2f z(9|U9K7Z)o2W1wAt5*fb?2juwO-j<&(eYO*-?)4FXDkkA*N6KFGmH!jWo2cTj&4Z% zopwqs09nVGa`W@^laP>T(-a{zn8D@{eURaay3JausBB$+c08r3vQp&g;1~FOpc(77 z+~Y=RHe3j5fPQe)ljGygi?df;tUL`2q6!M!>bjmTM_*}ueL6!~ky+d|%f3&or4=!| zA?@*9=HlRBYCb-`{J5N)xy89Lzwb}7zF(W_-NtYV>_~sVd3AeYVxp<3>80WaXZEf0 z3Zzm{R18o`1SVrUeLnAbUsWKPU1o)G@%??*K2=tdZ{NPMJoo(~9M8Eo*AX4UA3f4a zGmL(GD9DfdfP$vtEv3X?Lun=b+T9-ET&sD=N{uUn4`$timj*V2mp(vUvbrKVca>

*jnEUd0D(9sE9{JiJaT*jl2 z!LKP!{k7+T>#)lX?E8}^;5fSLEAy`o1*&h*o7JK;Bqt*~Bq(S~ZwA+fpPsx5oasGc z&Nhd;5@%AMsz%zS3G&qJUHbHTVPWBFf326}YtyRG;^N{$>zXX>t38z=NERBleSFBg z+F!?-%2qX8=I_6g|7olG%8# zEdB1?fw$u<8WXfrVkAA)3J%ixeZ0pY^Q*t7M~<)hkbnRjT3y?oHS5hIdOy=+xr(yz zox9Dsk+84!Mp_g1Lqf;jn!{st*=dxnT!AI4Jakf7z;`DZsi4J|T6&=oK8K;kk@<

16L>I1~Ga9sObFfm+=V;LZ)hc?QgEfk`40t7-M%x}8zJT4DOOrSqHlT3s z;?8H(B*4KZlO0A{vP0s9mekxQqR8yFe@c5`3P+2)Zqru!b0#LTHTM~OD9K1c<0Q!6 z@9d~PPN1?)lRd!hJ3c-hn=}!V$wKAZTOE1gbN!hYI>&|T>gt;F?32tg{aky36lJBQ zNm8TS_tfi!NXH$+cJb({P-zyq&KR?E_V)IwJv!v|MTWQb&clZ_)zyhjh1f7y#M8vY zOIJ1-{$@|SCRwi&q^opng6_bAMMOkK=le1M%#mcI;T&|n_r2#fY zg!uV@vVxuS4@uyju$X0cX;#x8Pv$MqaZm=atJb%$dP^U6oi-0pkgW;j;pPTpbU;QA zrvZm*SmF`=*dLh#ujTJUJ~=m+q`$@coyYR85l%;2M@RM@lUfI;fdihl4)*uMvB_Vq z$}ZM%r+S-VX=e7cxL9Ju60UAw^L{IDyS%pc_UP7o0Mm$3!jxZA&hYh?`e50w4pOHk z>1A6WJyTIon1^+h`{n27+xLB5j=FTct@r#I&_VKki`L$XD&4$}rP@u({|f8~$m+FK zyOPyK9xC6bYSBu3y+ z7=!bhX?gVK=jW+cD~9V6mBAPQ!T9+2xVpObn5fAjKh@IG($V>b%<{;QBL}U_%zB5L zGb^^55GaE;a_u~@jTkl4KF<#%#Rz17wYaLI^T^9*?*z+x!Hn zoZB3)cmSSG%&%vtLu7$M#>Z{)Lo^O#Wo3QhcC4tZtgNbHb$T&9Gn3eQSC$3bK>mr0 zcT0q;L3q4`Tr*LK;OFZg=?OIt`5s8mw3>W9;=hvDH%j3t_&*h)Fc5N9i_ctyi z#LM5`T@xeO^up_?;K75*a9k!2jnkds>WKdEmm=W3ZH1wxt21$lrPj_mveSL~#h$Ax zO-7z0bd)9IY?Y$q>qR(p@sN6GM_5S0>AV!NoH?GM77Cs<{YA$Ym5 zmT6#UXmMeoE;@r7!MnVuLl)%1hYvnwHroY<2SE-o&L zii%sdY-w(822K+djl3uA?CgBC_tLp0N8pu5%EBoZ>Qw#B>ej5S@2OTx_D{ii! ziu(Hc`1ttpvz>A*0XJ{Ty!*(;!Es`0GY22v7;+fWRd5$zbtfh!%6=q0c|sr%Ow7zU zsqZ4gee~!N?5(Z%ny7??A#d2!vk7%FEz0%DTKP6V-zhaWQ>n8MT~SRA;6HXZ&kEs7 z#%JqKTAgBdVIBkcTbF)L}dKcF+_<)K6{%}hqiVpff=@&0voTP0oIGJ4N zI>RY6aEPD31!G(m1p0^j^PK;=Sx=suRz2!iz>55G4iT*7JB=}2dzvh@FE&U6&c<_b zL}<|W53h2d2E0nvz0W18EH4f6>T|4(e9l{Zd6s^uf&Ju#2}M~CkCh+}_3g|Og_g}3 z6I~yPISMv#u)SceHclorHI)dS_Uw7#Qj!R>;zJS+fP_q~qP#rUePI%-%c1h<5MZRl zwO{w>4;#O|u@Tv|%S7kKF_U8)9DOyCt67W0oUN(5hLa6mY2Bg4ZFn8be}9Gps012(?=WRsA^v2NdW`}j9q^{q;zwOeS8yhKb$eq96w9R1~Y9kl}P;~bimKnv`B7lR3 zxLelQQx%3hJO2@}=7hwGS;Boj%*cb`h?xqeSz&wm!i7vkS)3aXWQIXV(vf>&yesov z50R6@$u7>%b0f)utGx!4(UkT**R~68)eUbziqY}f*47rM8>^1BXUvQK2q<81_AFS1 z6I8VP3(cclb_4Znzv@E8idTU6;Mg7?x%e50D%r|2%>-IrgZ|M`CI$vY$pa11AKt$o zZpp4fwo_9x2Brdl8f3+<>+3i8Y-2RLc#&?;9)r((8u5FPrz>eoafSr8GKX4b_r$%% z!F#|gsaDg<-~%qr!^5MQISi~2?96NNlX8H=S^dCNbvc#^!*;zI`-B$E0@XJ10KUGy# z*l2~@o=ckQ6K&}iZWkAOU^TQ~==>ZVwK{)3u9^PAg|0;9u*uyrytxQ!x;a*7K_ga# z5m*8gxM?X!NsyjUQ1~G>t3DPBKmQ28Ymc~VaBG-xqcXu4hV=my9K8>NkW~~I9a!@~ z(=nC+^SXGsii!$2iAx=Y!lj46Ab-c~bvf>Vmu%0o=g4C^CMfu|smbZnqr=nt`#K*| z9MmoGSVoB>233_gEkF37pdC7>ia9tq40jZX=Bx)H)hKqhFC3U1dBjVjl41mXAWkrg zJtKaW2g0gQ5hz*cW%QNp92i*m$m|KY*4^8?Y4hfqM~4$I((d{F;w(cr%JlpucW&R_ z%vYnNqLTIcwHf_W#CI41;4Dp14VSp5rs;a3;fanFC2!>d-(q;lw|9peG3KS`` zMASRlAX)z-j-yk@7<`gJMqm^ws;c@~=5NKnrWuv2AjP|s&0S??V)7|kH0<@=Hj^YG zuwxW@N_Wj)of3J*j}9iCWGw{W#|3c;gkM1HgN>=8u&fMXC6AKwIMckU^5Ed$QS;jC zUuu>MHL)UaYBotKE3LwmCU#LNDO~Mzx;StsrSvv_qIo0oAMQ<0zT1e65=>5MsSHcN zp{)%-OYo}!yZw|{fcW9lHgDT4Yqjkgj4j6FSHxn=z8JSWzRj0u($*_O0lHh;B#ocC~C$yb`|8uqLQqV&#TV!9g<9LXQlg{t<$q z@UdeyjHMZt1_o_#^%WPh;lZ{u9v$wB@m%Q%GkTGl3b$d9s+VoX9F`U-`zSp8>Oj4m zx_TP8D>#xP3%Lj?C*m|}3Gwh(s5~_`Gz2LS@F#Gr0p8waaE}#2N12$IkfTb+)go=g zkp<=A=;(+Ah&X0z41av}>eVu1TR3|4Xpyoa5^r`&Jn5*AP@mwNvNG@Yd)hYK%=xU! z!h1G<8Uu?652vyB`hdgY`D=i~OX?7!K77_Fe8*)fVj0XJ_mD~X&iY9NR9#(N9-UX$ zw;I4FJwKE7`H%|s7a%_O;;?|PIY?I=UYOrFICD_)4u~8_j}i+$ms+w83ipEc0}+~0i4WdK+D)rY@xVaH(AaVF-M^E5FMf< z7fjHoH%H;* zbQKl&I78BaqqRCZAU^#l!vHpo7iB~L0m5z>%>3rjSmviUNA(G>S zHNDWqa%pN&P2f$6LF_>51O5FNchlFeGjLUQc?PN4Nl%|*x7C2aKdtn)ps1h_yZpC`@#hrXiIn~H zSbUMl^@`nIn!~a5_4OqpVb9g#l9E;M4&^sDA=DOO$?o0Tdh&v%qO69722NV}nUAox zX&;iTy$lQtaQ^%I#sTl|`}rkU2M}(Yr$;=&f=}{30r3S61!#ut)RqT(gr$X^D3X>Q zLh!JK9B_nSipmS3hV)Z&h#=;%UkC~s8sJ%;tzpV~25n2zLmI|Ki%Pj^={2+}7`Bw;~VB`z$0a$5N{#Mg2( z)btY7+e7zY4Up&*8E8+~p4SDvML0o5L6MMi;LHJPFa~UFrWJu~pow?+%EFTscr1%p z$D)dJ?p&<5_eNh%)Eow`?h-(u^(oFGhgwvu(UrPQHjFRwJ}a|8JA%wtC(}%IlHR3b zi8@@R_s0(nIDO0uDT4nSWqUQ*^XGq}pagQ@!n@9)p{m6!B_>rN$6*~n(m0J{pe9`v zYKbd|8Y2R5?dQM`7tPF|P>e@J*;;y!Nj$>s;?8Qq4Xcx1PKgBt270V4TtpQat_RM% zwpK%RNpf{5NY)wDL|kcH^KtP=SPw3iFyz86`&Qh5&b4kMJa;IlUS^=$i2XhSYI$7CUD9iv9G``U7>h6}!mx+|shHuo?*4EPcf_Ee3b@j)OeaJrGtP3M`0#da&PitvWZ`^{t^>lQZv0v5I(0FCnqZA?A-`}tD zSWNfwa$D-F?Z4FlJtsh!hNk~ur#zeQpj+rXk>SY;@cS696m&Z8QDg9F*D1?}& zX>M+ALF#&l7u{#el`26p)#}r@>rx$;jBvM01lk5M{NxJc1=4Xg;0utZv^iCXsIuSy zk92oGaXHPYx@)(PRUtAg*P~UbgVY}6fjumfd+kIEBkBySM z>aobx=SX~Ebqq&*M(#{W}#DC$mbZtlTTPsvD0z@(l|(Vk!r^nb3! z83LfsU~uYG1B7vtB0|281TIm{`9D1icgOObbatTO_TqtgJ_Q!@2qN-f5^+%A@=#Oz zj8cih>|y9(kQoGo5{L5>s4&|x=rse^&SxSdfHN;%K%lqX`1tYTdU|>%Po4yS-4}J1 zj+PdF^5IGkN{5_JU2up&uYHM$i1_uhbo1y|Z{wqcI8WG&l9Cb(58s4Vrq41mEG#S{ zA_7qnamn2&Sjp7U@o2InN}O(#1{2#Bmz<99^CKluO5M6`8|tYG3y}$bBzNvti4er+ zdZcWvq@7$UnfE)GC^G96FeMHmB2^i3Y?K%Ta!wc~%rU~qpxh(_7~x8Len^|l+xq&z z$E8msDEaA4750g++cCQy3W>(#u|Pg$miNZCnP%0lo*($l zKG9nZzk@k6z96P*=F2w#b)P`(^L)%*9i&eM00?$W#df~d4p@xRpin&*C~ zIh7{7E|P=GSJtI5bw~;Z-60mx_rxL4BM7vqM{%e>77!9@YHIop*+cm5SV3R1?b}Bi zl6I6H!ny7iS9x482cF^~tmsoPu^w{bm?{e?$y;~?=QCtM)xc}#&YypKNCo*@UZz&@ zKHqOJcnGJe4t?4ox%8%J*t=CN)O29vh=@bK)Wh`=vR_`FT}0+#aG;}io`dvx@H$17 zT+goOT64+;nIHk-7ZAzdc;lN?QHz42C3N;Bm-#ZtX;3fhnI}*SBlkvT(OEs85_?uA zlPC+)+DqKm4-t{X(%(_Ir8>zl>yqWyNd17$`&)Cyx+{X{hCtslV+AU1q2*WaoAcq&TfF+hUfVJt=K?uzY?l%d8eGfok3D|+)y3NGtU<+ zcGjg+nn}%w{z%%FIz_b`pJ|phHqK67dB{Q)EOX4NcT-&fhB|TLBGP!h z9VH-|riYpys#N6J{3IC}rXx@iL4#A$>Ox;k_R1swN+Q|lK5yf59#F?^e*F9-iz*8| zuXkEg{{b`&D2H;R@*Z(!UZ%H%0wp2vHb@2&K}B?vADiR?%GkbJpueQa=#oYG=g%Fe zG5+BRMK65VI=Vp#^eqN{>XPf-2Sl~OGZrF!yH!BQw;yC3f{te&H|pfKGc%{4PIbR_ zE$wW{ zj|4A=Hl}Ps7`k}*vc3w{`E%!f{P+=@Si{XoODnJTY2^ylVbDYIyJggrkfWwwTXf85 zARea8B19?`C{R!TU52H*yI3B@8_2ny>F4myx%$V?#?M?uDQWnd=Fn-5wnbT+wCAze z2SY01V1gD6Q2EY%ru;xR6!=gu?`PlXc4*)@%XUCMphs(a=cI*Abz#kCe z<|VJ9^6A!=UGzTTVlMne=F*p`es*?Bv+uS^Gp)4@)Jru?H{R&7^FzFxUwK)LfbTQt z54IUNx1unSN~C8R>EVB;+dU(RayW3lH-OOwjf+{Jnxz>ic=_@rLVh!=DvOBI=%*{2 zuI$j>ry;lz{FfIYKG?@F@#MmGw!?R{DJ0-IAde`W@(CU?ilbXN9#NZh`7DsZBeg&pgSG<1* z?l1DuBZsk$W%#%~$865w)Kr{a*6Wk~6n^By5X~@REF5}{W%FcB=*sHquTFw7GI2RU z`6Iq}9z0-oVnbnolbu^ZMTIbR5c_qUX}>m$;;pi0hTzRJkx+`jW5dr(Cv zpOKoxejcM@gQ4t0PfUoX^t#->owc@cin2)g%QqZ%aa-+{%x0$q|J$t@jiDsanIk7} z`|>4t56yI|TB_nLF!8{d3_b@3<#%MA28Lx9QV*B(l*qd;3}5}_+0Vg2C1txaN}R;H z4&mMf`d;|O23Iz+<}rAOia2N;2jUch?l6hFLgnDwD*ZwxmJ`zH_($exoLx&Fi@B)p zqMkVs2!Z1{W8-%Pd^4VHnsVR8L`7SnX5B3Javjv2+!l9D<;DbCb^s5>QlYP-mOnQ! zLKZc@8WiY337P0QgT;XqwfA#0{AvrpHE0rEBz-s;K=aALilouI-bNpY6W)XjA_9~& zok6tb4Mka;e@PDCA06d49d6+)W$JmLK#OWy_4dFsKsItra>*$v%6#VzCK99pfJH~X^6Nh34kF{{ zxbee2#ZVe3$QM|j7~RgazBC4%@z zl%aviiX8^1KEKR+2mZgmy+G)+F}*y2YNo%g6lhjr^^QK%&>tD*XUN;l8Di@J_{qtU z6)G3&BNK#t>b!hMd=~$@ zpP^T%zPx|A4;$#SeXkOeKo=Ajh99HI25-`k*=z)+4Un}tu4HpI@g#cA#-Uk;1RW5d zCH=w)DJdx}t>E5M;Yv11H0hk)(zdAbAl#;{Cs zVwmjvva*0yX3QRi6?1XbzzU+W7-chLC-}8k`}}?e1%OtdLkA|M=qyk#CEL z(5@8*7Ik%Y7P#Da@BE|q$689;3s7&G?EZo|)iKJ48d6Ol!-7H;Vh%e#6>IA;{2^e` z*N%06s^WVj3Kb11<*)U|L@F|dk>sAZM~^%(E^hy|@e`K_l%VORPh7%6wlQCT7MK6# z+~QctjxAe$7MGo!o0%CwnZEQ8fYLN4J%Q4I<%P_3bSK?#@-+IztG$wNT`%=>b+xLp zGV6}=rHsqcs}~qK-}icZdxPPqU=Bmtd`pnV_)Dz<(UZxc^R<@cl&j)<45K2G3Z7_W zWF&hy(iGCninCi8d>FvC;BS}GmHcJ>t$QmHxLQ%up6=JIR;L1@N2P$(o}9Bk>JAvs zZA@a1&OZY9B(je~LPt?ZMNmyXokAPF1U;@ee=SxW>>9%LwW(?$h;9%?)3dV$1q4t+ z8Ujr)a9Ey+Rv(&6pYtCcGOMSF?-y#K_LT+4Pkd2Me799u#tRkp))G(8sorV^ABgaG z6}?Ur2)u*x7i9ka&3V(jJD!LG?65ujY2KEb4#wL09pyogJ?RbuCj;-;7Wfiw2t5Tz zyYr{z>1)K}n`D3bN`SfCy@*l(bBt3AMR&u9V&@6tYBvUU4h~Ua;efOTEC`BmFjVth zTqmedx*kXP1w4a{2AS|Lc>6Z{vbnMEsD#~i*FF2^m@PwPhsa1rMoJ{_wr}sf_Aw+Z zY!23h=7k`!cMWgfdUcS$oF>W-{zA`t;o-V4$BiU!fp461_B4rb5WSJ8Xi#gI!{C3G$T4sE_@J7p$4v_n?(&%DsvAnO!Vb!;zU9@`Y;!U+WTXI0l{GatQ241fnjb2x6u zuD1ce!oU%@QDfdhMy3O~0Wxw_dfpo!R%AiC`qb1vtH@!hSJm#L61W>sba@`LRD1Ry zJ39XSiTcD6-yD3%EHX0WpD+;+b*RZrPE7bdc%X)tD=NB7cKf2k!Rh<8q?D8tl%_6S zs;G`s67+>CEC$Jn@EchcO+Y3b&9cbQctPUhpk9z%o<0StqP+bJVAvd%8QKpBeb4~0 znUoZ@$vDs+AQj>EE`E-RQ_tbKPYe@8vES08t;`Zjg3M>aUYVUhPW8>(^+v_S~ zrTF4+)80C-8logsE*XXrqI4DXJZb<)cELqr!9F9Az#+jg1ZMzJSZ3&JN)yO8ta+AI zd&GHqd;2Lksh0QHjaS@}K|%KLk0>{TbqDQ=%m>6hB3lY#Gu9I26_iwvECGfiI3TUk zik+v4koDi3a97eToZnQ*!9gIo@JZmE!a^~yuV6i(+(CsELNpzH{WOC-J4n_bIk0Mc z5w0PAl6vo7Ex-X7;2r_54 zCAJ+tIe7^>j}RKEk87&A)%bb$?ncz-x;{<#dsfy2Kz6Lh49I(= zx-3pJ-%(^2S4|aAB(2JTb5Bx>{sj_H1RNVStNo!ekrn6WhFxWQu6j&rWx^sMKE1?1 zxWZ=}L`J?S%mvBc-Me>LPKRm{C3?_qmz0!XNr1eRpE}omfJF1Pd7UvbsJCz5wsBGD zgz|hP+%Rn>^8B0Qp!_4&60ja(RY(%;IPM_%0nb{1JPCTaEKzVos1h=XI=)CtvvzeA z$@zRzi3Mdmh%~G~6g_UPIP?kJYrl*XQEE_B1PY&sjGwC2Ho|(amKN}1$Q8Oeo(Gxg z5-8ieN<~PY!C5GI{ZXf&H&F=X)hp- z0qQ0&I3pFICtN5{z_(+dNPipZ zA6CI@@WB~GM7aKTUMFzuU~vtqca5NyDMO{J;>~i(Dp;mF9XBQr^1zg1EKnLud)zNv zMxy8jbHHz)0w7X{PI;@rRXvyja=1Cvt|0k6(%r?6sx!XJ43~i{Fyf)#!~6H!voD9G zrj8(QL;C+Nb>v9XSbISqh!>>#AS?S^Yp+0m+Sl7_hQ+}0A{Ll4bztUa(~Z5M04gXb zFdO?~F+-%Sp%X&i1-b$N-#n06!nJ0kr!U}$F-f?W7aZK67>#zcit{dAAGWnnjaH%@ z5An&4`pctpFVQMOxR4L%_}B;9CbzklH*b~#h9N;meugQOZqtTr9AqC7PhqHGc~_u_ zK|3EjK;i79x<@m4S{Jya-gTD03KM#pP?kTbyc%6u=PlYjH;?bH7&f*wN92p{y6QSrM5_@FH*HZ|@U(kJ!n2_?Y9` zr3lZa!5eTc?+h#04ssYWZL6)N4v_Bb+lLllyU1rJlUZ0;fTZ}S$Wh?av{s zJ@q+xmoe+D^AfN4dxxsuV6aikG>^7b6ws;fEUg$l4Ue89zQ@0H-Z+5ik6m$wsbqxhlmyLLx*<$ro>tx7I8UnLG$#_KS%^k z!MJ+m`n|J6;sl-rWLw}JPQkXG#7qcIaBLvl?3B0>AZ8LER_%cPFzlPMiV8O$kNodm zZmsiwI;5Y^98@^1v+?ZhwTmQvRAFu1^Y*@8;v z1u{{zu;3hH3N5QJv! zr)qJ0e>zlwSLN_IBTD9iwd*jn))8Bql@seh!D(H89q;@1gIc8cAkF#UTKPZiQE!@d z?Nhu3eSFhplG(LODy~Z<61OMWXIJ!^Ed=LEDJb00;v{C|6A_yGf2%z(zSF1Bko|R! z)Aa5?$ay@E1nNr#7703vp0!@Uo%37q#u%?#EPsaJ#mOxdNQRbTPRr{r|3Vs#K-jO+ z$z50f-9sRSB8wL1Ra@KS|KlEl|JgQrh}bp?)Bj{17q|BOyZf+&Ecd8d$kvun#w#{9 zR#LbM2?;xV0;C&@p1j0rPO1F)Gym3w38M_T$X&N~UxSn{8L9{hlG)$BeG4ux*4XlI z%EUVYX!bZbF#MUaM${XuG@8)6bsA` zTr#vcx9!-G=E~WB`0s<+(1;LkvPYBR&o5&6w~%h!7;uTQQ0&J0ow))D{PzWat=)`p zzzu^nwSFMJcB4XNffRJiMN&5z<^2gH>eJj~UAJe~ma;O3*k33vVZQgzbANDc@n6&q z?Dz7a?2f_W86|6eBiioo#R>tVC2LAAH@$vsa-GEWEu;`o*qV+|LG_)E^RMTMRYK1A z>}2Wv&ufEN@qPn`ns=U5kp(efRgUJsT5m7TrT`j5&HaCD{9|+LNF~Ulj@e2d@pT3< z==|4EuD|gFuAMNNezi89SbhqC?pgv#n3+~@fc*Eh51Mjep)8Bih5kHE%A3l@&MrPD zC0HpD%OriDY4_g?S(2~;l>={Lb=OQ|a^FrSCbg$>{=$^_q}W#SmbISyXZ=L~`HL)m zdF_++G_TUr_cySNf4NuhEkCmMTTbE@Rc;j&S)18B3(=_u%KoUo$2a-+x|{W6<8UD3 za^u#2XPZmXT^w>UnL5nOMt7~UxAXcNI(XN4V-d?WGkwNMg8nTG>-pBBzy34_?>unL zi%*3GRpK-Rse%=IaMaR7Tvm-nC#Z*3xqAlt`sP-a-K^4~03<3@(vby$N%7I=-oO9t z_wO-hK0(KTYz9e4DCFs-_@|(s_pMt{!_^yeSAiQko=FF91zx7j7|M@`qVbs-RVAfP z+J+WCyp)4Lu<>If5I_zZWV*l>+6?hk)ZdgcbE z7I~i2LB-x?toQLuG36`K5Cc^}MM?KbGgs#p98CePGOh?iNZp_Y68f4?RzJD7f>AK#&56Mr32kNTxh8 z=s-PoEzcv|SD~fm%+I=n6D~4XovSD>5U1G$ZSJTJMDLgP@^_#wnmjccjRqkVCT)gj zL6*1Y#^^sXW+2M%6?67)5`zsIUPSR*&@&`2KOc;com)U)V0?BavQMSNz*e!;5-zN2 zuA~Ha6#|FFY$sxL;b)7HGQek-==%>IH16TAHYBR;N6^i9Pbsl;R{HWq8GL0kQ&ooE zN0vi}{F|B~hQd`29Xd;}MonrKSv3drr3ZlM#-_z zIHmzNkfdhQt;ui6vuEE`SMzXk-qlw@6a9(=$J!)EfSBs#p=(@y0C|bJjW1an7^D;bv3dpCTSTQV2jBm6Fn3vvfdvNtel6v=?-bii+xA=5s!w zWo7l!j1Q8g8qs)YQlM2!$RnzoMw{NaLKW4G%-C zf;`5K=<>EQ9=&%)g(U#AZm^qUz@tadEjm{l!|Ap$>xG)4J=PRu2rjUPpT2$58TEkn zU%>6K&5t*bFWC5@QASrsXWZh*(WAY~TIkE!3P}&~an3F-wr&$JEXYhPXftzi`c_Cx zbsdp|LrT~af&<%&1T(i9e`y*ngB%_Ok@q}seP7Y3Y>U#UR8#YC z@!~!XjwFmSq71bGm%3Ke!3Euj%F7O~94rj+P7uyv+%Yhx&RUfLwHI7tp)r+jHym!; zsa))<`Cfip<}n)6y|m;GCyA%n+u7wxngca|S;~9FZ%WSRN~EDtM0cqkYRfw^=H#80 zme%|5p)89Fnme4hkyjyObk0^JP~k~dZHN*OXFS&>w)eC#Gl!a@UnaKM54%GZSWnEe-Y9npvy z;mOCY^61UbFn}zYI^L$d0)bxmJqs*GM0AJ(0T)&D%(C$FXTb0ZTgr9DrPo&*9mF%R zq;2Y1CfqP*G&PKtXK)vsFWpqV|8jf2U`;nMhDw^k4*B^57bA~~i0C!oeh38os8-!j z)9eSs-~@9eO}VQeB{7_`|AIRRT*@Frh+R0Ih$~_WjiIvm!Y%LmcKJLmlgeu}hC-?h z*ur9O28vpfcQ1Lg@gF_GAn2v}HI=qu;o}d@{ zM$v>9^&8WGY6oGYp!{6xIWbVtV!J@m)A7iE&J|eo0l9Xg$q%6g_3KGa%a*JG;)M*^ zG}P2Y?E>-iK?`o{dAPF2F0}|;) zl^L&J_n!WS>=F%80s8uIkd21OqC*xbbm5-G<6&Ir4OHgRO4dT_b76E~K+g<|u(0mb zO(mjH7AdG>+pmeFy@LoBoFcI;5}a;Ve}6d_dw>Fjr4`HaNv~dM4C#OmAhvC1Nkih# zz>usPnVfuZj8={)1nM)m(vpQ$+Ln6Xv^h997=^HLPRqs@&8Sr7mI0MP3HgrrJS4rP z%dKZMG;EN%RvW{|?%1|1kp`;;BQU20-P+}CiqxucslOE$9(CvxdafE~(!n72N_vR3 zqt_j^AgnQ54BS)hVRPI*)W}--?i~w(a7+I@DtKmBpouRuEOcMUK!naRnHybwSTuG0 zZl`POe7)ba*;vH6u_CrcbCr8+NAK}yt`~jZarusXIwAC%vC2JiopirV8gK5h(Nb?5 zh&FBZzH(%0uYHZvk=5pnCuF^Qn!6Nz!ktEo#>S#S?u6^N0BlS)9P}t4D7}Z^SPyqu zT7ElJv%0)IS;cq5$67Ekb{n3#&uyX+MXiI$WDviAz`6{9^pY_FEkGC-=Q2BGFlI_x^JFvDyG|BPg5W3r2@EBURT zU{OG>4@96kH&KLw%~^B}yd+9H-w@kvT-@9!xY0dK=XEZw$q&5|3AR{08_XMHLn5 z_r@qilN{VGVYb!&H1=AMsNnlt2@{BV2MWXie+T?owa zLuHU)kmjgk4oEc|rmn3l3751_;Sp@gq5TnOi(EsP0WwI6=nOH1A4Rq((LsYtL&$~D z(&OqUTVksm!Y$h&{al;4AMemL841$r&8LQjBe*4LOwQ8sg%#V6fdQA17QtdVEDCDZ zO{zSH4rz=pfB*j7sL2ln2{J3@BEwHHl14i-a8m&INkgIU5V(8Mx$+fa0ux4wSceXO z;treAJ?KKfd^S`Dw78M3gZTQ-Q3nq|Uol0xpJK<3rqoKnespurqoZL$+PWNGo%Fs~ z(N#GqsdYw<2P^$x!CRyqp+LpaAS--yhR#;_j4?~ylVI&E9-)F ziC(I9S|-Wc8(q2E7?1XMv;$~T-x>zGL&&9b{@K;VYBLMd$=^RUJ&mqPw$<#T=t)h> z1l{b;NACkCNMiyjjClFYiuajdI%0>*che^i>Wjv4%-QZhZFlQsX8sv1+)HX@0)Z|o z#+%lVfBJ4xQXgiw@cDnS_9f6*w)?x~Q&B4O(1bTLnWf20c#%1gh{&9j3K^ooR5EAC z7$G4;W>H8eV=6L*3MEA5IM?&-^FL?**KVJ4_F8AH*8X2D&13#( zOtylU23h^3UfH&_8?ghWCNA(&0zy16-Hn**B1u7^yYr?e@ub-rTs-!oMZ)QA75vi@ zfdEAzQkl_1hn;#PeT{K8bJ?c-*3M&MrptlH_S%JA8PZmMMqWcVg&9zG^?takVFM-Q zXdJO!Ut=gM*8xFJRA^{T$={#245FK7v7jBSO2w2SK-GMrggf9+K-%idLQ@NFz|F6* z3Mj3%RIdX*;#)ne;=-GK(boEUdanBMz&{XMkSm!dVq}v5Q|cSLZpStr19H(vO$*Dj$4sPC>!<+|47zJ+Y9}FJN!_ zQR4dmb!!kw#J7KggBPjJZL@#saYhXJ9XwMfrExSG=?ui05aA)f%=Sky!o03T$MsNHjzVqgz2sS~=U2X>EN9t0)}Zm6C3eKNU2i+~anK#H@w8mw(>zCFA6 zCPqw&HW<$njUD4q7?{mB6`h5cMa*9NjE8OG@Oz5~iW^{OU{DHfC~(Af$&Jm+o5bvT zCL0~uHU1eoCyZ{G7FkC7nu>mQZmu6lNjWKGC@TvtxR0;d^XGhvnV6W;9g0zWc)m%u zDxcW>HNjvLf+<4Z2y+qn0OO+U?zc1AT&-^+oR1EL0_0Mtp=&J+n1e|oc{g}!<0B(y ztB+G-rqS=HHi85s2{kBF`1;UY+y%}m#6*|gfM99y?)seL@rjAK4$<-Pg0{05;2w_) zoF#E{-!#`hzw2I7QWCQB_|t(^Y8o1yT3VGXE8{V0*5&!MlQ%i6hR#fTSJIlgsnjdJ z-%`brXe#{GTz6LkK931_X)7dTq%)iyTb|#46>bz6`(T%h1f%+C@=V#nA;9L5p zrS(2IHJ4A}naAJH!=E-}c=jbpOicIum2ba@{|;_&m+t&!bY3NF+o$rg6e1_0z2XJQ z@3-8ta3x@IjJA0+wYX`#GmXVBk@(fovc`hP{U?YUvgGXF()aadE)MpnlWO3s;*{4D=wnQ&94^yZ-YFDUP;XI&)R$sB5Tk(kC3BPqz*Z$?tit05B)>zHx$Ve{M z+22VwpY7wLTgp7m{)e|-tEu2z$34_{Uggoh{wDrqi7HY#kmw@dmrtK__X<4o$8T9j zwX)q82TAbwBRwcGymHs2t{N@fb zS%D9m{`ghrsN@6Pq)o#F{@ddUnh3xDUs!jph%B9oB9I!gI}`O_c0E;68mJ7DIIuhuc}1=5Fs69mHwfW*k| z{PSMBwywbi%LyuqLzp?hq{lUm|MuMe*Y2#OBQ^-?Gr;)asW?Y6-2UV5(ga@nn=*pH z9-|ytzr5l9w9(~xA}0E)Dv;PAOkZ}M{8pT-Tp2)=|)ohoTZ+V{s-ho~#%xGhmlhQC5e;XS?K z#UH-kqeobDdPf6M`_eTrLsJ)J? zJnea&@sCeel3G5HPb*Gs%O78LqnOkVoSKwPP)X2C z^71xZvwI=+?{`z`!i7P;Kdq3w3I|Avocqe30v98_W4~_rQwaeIt%W}u6Jf%*u^5E$ z{OPN%c@qZh;&Zb#gS6yAJ8^3NwYMqWKK0GUT=MTP&38?2%% zr5pdv3A<&1K0eS&h-apwS04PcUs$BJ`19UYq|@PJMA)4uY1aWbPTk>c|3?EM5QU-9 ziqg`B#l_zx^OsKQkjzx68vc0Uvvk+!Q|@k_^Zk?YsN9K%)4$ayZS$Y*CHZd6vOWp8 z1mxua1X+94*ZkQnY*rwwJpxWN0nqnn@)NxOM?>DGO1y9BLc^cGCP)PyfrE<+<>q-* z)`w(78hhA=^!@*M#IL2$pJqME6T!{R-Do8~EvxwN50$e9Hhw$hQxjpC>mXs+N@ZCx zVfB6?f1veD)x%-kF;E}nN&e=_i zWVU8;mA-!7t@6rr0>&*-LuIBf7 zJX>TH)wuge z&9V5@iRG+fL;W|Zmx`nW9eQ^a%|-7JJaZ?V?(Z*RqIk!%L)AgcT2(7YV8^^i&*gnj z%{^bfUQ0a4@S2%9daWt*z8h|@ReVpP_j%isqjBslUe(_t=lzBUT4WBLn+wzJ-0mau zD=%dM0g29Ks@F%vU+}h_`O!WdtbNSv(%F|wTW01}&ry4M@Ti707C0Wvy3}MVhF}pC zB(;5gGF)6~x0eitEX8QSD>x2xXSpsaF!l*F0)Q?SfXu_ZY9@Ur)TuZJf;++g$f7ulY; z^!1LDk)@w=oqxYp<(`PkYsN44{=I1qQ|?JWI&iF%d3xw)nZNJH+ILHo9t)JW&0IY@ z9)@yTw6-)FE^_B>qZ!rw-^L`@tpr;F#9%-}fX*bi_2I4)0*t-W5#LMnW44{@ez*I> zV(^Dy-m=jOQ;&@e$(xQHq~ZuV(N3KyWoj>Qb%yyWS7^dmZPC~(*YTIflIjy>?neJQ zT)zK>QaAOPBCQ?v6GDe45 z+U@V_(7M>NjrHkhUD`y71A9ilp@SiNs;xDjHs%UY14T7I0r&;a{AA^oW&vLRzRIY@ zqV1iPTMyTM?V9hpN1eB$eStU=hbaV@b}rxFdZg)CY*Uf_n*Ft|+^YLDL6__{hFg?g z-xQ-=VV~e=cBlSCaX?_@%ZKTy?}W5o!4LLtU!NYXp*bjg>U8z)>`PDIAHUd6vpdae zVS7f`v!oS4vM}2szfWIp{?x*iXTE1H-&*cFRvOKzp=-CpBv_e=_EQ+9@vt>1b+sxC=F+B_<9@B+XfD z-}EHEwLOm6XZ>?}$|hj76n`{E7)cm=cleL>CY&nq)zA=ppt8@oUO;H1ctOG`&LP3+ zX~athCE)_LF*iGYXI*7?g+U)`Tgl#Lw;v-e#aDTAf)l=U=Jr&J6g~=C4V&~~tExB8 zXS;jZ{M4FPoAkGq)~!C5WwoMji)1?cGGzGG`195jJT~PIZuPi4GWWw>wLwJYv-_8% zy^Bqi+szBM8&L4kId4m}?ygHSO5iXlKI0!Us3?3fCU5Kw{}2r=-vi1M(amqHfzqzt z^J{#Mc~PW>rT{Kku3j&zR7x=B=r5_Q4h}v)&m_J)J@or0!;wfvN;6gYtdUjs8V_wt z(+R14I~`gQ&qg)9Pq;puw|5E~M8qd=RdzJK@4dH2_~mMy9C^8b_hPj!w5TL}==J-a zozG%KseRIIr2>aCZA16x^wIQ_$8eb~5{KhY6-C#cQu6?J_6YOm@27Xl!{QbSRyIDG)Mcq|mAGz9QeO z@0oTV6|XMy1m{0;W=KryT{va*{>|Y-tG2VNjCOvvo~LFxUuXF0CvVK9lgaNEe%X0A zU1iH%pR3c;Vr6>AnKc$enkl)5wyyvBIX}LnAg8BL>DI;hAJv~4MGvKpEyHEt&Y4FC>>94x zN=PIhdFH~gMJkA4el^C&@r83(eE5aor!)`Od7Zg+U_E6M-TJK$p8fvW)1hyc-SXP= zzDG&wrE4Czw1ee5vn){-9~!hj^#3-`iF6sI%6PehZRwze2o)=%Z?EaO_ht{(H7>uE z?yXhb__?Rz3Xfb;!ot>Js|SnT%roM91XrrA4!y!ptn>X~<5&^h(-hJJ+kP{ZhB4EW ziF3UEb5usga>ClGMbqxB*B_oO+q`G<77A`s@>|Bl()otU2Mon##$lWq{JJ|n|Kch$ z-NVQziS|A^;(_xiTn;t?+EuqrzI@LACS9;~M}9<=sBPu#msIr>zIr%By@e+(7tCj8 zS$Lb?W!u(IHPybZcuckD-J7EKFT`wD?!0==O4%f~KKk?AN|S+0N0D>7mgeacg`m6X zMI1KsT}fv*-F`MTnyGlxI;}q9IyY6MGezuT)=pvJ*{!nyK^3VT2Fd(BPfeV_5QA~t zi17Z?9t%Mk%Az#OQ*2yCYTdIyBRO}Csx8S_GB=j*?V!2CnF3I27)m~+P zORJ6Q*3LuSw)>q=f+ zyN%F8f7YElE?!SGi;C?N+ zdvb+BX(NZuORBVo1u)jQU+M3Db)T5s}r6YGylKtfs)=Mu08x^YbK5MiW`<6mmco+{;O>Cs&%fTb)Njqo4v{F zHT%Zn96pWG>dw8mPVZZDmGj9b)t7G+D%|((y;ps2rOBNqMY~n#;6d(%=bV){B4^Z6 z7dUhjDG-86+1NOj7K!eg+{&ZHXL0uPV$naBEk3up-1Ix_7I4Y=W$y3%6{bDh8)18x zC}NGjmv7aK5BZ*3l^&jG!F%D`#*YunzRW!9;l0}~_VJ0*)=BwfH45p}QWHZ-bFUVw zvy67v|GEK>w<&i`{Ojn4lOnZjk9z}~DJTWFaG<;QlwWRX&lelp9up*{uL%Gh+E)Pc z1Enq``-Mp(@N{8e_lDqDW~VZSj5-M-wZEo7r<2{ykn!Qxo$iA(TbuH(48Qgr_;7dJ z*7K}rqdJkiSR#3`PQ0f0T@(APjj!P zeRSXp<(;Y>SM&WenfLxv;iOLWsU<%h0;j`2PCnF9{qber^lhRnhjo1MB6jJ=_fqGr zZ}P4Tw%%fo?J<=4_D;Opc#`817v7?CjLOyV!PCOFN;k7(LCc?lVk37>`q)js)Ce9b zNc1k%G9tiCx-Gv z=FYt6R#w?KK_N-a?HaAwDl;*UTH<7?3&h!;-HhIIJdKj#^PQUH^?8w0nkI`qr7{{m zr9WO&?zWKQ`jVQpXksF|ZvAy`TBa-3(}9h?SLO^u7cG;O14<(qB4S!(J_skBkGZH$ zxi97#kwi`QTFXt;Zd;AhXh{D0p3;5X>Sg`0t1EoLhIh@CHv22oBvWhdXgy%!(2@k! z@auCkISCa>o);$$CJj6&e%Ks7a7c^`#a$gU>XnEKSB;;{ufEDD3)^5^1MeI)e0olaj|77sR=kxDzyN=Xw} zbHw~*_wlO>9M==A>Khi%dVY8$A+c?sKVhGL$EhO%yEd#>;+Y~zoc%n;cDUB(b$G_k zf~2*{k4RTheU*0VVT2CWn(@7)wT1?XJ0?%6mhUCeKS)CjW%63hFz@Rpy5Fyfl<{i! zD~xZ98X3)FyQ-n(#`pH*_059!*ZWFyKXH>CcFbNpBe#V+)y-9UNXh7a;-2$YwTmfG zLCHh~g(kM9`MZsvw)OyXIgf1(teB}p~Xs^+8#vO{JYR^1PMR7|LHQ-mH zNQJ34pCx`mAdWtz%O1Tu^a2x6IhQT?ubSC4K(*;P4~6THlppwUQn8AoFi3i^gCjjl!bglO-J;v^|i!{ znw~JU#2^N`w`h7aCOdYYc0Jl1w2Ax|1$)3cT;gEL|K-z;Xn6LPx}f7m7opHy;7hMt zJmlMPt!5Jm-!JLLN0+MmoEFa>Ul!JWlb(~F@wI%-6BMp!83z8@pjnFZo!qZOYC3*I zX9w+qJSDDrBU%fR0<3=5I2mx?;^nw}KR-4q*8RRg4+&CJ&_4r(A_C-%rxh;KW`hRm zMM`KRD7td}yUW&TkEDv#EXGGcz2^u{&j0MA|5V)P{eNE=Ts_Y-tfG$JR+vW%RChQJ zCH}ir{LkNvY83(3MTeCTz4&_(CvF!oZI9eYDNBnzlKLFg%R8HIah!fdJl5O7Sc>G+ z8!2vSVe7>#L@NgZPy-@QAwE9Z|6~mfB)Nfw1Y)oRXbTK_)3SGCMThi7E=FS^P1STb zXcuUSUwnwl*uP)Mu5sWvFvIzrRx)G9~K$ zuqd}wh&Q|8@BjYIcq|9dZ~|td-vo}nS8_TIMHSiWh6eSN>9FFYamJqbBe8Q<%+FNxj}+f)RBTo zi(q*9-=*mP@T25(K;qDkMvr-DFU-n6+Ip;;i7m93`rj-eUbGy-n`yW|ptHfsOuTvc z|KFQW(sRE6F*4fhw}XP{iQW0UhwcCAIl|zGP45e&p9a7N=<@sbcl{@;@L!+iw%EGUJU8+CMIJ@g7`w8yMwP2CfkGl-ByTJF> z_NuvAAL^D7aVd#dPb;hD5c-sMTS{p=OkCrGz<;QjH$9E*56bLySN4km(%@w0_%ASS zf@RXa5a>Q}!+0?oCH6M7;yrfOdL#&B92SH#`{$;>dhS$LVdq;GtBYUR@2>s6vp5f` zybl=OcDs621Z-EBH3Qd?P|imY85u8NOt@Nsb4-x)dFFcm(*Y72cqE1xUN<*yp`uDY z)*37E75HJ51ZWI{W+N*f9cj$r28q9`FwgD+&LsHZ6HwXAi#!|M7jv4oR#ZIpJ6Z-% z6B|aK2G}6z<9#0;1w~V>$g_nP0|RS-009qv{`k3bKj6Cqu3&6<3FEUHHnLB(zJ2=^ zRxYeSD@pb@b`<*)(ewx@7=T^P_vl>!JHcmn&O~`49nt9&;oJ7Yhmt z!Lbey%K+deV9@>8-Cb5%Dhd2^ZS62I_^hQR71N_BEsQoT21bE2pVv9q^Pr1h@4@)F zIFMer=J$^b32Jhvi(wr=`*-;KpuCAmTy7iMfS^@UciIm)9{|CTyYFFA7-X^0S0Br^>nLrU9o0M7W8dv^LuU?CT=b8PyUodAFl1BCj~iOTvW8}_3PV_DImB9P;K9MBzl#&Dmo2}jDzZ` zYD~k=BuCa`me0Bu-UN-+)PiN5WvLxnj*j0!EJH~51UC(c?%$saSvs_(K`F4{=Y_Nz zaJGQ-sw!ex^mZv!MWILGC)gN;qfu44p~7PsCX#2`D6P9PW3 zjuHLj&+bjjRv>Qs@Nbm_FsJAm&;pf$QO%3fLn;ciSbdD;X;Vy$j=Ft%akF6fl%k?v zU?4UB$tVFsqPldfyI(~e4lZRgY<~Ltj{!y`F8V-70OCx648T0;Tt0JpEBqlz7%Q-#xav*oVc^j~don@26c*enl?pQ!T@uQ=o!KWi| z{U)P67ua|)K`g)*sspZ@xW5U7J6~Zz4jw*?v8W_D@g3wFtS=@THsU`m2;CGF6)%I{ z3UVuie~Q1dU;Bo9AXG_+8P3(UYHZu`(o%3jbdJ|{ce~@XICt+O$;x`axIukxZ53_4 zISk=Hbj_mx2{MwA(U>5dp~RraBy7Nfgfoi3N6L zC(M@44nT*|_{8J*hWi7(0w@LT&YV&D6@al3s5$xVr$Ca!{##ELYcAQgIae7X81>!V zvAu7ZOanRYmcgnr?0~BQe-UQ+F<9V*atX-Z4AaR>J)BS+kpygzk1ya@*MED`n+(7^ z;e}B!u!z_muIuP10JRC2O;|-w%LDNXmIX%(3x&Hq-Q6n6$^o<4-{XN8Z`*%j(GZG< zWmo6Vf$_ms%fZ^(5W^D~Bg249H2?s(72MFQEn4@B*AtM_C2V0roO=S59B}a6f`}Y2 zL@_i?(QlUZNT9qpkC_v&aA3MAD(V+X8#uoN1sV2x>LpbG9RRQ!xOG=A3xsA>)00Ry zmhNm^8hV z=`pb4aq{Fzy(`$!guVs%Pcr-pKuL_*4a@^6$u`(Y#u3y5JNLhas?T7!8W-3@Lhjz> zeZK==F>lHy1q6<`D7#J|y4ILec_^KH=MHd?XDlr()f$bXG0g^wXj-qkgjIT<$G#R^ zuEyT{FcvC@m|F{6{%k~K38{Z|<2YiHylo@?WnUxh*SL{%oK4s28LzG-yFQzMlKxOr-ZNy zFin6ZTZiTE{5l6#K148}m7!$^-8+1YYSOORNLVe17Qlu;A`w3da#Lrx(vi$udd>h7 z1Xp7Dr;VfK)er?P&8z0_>iOyy?OP4#A_jOcAs8MW4oXUBh=PF3N<4PmX|WmQsczh< zdb-|vGw}(DHzY_E!GBMV?-Ym%s^i1|6~5>2)CAWYy&D2Fe4p!;la;6Pu3MIDRSFz@ zA8i%IuGbBjgSKUrCrjInZ=J!Go$c}fLkO_=?Mj~@&DT;Y~7`&nHLeU~b2_h*OMJ$ItWLhH$gEg1t%?w-jGEDB}-rX;@}5Ec=+ z>wQsNLgJ!}%cl}U+ibnbh&VGC+wK+r0>zZ%yUqyWADVD!i~~~pv-9n8kRs2OWPYlR zivm$(4;GC2PB~lcpo_MKdaR`-Y2t%}g#|J7jqC8Zh+&$D2&Id32D^otJI1BKWZVBj zsCjc`r>!L1S6v0(w3^Ud;OOlwo7Jf%r6RD)q~-lN*b`Wx4h~2Tz$$A@@mUz}my-Gg zXgc@sFa#XnPPJ^zIt@t+>7+cS`o}V=_9ja^!tdYLv^P;;TL@{3i#BNS_)GbFa4fH4 zmO+O-F-gc1FV04e;UdQjkRDO`D z4#7FVeSqWVh8rqQb%g>gdZLGv@(6(djLvAqxxiQBR;U#gO43T@nad zMn8R0Foj}I$mwk%@cp1f4t)Ug4rq7&x@A~ZZ_p3HUJ_ z35=K^#kjuo0kSRx{lDX@BpCEDP@-TdVQIb(4-=tQfqAkrk{(bj?Sbefgs;5YHD$wRVww~F z?h#Z_KpBN01I%MJI&AH40Xnh+W+ES@KM?7@ zP^}JWXm}W`tEv}#!EPoAdO9ASvoLhPc1E zqOIKuny1fSzs|sV8Ipim$5g`@?PttEGIeDw&ky*3`(F#Ij3p?+g(70~H+7)kwgmqg z&H?zGy$~_MBO;l^qj?INB#_{2PIlRq(QXUd4Qi(uTq4r8K4{e-3ByPaf*X)WF;^F) zzJGf30jJ?89y%C`Ph{zFYiKkhq}zrN2#y5P+biW&eB7xRTLvQ;p5@*e(8ZM@E{5F* z-(nnw`Q0;w!U$$y)5%eo!^BLlED|tiTOp)b-5YP+jg<>`Cw%6*Z9vI{FF^>3 zxloydhp<8zQC$kxc4tORXYYg&AxZOSYvg1Yv%a;R{n!sA8)xt|2swih;mI3%7R)JhE<4G zHgnQ%Ypmve@NSR$f$Zsr{R)&<0jYvNM6{OzC zf(V8&h&mCnlur6~PkX@l0PFV@(XtiC-QZviB+odqOCya8eQ~i=lwcb~0=4Uqt1YY= z=%v7LW)FFuYM(XS39QD?i~M9Fl*9ZhZz$e*1h1NVFW!`W5)e+$#Pk`1(wVw@5i)jg z%}q^#UZ<(CF(taU+F=dxRtMi2Mt{JHMUa*uaRND60GIELgOgTUbUVqgON=FT;d`_*v=XNm1PIt0;7|+{C0%*STVvW?9r>?0byb7xO2U? zQw)%wVPKd+8YW8$8D1dY02dfiT4*61y*ki7)Rm=ggA=(z5~Cp&78d2uoc|7_l;B@L zYK|fAspi+BuQ73lMI@(8Ym14C6YGVsqhm>jJff%yGRL7or{02C%?Y#2RcXf2Z~i8> z2G4TWVqk<5vP-(XM~`3}x463GjmK`)hz zvyceF2e)k7_HdrA!3BoKl`Rh3gG7urCmyQCg;TIg^z^z@9jVx$1UKELAd47`54P!f z{pvEZa=T}evu*QcdkCeyIrT&r<`KRhd#?R$zd<1872jQ3|Cd?;egq89Lm5XSJ|7T9 zBOe*l?4^V~LxOa$>G10ph>LDg+R}?LNjT7-JM)yMcZpk3`FI|F3dXX5LYuqEqC4(< z!L5K4p`@T7HQKedt}YGs4{KjU>dGeCKzOOM-xJY4k<|?6Bb5Q0K4yEp=Gte~>nkkl zgD`?*(kekSjQ!{+V3dnzynxzPr#^CPo&|A*vZ#cuD4d;{PKgYF^}(SH3vNPjsku2j zlR|=qVaE=EQilT}`T|krUcZ>spZE5zWF&bHWhCom@t|H20_MjzPz>9JF(ve1IG1r$ zy;r6i5bA`>HSU_g+(oLyD`fDhDk{?v+!s&k`~^N_l6m;?I+V9;_58LXya(YSP_Zt% zjC6ErCS6~bJT}PE)6t=AaDj72ZZr~#?Fdbw#rjZkIw4Mx2`$7^Ii@K(&}t0*4c~17 zntCT~G8aAAlT+jISm4#9phK1<)y)%ZiVofN{ca13n~RY}*e)SFLqNmK+9qcxVCd#n zdX9FHd?O*D4?gY^`&J}eSWPCODG16Vp=$#p#3>eJzlb`$h|$X7+plObGqkcY(|So8 z(t~Hup2c2T1|O@fRHhNZ`m1cn8F=EviCNII-iUH_YHn=oF29uBKlccvi%_S)>Embq zc`B3(G`SLBlj!*?pw0pA>FvTPXEZ~USWy}w=asnU5S>u-N;ieCWNb-Hdb^xB!Kz*k zZwMm~Z!+>l3={Ij#h1^Ye^OGCF`0@@01xxv5pRQwWhBATkF|tqJ0hpj@^X|>rcR!P zP%r6$8u}_I%Q@KDsmFgo;Q|pc0u7WCpq@#drb?9cA}5*QF<@U0&0B*<{Nd&;VRCAp z2^QXtirbpsze5M6?1D9TT_EDo^B9{oqxHI;5z)B8B}OS?bQ46tQ2qluDfML(DB(*8 zyK7&>w{4~TLr2F2L@6r9%ukc@lo4V=i3GJGB04B5qkeeU32p~eEn2*&0)h09>pU(I zONQ1AZrb&-CX!-s^Q_v`q9~2(Zil{*kkBsBpqiRGIysGPXu|*~nodKdxzNXXjaumF zTb+@tV$6S-JVIF%$#2{Ka{LmO0nDz@2x&yjYWXUZbH#tFAwkQ4PzL{t6>oGM02est zKI*vDkLR#5T5VI2RMOHVs0+o%#&#nbEGuhYPB5re-aCBY9Mm3Q%Z43F!50C24m?qu ze$rn7aE3|)yq5%N1C)NixTwoda?2GL}25|bQrw~bO5YExWaEX zSIfoSL}3L%9C98i_Gk1KPEMx~*rD!7?}4JENcBp%_jRVmncwl~RW`0%=K~owrWnHe zm2r+%cne;IS69(nSXmjMc-E0wh|x1ttU)q>Vo1UQA$SLKzVZ_XoDk!Ty#M;7LI`*S zU~qKIt`E}L&!g71lPue%r&MlN5xh_%}LORhb@ z&c*@{)zVVYPjP1i0y|nh9SV>1WnQ%Vj=(df%zEqu2mzi23_a0mem z%Hi)H#Fjo~BX1cIOo9T|`N3-lLC31A;n)%6eS=Se_y^+UjPNJm-R=_6I28yI-whK@ zwr9`2Ln9h)@|M3pbg?Ii!sD-}kVHiDYT-qY85Po}bMJF^D|{Upk%Z<{)!F**BZ72X z_Aqzo5C#VXl)8?EXJqi^bR%y5G&!jqPSOl`?QCT=GBhNPfjJz?Q_noz!91R(z!9c~ ztQi_qWBiCNGZ<`oK7RC>u4h4R*MPbWM9)5^sWZ?M)U0Teg`e}KAbPYS!on@!96A9m zBTu{$QQ@FmQm$DQ*?NH-CGcx?=&c)k+`=b zY(TF{+OjU7!gP&Udc*1w4qtjKUVsi`@F__rv7qLD+ZQ~!6-i-)QylMdK<pZC*wzX&-85|*P-|VAW?rcGG=|4Pp_YiydVjF zILmsg8??%62S0-^0XZtduVeB1;Q{Trf_b#!?xW~(zut(X7K^wOA#@waNg$qw4S39% z{X5CIdAkb`6l&w_%1}=G0#1gJ4pjU4Z@vz?@@XQ9O79w${HfE&x$L}W_Bd0ZP=IFy zDa7vuT^zR6T?~3z5XU$^qD&ar9|`gC1Y1zSIcp@bAV~7SX+TPIU)C#bt`#a!kS`XF z<^2X~a8zF&P8Pv4qfIb1HwXT0f=*L&fUKQ;{!%!0Tk?ZSTi7{dFUESx$B!Dt>s z9)OxcJj8#%A&A6D3fu}kH+^TDIjkA@=r9_I)Xf&UOzJm|938tR8!{Xqsl>epp$jCz zSHQ~#ZVSR9hzNPQ+|N@Ebu%_G*>Bfjg}X#MdIBOlIWL1PPMG+kCC6zDutY;c2Alc;gT*o}e`>kqO&BnnM3LL80|dP*Cdcsm2}YBj>b_9m7iO zZ)`zij1?#Cwgj;t_V{5`d=S_Y5~he~B(reHk(`C;!waG4rnoKY?*IiMfvxH&$a<3w zT?&fkJaj0|d)%=jtr4ZKG0v);Fo}e{u)cih(y3y{ShGUQ%bOzu5UI|{*%H~(+`baT zeo2f7>1+q;vG24XfIa60Iv8ZIydt_dkT@G$cWV$S<1mD$(kI*u>EkFMz7+)%1WgDM zRmvx(q5@D90r3~Xo@5#U+hEnNwK^jOS$Z7H5j#~`7m%FzEgbVxOB6&vMwnm`6PP~4 zOR!12owk^1TY4h2aWHA8Q{%$)oQgFha6SxkYS3y{z7f%*pD`Ro1UQ&m{Ls3 z!Yfb1`(AZ-4_gL&58L#6#pJWSm;SD*o-{#$aQ5syH7?A;C-2^byleq=sBCn>$z3Q| z($DJB^U)!N{8G)2-5Xx43atr3NQ^cHZm#GXp;heTXaX1#jOnYwF7zIe1}eX+gvc|x zduqB!PKjcl0C)4}pUATjP$D!#nC;>2PM467r;Luu1(cYOo$*FxApb`4*^(&JJb9le zQ>%8P!U*{kJ_(5k#+Xr#k!4?G;zVtUche!_0YGLCF9*;J?bXj~56*Z^M4xPN+tZc7 zHx*<$H}X4T;EJAABThbAr3oM$a~cb?CksUB@pm>gjUzosQ!~kl-pr?boP)i@IGX!T zD)@&{Jat8wJG;?}^~>~d!|bIVnAO`+dk0#BjSmk`sM^p{qjr{M|1?h1EHpAQt;-&` z5_NaAd$fnfeQ$qC6?u&id?oL9xdP|j7q+ws_wS<&oPmDoo@ew5{rsbEUyRfzdf!I* zh;%(qeRAWWAFYt4I7Xo;Yv_$gG0gz2Vr2nKDU z@R0u<$*MCVAyxH6u!-O-ED}9>@N*s8U>zQ*$%A}C+r*N_S%JH{BrG zq2S}JP>3Fxo|;OQpq6p}nFhO8r}re6(w7-rC?5@R1Fj!pSh-)kdX-58YP(;$n1Wf= zPz;>*023%E&Fm*rvJEIyB4}Nm?bHsu4zoJ@@c>)4X5rqQAUBiT@vB-6s;&_cGYiva z9w{R&zPnR869PZsjL-Dr5ldSJ&=^g?;+^RW$_Zo3L?#vX0~PBv?dO zPmXGK|C+}!a>!eu_lF60yArdIVLg3)7NHaJO=p~(enX2eJPj8Am>drgkDyQSe(mbi z_!@RMvRiH&IPp8LTV08ucYOw|lxI}Xa4DuYVOE{`D;GgC1&S|a^Fcv6+%!t(50gm9 z=Lnnbe=U@<7P(8m}8AOgJ z1b&)h^0h9#a9CpLa1g@%a z?S8U!I7MH5);MEd*4N`wLOhQa=I0xukXlv^!b3@rZ(SHBb`CPIqEJ^QkcAisJT=*O zuNgrzMx?MZ(vyH1{tea2|Y+rJ&%7e$4f1i@_Qe(nYre4MC;23!H; z=WPW_K#=8&|BjkGAr5-;al7q)tWW$4Falzq(`0jI%#OAzJqdv@XC&lhaTXx62BJ~* zp%+GkETM6pnarWv?U)SZ;JB7obYa&Ov{?iUQ9IqVVZ*cr6noWsE?E=V)=ix@-c$r{ zp8IYeeIi8E0N4_6*4yYplmn9;ZUhTm&U(#&5D@ly@jra2FPTQ;@mdhIr8~4#LVa$oE#m4oIe1qGvKq9z^cI&USdRocsX`fjfm6Hqc343 zH4Dz4KhLpyouNP%idv1w;7|z;O-4o?5s>p^J2dKQXlQis7-e^%OP-zqG05P`iHJ(p zTM%JQ02>1mQRGf`4$*naNd7yzmejsJMMW~++~DVnj;gCyOnPwH9eQDQx5tE>5h-y~ zgvtjdpSeiM4+sg;oKL3ofNz&uzy0FHPX}*gMa4HJ?0_T@Z6v56+t?7C{qUfjd2PEI z`YPQcwq+oMlRZUoT^#ZdCRH9%WlW7iG|Hxo50nv<((FDI$y4uQ3Mw{uR&{%;$Fed@ z`w1-j8qU!u-|f5TX(1XBh#E(WWu!SAhYn$Grh%q-dh-Su02pvy5T~$9*&Cn&lhxy7 zZT$;%OWNTQU6Sp|=#~?)p`oH)ORg^12@bL1}X~M zU(Zt>{Q~Epp0^&=e~^QQyMozCUd0!{00`dS{8|@qk2I`@_;#E%(1G5~rUR-95!pR0Eg`u%%`T?8WMvPJa->jIbclp60k*Pw zNfw-$Ju+QLd-w{`5&}49)?tqv$H`*Hl;65CM~WhX8X_ZhyolE|5FJ-~WJBjM*)n%N@ zsR@8KZb9j*XvUBIz>lCkP`&?v z&+3tcsSfNEcw@iLMIY!(Ackw>ICS8^)YpffPBIt1nPjkVcGh0L7p4!;fbFCN&bM9! zwDEwn2=#=wB$z(0aB^{3A!?bmB~tzQh$Qc&!0)gb6DUK8sigWN?Yk5~W8iw_%KM4m z1P3oK+tZQ~Xw>biK21nLC)q*JxbgNF1vjD9ZjhN;@8-M{AZtE8J}PQz(9NZL9js5j zMbCMw}^B0<*!Qi6cf5a*Dx!37Ea!>!gR9GjaDfCoxo<4I#< zcQ?1TbG23$#R&I_J|{}`2Em*R9c?0a5cSUHRMe4yW21CZ(&rvR%19JM41x!sd@52s z63N`@D5*dv@X z>hGD8!aQf&RnZGYrIpZeazh#{ayG6A)e`Xq#i{ipNC}HXj!tg?roy<$HY}IE9Y*ar z1)t}R^e0=^D9Cp|LABE_61L|lqk?y7P74QzS55Nt{cBML8%&ovtn1uCpwc1dc$ z?b~Tp77)#$XJw5^N}BxkO~Y!#mMy_VrN!k$n(&>wcL&NYW+V%9e$z6plP%XkjKadVa#T3xaAOX?l0<>30cs_ruJRZ1!ZvU&Nr{4Ck zA*&^{pfl7+iRL^xKMV4L?TM22Isj7ZH-T! z)YnFqK0126#DFwPKB|(FU~%^BOJ|9Q4)F2;jMR4WSu6}rt<^?RO+c9b?f_iB{+Ca$n4Kmd*az;G|r^QgwJe8FY&qs>nax=D&;C0 z5~8CW8Pk=4)Tgbw-tRk|AASq+AhK#dP<9laRy6B+qMlBw#q)(+W@bf6;3h> zq;++Jc=?XqpERQaP$mGXgzk}5BXvfq4^a(H;EN0&aVCA%NL`g7w#o)oOe-^}a30f!#-l(#8Hx zNd2j@qz~KheqiRKqh$HrufdZzA}5Dx`{;su!8r}x^uH?`VFsdy9w1B@d84HhuD8s9 zm@yJDqXDFaMEL?~0ys*-aXRw&LoL=+PK}@&1Yp0Fo4}e71cnHr%sbZ=QwXJKT^fMS zAY$tMxrxa{5KLHc1Et7xK;B7o#%6Yemd_FjMB-LzsI`-=U0));(Nd)YHkDALll!`B zAecxolVtloeq08Z-T%s z3ZvAl{<`M0FTDcK{R}TL6b>$f3UPJa9mK00+smwSl2XZCAifq~rUNfpJ*9(7iO3WXY|}aWp(hImx97`v;@XX`_MiiaO{7hQ-7oF zw(vm0R%BROk3?h$%`aW<8wjKa-(^l$228JW`o*j%&~rP>t$qij+W&iC9919q z#UI{*T6#82R;SX+RuE)%bYL8y6V(wEF9blfSgebT_qM1gLlbU)VFu`2WcC^ZV6aE} z|2;_H1WID4lEWkupdQ1R`6tzYX>luUCZ_#v*hHNO96ay?HI&&;?N2O}6mk^Keol8z zfqzD@#Kj(`EI^0S*%y}iK7I(si35u(y9dw&z+4A9QrLjM9jZQwu1$x#2T+KR4o9&9 zWXJpwjX!_>guW}w&!XY^G1@F;Na2~ZO>;>~M$VNbla)~&fJB~}FuV<_LvnhvljwJU zskWPO4|h_G+V8Vd%3e7`^XpDDQ2``6dzpjbUara0Al68E;&K5`FS@RTQYXPg>v6Wc_Ox196=2mS%WwWyAlmQAcih1%K-eKPFeN^(9Nf@ zv1~F_rso~&;kHKaNO;Wus6zANr^jb#81ra^D#MhvX|&xd**4lU5T>klKTJA`5Rvwf z`H8?9N$yP_e&!zcTNYqbZEVrT4n}INq1`dUONW-;$4YkzFXpl!%Bl-2R-VCQ& zWxCiH+l-14htOwkI$)e=cjYy?m?FQcl665wfZ~%$|GPnu%SM{qR$2{DO42@=4c!b3 z(Tp99Ut@$05j3+sG|thHTZh|7fqcTk5AT(Wii#3gbay3)Nj|&qd2<;fT~&iU3Yt)$ z;5#rYpL0ATJ-vP3KKDrMntc<#08LT#j=SRGA z5h!zsqxgUdHs3%_kdG=o=LXYwE@H|JOvir1`RPL6-@G^IxVDOfh-!U^w+q)awXPK~nA*bL_4XPxy^Ex;8F9pU*du&1%Mq z-}LELxnNKFEq_epfcYM(gT*&DjyqTVdWTGqn4a0h8$ojwWlG5*LR43VY+AuJgp$Rq zR~5=eD;2q+`!0a!7Oh~QTV>d|4jhQ-=Sc=w4*A0Vd&2SoAhiN+YWDXqtgP!DugR);Si}WqUDz=}!Qf|dVa_{nA2vx| za~|3gO7yz@kA#-4Zq+7T{?V&moq|PSuKHO95Bb!dsqcvpii*{QULBMR%GalSWcH?q z-en=`ph1;u%l-gm0nHPty~?w;5^DVv){geU!qQU5;c{R&V|^xXBiSHws;w=EKt|~{ zGihOj;WuW)#uAqfPgWM<#A5t!_1$%g7_e)@jI?owpnC(+1se4VE=wX8A;&WCXbv{8 z1F+7>hyomFX;C+bjE)X(`404BVu&g4 zEJc0gvG0+R%*=ovkAJcQZx4r>rhp#d^AdAU$#gySJU8ppr{(1?pxNaEqSTe9jt;%0 zs0v@-^=tiXRz^V&Q&DwG_h*4LU(XtH`3`3fwPuVR_V?URk_wejpr@zj+r6e+W_nCy z7HQLUIMAQVjV`7xE@CpfO7RQ;t@$)L1?kmK^O+CX29wlMLZ zVdX(#)vPHW0-yv)&gQCJ7;x{A>bVRGcb{+^KoBY;lW@-NV94GQlLzrj*s3#mKWhpc zfh$`YfYZJ2as088hAQc|F6xQ!G--kwS=Nr_N4pl`MVBarpIv&xt z4850v;FG4NnjaQzY*<-YJ*S>;dRsj1qd?DDPaNzQFH#Y2yUr^%S-Pel<&6kH8w8~B zVL1Y2A6iiiZ2WpOiX0UcbqN&WKf@C5|5To2G8$7?HZWk6IT+jf)z36A!N*`cI71vm z3D4Zy=F8Bf!yLip+^2h3S=Hu6&}LK@(S9YWiOqzvMPn!T9tJuzEcLGeTDJzkFUjjH zD-V!~{YQ&XERhW46BMj~Hu@VfEV>t_*p{*mkVq&K-|s!#^zPk$KEBcVzkrLElIp_v zfw$LtK=?OoVXk}m5|bAgs=ytgPKv;yt?q`YXJlgS<5To>Y;5WSSK={^ggQstq&(y1 zo2WfzWsRX&M$ESmwJpyLD9lJ;s^P^+6sHIQS$_Vk$B%DYu!1)mT!rNf18Be^8N0Bn zL7TKXleFeI@GN2Yzy&+*rB#I=ehU3^KLUi*)cTVU z?5Tz%Fhe-cXZ7IP#XgN`LDOqoisHtw2N>b=<9;>IoZbVvh zRMF~!Q!zkB`Tv8qHxK7(U*E?|lngs$N)a+;PKJ~@GNjBRV}(!=sSF`PA<2|zFiXag zk|`7kiA+tV%u_O!DZckAopU~Cch2=YfBeq1uYK*q+j_6{TCdkL+|T{o4?=Nd?O+A8 zBma9fFCvRz#etyYl*Tw5MEF@H?-kXv>-g~joR~1*4RW&=y~cSy=@xpX8Dz9(Y=O}x zdVZcQ&7UX?1}osCqhnlTq`tPcw!S`B1i`iGuaDCTRZT-R5>>dtcTpd?X~F55&Mm^O zm3QtXZ&$fdZG{7d&9OY3k%Ne@9~iit%iO|3ljk&y|0ld90fGHUWm|?}ZxAXL(k=mE zsvfdiy=}fB$usaMS+O}bPlm;**j=cdF zP!~qQaSHYQD;L>`w5!j1jo@70EDt3-d$YHmIxq+o6&0B4_*;~iC=Kx>Ya1I7t{5R? zN>9(l!_&COn`jp;E4%3RVXvGy#>!rlxnnxvvv$+Z=FRJDm*#xAd^_CCUaQE(H*OTR zmB)7Bd8&L^U46Z*_l=Y4uSSBm#5%#b&$q!HOxC}NueWcAFGpP+_D1(Umq|ZL-v|UE zcriw$0l1vQLu;{3C79TL__6tQJBC9l2@^b#z2?GjH5aI*SRMF0i*T_`MI6e zHIcA@Zldv9?)B!0I7E{R;n`Jwc+Wi_W7iPJhT94 z5qr6Www9H}Bg6#?xE|xcsHpNl01}zO)>$C3wa>OGytE*FPTwv8mWhICIie3hHYi8a z4d_6PAHY(?vsVGRXz&2BI(Z=}`92Ea4JSg;!h{NR_-nLExq}y<=a0jKgY~_4yT~pc zPUHn+?yc|u&1pJtnCkoYQ&Ll7u*F#nz_mTSKZ4v@yat(C^jKnd%%+rP_h2R;m! z`&RPteohQ{w$(5Bjy zy;V;!o(YA|9lXX=1-Y`}AR*S)b526V8yI~+X3@bK=zLA4xJVt6YIS@@-QD6gP? zb|_XX->%69-W^~hF_;QD3DWgSkW06%etT2-^cE&&=3U^&iWLVJby_>A&wY1{izy>KCl9I%8SLKE;t|3lo)^ua`y z2y#0621TL}+3~#)Eh4D9?K^}d0GvI@OQ8GQ6~nh=zumaarj%WEl}o8d!$86t^ReN5 z5YBAe691z+Wm}-@!_a0`i@x2oy&BR;!-%-;lj6Lvk~i8+$^nMWU4xzp?$}5m(SigYqD9)}UNsrQx9gZ6qIq zrFQ_m2=U3_I}(w7U>;+r5WXgLp^ijzvL4@-XZsco*LOKk3AxD}!v;=H@QXB}jld7Y z%6%Vh34Ru`iJ6&-P3C=5Q^YwrVPOZv_MIwhuKh`Kf51lW@!-0^D(w>wtX*l`rJ%!))Bkq6=RXM+7NWdBw zMkN+#q1=U=4#Gs!6EY9H#q;1JJ!2!VlB0%VS=dzc6qPXIb2&{27b;4WlrP zF@<6lYMi7aS!~Nw)P!Y4%mSNTGWBMUOVz&Or3mIkSnb7)$J9SEv#@BCZsxTnO7Muc z;0{JwGE_?~8+H?N2Y_f6sb75p-44KF`8?S7L}744Is3au1c*-HaL8JTQknxZeBO{w z2AYPa9U@(tk+R+Zwk_RF2!AZrDd9d5@}okem@Tfpp*hQz5Gf(Z#PZn@lqS<(JLAj` zq#{x#(r42^Q&FoWc|gI0n}Z21b)_4@&V1(SQ7&9~P8}Un&rnCh9S_j~qD0SvR<71T zQP^%#_i0=AE}<8qAS?hgNb;C$zP+TBy<4&KJUmSA-FQ#{tn6RC?VMItb2cKqGe&Gz z)B|y-iGuES>?S)94TfGv^0jmLJ>f_#IGj3ta(Vx z5G3D~_m(S>-y$E#zGEC%5fQqJqxYcmxN~zNcs=kVgX`&+Ahy+(vGQ86N@?{k4 z2@^Ng*~CUCj&_In?TN))z84q>XDO!ZEN$RUdcf4Q4NU7s0M0&Z3UmYtPOPmvdR@8L zHp@LJv}K&D8<9U^e7ejRJ8fRGkGP>%2$4Tn#f?BuC)Oqd=0YC0ZP_ai$8py+B3mjb z6PgIpT0JyDiHu0*$4V+||3* z1Lp(wdXLxQF3+ zSy+PNCJ`}gVBI~9FnGG+#bh}7wH|0XpggIzk4RC764=Hn*hFGR;lsUnz10CovmUt! z1aWnTIJ``E`Rpi(<9_YPO=MQ^?ku>dMRIQjM)PiT-XpXcZSfy)Z4}p@dw)i9bPp=c zFcUH^gEZ|1Nu8qWvo}uoKHB*z7eT<#zQ8Tf2@|o~oeM5BCaW(VJ6vsk0BworQc?|d zuzml4qhvkp3sHoA#M|{g(T3GTa*{g;G+#?@&W}x0<>gUJ%LWj=kZ3gKbo0lek=q%E zy#(ca-!Gyc_@6C|6=88wjx&Ru>%P<3 zvn{hb{4!Uem_)lw&fXh`sm0!kC` zQ?I8K5f%b3vH5|4lJ6ax#jIW->KqI_JuQv6kkINe?gy0_Q{R->(0BKt;0*7a2f!b| z>MC(cV^ct6btcpB(Jr<)lmd~Bxx=^+AfJ^Ls3HX9vtIX%*NN`VO#ua97lRE@&54qj zDEJ1k36moX6#htg;U)oL9#{+8^9lUY+lbJSIN;8>g#cyr0*dFkB?Aqz$tw8O19xR& zO7CH6FPPKgh%%trcEbh!IIYbBCq31v&^L}U!kXuGZZh7%c?g0m& zm3Sp+fK)1dxLrVCYG&q+#QhW@LvP9{Y$+rFU=bP{8>0s)XkiYIi;WV&jn5dJ?u$pn3V7$b zDqvY*uO_0qm@u8F*U$IA$7V!4lVg&9Ej4bDEu7{EDEn}qiCT7udSHIgdBi5~_4?~) z96L0sZ_b^DmKG=C&d%nrZK`Yk+M>pW4heC2qfnIS5vSo)3>Gne7>5W~D9l8H`ntK( zPtSch+^B}27~53k8h5{lT9tRzSx&Bl4V$$%Uzym0c7sk`L~MiRtKGuzA;40TWFl@U zx;Pu(5Iz&)9i#hQ@Fv>6R3ePad_imz>?ZOny7w0e0#j#g(F9iu=t~GX<7a$5^$+hG zJC39x7bDXfN@5YBWubXjR<<2fp1cNRl_<+J9Y-TNFp(xm4#`!%e}A*BGwcEKHOO_9 zB0sQFeTenl3bYT2WUq4p8uIKSyoHJpsv>R(FU1^IkQb%-xPq+lE~4A!Odvb+I9+z{4+4+ETz1)b#(;AZAf&P|D=^7 z&XJ4BJ4CodyX2mD!wf>>>&=}LCr@g2zCm`>g0}`rJs~ zv~)W8s`bE;#GX-@m$WQf<$jpDV6h4(@)hAYHlyKF`fRk!LnJ-8Jv`cKvltkqw=fe# zW?VbpAPn3WeRS8)ArjtofQcFVGEQ}#w5E~V$YzkLiRUtfFU@bg^g_IyU)8OD%6 zBn-DWxAlGUlSzuRR4=f8XitT_R$HlesnR>vw?`i$N(09mWw?%x4$LE2G?NlK3@~Ot z@EdaS@tGMEF8aK0dpVuJUmrgX>LAbwR}YWN{{C-AoQh`yMO-28kdm5;VnP$zmfG8Y zV8{CQu$zyYeqrMW?cmB4Ou@l8@C{T{&9hH9Y>gANl~q+2=H~&CcS4XyLL#d4k}zNE zSR8;VoJla?kPyLK?^jd1E+_I)XrixPiEhF6?0WfhVG;G8iZzT;zwTr%*jOc~bC)r1__B=1Vd^JB@oVBy4zi z_{$eoTH1+1)jQGA-!Z5eLmh$YU*53Qev#jx!7)bj+u+-6_?CCyuNj(}ZlR_9JTgKw z3}fa>xmg71kNeM-mFYN~##}f8j+t(ukN-1s(PsG8& zk+X0%>*1Q-P{G>%-d^OPbuBFtm=CJqr8<^=1~feM_LY?>l&jRJv4zFNxB(l+?Vx3* zrkw*4BxvD-{!3{&}6EeWSh*^^NOft%H0jRcBH8o8k zJ4TO#>ktJokU+Q;xIvY?JiK^>n4ZYsrI(jcgT>+)ZvtO=pVoYXQ6{A~p2?c=^tk|f z?q&tde&Ys&J9&XK@VchI68YexRpI1;k23Vs{VL>=s7PqiTvl_@>Z$<_g9afOqSbYW zk_Go(woiYtgLZd?f3|{x1sQO(yT)9!;rF%4S9>xlV9Cw_*7Q@_L^^GP$2Qx_J6)Jm`jP1zJ@)%lSD#@C=otGB@*>-#L>z1g5l&t zhG~AQNT*eB!QL1=LJWmJO~Y~A9Nlpybw6dkNJWKGGW)}Xf(m#8kobVs&Hwg??I$?{ z8{SaY`>rBQCzhf5(Pe6R5;rM(ya=&4^<21TeLla7a>U~7D#DMH5~xV#g>d&Zi@5tlKNfNYg;G*t zuW0?Zy`nHpV8Y_<$?X zQdrY8I1)R!{}75rFkl@Wa*~pUH6$(>Yrnr~$eL4dWFHS8?kWJK;y>;w{4U1g6qfzV zuq|~sIqMx}7fKQX0X$f))PHzr?WXW6=$HWqS2I=|^Pkk`UtRJ{U|KxSc>s z|9IG&^SB5h=8unSQ8a(^=HUP5SMqb6{(s!g-Dvg)Rt}BOz(}$|L+Y_R2_{oM9SU94 z#L1xw{SVKB-~BXRK)SItp^Ko)7;hr6KJaAD(rDE&myAQOL4<`qX|!w4#GZ3)`KFpD zTZ9Ydg--Qv818q>a5O)jVe#(mF>JC)(o93quabt+caG8r)tu1ZYEl?|`b?voLg5YKt>E&idD~F$=WJ|>3GCc)>GBz!w~Zk`_s1;-ZStlJ`Gp@Y ze{IdNkbK-~sCnzWK~-pOWu=HfWe;rC5{2gczV>9F;SN^AtkzCN!qG-G`CKbQe!fsZ&iA7lY}6&|7`k2j?QoB&+g2mGZ!Q! zp=prC%oCFAN2%@aY~CaBdr-h z#!o)c*YEZ6zF)|C^xY!v`sS%{T^TBD?wqp6eBULa``u+^c@HrTedV(_Yejrz{qc97 z~n9V-05P>^f893r&2jZwu$|Aj!&Na}WXG9P=s(@RTl8JKL^w2BQ< zUv59u_a;tKy#jF)B0rOa2!$FmF9vz`=tsO-JMVZrkldW%T5Yri-eeoe$$dNvw^(;t z@_EeOyyl`FT|~S2#b2!POQ+N3?f9Niw)6!mb+V7MkQK{*cp_wQCKXD47CpMtNp=C& zZ`$Q^8?DcsE-no!pE)~y%y0((&Jll=L{HorF8YcIz13f$ql;XeT#0ru>B zlKyBzT1#6GuV$Rj>*$_>EyZ_+M`aR@(YW3rNzjTBd1mwST8~oPvp1E4>YuEw+sL6tgEyR?G($?iU|MW@qaH5;?{4ohVy=y#R$|GMz@eEQ65pppS zA^@lhcoSZ$Cfy86`mk<8%Kij89OrMCW9HGrvuE*`&7!g-XYR)h_tMwKYd*#FD+S5BYsvY?J6wWfK9XukG z_1^2!2Q!adQH6z}sr(Dxyf;}JOxjDMVF|X}HH#WIVkGT&P}W&>*CNAtSea*M5B2wC zcOi2f9{Drh%ZB%#@!TfT!{*g;VywZ0yf{eVuFR(n?;pd#{hx<6w49{=*n&vc?eP(2 zVX<&li5o-metXUsPBtOVCf7fX!Drtp>{2@|&vl<4ee`r#CS0oFyuYv6!$`Y#8nT_Y z)iuk$CpubEJWwOoFHx`}T_}$qSf@PezH_!aHF4>P-GH4p?nnr~lw@~m%G0h$G=Y6D~a@xb$=1ZTO2Z>~bwd%vC5f=XICrHWlc~{>! z_9LmSwP>lh<&4`&L)W?jCDNGW^!=QuHUdhTN}m~eF1WDB!(x(8n9S|cbqe@?TR{_sq3`bt6s#+?xVTqJgJGk{{5_^9oPfW zm@(#1&6%pA*U}s~eAD)?{MQW*&Xc_#c=vuYHWOPGus!dtn0qdy%b4b(!ebiONV>^e zRXMHE-i2{4MfxdejGoyQ2Mx{WbOP^qMI5-_VtPSlA%lC$i|O1)%{R**Z;evjpk7U0 z%;VF2w6$qrZqp{&`P|aO&fD+j*hxzy82kImdioC8B#t#5z-{SiU(8WI@jUO?Rf&V~ z53WBxoZ#?DSK`8h`6V;P@0*(3sV$8q58QC+3b@mvGPSXMq0y>ZFt{$Y^|mV~sf+%_ zzW1ut9D6)74GUjWTyc&T2tJ#al=H|0r~q=rPiT4YKX|L5zhhI*8G3_HPc$lJsgDi( zcV^k>M9oOFJ6ZI+B8dwuz0SH$`F`Jl|LDf2!8@@rOY``zr2wC-uVpA65|xzd+vvR?0)e;)AV3+&rGMG zMeM>r-6^LJVVVaDub9o;5}jryVW8LEkv{VF&=;9QnJzJX6Vs+XoS`r78--J!I7bJz zW=xO=T}`%Gz02^M3$xpctT!_;3L9_m$L706@gOB-^pa}kV`@YXpFCEbcog>H)E)u5 z?8(Wely64kpV>#88{X8p(4zrE7c$S6o!O<^m6`AHC~2 z>bJe#;_VB$qpZtT8zWp&Jlx-ID7anZ6vDbkqrKnEVA7Qyh_v@1tf*w4w1(K7&)k^nfX4^r6Bgm z`^=NyMy0W1Tb~NR7w=h6J-6^R^OJ$3FkAG8cYXKw!UtRUH0nz7$CkLp{HVJoajWv% z*5@u?D&NFZnLG73+qZ^9rrSjE3BYwecrtSH4QpJd_OWKw;RBLa^LcMY)OB~CGuTOH zL_un9#x8g5taO#ISteWC*SYrH^32I{E*I4`Dl%qU>?HEo1*)k7OKra9d!^J0n&emF zrL=qX-_p6Bs2gpU_A(A(N&7}VgYAhsP7jjn(2xX|`ljrF$=9+!_k;*7N4!kS)p z(k_DN#B>3?S+Dig!Rx;E=?z;SUGo;RxKQ_Gr;W$AW2&A@i!^~M``=UFdg{4Qu=BX_ zq4TZO%ZhLw9A#!sJqP#5$}b)%5h`l%y)(IHr?dE{5|Lw#A*@n9doEn1rW`oke^Jtr zI{fa7TvJ1y^L24|9N*-fx{t%!o)K(cLDN$F;dMXt>#$3iMFJjDex9?dh)Wl8(rkHU zR$MmLS@ki~`q`~`HaVmAcK!C;m~_2$Gx+=^kCR6@E(h~#d?c|q&`;M*X5v~fm-HbtY=gL^gVBaY0?*XQySgcOHTHN5x)*Pu}J3tNbhvOU6V>=X~sWBO7VuoJYVN zc%1t7r4cE!#}BYTi^U%jZtYRh``Q-`l^T&PRXeD*MN}gQnVJ$f{VfIoIjF4wI3RRn zxcNxC7hSEh*rv_Qui55;%?e_FoD*wG5@~9^`K2*pNb2S$x$rqFs)eEBvl|e*lCAFV zd0Q{C=I!~0sgYtBlW&_|9h~zqdvtAKf$RKtHU#&dZf%wwx}#Ca&F#GOY&84M>ytZE z9nYV=bw1AGY-e6c`tjpum(7QLJjb^pCKMp~;hv6&^XjMcj-9%Xy;LQRUU8qe(BH6{ zXV>+*H_zL5XV^XxJjBS|Crf#aa@Y5+w35!kmgxS&<~Ixa8$%_tDWxpT2per86TPx7 zUQ@Fzt*0gm1>{Z4#4MbS1cZz{mv?lSa&;fG8!pLAbYVzJPs|Eqm!miIDlrTWbUSX}Zx{wCLh)%a80Xd}a@7UfMh`JP{IftW*U zEl^NrVtjcGVz`l>TG3HD3jV#w9*?w*3H zR|hW3M}C$uS#R=)fBO;Ug9%-eQw6W7grx%yXk74WApQAiMRx9(+Bfdcss)8AjhPK{ z6(gU}NF*6XM$tzx_D1*iS3jB{Uh+1Qg31qMK^F>g)$a3KI}IP6+bqsS+xMx9mK+wB z22nQ7`S1Va2d=1W9h@lp`v?E>yBemnLaw7IprDd6`Te^{=}uQ9RR8zy@o`z=W1L{) zLhTniY3{;7pK&1n{d3yS6k51x`@XLZ{rgR@YwM9>{tK$FXbT(b>*Mx({jqJ&UiT3K zsQi~3`uU%LNtpw-3kpJI8~=`!+xHuN`1k9UWl*pOx*90TZ2jBKtXe%p@~@^k@)@%} z;`o2R=T)n(_2j8@qId+#&+x#&I>kS%l6~f?pN)f%8<3Z`*zNnT=Y6^|9`W_xS8OBZ zAN?XT6nRr0t#9rxP)Aw1P%o^B2H>FQRV)_mFD?TE&3hKJyGK=pa3M~RN3og(TFE4rwq@GltH7!-a#IO0Kg{Hi$q zc`ARuz6LIUqY)HKYyWXxfB)uU*$Axy-Gsa8+dsXJSU{t;y5*h!`1C*5$W@jENeJ|n zAd6V_^5wI;KJf;B*wyJi#Bps|wZ`lZN3ctRlAejl;_2xlU{@f|ZDdNRE7_Txe+{tg z-?s3y!LJ4+e?LF8t*C9?_PYY{?>EMR{b$(w@0Ypgviel`6}*L~Pj?lV3VZJO zlVw;%0%}Wy@+hkLQ1w7D=OX(bUKLH+b?lCR_+%6R8-7Rsbld6*_w_OBjbPnEMKn@Q z_&?g2Wm14}_)Ob9t*xr6Rm(qStV=lpU1Mn2{k4awKPuU5PmR!cvX=Ocpf2LAnX=-B6A1*4P z7Y|A&KYvYSB{wIhQXwGWUlpgn-Q|CO-~VyBGbn5$l+n3N$geT%Uf*j_6gaT=Z`+PN zo{2E={{W}lIW8*x`>w*u#fMzfNYMb5nVkGeXlV4(h5z`q%cQVk&{BG~I9UsohsCcs zA`8^&6}5ijyZ*2Wv7}aFA5bd%#e@@=&7Q+47cc6{`QrkwQm+X1{NpQ%+J2EMQB2}3 z;~&05gb|MS`I|QmsPUq7Dl$g%r;VZzN|r7h2ys|2Ti&3VA{Iq{FuL;=zlUaJoq}L! z+yZEtARNq|Z<+Fzy)dhtW!O{$$yRjET&YEA9FJ`mqkA8GocO00VzHf<_wo&=Ed!&Y z#Wr;;ihZbJW0c9PHBrCQ0q2uLQu2nyH;`Y@B|>=^%%}^~gS6iCkVQw8gE1O?_>-zS zpc;3Tt#*ouh|oi;pEsc$%%X~UKrclg$@b{+V+Qf3m?TsFLm!*>D5_+9#C0&(KqDoQ zI`!VYuOA=pH|1gWKb!?kU7Bc2oeIe2O0Gkz=@nI?FJ^k$rBM4?kNCCcA3yHiu_Nr~ z{eVOm6b-Ig%~lntPH6%GP z(t$>tpnsGHF|n`|TGuiv#$eD3*mZMBuQ2Ijc9Qn0Z_lm}y>s)^b}^bSzjgqgtvmze zk2tiniGW%2_~AoZ7e`dYeHlc=#a+N+_7$7pLzkX-wksA6wS&dJB~a_}kxiLl;WFxI0W|JYNS2yDax0tx}qo z7ui_?mLvtEy`7!gaP#)1+RHsp(T^RZ`tZ!a!E)jopyCj`nf{~z$jTK0cT-ZVU0rv1 z)8iMoM18&1ef>#Quu`sp?MHFL1Hwt=LE!&_TqL0Q0nD@6Pp5K2=yF`agZDjT4945Od~B9k90yMBiV$xN0I2 zeIe**93Mi5nD`A4A07zq7wB^?*tbz$UVbUkX$u%;)+? zzCbEXo3FweI=1vz(H;|Wq8ZCHo3(@L43@{~5~%b2(GLYZzI>E$iiwJ1SZ=Ay#a(9} ze#{RkmQG6;=ckWBKX&u*n5uGQV`JB@k? z4N_cB=}43m1q2=&8nnGG0nhGkHOw&=VphSuxXNqD1fd@rOwFLp^j8xzGc|ko&;(J| z+0O4sk3Yt%U++yX7Nc402AP^Hs1cQBrlq~==rC`Pg)RZ16k=hhtDERV4`yIrG}^mD zlHQ|l!TTK)10fzmNo+yP_L>5%#Oo3ma@|5%X!N$EN8fdKs2_T37_TY`MUOA6yD3*pf1~8 z5!jsze$=GA*{i-uG;#&i8fF@WLG8<83|ux$GT}&rxM{BCo(v~?u$U>8u8AdyACA?WdZe6ps%R-NM1O$j9!Y z>E2=tIeTT&P0=GtX!k6AU0!|!dT73DF`8|g>jZdCgmj&+7%~JcEv+R!=t;p#?stj- zn|(Qgtu~k7F#o(SaF{wvzzhWSx2d;N9xcW+euf~J;}Pf2N2%jJNCoajN550u>dD2o zbH|Q}Z{PYuIVB~(LAsJD8jQ)fQjZF!HgIh#(VHr?u|gLA9(kK|IerrTFSNxMpf65z zz4PH`s+i!?S@G$UN5vIdUop^#2{Cd$un9oH*K@*DousZ~FF@g__<1F(bwo#!D?Ksn z!m<*pg)ZmP_;R>#Igf8wb7ZT;scSu$Kqt~c4za)S z@724mVM-~DR!m@^I)rbRU%2ht7x1ziQ*kJC6QKE_DTCOSQjtFo7XgKleBTcHX1;Pu zw1{366*}i>iy-NqcMq^pGnT7`4Q>PJ+zy_g#0v+%m30yJ3a`tL%s&XO}zCwxd zBEIE^fgz5y88>uct_A1K4 zFe2khk8mZ?L{nqMwV|)e;S}Ra57mrrF-*@x-sW`)CG2jZoe-mZqAgMlGjMdbr9q2} z;i^)W;WAz>v6CX8g*I+-jJY352;I3@+e!HhQK}>-dhji0rlxwNz`GN4$O6R~6z|W` zAS1&08ESvPl+1EI%n89^BD02$38c|EN+qDUjd2B7%IYaunx*p`Fg)P8nYJdWZcx<5 zbOm-{Skzl3C9>WHFvF-Rro`vs(!M&8k&&5350$iS?Cs|1ERnKJ-otE%9-C)q$e7SCj%&Jv4Gs-arQOj_AngEP(|i+;t5aYtTz@%nPIR8g>PN z+C5RaP5-_=dgvJQ_N^WH{JGpwblbMQ#cp3)GEjOhnzaV+fna6FD^BoXh!vVPxQQb> z2PX4uR#appEGZ%TUGxmio-nE1t)STsj*Y!>6a^ipIOR*zy--VfK%)qz>BZk8Is?0R z+@!X)7Mcxo#4}uFkqEK?pD@#je%rpQUEb%-5jIZsADF1}L0<$k{UxGdYc_wQ$+U(@559~=|}vOA~n0%*N3@mwSuqp4YU zH=|>=v<=4r1X2oqGzsuBtLW-BLVkzT8mwir=--1R8$ zr4CwC702gWUiyJaBto-- ztZZyv=%DjHBz;HT+x$T{H!rURy1leP&5R5We{PY4mk$ATeqqEpOjn=R*6ue&fW`IR za{~nhhU4NXKYcP8pX4~h!3XO9ZOa<)356}53G!_W#l)zF_I5K~ zzgbAq_~azQUMw(Vk4dR_@7Y6{D#*><2R%GrF*M9#wAPX-Jp%)H=Rvjj6j_{b&1N!h zJ?JC7)Nyrpr$`l)ks+iWef#dpdKijY1D5P&(2@!2?mil#$H>MeJj>Vj`7?)68uAZ( zr)4E26_v}mbBy}#uCC-i{}@;%@m0L#8G;fL1~S%2P!N$U767yVs-!Kzy0kiu2l@gq62sZN1=Lso89!0iw2H{&Bgtr)JX*tX%Dw4pU zYA`}P`m(bcryiDGjXDMI7nTLP9^rWjj~aP*zOCB0zn zS~9Z0&Ba6@ga2c{1@Z|ym(P~xoY@_c3b?r*3i8WWl{ay z-TmA<7`KQ&V!FVqcLS zX2q^y%N=#1n($~(M~U4)yqhah#P>5@C3>u}FB{_V-IgKYyC|YGQYOwip`CWgi~fZu z-i$A?KEy?~vSHv2EP6*{kgATZE-E|QY_(;WQ2Iq{0BvO80CC5rN!g|aoXkiq17`JJ zR0cDVSuD~sGNR?oT-yy|0p+Hz`kW^QC?_zgvJzPqX%;an8Kh%mgorau`-g{XI(PD( z;Sfd_7mhxrfD^Z@F~NuY+tbsN%$fxnXe>2aA7<~ooAu!4qGkD1x%D?@*l^4Tf;!ML z|5RSCNV9)v;`$Ep-=G%%egfiGPh|b|0|jb2a!N{QToSVM*Oi;&jjOa*E)xZ~F)^I| zE!8iuA)aTw^1glObNPh8{q#4D17c-H|M)^(kn(Pvc4hhfQA%*t@%Atv+S>5DQpH4^<&y+>0fAy4~y{i@Nh9CGRR&y1JgdAAPM+=O(k5D z(bkn><(jFKRyH4Yh_s~2|TThs(uAmZ+7)T^nzD}?uc!HX%izP zt5yIk2Jnt`j)=*uUV)2!Ft(cboUt+TZ`*%hOgheMeD_vOY-FCMvxlLlYGT%~O3|NE2ii2%^~`2*a4J^w1wyOgi7FVX$0 z#`!?<_hV@5V5J!t_O2}aDw29KG?#vdKwtMLRVMZCo6*5SnJ8oK5Q-e_t zc8K%-+nQPUAYVjmf?>Y7f|T^Xmx!I+4BP2n3KHY;tI;?Jc|3?La?vjDE&oRmMU4jh z+|}#3f3MILQn1t^d3blVA@;?E^2E5&YE{Iq8IH#)2kTZYCr zOmk-2x)pp@7UuNdaO`Xj5ZX+N-`BL=Mogr{6Acd91{}$Ale@cS<(diyh>fauoUI4c z3*xVfW6N;hQ*q5rn*zDITi7Q~{`z)>5S)3Pp42UCRz9g8bP-dJ(9iYa`E%^zAYK-q zUzcd!g6$=7JbQ=k%3oSjY{8sSsGxw*=-Epr+A$QT-*&%6ZCB>_YgB zzF0!s;&7H1bzPGB?=_t^#B1s}D71E^aN?RpLI|rv2M_+(Nwea_*?qqYXg>(^e8{d3;ySh3(gOjK3r`H8r() zee?5|FIl?xJB)ZASpI&f^n_KYvF)-O6kGY0b)?A1#E-qCLhQsvyIXYgAjz-a#P23d z&%sCj&sNHDE~;fMEoX73Q0P$ObUCiuuyJL*A7h*92&JySvr^_6ynXTBy#cggi} zH8e~;bBEv#uh{1!cv-t;qz6}wzQScPM51UsgeaXam(u0q>&;e5kAsQWQ)agrra@XJ zHg)_02~a%*(7Qdpp#!BoPH=jq*cPvcMRl>?-LUER4beXBH@IE+n+t$`KrrJmn(NYt zvi>dUy{aniUe)W_5I$-wv zH1zc1NX>v$as;NO?!4l#Vk|o%vBXl`p?xdsmY!dRViM*&5*Zp7ZHouzTaT6dj6!K9 z&DmM-_j53jpx|^9y2?mR5K5R+kzZQ5HHG*fYzKW>amJOC)UflP&Kj*Pck2WLR(|8! zj$1X)7yYD)I#c9%nUhuybg?AfMNSAK^~#-3A7%#}iheu@xxg{F z%W6~o^=s`{`DhRht2*9xzP8BvYKssl}Bu0LO_0y|#oDqrv4Wn^}BcIbED^`l~u$)TWr7__ru_7n;f5KG3K zR-|XJcW8&hLW1Y7|X&4w80hTrYNKOCKXey)-@6<(C9Hda<2WhkuodyX+!Pr8jD0ar~xjsEZ+AqQyA(BrGPST-`-Nb|H@AVCVKij z^o;|0z(11UCTLIbFGEEIC{{Y+yQgY6~77p1_*Z-<8ej)0{0|CcZY@vOjf{soY zQc}#Zrj~xjTBTg<8giVu9}ptC>3dW+5V9g@R7PL);U_0QV8j)a_Lh6u?*UKa7L8RF<_1LEey06erG=^$OxCAuq^6XpeF&`fKcMuo* zfk4H3t}hxL{mH=2#jiqF=M6DG7I0`4T5``p4aM#NZVUgzyOBM$MV-`wt&})WX&N|P z2KPg(R~BMgH6H0gTiXSQ3Q6n?v~5X`Lc6Etb1fa6wGS%kxdeO`+6WK<3 zi+#Wmq~icNfx#lrM(!Ye?HF?^PGMxhdk&y^;=$k*1?0GI(&A4Uia zsiee21Q9o4WBJ)c3iS4=slD=BztOg5&04DQ>1ouIMELmPqxXE)(pFUT*=2i-d0&FI z_CvrG_>SEQ^TCI+g!%Z`H`314Z-@zo?po}1O`Ua%B-l<0N$^1-g0tIxE#fK?5vH5K zAD}Q*xwXZ7>9xI)&USS_-TN0Nd#lHmm!&cF0So5hl7~nI>aF7#3xP_n2oisyA>H2} z4s6-t>8Hxd6jZ|zOF<1GcDg57HP3Cal&Yf^@!{mwayk zRRMw=S0|J|kY9~-mM%jfh7f|p1Uj6-u(dti-Gtr=Kw3=4ZFmrm{e^$pQDH#s2XA&L zF-pVw`SRoQUnlfaD7Tj7*LCPV*LGmt^e!ZE(01O%{g&94RLVO#I~{ImL?<{8y2K1c zGH+D3sktpIPOY~sMXN8_&)$WDzuN7w%6(IT$}6--KaKpj{iwsu#a9~tmx}3VN_OJF^~*8 zYwtgP41WndoaOm;w!P&^{8Mi_IKl$S{BuqxT+A=!2!zrO;o4wqvB+m>N!pA#gwg0|N_-`r-s4I+bAy z%`4-_{DB?VCTx2#Q^Lz@2^+f;0uqK2^IF{8DeE`#R8&<(tm2lEI*($LtYQD@T?lue zM7K^w2LrAlQP0(a*>bFa6k=V?%z$%_sIfxJKQfYD_a5f0LSw`}?(z#Ah+o16 zpv~XV(54&DOS*O~Ms}y2H`qe>NA?UvXI5vecZmE7m&z_u0)IaWY;-b4IW0Zi3$rF} zEzBcayIgQ$n?PU}CLpkB!EV(LoUpZ}Ld`)>?+ijzdXj{FKynE9U`2&r!CtPodQ3Vm0Ngd_^dOvEj0+f^yV~Ky zhb=BlklkO-Rf5zfPP<1jExb0a`|iVsIcW9B!2Uu#nW$k>*$zqq?t;!DDjG5Q#~`qZ z!vqx{lzYqpbS0*t(vBIG5z#LA6{r#rD8wwlnNaV=q=W>Ho%@_zT$1xMz=Vi}c02@y z(EPkF-c{x{+PLOiO&jafPdS)lviq z(#NM9*cw` zn1@d#2eDgoc@bEDYo*`$JAdHzL0B?7J1Z)6;KF{^(qIRpJ%-^KbsdzRJhTX9aiY-U zO|ODc8Sh$K8?A@9FiVY3PVTPPgG2;`iHW|6e1XakD6enx*Ma#3L^oX|X?qU~KRfFR zyi%+gCg?UiyBz-=Wm`Kt@DKvn_L-P$_6%DN>OFh*EK&hTZbP+*t6d$+tn`@fQsg#e zGgLx1eXbOb-?@Ucc8?dLA;Dt77L4E>0+~To!xT*3(Aqv(Uks5 zjSEOy9XpCYG&d_>rlnUw<|YEY;Lc8Ye*R&Eq40;{&!qgWGLjJsB1Xso1TZn_t)#3} znPm{OD=9967~CPF}2R0b9_o4`!pv|W^(yf^<7r5-U8|>)m*R&CSFR8WRSHD1*AAWl^@Dmli`@w+jo~JRTqRhSK5PJ?Gza zc6#HTqbf>hT@FQ?CN`0sJv+m_|AuIsc>-U0J(n+Apfac3sZ&|m*-L%V7K4tcg&=zh z4h|-CKX!|u+=gLF)m`g$2R`*)mOB&o7IHQ?&13H$_7K8qP%h5S2H;rU!)zt3jfAw9 z=;)Wpk?a2pHXMoy;hoKdt1ZW~zMcZzyG!uY!~)n-Xd->S*V(Ly)|Oz>5&k-A@a zIAqGEZZ4>X$7XUJg`yHtGA>nhpAOz|Q`eD^5vaz5Y~l6?!T_adoPxqsoHSVcAEv7W z0%2BB8T;y_mi+k8c31}h@fDSo>;0cYdz_q<1Ut5$je1&bdU~3Zlk=t)UojNpIyX$B z3IiJtZZ23PLKt6-fEUCEtQQA6k__O;R%L7MD8rZ$f>{+YYyq$rg@yB|+<~|Ny}J(R z&mjFfv|FF^k}`qUUX%e3`ub&qms?hFgf*NGFlY{vATM9;>;E#brm>0LHZn?iaA*iV zxn%6Ak$MHBBvGB7V%vO#n--0(@I_(S(8~M<@MVs zhWe;+4&LK(zfCO=2p$PBcE{yFm|8D}CdAEA1cHt=|Ah^YAd+EWY6{z~x$k*lQF1+3;*%%mz!~aQ+`twJ zrQhRFw;UW~rlBG73xpTpFEPo4Fd%B?Qh^PGjyYdydOC7rgJeoWI>pjMj}iEYi8X@6 z1f}{zhoWbS*Ln(vR^37>0|Qq*P8@1>c6mH-@A0f1dOr{KMFn|ENO6KKhUfx9sVc^X zbO{+5MIgGc)mwAZ!tR1Y5uOdtQ&~JNDJ~8n@O+oY*ppYULa3Q~p550I=U|X zJPW5lpDXn5C`Isb14p`G*VaAf1V^G6UpFD+Ih1Ln$p5JOW=F&oj4#1qfSz5D+@1P? zPai+Ntf)Yp_U)c~7@GFAtsp`iEUIrP9)x#TNCmn=Fbu>1)r0paVK2byOQsy+@@;ms zw}%*AU{DaeE<~m`kdl}6_C7zhSsBs z3Lbf)gg~HW`(I@z{i2kwZk9qb&Lv|XVJQg-3g)A+y+EX>YAUa>nf( z9C&W=sPWPwAeYU?xo4L5T134q`NX;N=Z{-khd{H~wC%95F_4YhbM`GLoD##2-Bv?5 zD=aovBmboaCwv#S@3wZGubmi8#R-B}!NMg3gWv;wZ7)LXurE#^Obvk~h#g>h?!&yl zwI`1qI|HU{qnEk)UFeZX5BK)MpKNo^OH3rlLA_}qAqOzMK$<^HO=JIl%$HCngA#JT zEG@_=-=?RzR53>k88|i$UwTo|9(?CX`GmAIkV}@J+^>5NMhB$=}=;41bI**KR-WcVMJ@fsZ8kEgZX>=wjf;~eyq$% z_+;?Xs-vcGS3^>F8}<%IbNMEwL4pmY>-ve4e_c+(2!hX_!@|RfS?ZuS0^))Td0$^2 zD#P{s^JxT`SbJ#HYI)rU1^_c?m519WQd*oyH706fU>A|uA$mmUj+$rQ3l{s~wYF~0(C|iB7_FT*2wt$`X&D(OFdf*@(fiwIj2ahYK3VUNBOC!c zJNPy0&qF%74TsdLm1XBj2gCFu1yj@808FsGUvT-FYJM|@(VGX(VmA-}LnI+#VMiPs z-e|4{E9c&UTTd*@eK+m2v9-4kSDc(%l>afL_4@mX=|gmHTU!Ad*<+Z;d?F>{YUqVx zhztJBC7iGUs*S{W?U{quac<<7=jxMb<>DNV9uF7nGiv3A~4ALC?7WXG%2cLAl<|5f;_b2`^;btv9n+{aOyYzzqYPDs_8n4Pn3tTaJ+IuQNTeQsF;cc z%49qwNCY~ih!Y(zLrnpr#7xn6=#+3fM(|6)DC_I*e=kEKsFNy_Dlt5;J{A*kbA_4R;x>i+)Y6}F#D zdJ<^$h&>j$qrS7;gD%o&4lEFHB%Gl#F~fLaxoTbVeS6nE+w}Emw}b71-tU3$XfuC# z00Ld`E0)XDPHdT4qtVC^Z9sJmRf_+sw~8ZXta#r9Y^!1Y!NM%x`Iex)^^OkzM1+br zfBwLY8!hYZLZ`w!1+o9;SaQ;J1VIoy2fkM#o~3OAP;eLg8e4Bvy#@0?W20;5;1T(E6w)F&I+SAS(BpaY!)`d)9D)a%j3prQTv z$jTqqegS|#?TWswx3?G1GK>co4k!vJR}5Crr$7;fS2`*i8XhCPsk#afIj9zS=k*&M zAcEkyJOoJ)RZ_R&g~7#v*#>_Ue@{rzH`3YB(cMnE;bs=D^~sO}2r;B2B`x4sfyxhU z0P{8aYri1b!+Uj2NK@zskqKW9=+}h<)l1rOqO&!S3p|d*eh&juikyqr_rTG-J2H~B zYZsv8uHir#yhlGjzdvC!^uQB>6nc2HfzgDLp)DD37lq!E(_&0%Ns$B^6Oq zahfdxS$41Fp&LSiVezwlnfYNGTJXBE9k?G|v`z_6J*-~)Ly?`X3 zhuSVYWAOM;t_*tM^00(7p|!RKpAkRCOC}bJ;}%p6C^GaYyc1u{5E1Y zM8rD9iwn3W`4EK9xY6AWMbO>dT@uPJb!-;U6@`H6qdcJlSq-hP)tk@*Nld~gE;Ayg$6)_yY-A~Tc)s17y7&mXUg-d6ULt=80xS0i%2Ot=k zftJYQC?@$LC>*l=zJSK)70VE~(b?#_mYB9ql4`vkWiA0ly1Sb{3uWKWQ)=m;X|Wje z*T-QDUxa6;Qmc_sIfU?WMszN_#_Jmr#30U0I%YaOs(?ATdarcUy9^9$QYu6Fw)K~k z<+JIxx!@|ZbG`a$C|~uB0{+P#JQ<97WdERAJ*;el&mCmfx|M_{A7!1Rma}NE5T|i@ zp{o<|C5TQcR3JU&xvn@{X?UW4Hef_f_G3ue0hD=qejhy&yLx(ZaeMYUl+(1r!3HwI z+q@`dgc{M7E#Jp@!l9qgj@{AA)Oa)@DI;Z8_DoWwJQ@qzV|S907FcFRpBS+iU27IC zl|Gn|A3ZQ&yf*Q_P?AIQZw=M=H?d|7dhKs%z%Bu zt8HqZ)pShDZP94{#*SwB=G5dj(XHo5fB{G(a%v&(6KymDffsD^XK!XdH5fDPNSg|n zSXcTL8K%ntvl={&-1RTD(Ag@!}53KoUsI5Zpwn63&jVPQ`SmwT89Q>Bf>T^PU|rUjndgF*Eit_2kw?aUsH271o{`_g!<^&tJ? zagf@S%SPY5Yg+q$*S9!ub)20G-(8&lbW!3{`rjAehz{56s9H=9sbD4|vA7+>U2L9s zO{68&TXNh~i?3!E(sd@U$Es>hoib1R`G_v1ZGxVf0fSX;^zY&_Yoq&4#%=_JqdjJ6 z$=qWqYvd%fv5+OhHEA0i=B3}_Xz?h7)&=-6_uVApFV0WYM23uw^8KF#b5R`;t - - - planning_error_monitor - 0.1.0 - ros node for monitoring planning error - Yutaka Shimizu - Apache License 2.0 - - Yutaka Shimizu - - ament_cmake_auto - - autoware_cmake - - autoware_auto_planning_msgs - diagnostic_updater - geometry_msgs - rclcpp - rclcpp_components - tf2 - tf2_ros - tier4_autoware_utils - visualization_msgs - - ament_cmake_ros - ament_lint_auto - autoware_lint_common - - - ament_cmake - - diff --git a/planning/planning_error_monitor/src/debug_marker.cpp b/planning/planning_error_monitor/src/debug_marker.cpp deleted file mode 100644 index 60404d2059793..0000000000000 --- a/planning/planning_error_monitor/src/debug_marker.cpp +++ /dev/null @@ -1,88 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// 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 "planning_error_monitor/debug_marker.hpp" - -#include - -#include -#include -#include - -using visualization_msgs::msg::Marker; - -PlanningErrorMonitorDebugNode::PlanningErrorMonitorDebugNode() {} - -void PlanningErrorMonitorDebugNode::initialize(rclcpp::Node * node) -{ - node_ = node; - debug_viz_pub_ = - node_->create_publisher("~/debug/marker", 1); - initialized = true; -} - -void PlanningErrorMonitorDebugNode::pushPoseMarker( - const geometry_msgs::msg::Pose & pose, const std::string & ns, int id) -{ - if (!initialized) { - return; - } - // append arrow marker - Marker marker{}; - marker.header.frame_id = "map"; - marker.header.stamp = node_->get_clock()->now(); - marker.ns = ns; - marker.id = getMarkerId(ns); - marker.lifetime = rclcpp::Duration::from_seconds(0.2); - marker.type = Marker::ARROW; - marker.action = Marker::ADD; - marker.pose = pose; - marker.scale = tier4_autoware_utils::createMarkerScale(0.2, 0.1, 0.3); - if (id == 0) // Red - { - marker.color = tier4_autoware_utils::createMarkerColor(1.0, 0.0, 0.0, 0.999); - } - if (id == 1) // Green - { - marker.color = tier4_autoware_utils::createMarkerColor(0.0, 1.0, 0.0, 0.999); - } - if (id == 2) // Blue - { - marker.color = tier4_autoware_utils::createMarkerColor(0.0, 0.0, 1.0, 0.999); - } - marker_array_.markers.push_back(marker); -} - -void PlanningErrorMonitorDebugNode::clearPoseMarker(const std::string & ns) -{ - clearMarkerId(ns); - - if (marker_array_.markers.empty()) { - return; - } - - for (int i = static_cast(marker_array_.markers.size()) - 1; i >= 0; i--) { - if (marker_array_.markers.at(i).ns == ns) { - // clear markers with the namespace "ns" - marker_array_.markers.erase(marker_array_.markers.begin() + i); - } - } -} - -void PlanningErrorMonitorDebugNode::publish() -{ - if (initialized) { - debug_viz_pub_->publish(marker_array_); - } -} diff --git a/planning/planning_error_monitor/src/invalid_trajectory_publisher.cpp b/planning/planning_error_monitor/src/invalid_trajectory_publisher.cpp deleted file mode 100644 index 2931b00939cef..0000000000000 --- a/planning/planning_error_monitor/src/invalid_trajectory_publisher.cpp +++ /dev/null @@ -1,78 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// 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 "planning_error_monitor/invalid_trajectory_publisher.hpp" - -#include -#include -#include - -namespace planning_diagnostics -{ -InvalidTrajectoryPublisherNode::InvalidTrajectoryPublisherNode( - const rclcpp::NodeOptions & node_options) -: Node("invalid_trajectory_publisher", node_options) -{ - using std::placeholders::_1; - using std::chrono_literals::operator""ms; - - traj_sub_ = create_subscription( - "~/input/trajectory", 1, - std::bind(&InvalidTrajectoryPublisherNode::onCurrentTrajectory, this, _1)); - - traj_pub_ = create_publisher("~/output/trajectory", 1); - - timer_ = rclcpp::create_timer( - this, get_clock(), 100ms, std::bind(&InvalidTrajectoryPublisherNode::onTimer, this)); -} - -void InvalidTrajectoryPublisherNode::onTimer() -{ - if (!current_trajectory_) { - RCLCPP_INFO(this->get_logger(), "waiting trajectory"); - return; - } - if (current_trajectory_->points.empty()) { - RCLCPP_INFO(this->get_logger(), "waiting trajectory"); - return; - } - - constexpr auto ADDED_VALUE = 1.0e3; - - auto output = *current_trajectory_; - auto & p = output.points.back().pose.position; - p.x += ADDED_VALUE; - p.y += ADDED_VALUE; - p.z += ADDED_VALUE; - - traj_pub_->publish(output); - - RCLCPP_INFO(this->get_logger(), "invalid trajectory is published."); - - bool EXIT_AFTER_PUBLISH = false; - if (EXIT_AFTER_PUBLISH) { - exit(0); - } -} - -void InvalidTrajectoryPublisherNode::onCurrentTrajectory(const Trajectory::ConstSharedPtr msg) -{ - current_trajectory_ = msg; - traj_sub_.reset(); -} - -} // namespace planning_diagnostics - -#include -RCLCPP_COMPONENTS_REGISTER_NODE(planning_diagnostics::InvalidTrajectoryPublisherNode) diff --git a/planning/planning_error_monitor/src/planning_error_monitor_node.cpp b/planning/planning_error_monitor/src/planning_error_monitor_node.cpp deleted file mode 100644 index 4a8b7bbda8a80..0000000000000 --- a/planning/planning_error_monitor/src/planning_error_monitor_node.cpp +++ /dev/null @@ -1,312 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// 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 "planning_error_monitor/planning_error_monitor_node.hpp" - -#include - -#include -#include -#include - -namespace planning_diagnostics -{ -using diagnostic_msgs::msg::DiagnosticStatus; -using tier4_autoware_utils::calcCurvature; -using tier4_autoware_utils::calcDistance2d; - -PlanningErrorMonitorNode::PlanningErrorMonitorNode(const rclcpp::NodeOptions & node_options) -: Node("planning_error_monitor", node_options) -{ - using std::placeholders::_1; - using std::chrono_literals::operator""ms; - - debug_marker_.initialize(this); - - traj_sub_ = create_subscription( - "~/input/trajectory", 1, std::bind(&PlanningErrorMonitorNode::onCurrentTrajectory, this, _1)); - - updater_.setHardwareID("planning_error_monitor"); - - updater_.add( - "trajectory_point_validation", this, &PlanningErrorMonitorNode::onTrajectoryPointValueChecker); - updater_.add( - "trajectory_interval_validation", this, &PlanningErrorMonitorNode::onTrajectoryIntervalChecker); - updater_.add( - "trajectory_curvature_validation", this, - &PlanningErrorMonitorNode::onTrajectoryCurvatureChecker); - updater_.add( - "trajectory_relative_angle_validation", this, - &PlanningErrorMonitorNode::onTrajectoryRelativeAngleChecker); - - timer_ = rclcpp::create_timer( - this, get_clock(), 100ms, std::bind(&PlanningErrorMonitorNode::onTimer, this)); - - // Parameter - error_interval_ = declare_parameter("error_interval", 100.0); - error_curvature_ = declare_parameter("error_curvature", 1.0); - error_sharp_angle_ = declare_parameter("error_sharp_angle", M_PI_4); - ignore_too_close_points_ = declare_parameter("ignore_too_close_points", 0.05); -} - -void PlanningErrorMonitorNode::onTimer() -{ - updater_.force_update(); - debug_marker_.publish(); -} - -void PlanningErrorMonitorNode::onCurrentTrajectory(const Trajectory::ConstSharedPtr msg) -{ - current_trajectory_ = msg; -} - -void PlanningErrorMonitorNode::onTrajectoryPointValueChecker(DiagnosticStatusWrapper & stat) -{ - if (!current_trajectory_) { - stat.summary(DiagnosticStatus::OK, "No trajectory message was set."); - return; - } - - std::string error_msg; - const auto diag_level = checkTrajectoryPointValue(*current_trajectory_, error_msg) - ? DiagnosticStatus::OK - : DiagnosticStatus::ERROR; - stat.summary(diag_level, error_msg); -} - -void PlanningErrorMonitorNode::onTrajectoryIntervalChecker(DiagnosticStatusWrapper & stat) -{ - if (!current_trajectory_) { - stat.summary(DiagnosticStatus::OK, "No trajectory message was set."); - return; - } - - std::string error_msg; - const auto diag_level = - checkTrajectoryInterval(*current_trajectory_, error_interval_, error_msg, debug_marker_) - ? DiagnosticStatus::OK - : DiagnosticStatus::ERROR; - stat.summary(diag_level, error_msg); -} - -void PlanningErrorMonitorNode::onTrajectoryCurvatureChecker(DiagnosticStatusWrapper & stat) -{ - if (!current_trajectory_) { - stat.summary(DiagnosticStatus::OK, "No trajectory message was set."); - return; - } - - std::string error_msg; - const auto diag_level = - checkTrajectoryCurvature(*current_trajectory_, error_curvature_, error_msg, debug_marker_) - ? DiagnosticStatus::OK - : DiagnosticStatus::ERROR; - stat.summary(diag_level, error_msg); -} - -void PlanningErrorMonitorNode::onTrajectoryRelativeAngleChecker(DiagnosticStatusWrapper & stat) -{ - if (!current_trajectory_) { - stat.summary(DiagnosticStatus::OK, "No trajectory message was set."); - return; - } - - std::string error_msg; - const auto diag_level = - checkTrajectoryRelativeAngle( - *current_trajectory_, error_sharp_angle_, ignore_too_close_points_, error_msg, debug_marker_) - ? DiagnosticStatus::OK - : DiagnosticStatus::ERROR; - stat.summary(diag_level, error_msg); -} - -bool PlanningErrorMonitorNode::checkTrajectoryPointValue( - const Trajectory & traj, std::string & error_msg) -{ - error_msg = "This Trajectory doesn't have any invalid values"; - for (const auto & p : traj.points) { - if (!checkFinite(p)) { - error_msg = "This trajectory has an infinite value"; - return false; - } - } - return true; -} - -bool PlanningErrorMonitorNode::checkFinite(const TrajectoryPoint & point) -{ - const auto & o = point.pose.orientation; - const auto & p = point.pose.position; - const auto & v = point.longitudinal_velocity_mps; - const auto & w = point.heading_rate_rps; - const auto & a = point.acceleration_mps2; - - const bool quat_result = - std::isfinite(o.x) && std::isfinite(o.y) && std::isfinite(o.z) && std::isfinite(o.w); - const bool p_result = std::isfinite(p.x) && std::isfinite(p.y) && std::isfinite(p.z); - const bool v_result = std::isfinite(v); - const bool w_result = std::isfinite(w); - const bool a_result = std::isfinite(a); - - return quat_result && p_result && v_result && w_result && a_result; -} - -bool PlanningErrorMonitorNode::checkTrajectoryInterval( - const Trajectory & traj, const double & interval_threshold, std::string & error_msg, - PlanningErrorMonitorDebugNode & debug_marker) -{ - error_msg = "Trajectory Interval Length is within the expected range"; - debug_marker.clearPoseMarker("trajectory_interval"); - for (size_t i = 1; i < traj.points.size(); ++i) { - double ds = calcDistance2d(traj.points.at(i), traj.points.at(i - 1)); - - if (ds > interval_threshold) { - error_msg = "Trajectory Interval Length is longer than the expected range"; - debug_marker.pushPoseMarker(traj.points.at(i - 1).pose, "trajectory_interval"); - debug_marker.pushPoseMarker(traj.points.at(i).pose, "trajectory_interval"); - return false; - } - } - return true; -} - -bool PlanningErrorMonitorNode::checkTrajectoryRelativeAngle( - const Trajectory & traj, const double angle_threshold, const double min_dist_threshold, - std::string & error_msg, PlanningErrorMonitorDebugNode & debug_marker) -{ - error_msg = "This trajectory's relative angle is within the expected range"; - debug_marker.clearPoseMarker("trajectory_relative_angle"); - - // We need at least three points to compute relative angle - const size_t relative_angle_points_num = 3; - if (traj.points.size() < relative_angle_points_num) { - return true; - } - - for (size_t p1_id = 0; p1_id <= traj.points.size() - relative_angle_points_num; ++p1_id) { - // Get Point1 - const auto & p1 = traj.points.at(p1_id).pose.position; - - // Get Point2 - const auto & p2 = traj.points.at(p1_id + 1).pose.position; - - // Get Point3 - const auto & p3 = traj.points.at(p1_id + 2).pose.position; - - // ignore invert driving direction - if ( - traj.points.at(p1_id).longitudinal_velocity_mps < 0 || - traj.points.at(p1_id + 1).longitudinal_velocity_mps < 0 || - traj.points.at(p1_id + 2).longitudinal_velocity_mps < 0) { - continue; - } - - // convert to p1 coordinate - const double x3 = p3.x - p1.x; - const double x2 = p2.x - p1.x; - const double y3 = p3.y - p1.y; - const double y2 = p2.y - p1.y; - - // skip too close points case - if (std::hypot(x3, y3) < min_dist_threshold || std::hypot(x2, y2) < min_dist_threshold) { - continue; - } - - // calculate relative angle of vector p3 based on p1p2 vector - const double th = std::atan2(y2, x2); - const double th2 = - std::atan2(-x3 * std::sin(th) + y3 * std::cos(th), x3 * std::cos(th) + y3 * std::sin(th)); - if (std::abs(th2) > angle_threshold) { - error_msg = "This Trajectory's relative angle has larger value than the expected value"; - // std::cout << error_msg << std::endl; - debug_marker.pushPoseMarker(traj.points.at(p1_id).pose, "trajectory_relative_angle", 0); - debug_marker.pushPoseMarker(traj.points.at(p1_id + 1).pose, "trajectory_relative_angle", 1); - debug_marker.pushPoseMarker(traj.points.at(p1_id + 2).pose, "trajectory_relative_angle", 2); - return false; - } - } - return true; -} -bool PlanningErrorMonitorNode::checkTrajectoryCurvature( - const Trajectory & traj, const double & curvature_threshold, std::string & error_msg, - PlanningErrorMonitorDebugNode & debug_marker) -{ - error_msg = "This trajectory's curvature is within the expected range"; - debug_marker.clearPoseMarker("trajectory_curvature"); - - // We need at least three points to compute curvature - if (traj.points.size() < 3) { - return true; - } - - constexpr double points_distance = 1.0; - const auto isValidDistance = [points_distance](const auto & p1, const auto & p2) { - return calcDistance2d(p1, p2) >= points_distance; - }; - - for (size_t p1_id = 0; p1_id < traj.points.size() - 2; ++p1_id) { - // Get Point1 - const auto p1 = traj.points.at(p1_id).pose.position; - - // Get Point2 - const auto p2_id = getIndexAfterDistance(traj, p1_id, points_distance); - const auto p2 = traj.points.at(p2_id).pose.position; - - // Get Point3 - const auto p3_id = getIndexAfterDistance(traj, p2_id, points_distance); - const auto p3 = traj.points.at(p3_id).pose.position; - - // no need to check for pi, since there is no point with "points_distance" from p1. - if (p1_id == p2_id || p1_id == p3_id || p2_id == p3_id) { - break; - } - if (!isValidDistance(p1, p2) || !isValidDistance(p1, p3) || !isValidDistance(p2, p3)) { - break; - } - - const double curvature = calcCurvature(p1, p2, p3); - - if (std::fabs(curvature) > curvature_threshold) { - error_msg = "This Trajectory's curvature has larger value than the expected value"; - debug_marker.pushPoseMarker(traj.points.at(p1_id).pose, "trajectory_curvature"); - debug_marker.pushPoseMarker(traj.points.at(p2_id).pose, "trajectory_curvature"); - debug_marker.pushPoseMarker(traj.points.at(p3_id).pose, "trajectory_curvature"); - return false; - } - } - return true; -} - -size_t PlanningErrorMonitorNode::getIndexAfterDistance( - const Trajectory & traj, const size_t curr_id, const double distance) -{ - // Get Current Trajectory Point - const TrajectoryPoint & curr_p = traj.points.at(curr_id); - - size_t target_id = curr_id; - double current_distance = 0.0; - for (size_t traj_id = curr_id + 1; traj_id < traj.points.size(); ++traj_id) { - current_distance = calcDistance2d(traj.points.at(traj_id), curr_p); - if (current_distance >= distance) { - target_id = traj_id; - break; - } - } - - return target_id; -} -} // namespace planning_diagnostics - -#include -RCLCPP_COMPONENTS_REGISTER_NODE(planning_diagnostics::PlanningErrorMonitorNode) diff --git a/planning/planning_error_monitor/test/src/test_main.cpp b/planning/planning_error_monitor/test/src/test_main.cpp deleted file mode 100644 index 399bcff8f918b..0000000000000 --- a/planning/planning_error_monitor/test/src/test_main.cpp +++ /dev/null @@ -1,26 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// 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 - -#include - -int main(int argc, char ** argv) -{ - testing::InitGoogleTest(&argc, argv); - rclcpp::init(argc, argv); - bool result = RUN_ALL_TESTS(); - rclcpp::shutdown(); - return result; -} diff --git a/planning/planning_error_monitor/test/src/test_planning_error_monitor_functions.cpp b/planning/planning_error_monitor/test/src/test_planning_error_monitor_functions.cpp deleted file mode 100644 index 5513252b5fad9..0000000000000 --- a/planning/planning_error_monitor/test/src/test_planning_error_monitor_functions.cpp +++ /dev/null @@ -1,157 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// 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 "planning_error_monitor/planning_error_monitor_node.hpp" -#include "test_planning_error_monitor_helper.hpp" - -#include - -#include - -constexpr double NOMINAL_INTERVAL = 1.0; -constexpr double ERROR_INTERVAL = 1000.0; -constexpr double ERROR_CURVATURE = 2.0; - -TEST(PlanningErrorMonitor, ValidValueChecker) -{ - using autoware_auto_planning_msgs::msg::Trajectory; - using planning_diagnostics::PlanningErrorMonitorNode; - - // Valid Trajectory - Trajectory valid_traj = generateTrajectory(NOMINAL_INTERVAL); - - std::string valid_error_msg; - ASSERT_TRUE(PlanningErrorMonitorNode::checkTrajectoryPointValue(valid_traj, valid_error_msg)); - ASSERT_EQ(valid_error_msg, "This Trajectory doesn't have any invalid values"); - - // Nan Trajectory - Trajectory nan_traj = generateNanTrajectory(); - - std::string nan_error_msg; - ASSERT_FALSE(PlanningErrorMonitorNode::checkTrajectoryPointValue(nan_traj, nan_error_msg)); - ASSERT_EQ(nan_error_msg, "This trajectory has an infinite value"); - - // Inf Trajectory - Trajectory inf_traj = generateInfTrajectory(); - - std::string inf_error_msg; - ASSERT_FALSE(PlanningErrorMonitorNode::checkTrajectoryPointValue(inf_traj, inf_error_msg)); - ASSERT_EQ(nan_error_msg, "This trajectory has an infinite value"); -} - -TEST(PlanningErrorMonitor, TrajectoryIntervalChecker) -{ - using autoware_auto_planning_msgs::msg::Trajectory; - using planning_diagnostics::PlanningErrorMonitorNode; - PlanningErrorMonitorDebugNode debug_marker; - // Normal Trajectory - { - Trajectory valid_traj = generateTrajectory(NOMINAL_INTERVAL); - - std::string valid_msg; - ASSERT_TRUE(PlanningErrorMonitorNode::checkTrajectoryInterval( - valid_traj, ERROR_INTERVAL, valid_msg, debug_marker)); - ASSERT_EQ(valid_msg, "Trajectory Interval Length is within the expected range"); - - std::string boundary_msg; - ASSERT_TRUE(PlanningErrorMonitorNode::checkTrajectoryInterval( - valid_traj, NOMINAL_INTERVAL, boundary_msg, debug_marker)); - ASSERT_EQ(boundary_msg, "Trajectory Interval Length is within the expected range"); - } - - // Long Interval Trajectory - { - Trajectory long_interval_traj = generateTrajectory(ERROR_INTERVAL); - std::string long_interval_error_msg; - ASSERT_FALSE(PlanningErrorMonitorNode::checkTrajectoryInterval( - long_interval_traj, NOMINAL_INTERVAL, long_interval_error_msg, debug_marker)); - ASSERT_EQ( - long_interval_error_msg, "Trajectory Interval Length is longer than the expected range"); - } -} - -TEST(PlanningErrorMonitor, TrajectoryCurvatureChecker) -{ - using autoware_auto_planning_msgs::msg::Trajectory; - using planning_diagnostics::PlanningErrorMonitorNode; - PlanningErrorMonitorDebugNode debug_marker; - // Normal Trajectory - { - Trajectory valid_traj = generateTrajectory(NOMINAL_INTERVAL); - std::string valid_error_msg; - ASSERT_TRUE(PlanningErrorMonitorNode::checkTrajectoryCurvature( - valid_traj, ERROR_CURVATURE, valid_error_msg, debug_marker)); - ASSERT_EQ(valid_error_msg, "This trajectory's curvature is within the expected range"); - } -} - -TEST(PlanningErrorMonitor, TrajectoryRelativeAngleChecker) -{ - using autoware_auto_planning_msgs::msg::Trajectory; - using planning_diagnostics::PlanningErrorMonitorNode; - PlanningErrorMonitorDebugNode debug_marker; - const double too_close_dist = 0.05; - const double too_sharp_turn = M_PI_4; - { - /** - * y: 0 0 0 0&INF 0 0 0 0 0 0 - **/ - Trajectory valid_traj = generateTrajectory(NOMINAL_INTERVAL); - valid_traj.points[4].pose.position.x = 3; - valid_traj.points[4].pose.position.y = 10; - // for (auto t : valid_traj.points) { - // std::cout << "p: (x , y) = " << "( "< -#include - -using autoware_auto_planning_msgs::msg::Trajectory; -using autoware_auto_planning_msgs::msg::TrajectoryPoint; - -inline Trajectory generateTrajectory(double interval_distance) -{ - Trajectory traj; - for (double s = 0.0; s <= 10.0 * interval_distance; s += interval_distance) { - TrajectoryPoint p; - p.pose.position.x = s; - p.longitudinal_velocity_mps = 1.0; - traj.points.push_back(p); - } - return traj; -} - -inline Trajectory generateNanTrajectory() -{ - Trajectory traj = generateTrajectory(1.0); - traj.points.front().pose.position.x = NAN; - return traj; -} - -inline Trajectory generateInfTrajectory() -{ - Trajectory traj = generateTrajectory(1.0); - traj.points.front().pose.position.x = INFINITY; - return traj; -} - -inline Trajectory generateBadCurvatureTrajectory() -{ - Trajectory traj; - - double y = 1.5; - for (double s = 0.0; s <= 10.0; s += 1.0) { - TrajectoryPoint p; - p.longitudinal_velocity_mps = 1.0; - p.pose.position.x = s; - p.pose.position.y = y; - y *= -1.0; // invert sign - traj.points.push_back(p); - } - - return traj; -} - -#endif // TEST_PLANNING_ERROR_MONITOR_HELPER_HPP_ diff --git a/planning/planning_error_monitor/test/src/test_planning_error_monitor_pubsub.cpp b/planning/planning_error_monitor/test/src/test_planning_error_monitor_pubsub.cpp deleted file mode 100644 index e5002afcff7f2..0000000000000 --- a/planning/planning_error_monitor/test/src/test_planning_error_monitor_pubsub.cpp +++ /dev/null @@ -1,129 +0,0 @@ -// Copyright 2021 Tier IV, Inc. -// -// 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 "planning_error_monitor/planning_error_monitor_node.hpp" -#include "test_planning_error_monitor_helper.hpp" - -#include - -#include - -#include -#include - -constexpr double NOMINAL_INTERVAL = 1.0; -constexpr double ERROR_INTERVAL = 1000.0; -constexpr double ERROR_CURVATURE = 2.0; - -using autoware_auto_planning_msgs::msg::Trajectory; -using diagnostic_msgs::msg::DiagnosticArray; -using diagnostic_msgs::msg::DiagnosticStatus; -using planning_diagnostics::PlanningErrorMonitorNode; - -class PubSubManager : public rclcpp::Node -{ -public: - PubSubManager() : Node("test_pub_sub") - { - traj_pub_ = create_publisher("/planning_error_monitor/input/trajectory", 1); - diag_sub_ = create_subscription( - "/diagnostics", 1, - [this](const DiagnosticArray::ConstSharedPtr msg) { received_diags_.push_back(msg); }); - } - - rclcpp::Publisher::SharedPtr traj_pub_; - rclcpp::Subscription::SharedPtr diag_sub_; - - std::vector received_diags_; -}; - -void spinSome(rclcpp::Node::SharedPtr node_ptr) -{ - for (int i = 0; i < 50; ++i) { - rclcpp::spin_some(node_ptr); - rclcpp::WallRate(100).sleep(); - } -} - -bool isAllOK(const std::vector & diags) -{ - for (const auto & diag : diags) { - for (const auto & status : diag->status) { - if (status.level != DiagnosticStatus::OK) { - return false; - } - } - } - return true; -} - -bool hasError(const std::vector & diags) -{ - for (const auto & diag : diags) { - for (const auto & status : diag->status) { - if (status.level == DiagnosticStatus::ERROR) { - return true; - } - } - } - return false; -} - -void runWithOKTrajectory(const Trajectory & trajectory) -{ - auto error_monitor = std::make_shared(rclcpp::NodeOptions{}); - auto manager = std::make_shared(); - EXPECT_GE(manager->traj_pub_->get_subscription_count(), 1U) << "topic is not connected."; - - manager->traj_pub_->publish(trajectory); - spinSome(error_monitor); - spinSome(manager); - - EXPECT_GE(manager->received_diags_.size(), 1U) << "diag has not received!"; - EXPECT_TRUE(isAllOK(manager->received_diags_)); -} - -void runWithBadTrajectory(const Trajectory & trajectory) -{ - auto error_monitor = std::make_shared(rclcpp::NodeOptions{}); - auto manager = std::make_shared(); - EXPECT_GE(manager->traj_pub_->get_subscription_count(), 1U) << "topic is not connected."; - - manager->traj_pub_->publish(trajectory); - spinSome(error_monitor); - spinSome(manager); - - EXPECT_GE(manager->received_diags_.size(), 1U) << "diag has not received!"; - EXPECT_TRUE(hasError(manager->received_diags_)); -} - -// OK cases -TEST(PlanningErrorMonitor, DiagCheckForNominalTrajectory) -{ - runWithOKTrajectory(generateTrajectory(NOMINAL_INTERVAL)); -} - -// Bad cases -TEST(PlanningErrorMonitor, DiagCheckForNaNTrajectory) -{ - runWithBadTrajectory(generateNanTrajectory()); -} -TEST(PlanningErrorMonitor, DiagCheckForInfTrajectory) -{ - runWithBadTrajectory(generateInfTrajectory()); -} -TEST(PlanningErrorMonitor, DiagCheckForTooLongIntervalTrajectory) -{ - runWithBadTrajectory(generateTrajectory(ERROR_INTERVAL)); -}