From 616e611c8c6b6cffaf872752c3817566e0da6cc3 Mon Sep 17 00:00:00 2001 From: Shahrukh <82996646+smartSRA@users.noreply.github.com> Date: Wed, 20 Dec 2023 16:20:24 +0100 Subject: [PATCH] Firmware download and custom plugin (#43) Added headers for firmware download, created a ros2 service which calls the update function using the sensor_id and file path provided. Created a new Firmware download message to be used by the service. Modified the SendCommand message to include value from user. Added fields for polar coordinates in pc2. Added a new rviz plugin for displaying the targets data and giving the possibility to record and save the data in csv format. Removed targetlist message and subscribers from node Extended Dockerfile to include dependecies for smart_rviz_plugin. Added new python GUI inside plugin. Updated Readme to include the new plugin and GUI description. Reformatted the plugin files and removed the ignore file. Extended node to inlcude new interface for A4 T171. Update smart release in extract file. Documentetd new interface info into Readme and Changelog. --- CHANGELOG.md | 6 +- Dockerfile | 10 + Readme.md | 57 ++++- smart_extract.sh | 2 +- smart_rviz_plugin/CMakeLists.txt | 101 ++++++++ .../config/images/can_sender.png | Bin 0 -> 23029 bytes .../config/images/recorder_rviz.png | Bin 0 -> 180236 bytes .../config/rviz/recorder.rviz | 32 +-- smart_rviz_plugin/custom_can_sender.py | 95 ++++++++ .../smart_rviz_plugin/smart_download.hpp | 45 ++++ .../smart_rviz_plugin/smart_recorder.hpp | 62 +++++ .../smart_rviz_plugin/smart_services.hpp | 54 +++++ smart_rviz_plugin/package.xml | 38 +++ smart_rviz_plugin/plugins_description.xml | 20 ++ smart_rviz_plugin/src/smart_download.cpp | 88 +++++++ smart_rviz_plugin/src/smart_recorder.cpp | 216 ++++++++++++++++++ smart_rviz_plugin/src/smart_services.cpp | 138 +++++++++++ umrr_ros2_driver/CMakeLists.txt | 12 +- umrr_ros2_driver/cmake/sensor_commands.hpp.in | 31 --- umrr_ros2_driver/cmake/sensor_params.hpp.in | 31 --- .../umrr_ros2_driver/UpdateService.hpp | 15 ++ .../smartmicro_radar_node.hpp | 42 ++++ umrr_ros2_driver/launch/radar.launch.py | 10 +- umrr_ros2_driver/launch/radar_rviz.launch.py | 59 ----- umrr_ros2_driver/package.xml | 2 +- .../param/example/radar.adapter.example.yaml | 2 + .../param/radar.adapter.template.yaml | 14 -- .../param/radar.params.template.yaml | 120 ++++++++++ .../param/radar.sensor.template.yaml | 114 --------- umrr_ros2_driver/src/UpdateService.cpp | 99 ++++++++ .../src/smartmicro_radar_node.cpp | 183 ++++++++++++--- .../test/radar_node_test.launch.py | 10 +- umrr_ros2_msgs/CMakeLists.txt | 14 +- umrr_ros2_msgs/package.xml | 7 +- umrr_ros2_msgs/srv/FirmwareDownload.srv | 4 + umrr_ros2_msgs/srv/SendCommand.srv | 1 + 36 files changed, 1403 insertions(+), 331 deletions(-) create mode 100644 smart_rviz_plugin/CMakeLists.txt create mode 100644 smart_rviz_plugin/config/images/can_sender.png create mode 100644 smart_rviz_plugin/config/images/recorder_rviz.png rename umrr_ros2_driver/config/rviz/radar.rviz => smart_rviz_plugin/config/rviz/recorder.rviz (71%) create mode 100644 smart_rviz_plugin/custom_can_sender.py create mode 100644 smart_rviz_plugin/include/smart_rviz_plugin/smart_download.hpp create mode 100644 smart_rviz_plugin/include/smart_rviz_plugin/smart_recorder.hpp create mode 100644 smart_rviz_plugin/include/smart_rviz_plugin/smart_services.hpp create mode 100644 smart_rviz_plugin/package.xml create mode 100644 smart_rviz_plugin/plugins_description.xml create mode 100644 smart_rviz_plugin/src/smart_download.cpp create mode 100644 smart_rviz_plugin/src/smart_recorder.cpp create mode 100644 smart_rviz_plugin/src/smart_services.cpp delete mode 100644 umrr_ros2_driver/cmake/sensor_commands.hpp.in delete mode 100644 umrr_ros2_driver/cmake/sensor_params.hpp.in create mode 100644 umrr_ros2_driver/include/umrr_ros2_driver/UpdateService.hpp delete mode 100644 umrr_ros2_driver/launch/radar_rviz.launch.py delete mode 100644 umrr_ros2_driver/param/radar.adapter.template.yaml create mode 100644 umrr_ros2_driver/param/radar.params.template.yaml delete mode 100644 umrr_ros2_driver/param/radar.sensor.template.yaml create mode 100644 umrr_ros2_driver/src/UpdateService.cpp create mode 100644 umrr_ros2_msgs/srv/FirmwareDownload.srv diff --git a/CHANGELOG.md b/CHANGELOG.md index f7e0fc2..8abd1b6 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -42,4 +42,8 @@ This release includes the new DRVEGRD 171 and DRVEGRD 152 user-interface. The re ## v5.0.0 - 2023-09-22 -This release includes CAN communication for all the provided sensor types and sensors interfaces. The params are now extended to include the params/setting for the connected adapters along with the sensor params. \ No newline at end of file +This release includes CAN communication for all the provided sensor types and sensors interfaces. The params are now extended to include the params/setting for the connected adapters along with the sensor params. + +## v6.0.0 - 2023-12-20 + +This release includes features for downloading sensor firmware on to the sensors. It also provides custom RVIZ plugins to log the target list data, record and save it. It has a plugin to send instructions to the sensors and also it is possible to dowload the firmware too. This release also includes a python GUI to send custom CAN messages. The radar param templates have now been merged into one param file. The pointcloud has been extended to also include the polar coordinates. Additionally, the release also includes new user interface for sensor A4 T171. \ No newline at end of file diff --git a/Dockerfile b/Dockerfile index 598e5c1..2ed0efc 100644 --- a/Dockerfile +++ b/Dockerfile @@ -1,10 +1,20 @@ FROM ros:foxy +## Revert to snapshot once GPG key error is resolved +RUN rm /etc/apt/sources.list.d/ros2-snapshots.list +RUN apt-get update && apt-get install curl -y +RUN curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg +RUN echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(. /etc/os-release && echo $UBUNTU_CODENAME) main" | sudo tee /etc/apt/sources.list.d/ros2.list > /dev/null + RUN apt-get update && apt-get install -y \ iputils-ping \ python3 \ python3-pip \ ros-foxy-point-cloud-msg-wrapper \ + ros-foxy-rviz2 \ + ros-foxy-rviz-common \ + ros-foxy-rviz-default-plugins \ + ros-foxy-rviz-rendering \ wget WORKDIR /code diff --git a/Readme.md b/Readme.md index fdd5f7d..1918cb5 100644 --- a/Readme.md +++ b/Readme.md @@ -16,6 +16,22 @@ acquired by the sensor through the ROS2 pipeline. This package implements such a ros2 launch umrr_ros2_driver radar.launch.py ``` +## How to launch the rviz with recorder plugin +From a separate terminal and after sourcing workspace +``` +rviz2 -d [`recorder.rviz`](smart_rviz_plugin/config/rviz/recorder.rviz) +``` + +![Recorder](smart_rviz_plugin/config/images/recorder_rviz.png "Rviz Outlook") + +## How to start the custom can message sender +From smart_rviz_plugin folder +``` +python custom_can_sender.py +``` + +![Sender](smart_rviz_plugin/config/images/can_sender.png "Custom CAN Sender") + ## Prerequisites ### Supported ROS distributions: @@ -26,8 +42,8 @@ A [smartmicro](https://www.smartmicro.com/automotive-radar) UMRR96, UMRR11, DRVE required to run this node. This code is bundled with a version of Smart Access API. Please make sure the version used to publish the data is compatible with this version: -- Date of release: `September 22, 2023` -- Smart Access Automotive version: `v3.4.0` +- Date of release: `December 20, 2023` +- Smart Access Automotive version: `v3.5.0` - User interface version: `UMRR96 Type 153 AUTOMOTIVE v1.2.2` - User interface version: `UMRR11 Type 132 AUTOMOTIVE v1.1.2` - User interface version: `UMRR9F Type 169 AUTOMOTIVE v1.1.1` @@ -37,6 +53,7 @@ sure the version used to publish the data is compatible with this version: - User interface version: `UMRR9D Type 152 AUTOMOTIVE v1.0.3` - User interface version: `UMRR9D Type 152 AUTOMOTIVE v1.2.2` - User interface version: `UMRRA4 Type 171 AUTOMOTIVE v1.0.1` +- User interface version: `UMRRA4 Type 171 AUTOMOTIVE v1.3.0` ### Sensor Firmwares This ROS2 driver release is compatible with the following sensor firmwares: @@ -48,6 +65,7 @@ This ROS2 driver release is compatible with the following sensor firmwares: - UMRR9F Type 169: V2.0.2 - UMRR9F Type 169: V2.2.0 - UMRRA4 Type 171: V1.0.0 +- UMRRA4 Type 171: V1.2.1 ### Point cloud message wrapper library To add targets to the point cloud in a safe and quick fashion a @@ -57,6 +75,11 @@ this project's node. This project can be installed either through `rosdep` or ma sudo apt install ros-foxy-point-cloud-msg-wrapper ``` +To use the GUI provided, it is required to install the following package: +``` +pip install python-can +``` + ## Inputs / Outputs / Configuration ### The inputs: @@ -98,7 +121,7 @@ For the setting up the ***sensors***: - `history_size`: size of history for the message publisher - `inst_type`: the type of instruction serialization type, relevant to sensors using ethernet and should be 'port_based' - `data_type`: the type of data serialization type, relevant to sensors using ethernet and should be 'port_based' -- `uifname`: the user interface name of the sensor +- `uifname`: the user interface name of the sensor (refer to the [`user_interfaces`](umrr_ros2_driver/smartmicro/user_interfaces/)) - `uifmajorv`: the major version of the sensor user interface - `uifminorv`: the minor version of the sensor user interface - `uifpatchv`: the patch version of the sensor user interface @@ -124,12 +147,13 @@ A ros2 `SetMode` service should be called to implement these mode changes. There For instance, changing the `Index of Transmit Antenna (tx_antenna_idx)` of a UMRR-11 sensor to `AEB (2)` mode would require the following call: `ros2 service call /smart_radar/set_radar_mode umrr_ros2_msgs/srv/SetMode "{param: "tx_antenna_idx", value: 2, sensor_id: 100}"` -Similarly, a ros2 `SendCommand` service could be used to send commands to the sensors. There are two inputs for sending a command: +Similarly, a ros2 `SendCommand` service could be used to send commands to the sensors. There are three inputs for sending a command: - `command`: name of the command (specific to the sensor interface) +- `value`: the value of the command - `sensor_id`: the id of the sensor to which the service call should be sent. The call for such a service would be as follows: -`ros2 service call /smart_radar/send_command umrr_ros2_msgs/srv/SendCommand "{command: "comp_eeprom_ctrl_default_param_sec", sensor_id: 100}"` +`ros2 service call /smart_radar/send_command umrr_ros2_msgs/srv/SendCommand "{command: "comp_eeprom_ctrl_default_param_sec", value: 2, sensor_id: 100}"` ## Configuration of the sensors In order to use multiple sensors (maximum of up to eight sensors) with the node the sensors should be configured separately. @@ -148,9 +172,23 @@ value in decimal `3232238400` should be used. The call for such a service would be as follows: `ros2 service call /smart_radar/set_ip_address umrr_ros2_msgs/srv/SetIp "{value_ip: 3232238400, sensor_id: 100}"` -Note: For successfull execution of this call it is important that the sensor is restarted, the ip address in the +Note: For successful execution of this call it is important that the sensor is restarted, the ip address in the [`radar.template.yaml`](umrr_ros2_driver/param/radar.template.yaml) is updated and the driver is build again. +## Firmware download +All the smartmicro radar sensors have independent firmware which are updated every now and than. To keep the sensor updated a firmware download +needs to be performed. + +A ros2 `FirmwareDownload` service should be called to implement these mode changes. There are two inputs to a ros2 service call: +- `file_path`: the path where the firmware is located +- `sensor_id`: the id of the sensor to which the service call should be sent. + +The call for such a service would be as follows: +`ros2 service call /smart_radar/firmware_download umrr_ros2_msgs/srv/FirmwareDownload "{sensor_id: 100, file_path: '/path/to/firmware/file'}"` + +Note: The download could be performed only for one sensor at a time! +Important: The download requires that the transfer length of the interface is set to minimum 4k! + ## Sensor Service Responses The sensor services respond with certain value codes. The following is a lookup table for the possible responses: @@ -163,6 +201,13 @@ The sensor services respond with certain value codes. The following is a lookup 7 | Value out of minimal bounds 8 | Value out of maximal bounds +## Recorder plugin and custom CAN sender +A custom plugin for rviz to log the target list has been provided. A config file is available which adds this plugin to the rviz. WIth the plugin +it is now possible to view the target list data for the desired sensor. Along with logging the data the plugin also gives the possibility to record +the target list data, convert it into a csv format and save it. + +Separately, a python GUI is also provided with which it is possible to send custom CAN messages. + ## Development The dockerfile can be used to build and test the ros driver. diff --git a/smart_extract.sh b/smart_extract.sh index 0895494..6a2ac72 100755 --- a/smart_extract.sh +++ b/smart_extract.sh @@ -1,7 +1,7 @@ #!/bin/bash set -e -smart_pack=SmartAccessAutomotive_3_4_0.tgz +smart_pack=SmartAccessAutomotive_3_5_0.tgz URL_smartbinaries=https://www.smartmicro.com/fileadmin/media/Downloads/Automotive_Radar/Software/${smart_pack} cat << EOF diff --git a/smart_rviz_plugin/CMakeLists.txt b/smart_rviz_plugin/CMakeLists.txt new file mode 100644 index 0000000..3e20bc9 --- /dev/null +++ b/smart_rviz_plugin/CMakeLists.txt @@ -0,0 +1,101 @@ +cmake_minimum_required(VERSION 3.11) + +project(smart_rviz_plugin) + +# Default to C++17 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) + set(CMAKE_CXX_STANDARD_REQUIRED ON) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -Wnon-virtual-dtor -Woverloaded-virtual) +endif() + +add_definitions(-D_BUILD_DIR_PATH="${CMAKE_CURRENT_BINARY_DIR}") +add_definitions(-D_SRC_DIR_PATH="${CMAKE_CURRENT_SOURCE_DIR}") + +find_package(ament_cmake_auto REQUIRED) +find_package(umrr_ros2_msgs REQUIRED) +find_package(rviz_common REQUIRED) +find_package(rviz_default_plugins REQUIRED) +find_package(rviz_rendering REQUIRED) +find_package(Qt5 REQUIRED COMPONENTS Widgets Test) +find_package(pluginlib REQUIRED) +find_package(rclcpp REQUIRED) + + +set(CMAKE_AUTOMOC ON) + +set(smart_rviz_plugin_SRCS + src/smart_recorder.cpp + src/smart_services.cpp + src/smart_download.cpp +) + +set(smart_rviz_plugin_HDRS + include/smart_rviz_plugin/smart_recorder.hpp + include/smart_rviz_plugin/smart_services.hpp + include/smart_rviz_plugin/smart_download.hpp +) + +add_library(smart_rviz_plugin SHARED + ${smart_rviz_plugin_SRCS} + ${smart_rviz_plugin_HDRS} +) + +set(dependencies + umrr_ros2_msgs + pluginlib + Qt5 + rclcpp + rviz_common + rviz_default_plugins + rviz_ogre_vendor + rviz_rendering + std_msgs +) + +ament_target_dependencies(smart_rviz_plugin + ${dependencies} +) + +target_include_directories(smart_rviz_plugin PUBLIC + $ + $ + ${Qt5Widgets_INCLUDE_DIRS} +) + + +target_link_libraries(smart_rviz_plugin + rviz_common::rviz_common +) + + +target_compile_definitions(smart_rviz_plugin PRIVATE "RVIZ_DEFAULT_PLUGINS_BUILDING_LIBRARY") + +pluginlib_export_plugin_description_file(rviz_common plugins_description.xml) + +install( + TARGETS smart_rviz_plugin + EXPORT smart_rviz_plugin + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +install( + DIRECTORY include/ + DESTINATION include/ +) + +ament_export_targets(smart_rviz_plugin HAS_LIBRARY_TARGET) +ament_export_dependencies( + rclcpp + rviz_common + rviz_ogre_vendor + sensor_msgs + umrr_ros2_msgs +) + +ament_package() diff --git a/smart_rviz_plugin/config/images/can_sender.png b/smart_rviz_plugin/config/images/can_sender.png new file mode 100644 index 0000000000000000000000000000000000000000..c202ae8c0d67b3f1cd54010d63f06628cae32f46 GIT binary patch literal 23029 zcmc$`by!>7*EUE?3#C|bXpt5Q6nB?YC@w`>+}&M+v`}1&J1tIecY+5`ad)=_2m}jc z(&u^So8SA*cgd8&ffd%weGd82X&b?W2~Px}$}gr?HDUhNXj}y*Y=gsf)R} zgR7OJ8w?X9iGlGFLr&_QhF9j%vZoj6=SA=-?5HqBsVMll{F`4w5B8N_x;>K8kcy&z z)7BvK;4vv#)x(H~H$PuKeL}BKN<>TaQT5Y1mOy?SiB~xJ$I!Nb*WX@0(|Y*G)IaBN z$h`|X@4CvDA&~|gOVegxWgU|GFL}y1JgWTmzfR6ng4@IX5!qLT-3I?&&3~qD%til? zsD(8zA3gf7A4kwfKIkha2rN^^*q|nlSt!>#rh$H*i~P3((x2Qy%DFn-JpGww*(-G#c9DPS${d!)-=&Jda zn6`gg;go;UNV$zpfuy~1uE^r(Bf8boRNeB>Yp0p4#D@H8>-Q85)Uxdd<|*{_YFFZv ziLw+Zvy=rNN~RBi#4PJOM$(z9=8M0pD2RwK*zc39mW#Obb%k<$(zuZlG_Pp@opicF zH5RALW%K^eZ{2ap-v@PI?rVt!)>vxt?esxJ*4xg8pUV3qf_1loe6PCvH0lCPQP@jD zYf2vZyU_V8X%!Ar9oVO^#ol3_*jlTA2I*vZyfnTPZ2Dy<+Uu~?l}h+9qeqKzb!{5z%$%-g>~;cCKWr70R`Dp`5*SWTgEmkmv_J zq*JJdYtxYGT_iD7WGK4x@QRv$opJ7BIRdl61~Bk?vq&mZ`zQ$*CQ_LS?;*3O3}&fC42Ru z(%#;WNh__+kMyYZRXHsI*<%OPyaEKXet8LhIqpf zq0P-LCsCb|O1j<`CA_%FB161d|WG?&AZgTPDQ|w3fq^{o>dmFM=5z030V1M+K@qdzl{%4`FmHV zU^=c_-<}ZsO5n&!gR7TW4i7hbVro@fK7LO8d7q5P!i_uSSHocgYMRMQUuT$g>Ul$! zsYND=@m3S9S8Dmq>UU$m+@91Lt-W@be1R8mW9pI9`low?;yZ`LgGrreV>*b%r^jsj zx`qX_L2!|Sx@SCI1n>~)4U5&W#E#3;^;gUxj^?6$c;;^xMKzwBzC0eWj-g!`o0#qA zLB-Z(Qcd|qZD-J7c6yr-^|Y#NfZeJ>X0{Qx*pqqQN<)t*U(>F12@PBD*>=TJLv*qo zu2l1OF_*?`u#y;t)ad63Rp9J0{)P}{*V%ZDBJB1>p?sHAY!(^RS^#blkNJJ2cbRxo zgx`-%cXE06J!J+%OzME@Z3@7_G;U9$s;6k8!Jteir#i=Ta(OrEzP%ie)2j)FCLK+m zM_B8g_iLSk4pi)s&ozV7(#>rJ??uL-h`=DT( zVxir*&qml~%en6!ACT*VZ~nIQK!aT~edE==m+pkHs~K}f^4LbXH^8OaSyHsi{pR#f zP`kBiJE?z60$dY2^dL|9Aub1?qH#@yoT*45wB`9JPi4(d&UVN!kc+v}-xI>=I`7~K)NP&WU9 z-Z-$qT(kz|zj2Ms*Uxa#!sk{GFh=A*7I~_TVW~!a`gQnlJNlETIGo&c5i2XF3-N?S zuAr0jy^|iIK%3pzp6V6~U;1*;?Q#_t7IIFhn!+TIvw5#t8t(ougigTmPzl@uoj0)0 zQ(Sfs*J;#^k(7|1edV+D;(H;!S?`7d>9}Ssm&@xH?}|88y`D26^x3?Rvy7P9`M&bf zs!DnO?hQ<9J{W%p=-J+65=xvD`NJy^G)hJYScp#qq?dx^e@FwbPb zb|xDvPXSghm(CH`FTk2<`0i`@>uDW)Gv8yUD6t$9cZ+H$l{bZYAz@KA$D$k#=$X7s z$fp(;o*4Fwo`1Mpu&Geja%Z^*7gpnSwDut)!R%onrc6WL>sdrBohl7* zLJ|zi7J6rXIAMNusBsp)-r?!bOm${S~44#gVauJPF)-C~v3mObO~6ci-#} zi%h!c*CtJ#2@50TMFZsfB~HoxbOCj`n-eyS)P3vS$eXhFfYxV1%zaDL)U}4bpZ-E^ z{u4eVn`*U}G|~1PD2*=0AT&*K^`_32JnS(u4xku|D%;(C zSQ>mRCG!pN#U+82Z1LmFQ_#siHrxE+V$`?Gx|d7KIavCOsy>6%1Um~;NGR@Qv6ZN% z2PR)MjctbstkS=1c{LWuP^NJ-6`T%(S?De>8te&o2BzH0)H?SR+uDwN$aB~Y{h_ND zW@Ut1XHGhS(D!ZlGn92H^s?%s%0kF}>~;g^dGT)e`W$3P#lJ{Fk>VlF>o=VP3!l;n zftic)%^w!tb)*YKPGkF7d+mO5s3d!vBu1MLFY3`w-0HsF+W`7G%(F^XqY9Z zBVFua>-Pw<6FfWV#xK9huD67h6@=SqBY#zl2JQ=wUBWxW$a_RO|%(*Zpz2iCHmbEU8StijwJjLp-B}J0WcNjdD2z`b9 z7z4B)vaAPuH*`zDAo>xI`O)BjJvNJ3_Y8>Wy?~RzhMejNVn6tfhu$)FRB6sG(v|Djd z)_dRT6(0|^bamdX6fi@qhW zH$rlYa3WK~(mrfc9byfx5N06lb|YJVoe^%8F-GAXUTeyIEbL~ss6OCB%PM)-w>VA> z=b*adVeJmaupORfR;RtIJ2?44j_RU~PrCvWCJo!VTwwt{B5N6#52mi2-u%c`<*zvI z$wf7vNVZ%Vh+X=PMWxNt&Sk!zF60^?gG9#{D447ZTgZ~6&z|&lzBaxi%}zUgY^fL& zS7Yf?QQ;(j%4>G`WX4o=niT3S=#Gb)EfxF)CHIw|E?WF>5k}h-sbYvEtn_z()LMEM zkXC-kCw6VK|McF;cWmWPNSjy{9=R?Vy@K|f+wTWTHs*Gk6GG}#7t;OF6w3rjd5iYV zPj8XEF{rHiVa?M}+el+6sVzf!w9_n0WKmcc7w;}n&w-KgfVrZ+N#*(*neBa{Qsu;z z#_=#NyyfhK%Qh8YOP+)D%8cxIz)7Jn_%!j97Xv%A!C}+O;`6Tf1@0n&h!ydEh)mj9 zVvWr1G`R=*9=Br@j5zJ-wKbMT9HKk%q~Ye(U- zt)9!G_tbj9vW=f~-0cPuM_+L1JkL&JuV!P0OGoNN*^@~HVM~AFJtiL9Hd@<+C8*9Z z=WN>{g?tegaylM_c|I_nsB@0!K1GY+35ZDCRJ0khQT5s`EHe0Yl-f4Sp*aRt*LY?1 zD^X7r^n1u-W9Mx@x6^h6>ufp@O7}KHl>SL(8g9hHf`6y1EJ$T?AD5(t)O!4jR<=C23_ddl%Mz39k+(*VP#I3-Ew!&$x zp=-`!iTI7$U*GC`nk9krUQ~j#F?reci%*~{J4F9Zz1~PTU+IavCzt`EoNxtAq70#H z%DKI9&-Z7clb<>68n9L>k=&up)(4*D2D07e7wp#=hM8{Jx!;47WmYr~Gdw1aDMSZu z;FcFH$I0@AI5ocy8glC&u(+BeJX^pLM%TQ~k{-a3D&Hr_BhJ@CCxGm>S}tYmGUV9FPm`9{k-j#?dHU+l*SV1t z(OBBGPZ4rt09^BfnO~{qp8aabKRQz^wvQDj2xtbhT3|X!Zg-a-<4I2PRBv^w^^F6U zO>E`CO!s9d-qU!`>c>vBhNCa|#MDvY((_P{9PA!K(1^5!{L>Pqe3;f)#PS`b&L|Bg zGZ>^d)F{VPC^K|zG7nzG#$6NkNM+b(N-AR-1SoB0Giy50SHdYYed#KfcI@sDbx*3l z@_oC2T<(^TF*`M_b{CVW?@?vi)Ad4)z;et2@>)+0`2%Gx+jt9S9g>Ee-yK|zWk=S*2%?Xk6V3!0*+?jhPY2EgEdo9J4d2}FRr;I zbfZ$-#xtH!@4k~>x|8H$I?=D87{8yNfl-nB>LS|q(r?NFZtIUeZu}Mz zfkuJ$Gi9>D#Q)r-y4Qk!!a4f(v_I2}f~%5M&bl@nkSCjTy-cE~1RM%x$8Xxc5az8; zEg!9rh1Oc|u)m_AM9jU5xXYA1J@~d&Y`<*7>!e80=85di3CP*7^ASI_#=r_`#fD<7 ziT8i&VM+bruQlvpyoV{H)eMo7EzxKgneR4SolTqE_6wOgY3sJQUQ6&cZb(a3Ove$vthL#PEa}$stc-!Q>g{a%?L2j)*9q4) z6PkSi#(ajTI4L;!{hSUmG_6w8biWZOym|hr%1eYkUUIjYupu5gbZgb_@?w&okKjEX zVT5MI$NC7Muqk;@GO+uV9~@RVzSs;%q;-WPKTbHNjdIRuBzx<%U|hN z+LI9dD0Sge=4O{aDGV~?rIp^HvzQ#L=DFj%krx|y15N12%-L+#m^5 zEE^M^5aW^FCxw#B*-nI*kSZH~m>!4B3z^6nDdp9%nLgaPac^M(KV-=Y97VYZ-?(Ql zIGCs~b+mEY&w}Idr2zzeAw0~T+Jco=5vJv>s@=rW2|$_gM=$Rv3{Xhi9ndwat!;Fk zpB#X`6>ocxQ`=8i_;i%C(4Q)0m+H{gS>Sf#?WPAmq7j1t5g?LN@WNxeO}vvYSo%(P zqVfCV)sSPW4b)>>VonOA%8tryRK?`2>W)h(2A+yuW z{&QI(%vss;EoshJy~AL(&F|m59cngXb1~Knr6CarIEnEaX));2@P_KA&1SEn|>nZkXwv*f4zbq zDPvt^rj$*Gwl^0r=|imPH=0W!*!!=u#79<+0X6;?PYHxO?{`DRZ)BhMgdl#IUrapm z5|vYk*p)hZg}Cp?K0aldBdB%XbiA64_-Xc2Xy*KN3~Y5wXn4hRCl|!4Ad=7 z%Zm~!W~d*=T1!su{GlH}Wchgahd@+2j8x17YqH%NUw#p9jCOvokPODRnWxmdQZ*c< zzf9rJ?~u`Kx8nR2RgQvh*xsuLnBNI8@3{h<**oy97JGBJW?mc8?>rs^KrH%iV#H^e zxM9*Ega#{V!G1oX``XO+35aUz(T+@eB{A#$uPNU$QiN#VK3@~Aiz>pVDZFg=oV=Jx zPsF|Gl9lK=1znzk398)#*gyzZmf9k>Tv zdmmQgZnvlPRupi-2PRVZ=&FdX*Tf}@Ngs|q+92W8X-N#=jQPNpc9Tx{m&~)+=KX#R ze5*suOn7W^7{chw?Z^RCAM`|}m;#!<7h&Cv9tXklT_@iRh2EIR0ThtoS_DVSV0(6qeiARn9Fw=0eODDOFWfZ@Sfqh=`g8@sK((MtTZj ziw&^dEp6rw^NfkzF#?S<0jK*rA|5}3U5eWzAn{+9^#NYNXgx2m%U1{|MFBk}K_$f$=n&ysLHLTD`0hK$MUnKId?J(4 zW+*JNXQ**kTq|>Jcz@XUvw_E7D=xJ~*Euu~5IP;@axYdZ6z&q_8gXS7xw<9vax%DCGmusFM3*N`SE_F-rMir z&qUWUe|@L_;(JT}(x!ifrB~yBP`f7ojNmT~{FLV}Pxp@mr~VCP{tCJ`4grA+i`|$1 z_0_f6(L()j+q~Sr)Nq*Wy%kHx|25D2|L%Vk{}1|l$D@|y*}vmqv7={TaP)Y(TT;c< zJ5y;GP^4;S7{?x?OR8CQ`ZQdGLYIQ`^%!_WyE(Ba^nSceIwTl1Slm+j4|M~yE z8W|(pcz8Vnv$p>SH~t?BSY7(&C<`gEtDI|dZoDH2{v6`$vT+-mDhZSbtwa=5a6@WL zR}#)`C*yRcOV!G+g*#M051hB?WAY5)XZlJdlpB$a9GMH_D%=6P%^6wA1NbJpTQe%D z;v34MLXNV>#cvLlCSq0yqs(VCfg-j$4goP2dFiSgHKH_zDshC5XSS1P#_=cxW2j0|FYiU8`>bw$ zu-cfZubT>KeF(>HzyCtkQO?9emCX(3;i_bdxmjz@237wdm1`EzVa{s(o1YoGY1FGo zqDcyYpDUeT5*rLwSF%FMd5t%oPuzkAfcnGhn^cP4%j75h3isc3Timt_Hb=dVw!Qf; z=7)1r`du||8Jh06QzRMdUrOC8ja6^n$#^-PF{!cE7hFojsxvHM;e^hg9^2fDZ8#8& zYC&8_mmr{S#j6l=!>s=Bgb$_3a5#gz)t2}E3XM$4=?oHRE&4j}P*6%|cpRQqw5QeG zndXt)G>0}?%e*W8Zm(Q3B>NZDvDGJq0%o1Jjab0P3Cxp?OTmz~b@lM)^I&65Fm5y( zJ;m_7wz9|=f(&-Lnqqn-;mnCEJw+dD{E-t}PVCun_E4g`Hku_wh%9gE)uG0L`QjVE zb`dgh^#TGzNRD3|FKGn;@->sPlJp`&W&dmbF{o65eX zfD3v9n_a@UyVA7OWfyNC%C`WYwz;3&sKD?oCkMDKa&=3o$vtzRD4|uAX>m2U;x6Rm zPYfAyExUb>KU^1-h+->n8SFIr!i9Qz1f!}NyoWnj6shfGuDR3DcuvZ&5S#2fm>T^d-GvopA6f41D{mR1U^U*auRiY zF?PqB0)|;Bm7n#UT%PrU%-k3H+WI_;Y8>B*u1csTDM8kh7*{3<&u^w-jX!7XK!8c$@Qd2~uALte6_@hyNLbM>Z%by^ zeG(V%Spkvao5qNgMeI+zKfDz!xqBol`+8%g)gbtILILlWUwYpzE(Jhzseem;UFVXJ zV}woG=?f>#LVpt3-)ows2jPyhJOO-L2mF@}cN@93wu!`mKyR@>T98lZf8gO;TDXBwT z_#RbEZnitsVK~=>qO??c!mS6HbY7Fda`R8B<;kgXlZrlU%tt&ObD&iTMR1*HPCb)u zzkBHZVN#^Qme24=QZW~&D@5+>7eGY)7qbfDjJqIqSw zaO{}*R;{1+{Y9mBUVN|wTxQ~Oe344^+H(hi*Y9*>4j$83qR$H(xz{y&q+Tw~GU6Cu zsrhv3jN>QGOBaTM`yo#NhC>tHhr2Y}r&BlK|-sU2@jP2V!1j<*TDEQxN z0dCHWKC%g;EKW;dr@-*mH27*!aZWu`y|aR-dHWdEuo?xNpSwz{T5*#J4&(Vcl-!0);L(X;e>lGLyB!E5Lwn-;5)uT zp5ib48Dyg8A8BuX3MNq8#cpLwoH+Npimrs~8a)%y#Mga-_q10wmVtBd`=Rq)#emXI zRP44E?^OzGFh~J3L4c^#=@$fALnA6ei`JDR9qe%oYSYmS7O@|YlEU5eYW)1Zi(gAJ zym9wlxs^!3VU3QKtxui|JldSFSv2vW(Kl9K`mK8|oli2;Xzm*dGnexsMn$0e!*(60 z#mXgokHX;r8Z-qvutft=$0-b?s zj+{HuQg^7OdixyY-|}7m!LfIf{u61az=s%2_Vjxe8CLMgV4|^xE4G!?<{L+455Mev zm}9|V@l8`}deA0D^gmt;*&wo_&zErbtC9AphiqE#&w@S zaWY(DITS=7`ZJd--rr=ha$lpZlG**N<jSec717_p;x49 zm-ljy{JPQQ`p-mlDA{lTn2P9w+s+_Q4%4!gp&d&O=WQlKJB%JlyqQ~|NEdQ(^A)(O zWI3JX7>`;k(rZV?=tGrgO+6Cq2;Gj9E6HCiP57`vlmaqWxTe6P+o$h0BL*1fJ-O>O zF$*p3XREH%8m6BxNi6<=<9^i>+3AwsHt;J!LD_t3ZiH!W$iOZhBsuJ;jFY`^{?=X_ zN`0ILmZhDk4{BFn&k5EP2 zmHPC#7G9?@=%_w-?7Q&B5dmWCNG8kE6<`g9st57Sa}M+R-krK%jB=A)-CVyDKQn*R z9t!CDP(MtxvHQ*0gay?M^Hbvk?RTb8f~i`A>mO4{xxzif=$d~g28uW#nJ{dlADT&2;8joj1lefO|B(;U2eP?{pv8-ty(^-twC zX|_&V6sBLuvnmH7!+y>670LSMDT%9*{71yphr{yKgy(4m!sn!nJ+PIpKEhM*AJ zG&H?yE1Qv%wG6)$(C13y+Ttsla>KwjOI>ufmKN3CdUg$`d%4*ewk3CV#D9^rp)}89^fw5=5NhudaR%Mt-cG^0H%`l#$9>RlXGwPRWtuwf*>8 z#>WKZj@^3vEV=&9f?6y95J;pNE$fGhLF#(V>?HfFlwEn#tY$(#Ud9baOO+toe91zo z38?vCKTk)NAav&QXMpC*^#O$#q2zc8$`waJObSIy?ahT*#}_rO{b!>g`oey?YA|VJ z7az^sF_RWMm1zSSDf`KODDe3{sZ@=8PN}T(fej@-!m~0)53TQp_2>vpa<{E zEPcar%K*f@I|z%v^muILbIuujUcuA-1H6saZqzy;QY?TST~LwIwk^1(_=<74b9E=h zJ|O>eu_ozg5Taig{dU34{u|_1!3c_J|9$FR&dIot2dfA4y}KWC5>l7)*OG^$<51>Z zx{!fZ*ZTPqz9O*)yXCP1_Ui!1gaFv7@)E-lk~O?^1aLLjh5p70sL&fDxGi}2z)KDI z2eXd5!+Zy*d*-=uToXSJABVTqGG_5gU`-sPcj!REm;Fy0qcZPp1QqUUp3N6ae#5GW z{TqLrfu~Kg6<4BfC-RW5lG~7YbdK&t-Z^85Bb#A=PD&MmY{(J5)#>{47WY{)9Y)h% zunP`mi|VE?sPRCeQ!)Xsf39wg(ZcdvC-FU?jmevWK*hEAy>Pza8UrJEB(p3>l~S(BxH`t+q) zcVL?D{F&TBlDsA4V3xA}M0SjECt2;>=Uh^<_0pcULntj3DEdia?%mS8;kAXKcL-oP zT8(@b-p1nD*O+MfCsKvG=M)HuE=dQTMHBW1o)AI=8@W$CYilkw6}Ru(vxIgdCdzw~ud*{QI(TeLi z+vl&dgW;r4=xp%PyDaMg+o0N%Dkz8~jUp$o5A=x4R>*Ro?j4?0eDA{gq1+R@50!$= zkvjA9ps`-gd2wRU{50yfDq?1VN;5{VwTbi43LZ+_?CO$>#8eDiQ)qiP>xTsEb? z=c80NI)EF`V(HF$0=09n_BMiKU4m6{;Fw)&=Aqw~g1D~u1Zh_k7gEmoj;j9|T z6wY0vXHypJsH}5Qhzc;wqq1;K|2Gp27GM}NCe#~#b4-S=mh79Ww@q>QpeI{y2+B@P zP0h#(82}jA*|CR*d+Qg`Ybuz=hS}aXo5m(=M$)b|oH~m)xjo?V)^9~|ovBbZa$es4 zL{=#N3sGl7T)e#TXyQ<>5g9d-q)_PX&gf%jSN2690?l}m;uCBT9GRiMag6xelF*hj zPn33pKxpQd<>|llD(PbjYD4kaoa)tP)!Z=*Ch_I8Pkur9VFRGRf9Ta8xt&i6R)L^# zn8ofZdivR{|3SKD9NAQsLzIL4UQxVw0Yp=rKj>xA<0chEojWW1J2o_la?QL|)VlFs zHM)8Q0|NsYS>4|0)&IrvHp{nq9JkD~WLh@Q`z6v#qsVq)_51T84}>gwv(OiU|B{8AD89DV=yT=?Uy zqnPF>E5m3L|COth-yhG_Bj+>XbFvkc+h%dNdO8PAHde2i4)6y7$t5&2_+t?T)OHyw_&n_$A9u4gt4 ziq=5^{-W-c;Hos0$sw-82e=QW>8o}ap!kD?o;H1omWsD;qwHdJ6jlQ*I~G_fHdr0H z`pD4qe796^`vCr~5#%V`ms&SLb=Z=(CRyyyw=?F$KO4t#zDP4RlWusmSHD^y*0Rqe z^V~q*w^C=vPySkOzHp^W`pL&>hG@nvT+8zPUzS9_~1dGcWUZ`;E*=Gxk;lggwIyDDqeiy3rf2>b(nNoN1@75WAdPpjVIuT+} zV>eXyA)Er&9P zw8=;2^s9pLt6-+HD{f0R8ovTx%t4sqp~tbBQm=_-G!Rh9u%KdUg+2ZFhU_0i{&>oY zU_Sl`f)Cl7_0#4>;Js%B%^Z*KQ`th z62=`-a?#_%+JgK3E%gq{rJSC87Gv^Eb!Wn>V|mMPUqM@HLj1jVx5=Z{i>{RF%!IG6 zX8YJzj|b*URKstXqH{lNn|%LRw>uarwpQ&*^Mb%~EH4A6H;3o6YW`#nkgzw=r9oNs zmBjzS93C@{vn8j*rau*w@ww~lo?P2Sm)aMuyRX&y;#U?E$8~fa@#@+NkM*K~m}kRr z{UKo6PwebbRb@HE9I15@m&bQ{_W$!7h)i5;HfQZzXDobC#d<=CH5hIOFR^dg4|?;!78G!Zjtq#_%@$AP68^cxF609mIyN^f}Efu7*3are^z6^ zz62~q_4+!5zB5X39yxGX{}D4jK2i=4H(-;nz>_puK8iWM@9JBse}Ak4|@ zOQlm|$#xO5`+`P{9-(P@_3O}YKt$_jDy+5M9|EKHb5HQNWtC)Ka`?W46RzNVrMe}+ zDSWK^sk5Fdizm=(GEd+^ZA$I&rCagZzR%K&^8am-4I))`|^sJw0@0 zibYXlPJzhe758h(QurgVvhXY6*tD{94&NFl!amqt=4FmukmgR0HMY`NdW!#`dGp6- zRO>N*s}A=y3C_zBMyrh(?F1?ZpII_u4`;b7L}^k(9!K^ywKP3W%=xPgVM~-P{RR=w zg5q=+KY?qagW&-T0$^7HYVDM~D=&Z|0O}4=`I`uodKzzW zR3KaZr8x)Z1K{ONpM#sy^U*&sKjz{IPwt9v<(@ZvM?aJC6(}KEhhu^Ot6y!6S)WJC zn%)K$d0q9GdQmnYr3%j4RmKB!=$KaB0S!Fu{}{WKo5-+NlluYnt3){+Y2!*E)uqma zI#cW_sX*#Q&5^BR^P*zJ9wk;L3^Ls`D+2f@<;U`g^{Bv#=b`oOkm$^p=fiNmY|B4& z38~+|YiD1Q>s4h41{ntcv#i zhI8qwSQEggLy!Yb++A>*E_zzF&Tsc6zVb`k=+&jN^Vs<>uOy}=k!}5KU@_JGbr?_| zPV#pQKOUN+lb&n7DZ^tra!ABeepuUWTW0cBPL7_x4ar{lmE*9 zqYUeRWIEB{n*TL(nJ0zlxKwon@&ct+ALehv15`hoOc)Hm6kRu`q!jUA3isKuJi3ko z-ko9Is^pcdXN!TN=wOQ!@xDpNq?*oTjcXfd4@Gu;^Kasm<>^R*0@aE)cjQCtGvtvR z>8eod=_d9c5pMzA!n!U1Agg88bZ(@`dOPLfYw%YaA}u)4Wyn^jSiMOhU!mVi=?0nd z0>>^s!~g8s7+tl#72;ZDiI9?vDIYA}=A+UcrrCRYo#1YDig+#QUqi;Teyt^L%JMGA zp?#mkZfm>~Z8F~g*hxz%lyW2)2iST_ZU38{;pj`r1$zf7IZ8+sEfnCKBl^G8uyR0s zesJA;WIJxm)uxVLy8Seea<*GpnUnvLcd@29?=oA$w?ZbP+DSPq#1Cn0l~VR`>L^8$MI1HyJfK{HoL6D)Vsu3xny@iqFc;_6#}i+X z(B`^$JxQJf)mUxtNqH)4FDm5~Cmko4W@~pVz$6AoJ}!FA-r%Z3p*sX~41EPT zU6`ZQ7}4=Ov{`zQM8~u*S0v&+aomlUyB?xq^ipyLS*Nbo_jxHWk`28pgTw#ouk%s% z;9estzkhF=J;M#KtRqzPIi;0~&ytZu$2-$;cO2?1nIRApigo_eZ+NHfSR|?>0h<_k zXp#)`*gBdj?)5`+{l8pzy6G3-TRk)^8cv_t} zAPl>Zgzrs!DcQ~-yi4NfX4~`ED>p_gr78ZMbDXrkeES{?gocA9Wd#o_`r98|o6DN^ zYzn*~CzsZmQ3)qkT*$sf_*XRi&vSUfBT|2A+aO}g*Abvm@j_nPd04VE$v?H;G0Oa` z&E0M>Ah1_MtZ?#O3q$56b5@++{X#2NJ*(jrNK=dQ!O@mRCdrVYu%`t^(=G8HOy+GI zorAQAWMj|Es$pRZ_vRB>@Sc^8_Te9UsF@`7bT|=Ng(UQ1m@883LfU_zm$Qq);u*)i zl*WjJ-=2+F-)A(L+th?!U$xZYsucQOIb_MCFuO4+Zu^o+l354M34*;dum5RO7@=0*XHjdG9n$UT5pMo#Ed+^WVHRv~he={fv@0 zYT7%{lsWTRCRp*y4Y{OtQ|QK}|JbccLl+x-y)KB!a#R7dRkK7N7Ucx)a1;udA8dls zR>2lW4MLeOekYECFAgdAvIrD=0{cw#^p_qE{R;&Sc>1PjhjLdVb#+$7A-;h zBJM<7cyxoC`0uIga0=vyTPg1>@HV08IiRXv%igZjz&YuT&hJ1;rg;!CM<~Q}$ko2- zK>hKI({n+#K~1(53nZ{e*z)F6n>-0L^NbTBF@=Zn?QO64*9VsU#_Msskd#vz^6_c( z#o;Uo35jd%9gvcYR7LR2+~0r{Eu{ZZjq<-P=lSno^N-1s`sb-o zwYOu?)ZsA1^qZaC=ztO(DL{Q{JInR{;8rg%>x36CiW&fwl7RCeeEZw|ufN?DjZZm2 zvJCrUFOPBMI)?t!Ejw{;MMs>Zk9P(O@L=MpAHQLG`y*aQz%syBrjcaL@|Jn6lkI$t?WR4F= zPY0ecn>tI2D%&P-`-vPBt@8pB(*foqQcrx@v#S$-zH3}L#}PcUT0@)6L^|?_>BvHr z9OA8{_38TmW@nN&6vj8jy9yg=bJdS09{B)G*|d|$J=+H;0>mIf&PUoKduV!&D_2<1 z(b0~vblm5p)K2(dVCF~As$p@g<=*nhl^fo&ZA$m*a0;>e4bKHwYNX6!2WO^oIV8`9 zfBAQ-rR3hnAlfXJjFxaNL8k2hT}3gLL2F^I>&!@JM>GF__P$GxHQK===gW4FtuGut zf20#dJ)9}@+eGY=;su3oZ%bC}F zs#8OVK^_SEdckG3*-ox~o9$gNi|6Hf_^Zl^jUwkMXUwD9xq2a*#^;}l*RT+^;rYPZ zO)?_6?*d8ft%MsdS;53UDf#7=X5Z<8NG4D5qH}xVcD?NF2w5%4Tipeq(L;m@=lPSF z;`<)PSmRDT%-qlDZ2kXxF#1=2g*_l<=ZgVqrsponN-a4K&tQd4@g3Ts&+vHag_;_C7UJ8WSCRpRE&k9qEBX zdeY!~77tG?6~*lY#SxI#EpFUoSnO-x4KW0J>++YfacbJV4cM;C~Gp$nU)8PEC}`UdasB!90T5&{HB@Qf4NLFcAB6(AQ^D1AEcAS zg~9R{A|vgy0%5nE8o zF6N*&?5QT*<;`|VUzQI8z|16N4VN#BJb<2cCtK33{{IwZY`ngovZhYvjtDkzsFvql zjoFty&rtS>@=N=8{F`XUw6FQjy#-$@eA#%%%DxG>mVM{&Ipl$`vze0X3&Dq&cxoiX zvbb~u$RN*$M*STh0HT+a4Q(91Ydyik=|2$fswPo>GG@xe=7*cZzVzV~2-v-2UR+DMc3OCsP`guL=%VdF zBqiNsijHzXM`n7Sgmah27L`2-KA(qnHg7H>)0D9bjk`>EDmWb;Z2t=dLLn8^Xo!8e zH6u7xZD+cUT$LR?&BT7AlDm3Km@v4+DqjJ=LsP?TokPjFp8*)L!H=-%d9`)BT^+qu(9i z`1id4DJygs7*(uk)t1p}^ZTiKPRMd9ukoKp0+w1atM;}0Ik(E$pv#I8k@F6{Hrt?l z|4O{QMOL9zXLG3J)&cb&<97xxfEFFMwU?7Wr`k9_Po9cd?))shgfIrh%E4FLHBHZPG3FFT#*ElESbK<`BJ{isR@pBL0*CNx zKIdGVZC$B~T=rXE7cU7Pi`u7rsGv@Ohalu?MW^o6ZZR=1zLZRS$00eWv7vmrnP!RkWRjUA40p+=(#F3J71Q4W-X}e)x2|~xp(<}pmjNX z$W`KFt<^GR*aC_LJ@-4T7||bdKKNY<{auQSL8{U|y^K+YGo(&85DuhH1M1MG!yReU zJQ5rr&AYUj5<8Od6qQFA7Vh)bcLpNH=KouvXNsnYTBVKYz3exmCIMN+eh~t z>N-c$L->tKJ)+U-n)>dV`uZ3@Wgh{x_J70sM*$-=39Z{@&Uvo#mp5`)W}77vHJimh znm41e_{@Stm&Dbp9U7?X3=xj{H_Vtex}J;|DG_Cpwnm86fMsMYL5gE$%fau~gM)_{ zA2+`E&WH=BpJmvFT3m7nDh^9WPx!Wv)^4svo?WflNYbd?^>gtaojll|{-vKTWRtja z=sw0NV~}l$GH9QR`3*0^1r`}+^tjx$TUx?6W>jkH)6JG?v3Gu>(z4ESjkj66cfvK* z+pjzEZglQc4D{G^p|vs{q9`G6WV47nAlc>f&ZvG|I@i*d;TE=900xFp0iP)(y+E8# z#V;V`$a}f$$ZIHU39&gkiOg#}Tbj$+Etypr{)+$nwcPJjZ-D^2D!-TxBP&sdDi78| zlq2+d{REGi9{{=^)!y%zV=h8=`88kl^YPwfYw{JIT{fRp-MQY3r&xkh#^hps5mX2ry7qS6FjUK`P*{3z$cCFe$U>98Gcb=kS*0|K zCw$X}wCa_dHyihBtS@h^xls_o-BpB4m0U<>yknnM*i7b_Y^vehocgS}{8^I%;|(z% zqD=KSbIe$kDk_EZe{0uVqmoS9Jx<%5zB88Yc{|Na9%jlkQ)5!mK{Tdu%rp;^W>%g$ zDC7xBLq$ZJv8EdHP>3cTs5~H=Vd5cFq{hkwf%2>fG%2E@kRYH4_%eHcc=w0B-@QNV zwf9cGA^1-_ya!;|Z?aQX{@2Gdq?$Mr2ZR zbg@=+PX`z1e$o-eZ2U*n+?J_k)TFhiTPUIZm?9()#$J7&2cIf^sPE*(er&!=Q;nL) z-xzhkURG_DH{KQcZ)~$>w)%8@I@~VxpOalQl`qCewFL3n}ytpBN{tDiSrfYjXTRf9H96Q@OPkwT#95v}Ef#GRu%89PH_aM*&{ADeT6eDg;jw~aL zJ$dsW*V;b}g}(i+Ryhk z@-bFh1gQn)FCd2CTJ?4=XG~)T`04b!X+pGXN5wn$M66u?Gox5>el1Vf5}@>mrJ5;2 zLGc#^4a`1?6n8R^aNoUgcU?G%GJ0O85#tjZLJx-3JbKicg$h5B0{}c{p3nD6ED9Ob zX9`#9GeGJ5wVMMm7a~v%yPPV4Ty8h|e^Au^6te##A^Qg!_h;$fEB>F|`2W$3)BkF< zKE>GuNAsNwFZJ>E+E2FG7Kf*AGhBSff40M5T>+m4G@Aeb*ZyhS;wAv#!SjE{81C)= z=7rV&cImNT0RgxM3MU0so=P{}KJfDPw(xXQz(=HSv&p%(zYft1r z%E?~!A7L(j4p=o0MWWmRjg#X~FD8Nzs~>+a`}WEQf2r~5>=CqDic5WSOFVR`D>r2& zN6q{te|FYd)>8&Oyb)lPi8yDB1hFvMTS|6FjJ0uJa3u7~6Pz1g_ zZY&Bu^X{ezOf6*StB*WFYtSVw%o} z*kr00r}WLV8m+?`rBOqvH?gVA`@2dtNo+2!@Xo+HOcK$GkE!E6|C+W^DuW$qg61fP z;<#Qz*@NC+Y>0hW842=2yVv5iHVy1YBFr8u^=bqE607GG&bB;Uhm|&UiW6fbB?7GR zOhjKHQ#MQ;*Zl$SdC5U{)sU`u>|PpSgsd|!Pt*v znwm}!S*V{9?A4-2Cqk*bS8DMX17i#IipO=Us=o%$lW-T>po!NrEr;mGryVn-ofWBy zp|v3)R71*9i+kJ-^jSDNPS37zit;Gjz_Efi`s8R%VS&fNu?_T#zg|qN6A<&BWV-V< z#)1{A)IxFH#WAi!ctwS2)#_K)zQPokCkj#Exm2J{R#ZEu4BU@A-0Can{BUPV4qK{D zh$DG9U#2odcb6I5-)zWeU|~MS-pOPOb2NV;W6Ma+KyZ+!Q+kgODnfSR_eoDyhB^ zMjCd*m@~eiRHg*IF7P}!?R%=uud86bU8MS=S@!h=h5O4H2fqYc@lV$LBIskx57};- zl@+axE3z%HZ`eSD2rI=^GkR8sYecKCVQb2BbT3r~v)&jQU*M5u->)0T4P4y7p>^xE zCzO!2SHV^T#T2Z&Ix6#|TT{S2!94Bvsm1iSa{-j(jU7wW_2{V7C4Xxfb&&>&=bjTLfNoPtu=Dt}d)#1>ZJ%d||^S|Vzx58Dt=NfKh0S9(r$ zB88B^Iz~mQ=R+ds2l`gV-OtjYm3Fc(@p(Z|kKFc41a%c1B(|mpn{{dMS@&(Md+v*) zql;8VssQyX_-_)_n;=M1abYwTjC53eTnmv{&5xXaD&gZLalJ|h=X562xzX01iv|IM z_QMsMj0UrxcIkGfO*moQHB*FZar@(Rn~a81XMrx#8xw1cn|)&CR`r|bQY94HTGIDp zf&k2SYv81Y6H8dK)wpPaEB3Z%(?$a3UaSCumUp_Oj6aWRNtRj73+NG<7OoyhPL4ZL zCz>WYiNFjlYa5QE)66>LS*Fkf)7hM*UF*PCDSve8)xUKLehL;AUNbV;RMP$Psf3cY z2=`-a{Iaq(i|L)@OM{+)rObc9vkA3+Fmdk0&Pl4VJ&2jfUxzWISZd5YLK#rBaIugR zjOg~5Hv1fB)BuY;8io>BV9#aVIkP|qg^?4c_E|fosWZq&dR-$g{DiUJQEM|2Mh*(8 z(j77E3|neXgx@YaM@CJypXrgz>{!ykDai*}wQ50;hQh!H8b_6|9Tc>En?ckB^p>ri zhCpbn<^{-o_9us6_WiQ3`0*zgV+*}b`~FrFHBH1Ak0#(rT<9JBQIgwX9|!s8M&wb(P5hXU}lJhfQ6k*`@NC zN+_qcw6chnY|RS8v_-2_ddkehKKdnm3e%H;Uj3TBU zVcnk)!ztf>y^H=dtLO!s!rP4(F)V99rKCj2cCipQAYGjgx$!8)w%#lTSm1p1N_*jF)(@{7pZ2;dy1tnuk*Uu9YEPf@(b& zY!`@rUlzT#3y z<=t!vaA0?#c0Zi2j2=C!eS5&2lig=Fzzyzkwli}O&FDI7Css;R#2_{7Y~HUmk3LMB z8pWt+CV&#ZW_Z3!*6K$f5Hc6A?0xw8`y!2aNkLw2STcfYRuu3B0D*zB|3^!`p_R??R!uY>M<+7-kz zRl8RE8%7~mtcfpIwp=MSgzxWFthF-x+A!f~wD_4F;Ejcc^XY5du4fq$#ujTraJ#09 z2HR(mkX-n1xFIz&Tj`EoQ5{cRpNU^oL!0=hL3YjXIb018Ta3-3=atGFV z4(RuqL`4z~Im7fCReUr|!BzwIJQ(%IZw*zddT9%SMuob}dSBpJASt=0(&3;rL7#}( zV+D9@_OsXaqx2Qe>E-UU*9%gk)72m;zM9hG;!BYp23!lKT{QbIxM?7CdDH2p*9Dec zoe>7mYW*XvXEt_yVp#S7VK{yM0l)nBN_e-adT;a%b<2l8NbVXaH2#$!T1FA6{Fub+ z3b~yS=)Z6r%Q%Lfw*gN4flz!${NnLiF46(t^L{-f#9t4s)}Q;T`qubm!+L<9PtXrf JzCZW#-vE0F0Gt2- literal 0 HcmV?d00001 diff --git a/smart_rviz_plugin/config/images/recorder_rviz.png b/smart_rviz_plugin/config/images/recorder_rviz.png new file mode 100644 index 0000000000000000000000000000000000000000..dd45f9159ddb9e0d71660fb4e6fde8f7e5cca783 GIT binary patch literal 180236 zcmbSyWmKHI)-V(+rG*xET3m{|m*Vd3?(Xhx#T^P1cXx-up}4#200RSqew_2(cb$9h z>ig%*de%IdBs*dCYj9g@zbBu zF#MQ0fnV64($EJ9JIp`9#98%yc}-=8f9?{x8yy3~*vR=K@gEb^emU|tp+BWvcruR2 zKVc%)mMuSp-HCTWGk{ z)7k?Dine%dp*-^>%-y7an5Z}sXnFL%gWPSN?MPOx_Mp@1W;AvT)|?(VzNBCjBuwTL z8S6m8e<|$`R-H-wbp2eBk|}6D@+azE6>}Qd*fVDrXkNIvZ4#tS#Uy^+g(Bx)7WEN4 z)TfY0cJ=YoUq=bFJdm}c2K@Y%pUpyb9L39*4x#|pIX^kwdtDG(>c0Fa;EmXcABcH!qZJrvgw-s(O_wFJgB*{4yy)yJb=4E;L(Qmxu2>SkC(HYw{sK z_o%bqF&OK6{Rv}Yhd|C9VJ4Drf_&=DlrreLms;a$D<0oUJjsRDf*~Sov324k_tOE0 zRhyn~^_PNPDql^HhLKRnh>Xv27OdaXBEq$$Qd;$oZw?RyRE0eFERo8s*gJF@ot5E$ z1McZ&56*~?UGnb9obKPXEQf5-KpA!5VuZl;dBOV=wXEu&-`)iFy|rZzGWIlNoQ|IO zY;mCZ-b_6$&mCq61N(c;NVJ>%oIDd(9!kR5s>=SYt#DGFJL3B>*^*^hMw6#6l?83d zSqV8^GO;cninVwWd7z(RcWJ&CkgugypMSPLB6|C$g$vv5q0#Pk6&Vaw;&}g}M5aHA1jv0IjJD8ylRa_@)X`$gJ|J{0{ z1U@JiDy#G!&T#XaRH4hWE$b4ycOlajRG6e~%JIrsKhxdTEP7Y()A%8n7mdTyj@|^T z3Lz`nXEG{M7vun`+4cm%Yj-`s!dpiRODd18M`Zihw06oqXKQx{Zn@)rFiDt+NA3SNj9n^^|+_2@r=f&`Skma zuw~i?VCM?~bYQV`+fXKaEXw3_Yfli!FW zMXl))w#c&)0GFt*g`{n<-I(Yg-a)~+UyN(7g?V6MWUhFWlmkJrrk%fVL&lLB0F^Rp ziEcO|&~NB`;rZYV2J%OD$oNF{;i+}4NNn!VQrU9%mEdt>YeYxzNvbu0uqGC1;^~w2 z@g4Sh2Q#}ToQbNddS((Yqzv0$!m<`O`1UI{rqh95mQ3bYM3ww+gdeWd4l!hMS{=Ma zsE8%FYtIJ>9z8JLd8|LokMqsByQ^8MIOzjh>w_x;Dr9Gd9WrAC=oyaAg#LnVdCx=d zd^V8KaAlv*;JAHBpUSoEy#8cDWLmY{eHs;+@PRwH+Vo@85Vxs%)`5wU|-ACh4uaaFl?qC!>gB03pAJ2~s?Bn?^52lApAgW^wr-PmXt|D*3 zodp-N>lS*O4*MHQ(TT-s^0CdDX=VjPjtEIcmm#45W_bLKqi{SF6OnE?_{fw0Hi8K9qQo}p@sW1MHk@h;3a;gwR)%qTal z9e`p9$gns%KP`UGY7S5z4HMxjxfn~O>GurjRJ)&Y2jcDX#3-)wVQil0pZnjGnAm54 zetRv8P&?}k#zR2rR}(Z&Zmx9F6qQ>QMUkt9Nv8-yMgUlj#gm!sJIW~sl*@L_=xd+i6i`R?gO(OANWMGv}yMITV9dWzi&^H1HTWe-nQly{03?AjBPH7kLIE}S(RlkIXl1Ea^FS?0Q+WggBlYif{(DB6~0&nxw zrSOhJAv*>#n-{Y3*g+pa>z00wA_SEuO)Sc?`C(B9c^wC9q zO>63md3D?g|ygLWqukPGZxxRY{N~jut*aJe(XoNnOT7x6k8GNZ-A@o~=w%||f z?Qomlmwd_~wcTIIC$z^=EH}2xNJSm?>4cU5Ep9%;>O0?ZeY`NEOJ)a1zTN=Os~leM4UZXz7gxtb z2VkVC^WehriSi^lV>1YNXSeQ=hdS1LA1qh6Csr7HE?Fb$qZgkBqsed*sg;<+65Pc9 zkZ#Pc4b83_(AP_K;GVzV5bg)wNxgRTC9ir3B9fK*>A81O_qAu%N+D=eQ>Et4irB_o zV%lPHH0pT4PYb0hr1?*WDQflda2*Z8Rpi+@5v46GLs5y8Zy zA%-~d@_(obai{0me`aPvLWFRRDhQwd$S)iM`;KOc>bT(luq|GTprpdX!$njOzWfpR z&8A+{%Kr`f|E2D1`KT<{nW9WhO=)#{K?DX#UQl&(bnfo%DHisJvs=y&~xo!|}*56#|TehnKo>a}R# zi%Q+q?KY_Sh>F^~)fZaFh5jeXKv0IA5cfw@=ndI2YL=`}NC+V*)k{{X<0f>votbmF zf11T1U$H{8KVtDZLzoDC47FVFkQ7BC)ISUuhaimcXHe1=xq!Mq4HssF_kSyuJq%G9 z^o`alB0@s2DrGl~M-TSbhw@NY2a_*Qy@{t^jfvvRYfQ#*V+eUA#Khj7EjNrF+r2Ug z(u`VN9?9(yh??&MPC_J2@^>;ji*+1FyWDbQ>HlIPyM-&%9HK%(zqqp02V)2f=Sr2! zH5wue2V>TJovx~sDz!K@8Y~80u`pX}Wv$R`>MS~v&R~yN(2E43uvM5oRr1jIiPD?d_rZ0RRJRc=80Q$b8he z2m2AH82cCyWT`dw42+>p5c8OGH+jSTAU_}N5xw?F5ofL+&zqQ>xpDxF-;@QMI_f$p zDM9*tX5NfN6~4s2nQO&=6zeRdo%U^1p8(OZ*|XFBS(6;)CE&42>ZhO&XbtJt$V3f& zA@hsd2NCD0s8N{cyBEROk`4O{;4Ys$%TOd-;IWat(0^^$VVhCH#YSs9WMpJl>5a12 z53Vs7ct=b^Qls`&?JMSMM!m)$n40s2D2>aRIyJLr_d~M6Fh7n=3bdqt$Ok;IUtYDn z(T)V)k|*>7zs2B0!A93k9YN8vJ~zr>Hm_$`R1~S}`D!AqW^%hbh{<-H$LHa!>8~Zh zv=vX4?jMstxwRbe0TB-}-^x)YIPx5&hHU#BG%gyi&~AQkxIK?fxt<|Qhlk>o5N_%U zx>0Rwx!cT`Kz&*AG36eYC8{(XEa@+gA=M0DtByKEG7WE768ox#e|uDBm(d<&>3)S~ zS@+42H6}H7-P>$McCjIo%GP>Y371_7T&!)S))r2p`r-UZqw(tCUj6IcKIQH0+?Z6v zi~kp6kfJZZ$LhBFu1kN6|d)n*=DV^#_32QnNE8o zPdM^$x&VnSBN~~2tJ)o8!e+ZJ6^cwytx>@P*-iMWQGd99wbtq^IThct$GS!(U(1Vx zToh0D@r8K@4?TbTH&DFQ^IXuht3Cr`$K!XciMs?kQofWM2_X^o@IGjXagUXI*oZCk z2^Nh)MhXIdz&`#<^GN{~;=Z*bK+Irb+$H-<(*1(5?4Drcd1koDrea3w*Y&%w}>5) zcL_6nFetLN4saM0?ZUEvs^z}DdU&Y^@%0n*2wP;7RbHOU5e%Wru=#e52TvKk5tNlw z45tg{E=!&fc>_w#nMjf&QF8wEq@@+K*G1GzTg{-apL@r}ci7tDB2$k4t>}v-rwe^r z^paXKxb5T=%jIHz^emh*8B3R*-XS^Q zp6#>HK;O?YHyZ0+FIPDa3c8RuqNY$sS_*3%f#7fSJiI&?Lr0S50efb@jakaT1M4f= zWr0`%`ugbOJN76^JulpbA^*vN#8m7UqBLJ7WF;gdoVjQlEEi0!52qHb*tlFyhmPmU zE^lv5R~oI^Q_NQyX_ZTrwptFd4ezgy%C%ZhBL^HrC0*z;xns|keK04V!OWm~s|Ew+Mm+TjMD=g$1P!UIb=Jjt!zeMl1 zdWXMr^ z)KOD;iL&Be{mLBsrt(G27b*#uO~y8-3nW==*E2uhv27k4h<5orsWn(&sFWqelS!_x z`RV)V_jV27wa>M&uv<1{bWrX(-g0_hZ!d9|(T~Y`+V1Q3myaDzPr_Ibe~jNWpX-WYChVSbarMJCD#Mk2i&}N*J|3GDG@cd zKw7L(qFjV8DcIOju3oX`F~E=360oR@@s%}fHhgfa0l-%H=+OeBw0(b*GH_=CrW|MxdrAKO6&LZ_8jk;X$;KYK9RJ=^ifm8J6G{i9I`=CD9- z3&|sRCr67>^BH3LJ6h3MbVDpVMf%#BnIC;oj#RaXOk?-I}I z{IUIlNW8dmxnt)jMTeO_)gO1IW|i*!C1 z8BVS|nd{Vi^nZ4zn)-=i3+#w@d00TM0VlZxVT}g*>V2}{;f>76vl%eset?``$^T$!5GzI%C>=ILPsQTB%At5SQJDSR!r(ar50n3QD1H%g4v3E4g+Z zl>J91M&UiHz{9Law;FNtfXAn|lyd$Pk;n#;j{)mF&r~sSJ$tt+JGwvVH%Q-zuy7OS z6qv+)^YVH#q}vL|?6RRvw&-H^1qN{T+313+)7zAEvcdd&z6rr0p8;E4Yf?8fji+f- zo{|{U`ucNFqGiwT*qHV53m@wfqvbhj$y^>EH%~}H*VRsxE=#C?MVTDO?^vzeq(c^S z#|TjXp4KW?#`%Ylc>d2=J;p?ahoQc4TB5UnoY99Vrgjd2*JBIutH^=t3&4gSFkM6= z_xU#h{YHDD)$f#Buy)4_+5-x~^9i#kT-^$d&QuPkqVVQJ}u!GZogkJ!zfsG|-F)CW?D};Z6F*b@L?; z4*objKaqsI_Ii}AnsRCI!cQB}#C1k(3{f(Fa9^u`d;OylZW2(Mh*oZNA5l6;#VQ|9VH36)|Q) z|4ya+dy)mK+3!*WG*zj*mYTG^lZ2i6EJ!w$?7}azpY$!?X{Jr?Lh)M}_tkv2=H4}d zkH8Nf_yZ(ZO}Zljn|RHM=NL(lZZaF=mSN`C9$OSg+Z`{)lWb*Se zmO>S*;Tev?zd0;E?~kS#x;Yy`Q`7mzJPKV7g0n0`!x5 zexQx=9H#8Js-&OC+cL1J)3M_uU?_gCTlUO;S;)>flS`x`my|IH=xz zk3o8H+|=mOjZK=M|7VedoYl&Sl5=OiHAylsq#^efa21u=m@EEBlm zboc&Ecih1fvGnAK)@2MINO5hTaHH!+vWmE}1?ObWk72nG-ppT{#;NS`1CL@&pZIgkXiO-m90mBg2}>;H`fcpn?2 zEp>W93fw2`?#D>Dc(%mp)Ab4Igfw0XEVSRwp66e=-l$3WuVatWcklRI-?h=MJ#rVc z#pD}Ccq}bU*wf92|M<=GYi&*HZkFKt#<8Tk`O;vfS004`4k0Ys`FZ6JyJ%QXcte3W zH9p*D9$-Iz-)ig%YOgx-AQoU0mh{v>fqXJpzs{gR!v>(=sK$_SitlL(1;c-1bkRF$ zhMn3UzC-?wL%<=V0{M5ha199>ePWGo5!Nyt0Zc_ zQR}tF8FB5A1{N^)j-%U|{E}d5uhGGh!RGGGkh3;)-9vK3+3=2Ar%Vi>JK4s)Uw(WW z8!wtxn#t{RxPQ{T;oD(}^D>>pJY_Jl<6>)xEgrsG&h}#oCQxh{gltIRw3~*nskXt( zvUW4w=_|Hg%~?(EEn1)db5y-EjV>#P?U=7(E-C*`qV%HdGt}|B=YzIc2+{tvlFo!`S6)CQrz4I;47z*R#9nu7A!edEx z-T`r$&(Gv|SrA@2#}ctl5{%dxpv4fLLgOCsljT8OjG#yWGo*N#> z{=;f=^>W&X|06Le30PU{)#Q9KUt=_k>aaW1(`>&}tX4zZ;c?TuuyDK2q+F)5w>=P9 zuG5jO>jMea?+dX%nkLJ3-^Y11UnRHy_|&&&#?5(!`Aa=xehdgf#=D>UmH(1c?r}@; zJzGuki3f!34MCN6VKC_2u9!Or!>&pEa^|4_rW8YZdlJB`R$D_cQ#SuA)0#ZP1u)Yd zL(>?TvFMQd*1GqJLAYWk%NemgmD}I6wCxQB<)SMME5NH~GW@1EgZNXg%Rc4c_S#z- zWri#vLiUJRE2&RVBMLnFNM#StBmP1|Kv+FMkr+m)@7*}h0z;4tSm=1r~ z!r^kFOf~fLO`bERT1{9=@YzZGG)~pf%5|3G6JsOGFM^|sQ2jJ8GBkO4{zNvDO&bX# zXMVilrMxB0x6T_<>biS?jm1yw;QoeSBledpFZ)mG0i7kWDS;CRV=m6CyU%pJ6ZJiW zDxNP`fw19lSFK&}EsYL-k#D`|%UF%!V6kQs9hC8C^1#4A@Tc$8;k8 zw>X6G2$84q~kF9x0Y7c61m@>Mt(IW zCUrgYyboScSZ1!^GwN;9Qq<7$RW4anXZuPt9s?up1n%-l*7{zoRs{b^MsC0ntE}@S z`ND<3Tx<5tmd&Z!dQ`>A3jmXFY=SKAl=6~^8{k6R|2{Eis8bg2;_^WBNcAfv$hX3s(N=?t8lLZ4^YN z8V~G{%_MjpG&{ehgQssjHXAc68%p?jbaqq7fW7Og3Ua!m%rXZo4x%$LxxH4QM5KPN zI>A-L!c5CArRDI>l$Ja9$WZOd$QgG0 zG#RS>=I&zO(iC@$cWAj%M<}Z;Y`hJ%!9uk#3NMk$cLjMnjXi36fY+we(KXtexpTl$ zj)oZ4QAnK5yEES3M*3*EmaY;zk>`bq==};H`Hw#w z@YU+*xlyFgi`ibqTISlxhV;ahl;F9>__Q_2_|E>AwQ}T)!BwgB+XB8ST}bqKUeoBx_$SvWjfhX0(6UX!4Ix9<`b83cHq z@*jfg&X!CRCOcRp8t32|)Yjwalh+VL@z zh(o>}@g{(F(dB7^Xkp?~F!o(}M~gR}_`XGEEOR%fFgScTDDC~UQ$^7tHm83Jp3l}0 z1U7T+^Sp|`5Y1}VhZBicuY}kmcZ3^^mJ~V9S;ULzEehLd!jH2ylpEd`bhh;8 zqFFd~Zd+N(QHcEA*)W%nHD!d*%r-1~gXxD->vfG8E!^<%A^JbA2X(-MIr}Hb0`0zz z_B7%9%bDTg+l%KN{ktVH4SFDg2Sd^(W74Js7m43}Sorv3o!$>&k&!$7;b`deI)B;Y zKE86fG-gvMwKf;p7RQ7Ap*WJ=p}0Wr2eAFst~d`bFXFp*tqr#D*r`KvCge2tNgdg5 zZF@OYKYb0ygE$i<9%;bE;ys+o1zk{gO0BeI%*-2{u063=CY34zmYR8GkMFMlH#=}m zFD~WxEZ)?OCQ@f_8(ofsfrMGbI9{fC;r>fj@O@5C%|$LO+YrMWH<2-&NqS%H{^O$< zR>nBYg{ZbhYizxdqztGTGCHkVeQXnk2eeIF;(Z4emj`3;i%Y;=PKe_Ai%M+{@36$V zqG>e_L;(mR?h6{&-ICJih~}RJ>>TS815}bM#mxsYJJwF|8qM5}2r__1ff^U&SOb_641MJA@g3|F0GW7uPS&C`vYYy@9+;;^^%=Mie&X=)I@~EKNO8zAq>TP~stHHz8 z28mcJGIN3sVEev@59_x2Df(yUlZ52tmJMC}3J&U7pnR?rZMY*!=$On+$5K z_HM*l_W&&6^K&z~7CF~cx82C<;+xez)*lV(6-yNxIONRaW2xh=<%VmciG>79i&nHm zH(Z%M8+FPQ8w0dsIGiyB{P>$j6NwdC??5XL9I1LAT@330YYUpowKsrtaxzv>2gj` z+^Cpu4t@aQxT(PkL~=1|wIl{dy~6AVR@FpT2THxU7NTEl=RKs-80elkWKeRZ>M{DP z36}g1i{|djl66CWZ(pBcmW<@L?la@D2n-sLSD)BlPBM9Uc_^pj*>Gy*($xkVJw3e$ zRr~${oaUA`eWrs#=al6!Pj7NVm**(KQFik~!`|Kf7(CUmj`$w_{0}f=(6iQBG3=N= z<5idbkM}qF5iAyBVS64-0R(wO;}TUq#aU#-{P?;Nsg;%h{9ZEMslU8PiQE z4V%gUeGUcpLy9q*J#U)mWg`G{EShT)D%<<_p$6ApF9g|$(()41yCQzE;WHu7sS47A zY}&f~WewIVm}2LBpo7VxS1HTQ(^Ij-!}%}UP z4h{fB?nX^4!kC!XkObTFSk1t2FV;@BrikVYyX%n@K>qF-zV38Jr7Zw-y&Eh=dnUPE zck6Ir+rnAFj7~2@IGbaRfqdL96^hglC96qfZ(Ec z9vVoQvOP1tyDch)NrBmEtRd}tONH$c*xLoUG_NFsZ9RCi5w*}U9A>-{~WKUjQ& zbd>o*IO30cuvB+ITKE_|lyl73{45;$jA7>tBK}NC^lY<$HD>pfA)!r}lt1}wtQ3wp zb-j!{PLcw26j21+(Mr8|M=J@rns6Prr<_gN;}^ZSnHDn{^NKIEZ8Ye?0-5jll2ndG zO_FD364<=pyEyfK;&yrHh@vfQV^8T}{gG5_*j2YXAsaTTjQr>VtGSaXn=VFtKJ8AY z-LTHpZ+^qOgL(qb-*XozoyOpauk6sb&N+Fpopal&xKyyg?_tb+t+z36tB|EyX;}4s zUgn@#ziZNd1^M=>J&pxPv=r3y z=WqoFU#H?%bNH?K7zT+Oj|~}s;AdOUoU{CiY=#aGQxY*_4CQ8fJnOEu_k^TYZO9v?@^T0`#*-<+EIZXFm-pi^ZN zA(_0vYxs4XnC8_ENbnAon6WTu>^i(fr|>GGu66}S%FwE=670H$H~r6 zeX(-3j>+U4C~FM?Q*68kBmQ5u3pFC`^@ty*d4qI5d8xKQ(eBk$+Vgx(YUNkUC^NhiPZ3pY_=5V z;UaEtNS}IQSLn7i3rL|cZ6iY9>~2PBPsPoo3KAh9jfgT#xoGb z5h9bQZC$a7^s?dt%SNsO9PO%&*!Th^b>D9-iJ{SZU9+u4thp=y>YR90D)hi66c)0+ zQSBu@o7yjVf-Ow06d+R;OfB0<)@Cm4LFFRrz8;}^^&y0Zw&@q>9Ha!%FSys~B2Qpe zw?+jNOlxfEGE;4PM^+9(fL+Rx7|&%PTc) zlvet*0ae+_f*M`w1y>R8NsbBIhbmNX|F_n8njkp59FW@X+6tF`0QhDrY@^&28)kt^ox-$`TgUbh%lZSh&?6i{5;8* zF6YZ1WCJ9Vi>%JM4eLKDmBMBhHP+rVM~}eK`t|JPG*(aIi;U)_@fMZD;{1oLg_zjE z*5*O>>E9Fz@2c0RyTw{#q}Skye5DeFZw|q;!jXSnl8FOH0F<{Y{UXaG9VE&f-LpMP zxDiEZW-7lq)Rqj-VW@7u?&rccAKY7|N!Q3xj7kM%Ej)6z%35ZY(yGvabK-Qj7FQLr zC+TSJkmv!m(x|-4oA-DLz9g+IvAYl|Z|sEGEO_CLYF&;oxEJ#J%3W_yiOS&&a{7+3 zdl{0W4aSI~Y#Z?bJ=v&Kw9^gy^xnzae7D@k3kX7c3m?5Sl4s8rh;-GopfSooGJ2`# zb1tV0XfFP?*q}bhrz7F zr=!Nd(tXT3ccfGb*Rd>92r83hq^#kOO}YTMoTE&@)#o_|(c3t;ft-5w+b?I4Qgtn4 z)phX>COki`x4s(~4bsnO`5|uURlMVqj>H#jrnp3raI}J=5{^n%t@ib=(5>|jPshhQ z`v`QZfT}9`*Lz7{UxVFVO<#)jW>aJAHdNn=_{P&_3_q_S#pJtUs3Oz(MyrdCFgnS@ zPH@N_9c3$dnSNc%xiL~(DBWcgwV&2X2Rrwf%`y-%C%-pV>hWiJXTLwaUbiS-xoE?E z{TjkkCzq!NHBsZa=spr+`rL+=OCWixuTb@&-uH|#o$$ENFoRb9cxzIJwVR+bzA@4>#)rG&@E;ia4aVaFYKzbw!Ld)@G0Z$ojy>4Og$(#A?e z%N~BAOJ{8VN)+G?NxC(SiaoWf`qe?by#t6yNVEN7*t|2=QU9RVpVsP1JdVxW;fw9j zRr9IVNQ&w^IqDql1!U`;A!Ujyk2XUG%I|5YnCrS+(R*;3@ifQiGRoXP0IDVD;;l~@ zXg*|;pWO6m;~Y-}IPbXGQX9u-y5MWK>xeaPxfAFs0PTR%kf)>NP1KHir#ueE=Qqz=ISyrO3FrFJsgJ9YyIut!zD(hzu^PafTc=FZ<=`;g z{0w0ML=8$fF1VJ|`a9%imyaKR{!fuYNTHdQ{`24dIZx#-A8#mRLLRa4bXHrL*C@x; z%oOSqj7kjx`z}bTB~p(xJV+x#Sc+Cc(vLuSJ8xmMCMuNr#%(TtdJnSq4)N z-I0wUY=*sGE)V2x-p@D~E3Di538&IJv)(t>CT_BN=Na^M#|EgCE$s& zSxWwaJO=sf*JMJw+1Jvi=0F7zz8=%CvwI|{SCf3V zCJPXTuPI0;-NWti8=hpg*#3U+oc%2?5KrehS83wJo(P%;TQrt%?}SK_*?O7fb4wnm zKisyE+nYU*RFs}argNZPV1^STDJ)RdXM`1dV1$vEQjbyaK-kNOXguuIvq#SKu8*0h zfU8p=qjArUl~duUCAa=rpQUQzDZCMsG3B-_+P?SjE};;-y9N?(h7Xyt64K@pzB90| z7#m_8wevLo8b|N6DHYERDSf}0mAsYcX+vCPb<#JcQ;~Lp`+e<`vAOcnfevBuvm6GE z%KMCQKqjZ-TV!N%-A=F5^^S~Jqla9b$@qh$4ScuIw-Zh;H)mKu^4t8ie$qz?HvPj= z_Cvhn)f$3`&hFX17Fvxn z!KQ!NI;|@AHYBXVj|J@Gim7D@jCmHYxfW!nIVd=;7I~>yp(bF`nH(Y%g*CLrmwn^3 za5a}vSb}cn1jEvgpN|`&RT{Y5^zt{eGEg_(z`2$d+%w%R6|bxo!ZF| zoDeHNOWVLY7R1LLc;x$jH#%kc6OQ2^RVb0Wgv;m8o|tFtuJat*H#}Aps)=;ZutmutDLVNuJ2QW$n~)=DIqnzA zwczq_-r{*Q(MB(LpZUNW`qM`AZFG#65fN=#wZm2Yh^WtGN~-)~^11GS*q;c{v>Tde zs~&LlG(5?3^8mju_3Yn=g=T+6BXs8&7iGKm#1B5_ZZD;_-npogl?Eb`CI0rrNFw!$Fsta=iyVpKLIfVM&8paOj`!>da+>~kd4;j{w3 z_B1WsI*(BbSl}(AL1^TA>Y_K5pG<50o#Wbg&wkV=%z6#zqBz;{ebKi4g+79bpT8XK zVexH6Onv0Zl~O@4$6FH*==EJzi(lK^CNzM!ti=39Z#6g>jr z<-bZqVYq{c6t+0%wGa?hPV9}IGmOIX&wKUj&3vbn{u+-@EdCA|8Ej7m1-1G8!0z7s+WKYoaOGLN8Ry?R(fVOE!2fD% zmMkI434aw>a^`NJs3(q`EH1YPN)?M@swAPIpnRcHT=u2^x-|a3X|q?Ec=ObuMdAs& zJNT^iq!Q$e_`h}kdMo#uq!(6Mb`#-Ge)+4&m&I{^Y^rI)NAtMF9|pnV)$V=JLi`U< zHzKAk*57}-A#7&9KYzgIxJcXy%6J|BU#a`{EeFhB`R7C#WKJ}je`xN96ga*B_jj{R zngN*ce}~%a)nk^PSzz5ni8=WA+Qg5)7EL=7vi=V=6y5ve5uH~fFm=@eP1&3W-Ej|5 z(40lm!iln(S@GW#_`BD@`;cB!W0NI0t#;kI+FOA=F>LN=4(bgPp1V3#d6PQ@;D( zr|R$e3AhaNc-w!&{qIsc{px|i!H3rWE{FO-io?mtS#S5>6?OvEuO7Xr1=fEX)K0)+ z`d4_B}HuIl(`=551j_T^_7K_!n@B4nNoY6UIElrvJ)5HJdiiuw-Q>*s%%8jRp;P&8j z)2h(&NtNihjYQhHuc8A(at!Yu5IWq~z;Oi|o67k3cxq>DC#U*1FfhvbBGHaYf0OMe zam1U69YFNVt2<@FEdEtlI;m({FRjfZ70=GPKLm&0GrVYY+?~5MIH+u`nnd`d-ISPk z+RXmwQr&9*XBem)E~mpE0RaIlZWo)(tv*}5!CYQ<3}606{vtQe5A@pq^_1@O)dOON zbekqeL(^1EtTkIkxk}lik0sTaHEG$LhSOu5C>@n4jv^Hj;X*T3@}XU$qz+E)0~|F= zYYc8vtI*p0hk3u4nkyQgaBg+aTNBEeq@N_gg&LgEr5%p{VACy3!OpI_pye1XHN%sC z;t4)2!C^L0vRD4AiQh8^A3>QMw)xRX}`ea&Kc{wW| zsnyMvG_O3EUMRsC+PD)YW2s=qOqxJ{XUQi z^Iw3k?CNNDJJ&d4oV=~?OIwE#f@#~D4!RxRWidxvI&!NZT2(a`!KI1S)B-(E>2RdZ ztah?o$BU4xusZ4R4__;!hSKy0*nd!X6i+QwM|XI|;P6lrNMnEOHZ1Dh~@QQ*LK}o=_Z?nA12HSGP+@6}&oenzVhRJ#?3(wdsMm{`usGkg6u? z(L~ZFwstNh?N+TK)%g}lt)un3^bnV$(k`i`FR@a_HV}!)bw&jk53Nd@HBa;3Lp2^I z>jLhR7DfMjKNN;N@upRJ;q(D5AEwR3L>wiDBRF=Tt`<>#AUvI&}SAUlI;ZCc;;kb)hdU# z-Xe+O9bdjU;eC^0nP+4~Fn^wp40)x;(o0>Z_G6iqbnD58|I`&Tv$Nis#JKl^4XrM- zxNRqc*3IacA)bTA*}LKm;lS45;Uk&({Q{($8zfgM61&#yW3=2tZ92u>qPqJ16j=9V zwnXLl-MOus6K5s)R&cxrQ_RFvf@^27n<&yvYh}|hJSH`ne&~DCFt;4~f4)D{b0Bbp zirHi&A%VnGDQNrosXD&vUWG|o_(PipA_@5)T=mlmSk<)-t^LF22Vl{%|Rh^xiz$C61M0dUqT`7JZ| zDRLSGT<&CcZnp`o^5lJBBM>5ewC)nY=N?8OaCwPfG~Xuw;^EVdo6=IQOdG;q9*O`@ zgoN&i+Hk$Ja&wW{bUku9dUO2am~2G_YiHvK=utBR%<&X$nAXnEp1Xp(969Fw_Jy|X zaQb&zdY3^k@}sWcT!R=BbA$exjXO-0T-hIJ)cPi2f$-I z(|<77JAu4JKsL#VA45&m|Ms2A&o5~$EhDu5kF>WAXmWr1$Bly=5#*?Zv;pcyDW$Z6 zh;(kqU?56uq`-)gM+Fo_V3c&nHpb`}r6N+&8!@^YBu2+?;^+D3InVR^>&qYaZnit# zdA+ZAy{Q7{{6s_VnelpIVUuYF{DULc`o$C;J=_i+V46Z^tXIAzcL87PB|Kk+;4UX`EwSi7-HU4#06u#aKk|dAd8i zo&y}>Fh^MnVebcbq0*2DlU;rOt(mtDfB#zFM)z-VgU?%c8;kH#2Vz>FDee_sgY>CM zk6GL$Y*FU|>MBh!O!MbjE_8*jt0~hzu7yr|z_t`9P^Z7y)2jOY36l;!>2q_V`rh42 z6JcK|sIUg%5vAL=YftN4XX72b4G1YY@{~P5fJIS+p3Q=Om3v$FsA@(~Pzs{x-5{Tn zo#biKF5~q|>S1Kn=T6I%-TGK^!PCE8J!HsSM@8?+MssVL7aFEZzsxr8$#+=k@pO+6 z{;+QN))qJPz?^uhoe}?f(g3dC^;fhyS`0Wla^2vOU zG;Tr{{&5EAwN3iD%8#DXwWOUH_f6t-ErsAfM*cQsHM=hUP9gL2J|MMzEd$4=Pz2kH zvKzi@6(*Gh6*2?zB0z@9dYZkGt$gL4`2vg%d@idCe3Zkm^I+a%OO3D+U_)FF zTAuGL%Z5Bkh%7A??-^YnHlG%l6}ZGjTW#j9xkgdT$M@|v+rnCWeaD?<|c)| z-JM%H0?6UhI8ObVAon*_b@z6)!i#9XD6%+^-A@Xi8;>aFZa1$waL-$+qCMXtTuY?(Z}5AKWH~661kxRL zRgp+V5vvM3Z@i!bz4O4xB;C5@bcAB)!qDZ zK$VF@W?sp$J{|P#os2T+SZD!1zX=T$Uft|oT(qV7ZN1Ip)~(=83#(J|OmqX$YFu7z@RyQL)~UyyCE~N#jUEfGl$3JK}5< zHP~oTHW2mux=f{_tDst@)?V;^tbf%@N*e{kSSkH2$+dx2nNgKb5&z?W`h91kGQGtYuj)&Ka+&uM1@Ln5(>h`ddPJDak zth1=}uRDI8sr-)#{QD0#|N7tN+o$}@?Ck%s_pSg$MfIrRg&LvXB!pLUPnm$N!k-?8&av2}PJVICNpWw;ThKi=NOeN(`w^xI9uk4Jn=POSfrIsNl? z$C^lHxX|HuWOa?ur4uI-o}1tez*y3cr#0XIUqV=YAHejc%iqde(?Ij7_$#}@2R^A+XjTkk0xs2bVR#H+hjmNl(gS-x$HDQD zhhIQ|xPY(Cs|#dY=%6|c*IVySIUS_>rqTcSoi))(6iem1c2I-h7MCAI36#T?<1qev zF#RovQiIgp5dE2~+GIRa?~Q7i-80oC!Ew+R?pHMI7u)IX!V;A zN~Vt2II3gKb%_jev7Kp4jFUoOzJ~IcTFA4~{wQifqEk`+`gCh|BtUO+)x8Z_uy^L6 zb<qB^Fpu)}4pU2r zt{uG9wL;MPK;)KsZ(p7UGsm=W;ExAl)$etUp$4XBCei_N#>YY=Yl9 z7V*-Eai;dldn-T>E>c<}@YYI)tCu`#=Z9(;JENA^b0BYO7vG=o?}cUmT~?dN!&sr# z?{__}s{v4Vo4O!yawT;KyDuZz65S78;sY@!& zG8l@ZwV6m_s=t{5ln?!~2!gOz9cxIcEc4@oWeo%gHA(v%+o7Wlnu<|Ppe_A#+#IwM}U_4uC=tQ+6d1g$#rzgU0P z>OI2)*^alY4p=8i#Y03V?OE@)1W$P06<`KjK%S4r2omUh}Uko%CKE-FL#-+ zAmso0bwcN}Ek?VHYLx~l@jXe-`5u`k)s>~;#U}DA?I>P^Jv&+_W^bWF*ezN<)iY4S zwkhJ26voEWYG*jQg zSFwEBZs%F?HF_11sG1FK=_Lai(Crx(Qt{*HxbzM3H=SDH33e>Y5P2@VUA|LG zc&o>cZt9DMh5b;PH+MY5Z9XTz(1!zc0rNgFu4R)1vFnc$DDn(R)B7aLLp(YZ)oyUj zzArt@k;y$F-z~q)ktUZ+Z!q~*GUR>S>Jjn&oFb;@@ppRPAC{`lI@0fc#A zub}WUOEVGqHCT3QN)tC2eNDy5V-Qj-t~?@aieKru0jSN_Mio05sn&mPMVVXjiw;Cy z;7tAAl}5HC^t2~s9eK0huMdk%JK{Q7O_#&i+|s!TQ|?a;PzkMK%bz-fDE1`QWPD6z zA75$MUo5LYr0;xXVz0PRO;5 zExaWrvnXaN5d8VtXY+7_enUy%0+=tGePq9CdC?lQR>os93@8DAWLq>i`zR;xa+lE^ z)y}LC+NmgWJQx}t?S(-jDYr#sQ>PNMTjetBs|Z(RrRT26m=*G#IxSyU2hDv3$@uhS)-oe+}SRJpUTs zC**Wf{hX<*Bvm)(-Pzemq`ZugIN#e@?A5xx>Ib%03+JT{?=&`f?hfjAQ1ZR1@d&og zdD;A;eVGAD=fJs0*BgSq2kbdIf>`7DUigFxjQmo=ri5e%8oI$SB{Rf1d;lquP{}g& z7SDSgWwmGAIy?>@+&-FLh`BMBW%f$kz0Xv<9BR#Xx($UJLa-Z;U>0{A=Bsgex((%S z`vwkeEs>eSe=*b&eRj{bGTDtJ-NL8m&G(k7q886rnzLZ?^G|U+Vcr7)1K}>aSnlM* zBG)``t?L*b;$6lAqje{s>~B?$Y`Xo<8}|;(Cfq zY^h^)V=zX##Qb^TGRI%3)o(p897}lW2f^X~>u6i`9%s{K;>&DLeaA<^^Ml)Ahv1Qp zL&mSOc;Ta5ruI2}et#}17QOLp!py`|nt_A-39IP*2 zqA*G_UCmR@=W&EV1#_own{8n5m%%xGr#YhVLV68=%kNfzZkz02IrQpOIAT;0IeP^da?MLJB zsZ741%+Gz>@|V~2j-#`wBD7XAGBnx zIs4*!8{X;lsR_?-3XKsq4trf1%3e|CzqG;Sw;)i^2yt0SRNOaS4Y%x}u~p39&n#)v zbdKF~?-_{Eksr3M&18IthbM5{pl<}hM@ZJs^lHMi%{BWU;?)dQoijqSQAi7mPo zm`^Jufp_)Rp9HgfLuy~=xlL*ARwR9oicr0{F@zp%>O!pc;P>_dl4R1ISCT0x?ZoA>R| zatGI-Z9N7UHGKty+)=!sp#O0#v4N}d(v971qEEpNSWt0+jk9)biAWD zYjvFEo}j;-QhY$-SSU0yAs!qhq+sD(S~myCvw!1j!e(l+H^$PAW-ElDg*2~kUCVke zRE;TO|ASL_a9C-pcJGbr5GBtiq4t5H7K7lynGi>Ww{>0*l#*)Vfrzs_D!-q67$)rb zkgH_zi1EOAe26gB3~@?Ark)yL)NM~`jgz!^FCw4=_u5&angcfxYI`F_vK(f;vzcs1 z;IV24_;4V8fmXSg9dRfR$lh3PdPK8@eWpG|^A#v``zb?ny+(4L%3aW-TO&Kxv-b8Ot)Q>HK49?*Kxd0S7uBPH%Ad%Lp;F?;ZL=Ii8R zyOK4I8Uv=%DR&6Rm!A+~rzX9V&wS-OV%k1ljO=r%f-ANP@2Mf35EW>+TZ+WnY~Hn&gBFHno1MmA36CoHCk*OR=}1{<$~5Y49Xz6xdg22n~?S`zZN^jXV>OK%|ri>zfs2JDpyCjs*PH* zi*j+ooQ*zK<6WHb(1X@MH-m_iT>4mx*M+`FNc?ghzUqLZO^1eiYROA6u;(bntITkx z>CPsFmq2 zmTRIUK8s3=WH1j)aPk_M&w46Vmc=P3*qJ0PCUsY&e)uusiQs=U9vW3Z5sKkb&I*}y+}+gR0f zP-CFC$Kc>?@-4E@jo{qgze59IwTG#jz7>j^$;A;8Q;=@c)uNbN!=+{`MId=)rX|HF8z~jS7MdV@x=g)+8d_ajH+x6 zx1;XTS1r)L{Dr@MM>Kgt*xJH zAD8QnO0H5CDl5YPO5BoFk_(%KAc{gP%oNCQyFRW#K8AkA6B_y!4&Kit$0;7 z2CGpPUAqz)d(*APd|f4b%DLeU9Ctq+9hsp4yiMC!JA3F9$s(^)YuBioQ-c2-?B?d` z0CL3`J))G-?WdQ{{R(p(m)I|Z?vI3-*7)pq@93#`vq#{C*!tH)o?!lB4UJgza@zB( z%KMgN?uxsTnxl{=7=n{>qMDr-5n*Ynk{Lq3(nN7|OzZMRJO zb~$btkaypuQX>u6eW`;KwLRB}v7wY#rh{p(_FQwW2x~cg1?CTjUq`Ax1>U$?J3_o{^QiaJwhPN}s%0u}YP@*~5kDQK#x~s+xv)&az40 zXM%23x?34k`?AFOZ#rQP(~S~|h+aUiMR+=7;dukFa4Shr)p*T;tN#){A@a0Sg+QUd zNh%@Tl3!xnfGc4=1NGh(WU^~kK?fB{C}Ac#z8go5WPcBHGL`t(M7pQQtO}>5-PDbZ zjg7l)_HuuJA6WfH`Z}mB<&17xWuH#)w{NdR5J(&x|4E|ap8 z`_%R3zphN`CcqKwuJH1Tv^7@v*3p@T`>5Je9HH7FxAk^BYr0bVWh28yl^->#xrZChQ1-$DC5 zzbe<6&Ag||u=xEn_NHft8IvF$jAiSQwD&!7m+BpZ;hZa2UPE)Np;iDdn=4zJ6dkNn zQBxi()3hE{PBA5;o?({yZZaF^UcSB$AuV@M`YzQu0&jo4(FARNmT8|M!oo<5jtZO{ z`7Vqh)dalT|6|I0d+v!u&Hai!gPfErYQqNuQ+5WX*PqA99e8xYUknKda>Qaxo#cVpt`+WX&LbJWzo zmsLScHYvNeSVYCDRWeZ{9cZPhJOwtE;BS{`)kDAKo?hd%kFwPSJg==%G2*QYyKwpX z^_)0?fZD1G7`4v^Qxh^|nuc|*iUYf{D#ZMoA#ysj5&O({o@PQ^tz86o7b=Ws<(Dzg z)k}yJ5?{x$2>Y8VJ`mE%8 zz3fyMr}ah0DbXIHXLpv0eMs4=QfoOcp9eEv>QWS!)`~28_@wIPNvjo!%q23Pl6;C~ z`e9~@URTS>pv9dEcF;(=AGlhJ;jS7gfezCT`MR4NnGzjo=yX`W{4Mky~`v znwCkUpq2@0FzKHE7jT4*qc#nV1+yNVvK6Ts76PHLWos`;aT$uK+L+koP@G5fdH^<2 z4UvW)t{K#%rbsQBuX5`?h|WeiCj?yJQ%-?el4ZDtobP9XtX^+|TZJZ=z?SFCgE_^e z8{2PbZ+@ECTQheNIAvkGv)R{6lu6003$)lZO&fg^vG*)_YB)x~ z*sK-VlE*Z~DeG?O{NJ(s^CZQXd3jVog_=;8UE0-liuEim?{lPifA@K{yphV214vmw z1L#P9?4|PL;n>_W*1pNj%Tz4R*v2J}zYEC>fV+yzy3W|Ws6z917oEQ5Xmo2jB_#Mp z@ow2qSs=}c4%m+oZAQniPkD7%%NDnfhKDqC2?I_nbKJLR-sfSKFM8wJ|d$P)4 z>MA92I;O(uvjxDR>f+IJvIlmFpTVXV5=V3%X0t}sZs~DB4vWv{abqd87m2$LN4kwo zT=81dcV14ix&_ah*6OxG8k#-b3pedFgl5ugGri@t2YgI~ zt}hFTmoJ|yxx7=rUTSYru{k8dThYSsr;*Jt4qWD-kM()Z^g-IlvvxUybW~vgtB886 zJ0Qg`&;t;KWfrcjM;5@c==N!EW%<0}4OEC@j83+SMU^ha+`VIB=ntkLEdeW2oy)dR z=6&x2qcvTEungT;>2Jm>RQ%j9UgajMMpDQub(dR!kT9XvHH8tl$?3w z;xH#S+Sv28v805O>(Rj6O^Gz-;hZ9Y;Uy^o@&Ow(p~cMR%F$ogZ(mB9S0iPnG>oyv zc#uyxgI2B1w2uXkCd!sF#RHFul`#OQ*zZ8sOiN}(RY-A+VEy%4VBsTclFNZO29O3b zFpR|S6Hhk~&KfPE3~zNicinLJ1vS4v(538=y!yI>>}2(IG?a57by+t_&tlBNCjkO{ zH8zdYJU|ad?3DrM=6=0<@wdhcdx`U#T=4EC-Pk}=Qj+)pXiPZtLS_d+(4u@Is%A!- z&t6(UIbwl%`JRuIYjN83!REegbk~-UUd=cY=qYXebO`+tTCBWA9;c~1SPizV36(-q(SsI2gU9(4d?6T$Bhb2Y^w$H4DNj$44I=KpEz&QepB%DZ1n2Y8- z-xN^|VguNtb5@Hr4)17Ktoqo=%C;E%lrHRo-Y3Qc7QznBM(2O6UO|Vzhr2`vxcQXj}y@ssvb@mn7D=L74m2@N|aAG7(++{sDUZ##Q!r zLCgQae*d>Wg&t3xNxtW`qMOG2u10%*V5tVG8)Hzwph zQCVBaJabnt`lzb`Vco(iwI6RDJfGF~Kr6?7?|ot7pIig+{Am`Z73XdBn+Z{CgQ&LKGd`)L+a&=)qvChMT{pZ<<-lS2ysQKO@8<)n1JVj|45zY%vuMv9Y)%H%@ z_yO*Vn3suqQAvq{-RwXs7XuRee&l%EYqhmoDVnU3uJ+)^OEMuT@mv%VLJmmS`p8I)X97azK44SeYyR1%R{2wkWgBT&G zdE7LBQ6-aGewE5+g_PRH3RNzO@QnBq)0G)bW3&NOSUJ^EMU52H2+@>Ve zzuUGoLchJ>#EDy>Bsc|eR_=Mh6Y~)~=P2@}kCcPBQaq^x1>)Hc#edZ*^kFm}b#x+7?jIXK{ zKvzb+SgP#H&ht&d-LjMfIcNc0-w{eb%HkJXFI>ByM&(n85+uaL^tq&5a>j#>OX-K7 zoSfVyyjGRG@a0>3`xXN5QK^m^&Y4*K(W+s+3sDdMx|E}OlkjETl1`uIR9k(l{XwC7 zo#kx7I}0D9!ZMskNgI#`N{kVI?KR->nNZ6=B4DnojCDZTzYgrf7@wwsM2lW zz4UU&klP53npr7vRmNXM1vwf*A=oWn5FAd%M|$C9Oz?$;YsD{=)2O>$;aSYVPp{ed z389}y)Q2saU4?U)fPa#g{G8jL6-4em*)s|v$lg{HZY68G{ATq1(=DWfFdO;&S)qD+ zJQzZ7K~vcpSsNQJAzad6@7;~g*Jm$HI^F}y#Kb12vdRr+_N!#6tCW5`fq-$Qo%saz zSX(O*ys8+lm`1u;bt;0*hyBHKX{b}q{k9KRNKQ$sg2z#HN0TZk&-6iVyuv>JVYS$C zr~Wu-ld4Sci>{Sa+#6o)lTyl{-#T@}hsf~o)H~0=QUi8Ll$WAbZNveGT0s@$JUaU@ zxq6R2G|hJ4o=;n}dAA~aYM{wQByHxObX^&AZ&L7#tuN`)(w^|tzhu_ech7xt;z8K8 zlq+dh9y4dCo#nfqGly`SIr!_Nw!*1DqSubNl;2;k^lbMw6^-!vkm!sD9qdy0RHA^O zE^1E3jczS@wC~a3JT*i8NlVcZ=N)?uNz^6#O<}0&#EM`hS+1g?JnF*@nxsanco-mV zN4bh+QN1T?o1Uxbwgti+tzM5pW-Gq|YZ>FLN(mOLAsvBQ2HHiJDi<|Xddkji&JJh* z$PqV~-+l)Xs8pSrpO;<4 z{0-;%1|`8_y8($G{ypkVW>1fzwq$>i)k2Sv1L)Nm1~EACmiKBs zD{{GFhM4l;Rn<*I_ChuV-7Laq=!Gz7Kv}(}B6ZTPjQH|YoagB*S6U@cw2AWy>J`KW zyj+9pCdOuz$@gbyF%l3WU0$>I3(rGm9~^h)=(S7>si_6;U5ot>hQ4a3GbK3J9-II6 z^9e^B@cU5v4|r)wuSqwR^ul!cviqlV8c8ySb8~ZXqE_#1CE_8))~RK~NHx7|%_!ay zSofp40EP%&aX9fYw9=JCO&`+60w9-yGg3OYg_uBoW>FxECK;ET^ax%i`4e&-^Srij5Kd0lI` z)wrW)v>pS_HSk&Ut?9564nspPmwzMk!)*wm0>6~%BQ=x zxg`GV%b!1>vPNb0q#twF&+mly_E;dK!YOmPX3ze|Jfg-3yVFDEki(L#0x`N;#rhIn zc64&rQxXoea*^#S+FA4gEv`!=fx+v}U3dyO?#@*Y{l5 zKyKt?>bmsJO|#BEYT{u|zq&JU>|Jg_Y-}c1U{|CW`hoO*JFO-`*6X=KX8^a7Xd<8G3Ch9aEgT56LP2cs>=^ zz-HDam3x(XsEwIVErS~UQ$3PMnd3R*Xh;HbWZ7#p0|dL#o!y7KWuDFhaF^f6fsR9f z4rs^M5DqMLq8CDN{)N`}@B96zI+YYY+i#T|#VfnkcpcuGH{`EjzS=Da;@q9oCKxY^ zdCT6^#H|3()+-8t^)KwhK)o+vFTPPFZdx>_1gJVk=gm(9H}rxc zt87A-eeOOeQ=-M>)`Id*!<Q$nbrN<&{v&h#iP<|EA3SokXO01aDOZ+lph}hF&Uqel!@m}oQ6vId zjHC+!qK{-RW*GW%62G;okevk7RQge^_Mpf4p}?p=iFVA@=HZis4>Y+o1gt4T6qF^q zy_dU}P-m$6f@6(B(OvzE2ZX+y^H}Zb%1_3q)%QZfja}Ig8R&28voW|=>7yaa_VDDq zlaU``FuJ{5L?=!jI6o-N?uw`^3nwHlh-1sxNAxvA90*?&em0BWHKibHDp;DeTJYB} zG{)w||3}m6jiAzv-3h;;CBOd}oc(W@4;7O7AIj~ohny&f{~v&4(v{I)?ep{EQOtw? z4GjkU9|1;eKx;Qm%87)2GFuD=N1b`x7gB{RY(?_iFJyJ0M2ioe5=0b&avsb^;g6qe z&-+6(J$p8;WXHk8l!2toGdmrtSU=zEXyGnKWzNS5sfZ-6t(vo0i6%lQEnwM0PmC9T zOlO~TFs6#+Jaunk+~sKdfIK0gkA=RG^1L#dP+}1X@$q=9LRH+5M7;xTt=G9fT66Sk z_=gWU)b=tamfG~>0w#agZJH~-O5ckoA2zTI)!x>j?H+Q9L)AYEuWQH~H}k<5@Ttpk zyv78r&^&qpRoS&yNjq<;N_M<2U;3sa>>2Crz&Rp0>cy^^Rh+8@?HpRJ9#rqNoEm%f zZQP-9)wI1@Pw9lAs;eOr=VJP7p%O9ACxaYQYWid;Cd8v{=KNAnZ?+nvjgD>HdCL!L z3>%;&%msFLwG8+UboJVC$q5&knDkR#D5FG}SZ2$=k$$$&kK@Ovu}(i{GZ%YJmB+n* ziXEIuC zaZd_NBPP@h>%5{o@@(_fmqyCf7&T;bTG=X+-R5RHnGRgVl(2f$2)&U%nHOC*qo%v! z{Np!1em3WuCfDXp03aL6LDBV=bHRIR*stQ;smD`JtMJL%cCoDxwv5Ulxyx#OKOTdu zQp53UGyf{Pv5A3z51iV=b0ga8v7zh8ywP({K-n)~2>O^V-7d-up>Fr!japmAbL4t< zI^5gf16_ii1Sg@$)Q&Wi3|RToH)^BiyVF_(TbUN4mRwG2KZ?HT?!EgVY5V$vX7jV* zOt}6;G`qM0)3aH9_r3XNpt-c+wL7RNF5QQT3oJT(D*^|b4L*WW^Wd+4yK4;V=!yep zd_|AF9*(PDzwH`n#u)uAXOblJo2f%r4;nDt`drt>0?N6FHeq(w{kA3Xz1#1u+ia*U zz``x9w7ibk2W(2r1hs6z_M4wWJih>9%3?6!KYL|yK?^;OSSon3NZf85E?Yzr40d=e z=S6rKXPEh=?=<^*!wb82TD>)2Z22tW3ni;SXs-`vN&#qas#Tx|RC%1Z5L=!=+jB*B z-Mx7C4@+2&)?Nv~2xX?zPhh6hwxt5?TT7siN>R2FQ}IngjfaiI`F=Nz z>vzlN#LaJT5xpH2iB8!}y0vjWOY8!kZ5csBO)76CJ>*>!GCein47x zx)(&F?2<0ee(Q)scv5rbxwKrTbZFCQL$cu&xhiAqc@ zfz4co_vx2eHo^wDHJY0x#qhX$@_zpqo?=ucLWiVM$uA}ql<*p&=%Zlz4;)I*hs9(F95H!UN-Fky*v4G&)mD@rz{z*>)=gt;psJWQrKQV1 z2Jw}<4wayR@rxxhjzMw<9>L2Ftbzc8t!atQf2e0rNrzx)d~4QK#ef|3SP@hPb=x`X z#;~h}{X)xM(W~%X^k3^yPq(%VdNoNKkDv~QgKXp%Um^ib7uj==pKhKa2WXVE>`d`i zx2i8m&DW%e=YBfREdPS3s4KA<_)#KY2orH(nMhoeQLLLm#BSc4a?g4nkD^zMQrk`B z?rBpbAD%{TM?fJ7=Bg5bQm%N+*pw}y{7;#mRrsml@~QCbmp`Dr)KzS$thqJaaUyWH zIA?Z@?pVz@p0Fv7Q}Oz)_c)P@1r1_8`|i}l9opvuCs3@dLug62vS}(d(hIJOg%br+ z2d?F=Q3|jR%ah^J8#-YW&gZRF*#!_Gv1prHTQ_cI%aKOOGM;zTaza%NGoA|po@=Fn zE&S1j4^Uq`03Q$c2VM-|1gt(~wYnx+jbBPo9;ftK6+lo_vvrwx9g+@rUoZ~j`cWvy z7w{+sy|NoqVoRZk?6OP3TpDd*ybN%okbf9H(lbk=Ub;`8rUWqZBkTW*Hm`e9cCU%!Km6NUN8|pxtP3X}zgP-n!JnRR0dQ zzWl})sas;x=XboB6# z?I+GzFRWk=3d5f)j{XW%5J0Jy_1LLtkMD@IExUM&3xb37)SJdL2MGGzEkD68qlNBO zHiA1yD)w_n=%D6Kw&yyu^&h(F?nJnRmWO|Wvzx1sO8~Tt2uLd{;{m-CRax<-gzB>Y z(fnfjjhs=kU>UDxr}hww;pLN7m1zoggkbu}?G!9!&!`_!SQGRer5n**0+29_ElC%zg!<7t#P2hxh)~)wvg|xMs@2c; zg{-MFXiG0F9FuNYI(<~EH>LNI36+%LzBQLQpyof{Gx{pd{Ts0pAuZmRl)7wDo#D;a zEcN_u(KE)`U|FG9)G5`#1s3Hv76;Y6t=sp!i21pp`*dSrKRhlULxiq1Dl;N-@;bYF zR8eO}G`B2|2jlUfHygXFX>CTEsA%(W4y^%TuehoQpbed^j#bvIwtTUTJ>sG&TG!^h zpuy+9r0pU;>(Ap)lb4)ebwN<1lRs}=me2(yl2}LDclIetPpW`y)h)xfS&>Kq6?q;t zDLa;htaNh6jr%2^UlPTL9n*?g#%CMEmhbwOyxr8Rc)1+Pn@kr@z<#+DrY4zWL>$bW@|5pU=vgKC%)Xxx&dZ-?(Tl7$O?<*YjyePPq;g~sh_WU zSM2Be3?yb%H)&dMu+W^jr(fU_1|bD$dj#`dzt6ad<87(B*Gi7fDt0twE_>WXvl!ZH z`f3Gz<7mfI+(RvBGlRez4|;Go4CETiMn-W;h5LiURV^s32Zy`nFRFZoV=>-n`zCw6 z$0=oLLAzK`hEhPrJKL>Ht53($gl5{JXqMv1?(rY+~+R4&D4dGv&4ILrC2H9RY@ zra~!y7-+gJAIMXCB@EtusQJ$LEgyfWL+y)oS4VhYR`mr#$xm!&xo<|7c>x zd@I@EXQ;*&J!;d~bon@mkH)zw(j*)WRwz`n~RFLml-aB6$C0}3AN41c~&hhNlCkL%WL@$yAM*T2M+l3oZG&VoPPr$ zsj18Ev(VO&*y*|Xf4$z3tJ3ULo9IzoX621R9NmQ}aYBO)oy#ASMM?y4m3utoyt{$( z))}l%b|u1eqzw*{Qnb0@n^(UIRzbzGXXB2(@RJY))xkqj1n2ZkUUMkdP-u70LOM4> zf2GZeQlE?lcIO5!&kvbU6wX_Z1=dkv-FmWOqMG(vy+1wK|1FT;0;)A4Sc~dJqUvXn zW|w2^7`ny8J*Jo#;$@6wIR?>g$Qn>SgPw1f=L#P5sHrB7uhqmU8Yv;Y zdT#R@v)N-%adTvXD&pvV_g6;n(rCn9VrKb{aE{eVuXx@F6j*DU8UUuuCLhy^{`>Y5 zC-M}zsqjXJVVMvfc@v?Sg+km5k-@>#M|&>=3|2X`#E+gPPE3r;pox; zheQ+?;bFfB;`@ZrR6a|0N^+5=kwa_IokCAiXA6fWx3pdZ*emA&4g>5OF*1?+1T@J+ z@A{VL38`3q)!w(X6UH!q8Qa;55tI&xsWAx~Kqpwrhduj+NJZ z36r9-(i0w_x4F5j((=9!1|SOjSk>2{+QZei!v`hUMqErGW5=%Vp7^ zI==+Re0;0g$vaCf4h@bw<}1C)-PH7RwB!ZrQKZH)R6qOLm(BV4bp?6ST63&$j(z`n zuA9WxaJx(U5+kg}O_9R69|@$joFAR0Qtp_-l~A5Xss}YwAKtUo!YEhE;%F0M?c8j7 zbJ-vfFoU|2j5*;W6UBRqJq75HZA)7A=!&^9ANL8j1&tU2^ z?vT#k+}}T{J_;FM{lU;1EZ6zrxcm{Upz0+GvCf^*rsBwDjzXg)WOnZWkVSv-^9{#h zVg!DxWAG?Gx3dh~8Jc*QPJ4#21B&BM>Z~?I3DDUQ4eA1VB^Ug5OV~1F?GC*ceToan z1{@iZBW=B_CI?JTB4f6=ob#dd2Kerm^&X{<<4clEWqvJB+#t)TPqAC{namKq9k6Z+^uRD(r5A3i&j3r~Wm|Iz)kc*UC zz{T@CI`GGe;zAC3n}^;~vo&uD*PaTqqqWrnz+PJ=JvS4tU$*-LtGQx^EcQguT(+te zsE9-*2z6h~2uoStH@sX!cYZT^OjF0Hc}{wCP!x1pn!ZzJC27}u+Ir}sQ=9+K;rZXA zpA1y|s6w>GZO&~I-)QP4c$|HaNgAa;cNa|5<%e8aGVMvRFxAK3B4Mir ze!k1{$pV7za}P8I*)oLip*rndJu=zNvDv#v zSr${!+kAv>SGyzz+okv3YKkCaT7P1!G%I-Q)EsNdPS(|h%0X~AUoUic*`CePb}HOd z76NT>5PDh$s{}UahqqR1@q_J%2e{q$s4J5~-9i3y)2$AapBSm~ zdc?{jYs@r3^5%=pTp{mf>FaCj1}PF+X`R}vV8uIp&$Q0jLS=$&SM+NHrK-2~@~zAg zYL`mej6n|l7e*6wc&u+5g}pz9Yz``uTxnq}ban<54qGV@zP));HtL?*e$(C|YtUmb zF3dA-$)R+snUCWgcUfvA0B0c@Oo#28?Y>@l^QNyIW<#tcJX=arwU_e;@nBqqb8hLj zbyY`Oc#Vg=b3Xq56A^sAbOvft#Y1}%t&Y14?e7KsVD9>*pQ-~TCq^pV zEWTS;AS8hCaofoh{nS?T^ZkT8t$Rq7jxF(1(^LGuyuB425y>G+*3 zZ>>tzlJv!DEWE-{eYq0rwV({0@I_;D@Lb@h7LaPnt0ZEzh6|%po(xp)fJ9a}Iu8c) zmCNBpI$`J6G5uO~9&AZze__6zGZH^rzBL@MxkA7vXR3?!YaXGFGlclvE+K0el&kdQ zw?Pk5ra~cV3cOj+{KL|VEikzo--;SsZhR|XfSWi&fZ*`~(l{l=O=jcJKl^U};l|7q zvr3#GVSB{|f_WD5Y!gB=VZU%LP{T)t!G%Oej}dYsqy3CVBO^~0-=I%8(CZ((_Ahu* zNG$vawo5(tRhcLKxYOL;8C>14>?o+S`y*=&kUDz-f&lW5Uc6-^!3##~YRSQ^PbisX zdF=$|XbJjz^JRd`@m2;NwaC-EBL&l=T!r^Zx~QJ4bjA8qWuZ;t)vU4p(Y{LtiPujO z;TjjVg@AIQgZ!1PSqN#jxd)@0pl9ilsDi0|!`{xuba}wtF@SlY#@ovS1*Zv&Y{&9` zrz@_^n*g;@j({ zcB+9L(E+j8n!*Q;yWXkU_sX%^rSo&;=A&>`#it)xVvCS-(k2ST!-F-8C)4*r^DYHG z3a{s`v{Ylpp=$aN=Zsje=Zr9VVTKNC{M0Q%&gOOyT)gfGJ1DQ#+;_1M@-Y0G(PAjy zx#YF7>#=DCk1lX*ho=IwR`NI3kg-BTf@ypt@|>V*`S6%F^-5=7)o^9_v9L;WoqBF$ zC4*KMY9_DKW_apoN?{(ykxTtY8Ym_;ETP*M>ka`zLTkf2+zL!=0`K$sTD^Y=L?e{| zKgD$C5;OeHq&tJPeLv^PDxu9ZD6D=&KH``>E$r;l!}C!Nq}9_$ zjN$h$P&2DcQl~3!96SV8Rk5%OC)sIpHn2Y)uF1bg^TMkE&-ff|ft&VvDDz9tS>^nc~2UZG` zxx~Eq!P6oT`KX&?dVzLdtv2wWMAjwxoPIT^hhl3d0hqIYO-{`cV2cVu;XaIW0MPCA-Yr%MJ zl0sI)oe7?k@m^f$j2=qVHymg(@U+>7Nc5AiF>aennjS=7_yQ4xZ4DRtFf1a9{{sm2j~&|sC=U45 zTC7El^&hdy5Ge31+^bz)XA?w|R2+l^x_o?AT){YaS7{kB6f(m4!vEE#}(G)dcepsyvo?^wZsA5*>? zevM{8m!S%E4C<>1Qx;Hcx&HQ_QN%8v@!qgGdLglogIqV7qvyL#1tJg^rn8yRFokj6M_A9ICj}S0ALdd|k`>48YfAI2*i_^PcKc zusD1sEBRu*wZw{Wd|BPYRN;5!?xY?=zUL^-5pkQu0{r`xVQpcnZ5tvrVJ2oEPfxKs zfULDJr&~vazrbgzZy_JUSI-XMIaDh`O;v_7-}W&F*b$a*th)1A!*TzoLCcg)y#@{z zXrm+ZXA#LQ$oWB%&KjA+sR`rdZ5BCW-hLe^teJ4vb?vZ63v*56D%hchK^pDy{}X_ovisqI@ZTGvJSUX+pUMK^^VcdA1y8AXchAZ zH^UT&uHD)^Y;csn!f|+!M**A1o~p!LXny;3y@fT<7lUi#cT-0qR z08>eV&j9j?aAM!i!beV`TSE|dF(}4$2_36c~` zn)h%J+Rwf#=y1OjM4ad5(2 zj_5#Th*nPFWh*USB$VTkPnUzqG(W6x4c=Uk?K-U2Gg`1P%xg=Xcr?qPGs{4v@5JsZ zHwc;Pi7s56UpVKY>i5{L3bLJ5;* z4z=%xIDM4+Xf6z|%A0;s$OY#M4mDSz)W48q-&GwE`4utz9tnecy1Eu!*M936c)iOy zAKq8d@`eP1F?_C!+|(EY0#@N;f|FxK@Nrb4MAwN^M+p}YCdZBAN_OQ!HiG74)T;yN z?*!T;&h^e}u=0%@IFWDs-ibA$(xp_ytZGPh{{7aHhPf%HP~TQuPDwMQqu*8R(hY- z?E>TK6b57jtDs$Q5t370v5*hM!lg=YzT>x2cN+AEMFQZlT z66ueViTFuFLtAu7%HKzio7)u>+@Q`RI%jMy7yC!XtS0N}zrCV-*6E?L3Y%2c1fe z^*HlV{hYyr+2-f5;YkAkN{PHAZnQ5H*k9xLxx2r)-QWCrl)6a%O+ zg3yv92=R0eZ(n*OoBkLbAmd$ zGrQ0#KYbb?an(rt;`*9cXPwyhCFi*@RM_BG|fpxO#Rn*!yNQM9t-~Jzd6g8S|PctQ&*gPG9puec}YyKLT zE?d-x_NM;GbOPBE5 z>r3-TJ>7U=V_9lW8WSBPMsFF|Kt{WN#&2hDkpbRsxf_02CBYfDaUvumGDlv2nfL8= zlhJyJgC%$4J=vrZAB1(VZD}uyp}zIdjZ+tP!*bcx$Vi%h`cqAzsr#HuTbI7xyiIQ8R57Wgx%H3IoKJ5Oj z*l1k)N_FM=E;}V9GE>%gP_~K@XW4%~`OQsF`Jc#<0h!q2ncULuMf>#KHgMe=>5_}H zz>@dCGHEn%+>Gw)gO;mH~8sg-L8(ptTJe*Zk zO=lHt5#LZeggtqW&>1sI3-E{#a0a!fQOK$DGNE~(IPoS%%%6GB`V)|wRJ^R7MVaU;x< zL@d;iLfRF;ZgeCw7JN#6db=*u_)>i4Mx-)M^})*t?X{SiWj_K|>*$3be$sXTNQkd% z@YJ9ys72cdJk)rxawF?1@`~2IR?^6OY?xzq$td*Fqo~MA_k43}_|A464SU@L=^Ow` zDfOX5)@939h+baa))Wn^GFS}k46KKAJ%}~l2n{HV>_Dj;KaIQt`}#`1=8`b`+nvNQ zhEtvRHH`wcu0XxBmFbZr2#jlP5b|^6N^`~fd#(_X1MKE47OdG9kr8tvxnifKL0PLFdR-0H61Uw#t_43~RCxmkcUr=zxz0{Wp_>RW@?`+-f+DCmC*U zF1QZ0f5a`Keg`<4>on4#@3W!+f#7GgF6H`(#qvSh9B=9>Wc^+-Ltc1jXXO$xtJ2u; zRccbbJ8J!P-M&!qOIgX&-R;{~eS<3faH!1O=iL5CQk#Ti={~fU{o#%B|HB!VS;-as zSnqVla*^283;_pseyoSSrlMJMx&5R_HE@nlbv>Zm=(BX9WT_uFeG~<6JvKC>xF1m= zds4qMuruDyD0-_>h!h<_eV8-sTWfKIU1Jmuz!~*52jG}<0wr&ne=IbYje;-iX9X1o zWsq1j#|n@3%{$jCF(R%4o@%EXF&xgUfNqw zRZx0Y|E#l$;qtmlgNM7S+`BbmD3OHvvfvMy$}-t>?P8f!Tv0F#zxM-xtN*uIm@e_nC(r^3hSS5JDcRTVRFC38{7{~t(k=5zxodbdN=4VwiJMQ&%Rk zE9L$D(8V*tE#GMv=XM&5rxEvNk|}FJi0J}rtUT=U@|S^?J~}gy#ZN; zi~_6O9}B*XVU2)d$@wBm7q22$H7kz3odqVRo$!Z+%Ry_x^n_}^Nju~`a|~A zqR-5ZI)nSRCEm2H@Uc@|u&{IF_8W~bNn9L&WxcGI&N;WApI}!X?=q94* z(-(^a9r61cy?gR6K!j&WM7f@TJse=36Tq|am|V;@wJ{OM{f^DUobWy4SneUt=7 zvJg4%@!rMizL|E--tcjJPdoiYYw0jY_fd0eK6V)R$FrQy#q)w+9tyzS^ZDVuVzj`f-x1(#@(uXEgZfX} zV*Ulbuex%xk$WM=os|jnXGuKsuC>w^Xsh8T0v-M?6=qLs{J#Z{e3iHQ z0Oa>W)n5cyhoxL75_=A|4mo}!C^mH0KOD3(UZ7qBiU)K(bzjb+6^x~)pe<|yb(b5W zg-ow~f6#;>${ef7)rqd6CbW>&b*r?yCQm{IhViRD_bLV^wl)g9q z$H!B+hE4W1%%w4^axo>f|3;0IFqT9xgzlC4J#IFqi*5TPQ+D6uOg4O@`QM%xstZhw zQH%dkP;92lwpvj!_2=9@#5px|`ZjF;J#EYe`6eL*z$_C(y6Bz>X-V_cc7Dos`iEQk ze;&>JJE3g3fqFM`!YfkCs|^Hw&GqsEtj^&8pb_-8KzKabn6_hY{JHruBM(R@Wta*p zSjNS)9vziZshN9Yh<8Y4pQOa;Jum<|5wxcJW%Q!I>@1&2F5wbCr4r7kAL3v)x73El z0Ny#XC;zb(pE{a5VTdJoeXAVG^!Ep(ao2a#-E56-ey~uy%Lha@=!a~XJZt}L>9x>) zKs3)+bK({H?5aSXxL*wk?mV1i@WkzB-yXcgleWcl%7p6)RFU8r5PheaA3_^Ia}mWY z`+Z{Cdz(rE3b(s$?BPUJ`X%Hwa?JJ)X+xdp{|J$CGgK2$w{8x7H!O>#CuW1CoKj-g zQ5d!WtdTS2+VW_oa8Ng1!^NVy6XNY@bd)>clm{?M#*3>KwSEEvliLX}Dhx>Xr^~7` zy2e5x)D4!I#8K@jo63SG04M4=Pw43?l)HE2AvAAx96hfBfx6 zUA}SrnB29?bsqi!p<(*>{)jvDFmW|hLGO}O&3xvz?gM$i**3U@C8o1 zKBGNb#8m4$YLLyS6YIL>s0&K<$cIrTg3kLlqn$$MfXI%k5}Omi0q3Q91P=0r&UHQ; zJ&xbj%y&119~mzqa2~m0pIPz?OYngJ^>M8sAIua_aEXy19aSL-Y5^$BVhDv0LOV6k z?LyjfqdL$&VkD<*HthU^Y_wpb$RXO|!2^@JX!gxA~S|$uUMy`WD*8?kAM$1-ofAOgA&#S~C z=3kGL=Ds^TUA{JanFVmI#dzl#KLI{G44KWD_S?`4KxoFh_;5OH7piZrZJi%ww29XZ zLlaJE%w4sTtQyqUfzY)S252XU0U85(=N=~RGql1-C zTP{MEj`m5)jmo>-(=eQ5(b;#8AQb1Ik;$kdyRj>6Pe09(MtZegl2e@RJC7#)gYo2$ z<-2wKv$AU~h*ePK!g!)b&q)mz>PA%nwRM59xUJY$?ml9ugM&wIxeh~>1H$WhK_=rl z{o{EHR|UMaWJA_$O~iI_z5h_pTVwM z4qm&s(YdusO|&Q0dQs`Vs2jZC60Hs$RvBf)2L-Pkk0qmK8!voFTJ&#A5};k+@MJ20 zms`e24@1`W04(xUAFa1s5x-Vf{IMv^8&^Hq@T!mAg*(zYsl#(_L$k%C)~{Tp=~2l% z=P}lG$V{>4!4Rph2vQ@-1)*liI%pY1ozD>vw=faO%d)ceZ}Gi7bK718E!;<)R)g8D z>}rqW1EICdx&tg0>tT?Z+lL)#iYV*En|-ikQh%|gclKBlCfxQ4%9~dV2zBxB+Y)K2 z`b9e54?pl3@28Ue_?^iGcI?^f6_4iSg-0fn_)63Bmcy^qY#GRn2X}<+@^xr?=LE`U z=t!ltwtSK2I3wb2qjF|+7x~;Kd#;um>A)*sd%@nN9HC}5J5;YmE{z&PU*)Hjhsaba zFQ>2S)os)m2OE}ULxDp#iBM-`$KqO3|kv-NRz>3{|tn-MmNv!otm zA}M?@DWggiDN(c7M!5vCLfXBM)Nep=&}Ek|jINf$D{U?m4mB>hz`bh59zRS#Us`(# zkv2nQ*U2G3#TL$T{cW@Yft?2rSp6tO?XH_y?}KnS0Hf7OW(x&`%*O)u(Jn+-OB7^( z!-635s2J^bQGi$LX@#(EGTa=t9ME4o0NC5Fj$HQ<3~X@K+4V~-%{#U*J%Bc;x~w5Z z1Y6oDcA7!LzFHwR=eTkBkXN`j!CKOEabp|BF;FyY3sjjxoS|qBj42HWkXnvHFt9E@ zhTKmN{SQ&al+~|(Iw|@X_v+*n58_rBte1u!phR&vP4*IpyuU&hz8!|Fc63o!gsHxg zr7kAPYz%#TlN6tu8C2EB!DTD~I}|?${rYW%)R$kPESyk8B-X~mg@sbUJ)K}KarwJF zDYje5ItI(f;T|ece^nOsej4OlZK$V;>{m;0>|j(k_h&gXw^U}*u6R2kLHH{koWkXBLk-%u5%OM9_ zb>V$xNegIP+@FKXTYpg{bc_m|1!ZK+hzOt%loUyc60KkLJ;66OI}82vDM1N;{!R}Q z#K43pWa`3TT89Ns#RyGIO;_P+NBxK08o`x5^SVHkIgm*%TeQpsTX#h1|ER-Sb*CnP z0@BugbM1SL9ZfAQIgFRGvNC~bY($yZXMg89k!3Bp!#4h5No$*^sR0(FPqR=5 zkF0-A$Qe(s9x8K&^(IKUY~&_vi4dMS4&S&Ad3Aj@$+zKWtM!AW^f)~y*Ee^gMhUY} zqF~X8r3p<(-;crMMl#KZCN{zQJFZF==Gx6&>`rle?Omm<$9d3#J7RBJ^@fo23+}`f zdfblGYKokwl}6BjOHTlX6tkA&G&Ni%N&R?zU0@|n?S=bAS_ar{161~y@>l;fsI`-I zD8pJO)9l}--=P~ivq}@08^|%ngXneSXpx6Wv=QTv>Cft&o5r)p*muQ64_a*>SBb8A zl%z&u2*oXZ-G;i?uCs;Emi~z5-7H&qBh}f69LDNEz! zkNqY~0yfI0BN%<%Y*_Xc%2mdyEXi|PYscAfUqj&}cBw_SG!WazJ#5vCqoZjaWK>KC zSOAfbQ|sox9o__A?hbS551n7+W`=z(A8zhMvS!%wS`{g42!4e-cd;4=cl^2iwT}JI zGe`~v>;AlvUb@-Ot}T4rN@wXzDTW|;or!zU98%Wyz+&=?Kg_yD%nb(Q->cV{D5Nh{ zG$C}Lvflm}*gQzIHP-n9ElyObP;n*hbCA}cYV>?}IBf^Mk-uT@taztV z-rA&}2fu*yiY;sozbI_I`X)Uv`O}Xwf+9WzmLdbM2Mlv7VtC#QQF3zI!C8_MTZ$|i z7EoT8JZ66b1YXLc_&TEU!j3+eb0f6B?!)GJt6PPs=)DYN|Gw$aZ+pGpac}MWWG^bP zKNE3vFk_*K)7`*FRHO99w@6d7WDMWcpv9d^Hbg&GnzZ(?r}RCgKPM<;rYrDggyqR! zg0#bq+t-{v7m@+fTN+%W*!lumoe^zR!cqkT_h}_Debr2rG=oWRD$J;uep!bGE+IXf z=k$=qZ@aDiHCh=uCquhZO~^>1n7-<<%+cfc-dABAiG#}_!dd-6Vo5LA&l- z8y!6ESfnOTkKWO}l=sJU`=evN7jpHQw-PF^rCmt(3)8Za+cF9%b$UNl17Q%m&DHC8 zLzSQFDUSM~iK2Md)WKC}owqv)=1Gk4U#MzV-}PPjFdO@S>FDZWYQ>d15yyyt@_88C z+;6F+zSHj{Rk7k+2_7G)em-;KRdcQr6$fpxdFFxNa0!0$fN$Bi49RE2Z5%q%II^D+cxS~2TlqprwpU~ToyMi) z7*^8R_;cx>&=$PIjPVz-c=$!_D+Ipur``=~n!TElalM3Ma0kgdYNaNY#1po(R~Tsf8T(?}%K$&vFdvU*Fw%?pE>`E#>n1mEns#O5J``Q>?7GVZ{D1& z|B0_-(nHg_O)+2QxK;`Cq@KD8rj?;1&=+UV}F1y5%GuEOuy?15P z0ULU0tl1!nY`?^o_|0&;*Zofn9{H-%jfO9*qX#XwqKfstch8fyw`U4-jS>L$cv>Kv z{wB4b|$Mnd7R{>GfuFOXbvf)DV>LYwZY@i>eU?!gr~Jja-`KqXtk11c$XmjuXprTn$?KV}52@ zdsYiE4m$=URJd#Q!}aR?mNH>4j)vUcj(Go zQj|*GYiol9800F~jK5pC%n3P(1{whK?fl#c=}IR%#|W30L6c3RkPHirh{VPVzc8gF z+@9X~Jp0mTIS7Yd=GH{?>GEI-^9%1pt+RRb<_$(+CFG1v@ZPaQLwrZApkrA_s12fe zs}A>P_4+uqiRm2BwhD zoh?P(5;_8u^M5<`*u4~|CB&a**MFHPrFV_g=BWGkFn=V;m#Nr_Kh7mE}uuzP*zt| zTxOOzDr{j_tYb59JOd!QBZ!SWnP_r1Z~xm`nE7mEceDvWgn~2o~RXV9vL?Z=^b6fg-xt@`;6Wj@d1cYPq zxGdogXyvSLVy3o!8wv^l?~fQ9DTdp4V}^=aW>Og~-FFLfE#lZO)io16oiu|KQfu$- zmBo-7E3Z3sz86bhSv7dtIbN$Um@&2hwr z5M~WA44D$?T*L=Na7r#dKc%p@V;r)PGb=9Gh#)EzwMs!(5g&&n=#M%y+Ee;26@gjh z7IM3+`=jW}z8?pFArVPsZ;;g480io>+iA69cgJP4av9WNu@Nr&4TAgoyHGyN+A-O# zB458=^ZlWB8=v=?Yd2tGUV=lk{MQDS{o9uPU6{4*!F>ff0zi{sCb>YiNbcu7Iz2ft zae7hw3CqiAma3{BQ04WF4FxL}{fC~GR%3G=874*kWsY5-;NaR!-FdU&@C|%H)9lhO=YL zcNE(AW_jpP+1s0||APhiamByBKO7O+eNqM;LZ#QvgP1t#|M=&jLw6GXHxIa11&4>o zhVKt|&K<)lA)tCu#Q(76us3mcC|DibXd<}y+0Uu<|PQ1NWq!q!o>{6I0tmPqmACxCxrkuYy_Kpk8^B{RNZbYQgd;Q{2ViNo%_i5*; zeoOl_^Kg@pNxQI?g zV^EzD6(mHC(d_M6pD2%a`#tdRZ~~it5)nSSn?M~ux(ncs_PPB-*x$crwT}LA+k#MK zr9!XF!n?}I?1ZR?vvG2+7I% zEym--Z~;c?YAc>CSvfEzHk$<7sK$1^fq)DiQjese!m~txVng3SyyZ@#9I8iQax6x@;b*mPZxZSXHWW4^{a-4;St-c>2DZ2Meh8sJi5yT=;TBLeFCD$0Bji z`c{NDuV=;MAc0;HnX_f(D-;deYL?7anXRGK*WE!h0w}Q~gXrdv&T>SMod3`Z?4}T+ z-Q17Dtv8=zzhC<8=wdh<(KlrI4v^|C1mH802p!Ikt(eW(o+_Tq7joIwa6S%Df}U?v z<(wmBU>CWpCA4)AJFU2@>d~^&1M|WssVno`oAx+knBUcqo*rg(jcp?uBVLqNvV7_i zGl4?QZs8@vttZxusfBBgf+6qxs>~w>?S0NUHN@NtsalBZpUXo1fdoqzq9djo2v-Oq zHErI@UqIqKH)Jg zuK*sb5-Qn>hkUdRf6MAD<2ILj%6mdq#HJ6p${oX9P!J`K?e%kZIY==$kld3E;L4HC zl|A|8P5=?1`QE)K8*zGzokQrc3x^$fST(5p^X>f@RX;9cAm+Z2#a|mUNp{~ry?xSz zz7KaILdSzm%QlL@meR_V)D!wMvE3T1Y78>!&m2shjH=jODRZ#b}gwY{&dC1#ho z1&6yK{TDZ6qy6+E&Qk}mW_{wUK)1h;LC6gAJ+eDJ)34kEl|rR10`GeBLrE~;w)fHF zNR#RFA?MwDmJ`{W$QMMMjuRt^5d-0Eaxy@rqA$SohejQLAXzSkE$3bp)8fuF09yg> zjJX*3_17NI*iAf3I|_#c29tU`mc~@2OLyQ8U#OzXUERJYErtYS_w!fV5vV5gL(Y79 zQ$H6eecdGH%AI*(C)glT*7x*)+kmu5^Rh;It%!ld){M}+YZO1{oKrs{^X&LB;wvI2 zkFe%wiAq<|mt-vtfEy2zEXeM(9zX^_Fh&K}9s$FxYp`e>HnKacl9w=crQ+d4pKsKEQ8OE(3*+zLZoi$9H;K|+Q=I_>f* zxt+}Jl_bi1HZcekU`)uCf2&)GP%m?(z5V*9vqE1n ziSeZDy-G#}xryLAIwGqXGL2Xml;@3P0Ff~^pDUIv}JYF@V<7b8*lP*p|4+zi`%_0JU(||?)u_H zN%V`);c#rKg;s^bm&ti(Yx542x1DfULNhu)#C|l*Xoh9LS>~m;#a>eP-}?ByY-o8N zIw(UII-`;Dca8FoApD)Q2d2X7OxBYTS?W3Bq_0+KOO0|S{ihJBEREx|G7EaoCQ|of zTXw#5*<^94x|jx6t?>L=h?D4d`CRbq%Cn~C^VXz(K2Y6nESnukqv<(8OCdF}h;8oD zVY# z$<8+a&6~yVZpU)|Vx)=ZJ^MYAVfZ#9zgnomrDa7vM7})yuOSfVxo{A6?bPyBQu9I! z&VSjeOoKv^32C%oD09)ix%j67Jjjwtx*i^e%Lx%vW(B zHRP(wIbNqPZkk@yD+F8n7|^AYW*G$nX>1)dUs2%=#jED<`t!Kina(@{T!UF0E&9P)X#cz~cjmX2DGF3yrB&Xm-r>g0 z57(pQ^j^zke*QVJZzu^`e%P*hcGcND$=oVhCB&GBxN@X3+~)128gb)~&Jk2X!l~KJ zy@wBMd^t?zz?Y@Muc0zC8N4rF$`Val_#>Vbm($_$u|?C7Xu>MgwY# zgKW+?XX|ipJCbL(ipW*{&=^r_!p~cm%{VU4b=h0AdIJj?w&bA6K&gZ%rBYL8=PN zo9@-Q&~=f!8t6^SWp6ITr4^x^zn0qvO_@nAnc*P8?$0v2l3{)B(L<(%Tpf@6JOIdR z0&aSUes*&LDH05(1f=AS6l5j@*P%)|M(-RCxb9+BA&`+{^|AS{p72V{)NiNk3uXlV zgGd+;v_{yX#bZx5vPIw*DH6oLij$`IMq)>Xg z#QX>~K952yHNEVH2ukJjcc zb!wgX=E&)Y^5&#==HA&ZMMQ&iqDgiO(T#8xa`*k%m$P7?;nPxWWL};MQR2RAxdM|I z?qymC;&*sF5enEX13sRtIdC{s-A|CF^i^HIi^GH*iH_1H^0IkgktQ1PgX)``t=d@- zy&vx2gY7!WepYe9)#3fZG*rrpoAZ4E_Q*M~^vn%UCra+MkgBaGO&(pTMhRY;Nf(QlLTb-HaXYe_D&vAS)<2Po! zDr-}Bw|AIx8l((weq1kl#Q6yYw!kDjyLchJY*>K9^Sh7ZiTLNV{4SWgVP`TxvfTd# zx=a@9NI4vBT5MBRreO6GR(dGuP0wC5)DEcibdtNkpmM-~OdkfUMqJfg^S#UY<*##4 zvC786xw#ImZ!S1*d8_X!kcW)#Orni>O2Q%kV&V~eBb`1k$mHFrudnAL&HLBP`qyB+ zrq!4v#sx_Tp?W5Ryk4rl?f(9LYs+M-xTlzxe4x<=c?-~B=PebC20zM$bx zeBff(z}ZV7sgwEpZlBogALFt&98W|OR(Jf}tgse|eWt5F=!5@t*`4h{r%L-mW?A zywXe|l`V27JEznJO}2_bR^vIT9pS-Q>H+__;*g`ki3g+jxL&@pagrcMsfX z#;0D&HM=-vrv4VLZSWKp^>e3qVrcyFw@wka{k()VaVoC<+sEV%dvU(EP{>KetbCAO5+GH?YX8r_#|CdnVgt)$!NOXDx zb<|NwpsvXcS7Y*m1U)@K6g@pa%b^$cC`1U3+}5%Qhz#A`5~A1E7yPxuYCySFvwpg$ zr|5zQsWYt)OR6~vVGMcF0WaX0u2Dn27mAR-ZD4&SPwxa0Sa&4o{HT4s0489{E|JK= zgsq(h(hBb^e&OA5o-%g=DXMV!wz+K`AH} zG>&AzV^_iqjtt;2zvHKcmr0V|i2549jMIWl7|ME~Ta6(-iBI3BxO4qwd%qMp`lN;(S`r|XtNS*Xu6*vyg}ir=SeFtN z@9J0oqsj6#dswJxVzGkTr4Vu;yQ?8&(tBDtj|`Fa4&IU2G}(IUph6b(6pI{G6Nj`HzvWPYB)RlDE++ z=+G~vb4AnFd{{BA7g2lysy6Zx8r)jO{}h_%_6^42`K9Weors1~EJQnhpI!ydNmmwm zi@d5N(*0H7EOv&dOR}wOaY$}2KV_c|tLOk#s3g!ADpx+|P@7<3U)UAzg$$=&<8u4r zP^RgC_V(7%XbPnKQX^<$Z+mA4@`H@}&WYsRCq8pU7^+Vxu!DCw|7%`~>6SZeUm<_9 zr+J)A-o_xcV!>d--==dfL^r!Tk^ws%FrqNY$!K6KmVjS_P*-|1dxl`pzR>Q-&-zw! zbAeR2aY9^azcpf4Qt0lxA z+Y^z~)tkGJ4FP}pO{X5Yb)iY|tjgpOMt)B7NIqLA_vUhqDETEL2X`*G z+jAYy*^^aLvT++K7Z|+~#Vk?(v5zn5Et4(4+nc%3AJfnEWbV?u&Fr3DW+)J|tjX;B zd=T#3;}8G6OAj-5=^u0G;IXCG|Ni^V@^B@S#GSwX8hyDduRg}2_Hl_i=|DAU%lc2> zttUKFfDpW%I=sB)oA&(%o@S4ZI%<^m6OGzQ9@&n;aK7khMpYfmmw`Dvo|3 zL^25Gtzc#Qx(Ykpv9&IB>Vo6$Iv6z|RWqYImKPl%Q6A98X8+d@m64@6t5lo!6uAgD zxxdbeK+Mszdjf{n<*hgl-hMWnIW#VXY#My839wG1(R^jTpMPTX9ZvpIA~~nrWLIJY z(KmmYig=VLq@?m%j?taqq3+VeNm=Z;>p>d+e@J`puqK+QaTM`I6e$)ErM?O%1OcT= zN0Htkp%;nf6llCDAfYMi3vz4bkeCGac@@l_#l#?fEpd4xqEA39i2IW z#%cKA1Vf65T+T6|Sphq?S|u@qnCAC&5jf^|nMkAqzrT5o^+bI- z*4Bl}!*Mp{G3Rmf;{<4cv^%LN{aFb`r~N~T-3U&L_ieM1;7ApJsm9_g{l}-wA>4ao z{uJ-Myp?x6g-;u`;28#)9CldDQkfUd()XBS3koi=AcX*KZRb0vVu}IjgRqg+xl~)+ zmuI~Jh+01jP|=Qqt$=kyxZv6W_WequV&LK1Ux}(&4AP9a$$Z z4a#^&RoM?cJ+{t|(BfeZ{o;70M-sz|I`BKIM4&~CaqwV{=63FSr%$#Xb<#WiCPf)0 zXr-AHjCvt5(XYi8zGrlXS?|%>k?+GSJEdbXerxY(yQjJ~yXG|Cte$m|e;zpN1AIKP;6Ii{4 zM#ZU2;8KT1J%=IXhC&%O1G( zCt#$i8W`t@TA!^Ch8aLp?2WVJ0$$B(AIVl~qD>=hzG@x9yu!^1_|e|=qpuGw6tL*> z0uj{(g1Y5(J&di7KunHpe1ky1+kDSqJ|ytU{W8cB3HTt(;v}eYm6d$(0!ln>u}) zcs3JMZjFjN{nz5%oTpLq6h2DRp^dE4hwz^I%#Es-7+mT|tI@WjbY=nlGcaI*8x0_)??SkOoMp|k6-^!U2M!}!x= z-opok7<}srEvzE#~@A_HtgNmtReUU9=%t1_UbX}1#X_fDqQKRU_ zUFc{xnjdt&?xjB5$)wD$wW!Sw0iA8N>DFh%0KZC++>616n)a<|uk*DuFtqbgSm@As z1$CdWBtEO;mEUd{M2ZHMmiceqy!l(b_e3E@&_T@T&5av3#EhPOJUTw+eDI)s*n)_L z4A{bUe{r15?U*HCx%O_g74ki>Z*6byUUN^cN-KGo8ussk`x^#b=cn9d@titc z-Q62+O#a<}rDXncoeNYd29j0LE(!btIwJ6Mz*_G7XY*3qyt854*uVGGub2HFD<1z( z6_o$qpKH0VFokl`(bi7T)YKF+q9P)C^0u_}5eX?NCpY(YszYo{3|L(~v!|y=>DSiA zUX+>n=h4rf?Dy_{PjyHF{E^s?KTTaADtw~Ii##72#YhJrBM{(*qGRL{Utk9e>Po2( z&US0OO#0XEXO@zi%c}SAmVo2*&l|sXKSkU22u4LkMNM<_#XD1vfJW5)AEAJw3$>N; zxuzwK+W_dEh}ZVRUqQKmC>l?KfxubTpWl#JImBjUAc5pHe7`ERwYIj}0D-iu99kME ziKLD`PXotRja2XRaNp{64>>qE(h)$1;+kuhw~LF5mB0WmTBE*_j5_}iliwfm3H1vR znk(#Mbb-uWfn-6oi~xK07HB0fVD?nUW)5BsX;L&AhA<(ELgrZ1rX-goP6c32;H>8E7A0BFRZLmGOAysy} zEh+Mw)??JgC4;Av{*3Z2aLryiAjf$f9Z}xve|i%blEeDz?SN05`*`2XA5z{rHK%;y z_yH@}@c~8Mnmu6O5@OlplaW5{S5G%5{ma|4|8abVk9_bA=%NAPr!Tj~rg4Faf+xm$ zS{`yz({aAJ0qx~=+Ah7}=(-i!s=0k?r2kONkjWwiu&57dlXiBv=Ln5|cO1JFTxlFWc>X zP2JS=cWg?Hc(!z_#sY8La4)q;w9?-y=#4E(-H`3gu#_GE{y0iGtTv&RPliPG@T2hD z@)GA+<~12v9gSCkTMyNwhy(Z9rzs8ndNzo-Ndb}6xgo^KiI~wB5>C#~4Bu+X8NQ0$ zj9~e8LUZdDz;%3UpuTl0At?Y2q%utBzCaro$fvIQ=?))mp4MQAe`fN>#O+?_Psw#U z^`55oNTfQn#GI?tk|x zkyOzm^Q$46%E|*KZY68#ZJ!w@tA#YC1oh0FZot1O5dwwoTQgPP*4QjeU`a1*=ttqQ+N^uV1@Hf9rXv5zSS_ z9k#~9I?=sjmb4qhm#zTLU;SdN^?Y-}d@1vreW~ILT5Uo+>#u`NhTGBhnq_?2jlq;! zhA;>pB_qRYC|xb%IP^e!CYHX2I$=O%26j4v-6wbG`GEQS@iQ+g#EN?ixzSBMeEi7c zfDXqJ?|38~kWXhD(DB)p*}rxjMVu*`({SCzea)FDjiiq$htrf z2Zel2dDFow>rvDte^xk(vK8qkbqAKeDuTs85*6Rb$7760_t!nMbif3y}Ey$T_73x$9!IlgG6Z0bi*ZDH*l##8fR z%E=(wkZvb>*GoYl&|`(imRY>Ku3%mLBHO8~=2GjbolnK9e^w|Mo|ZG@IV$L=Y9zrN zf{DehhuCH0dYU@kDTg%d3UPHuP2z;XjMDUM-@C}Ujvd~1<@mw^#x5tt_~q#-PQ)Ol zv&oJY!7r?HZ^XpX+Tuh1^SX+Y&?a*~+Rm0q`JZ3=* zmlmYI044rwJ!g<-cfNFRAzrd6&nuzUV_%E5(CbwgH{+Pz8R5_%8Q=cL%otK*qhlT7 z<2}7ww*lIsq?Vn2O44#av znATey4S;ySj>cu=YH`_LjCi+f;}=&r%(gTwIp?c3AP#&=`?z|1*((E%4~ zPTfV0v9we#an5EhacV)fFGI}j8;Cbum#nO;x3FY-q=#Vp=DCWD3-+PYl$A|JT^r?) z^fJwE!CRe|KZ4!;GQ&cMm&~0;LU_^meFbpo-AGe;d4k7`|cAH4wPhudx##iSU{`Q9WDr3VXw

o#{D9R}qVJbu(9QAp!Y2ll*_2k8zU``CYe2!zwtJ^l$27e2W>lYtd-x<^EGd;=xN zgv!ds^2SfWYFBGR8D^h*tT7;x?cx$Z<)gMoL52>K3`IX2HMjy|jnm-0DSJy-?F-VO zB3<>3Br_W8<1DawFH!BM-KPTy(+o6TKR^vlcjAh^6~1cqO>vAu|0$D#^&?YQ&zb#r zSK#qf8JXTufuLm`C(m8w$J`f)O6N*B-QtbD#iq`al@Px7BbKD4(`zEuskLH1ZF$=0 zAFNo$zxNpVEN*7I*I=SSe>%`rY`B!b%E8|gwMk~-s0=Av($LJ9RU|J`81j4>G0JUJ zkgCEFLb=0=Y=^7MC6JMkLDH_VqF6gMT};bP^5y1@3(ONa-L&eu7zWpUoONU{Z3)-P zo(3R#H1#b%zKjw7E=x`nNSHam*1^iFY?Pv@XEmTcUyGJ6DSQl3)yvQ0xTDAurjr;% z)$RI@4dzC$dW9wvI?0Mp((3}L#0RB13wU zarFm#Ow2g?J@^p#=sn48Pzg*u&!XE@K88b0_d{3@F$Db6JXpj+XORQ-HHHuL)aA2m z3l<^I_BEG-M?kGsrju+hh~r*QR>K!!8gMIyTHBx%#J=CT|GZmPHq@wAVmyn6ORjq?Wr;dxBnYb!3q!Q++7KBZ~$_8~7!oWt!?(g1#nmfP> zE=doaK7?)g2MN*8&Bycc87$>N%3G=(Q|voU926q1c@vYD&#s04oho#f??5#QqYJz(boC}H^9+Lu>V4Rf zdMQ9>3E`8QUND25ZL;ZwDS$&bZR5!>iBT3#R;%T*`h%VID_guaEW68bzTVv+eu<`> z0`=yNXG5ToUgk(IM;AA{R=kB0uSIgTJ&7P9Y4$Y;7&$h$e9GC0N(#z*Hm=`FY5xN; z(PqWN_@#VU@gPf(s9~qL2;8U;F4#h7^|OAmw?W8KN>JSmi2iDS0|!aJVk^r)d~snwE7ITstk~{m~`@J4E&nS_|vF z1m&ef?Jg%JUgf0nyg%!YB4_LOC0+x3)~`bO(B1jcBrhj~xuIT)?UYwVoKIB?mGpU_ z!G@XBs;4%j+Kwl0vbwmWj%RYpJ^7J&M}mXEwpf-!y&`swxU~Ns>S8@ofpmF`Q7*m} zR8(p42MK3sHD5(Z5T&w8BJv2;#OF!?AM3X0vk5F>>mJ+rJKVO~Xir}Lx#gf-q^X0{ zwta6fJI-2l_(#Xx3`JfPdt>g}6VDtErN@pu6uqv#we=?(_K|msGJ8eSh1~o$Sl}NFknP^4)=eHpoC<6?Ygr{xELrN@oQH~Si#kq z_2+%ajR?6iS$%KZnbZj<+_ZK~T#o?PaR=*|+itD*f;``W@`2p+#Az{TWnm5*ko`2_ z2-%=k_%ZD7@nxrea?#;am3Q^*G2&UYoN@MUdmG#)w!^jr|4q2}bX^>3l#su$G-ulu%u!BV{Mk$vG>Qfz#eP(e zYHzk!VJ2iSnS5$j09XqOIVc z4l;<+bwIPh2X{`tlUvZ}@k+PQXd5s)+zw(z`<*gUtzv_^&GbQC$~uDw+nIJFGgY5$ z1?NN!9fcQly!BeO_marMFUJmZ>v-ySS5puLLX$-m8Ds7(!urM%;)pT1W9SFWbQk7B zEWz%r19hD3FPG!OFKmmtE_Of-l(q~4v^^JG-~ zi=6U0vL6FdJT4G9ON~1kCmNaxWaNeN4S{tDV>)IdvyTVM52k}HU4IKoo?OEi9cG&S zF);d5$8NNT4J(tLHz*ARC<>zsk=!+B^jx_|c(QQOq0aA(NV+qMNpi!$NSJVmf{|aT zfLv0y3_)gbcJv;*E+R8tZC?RLy!x&U^qt&cb~C|V>2zH&K0dCnVKU~91Xjq(XW;4y z_DG|3C{nO$s|!Fi;rxsk1okem-{&wsf@{TByA~@BoMcX+?tUq9W zJm&;GGFT&d&rAH0hS5?`-zw^Rj9EPTzLpI<0X9H?KXU3WkZ77mfEv>no4wvoMr_Ts z==ox2BEEs!t1{*Wwi3jqWS5Z8LBFjLI2;8r%Hj?9B;xT=>xIh8IZHnQ{~Ezy(Pu47 zF4UlaVZ{>e1JKv4C{vxH!mb2EilZ~+`9upq8Fg-)&o=S5!;Dh&O9qb(+!BsxT-rE9 zM9h!(K5eNDt)3pP9-CO&9@N1-v{28}PQNFHF#mXWAC3Dc;k`#6ugmS7eFL*GUM8~p ztrSn3`|T8E+jp|6t=h}FpJ$#ibLPc>3#M#^bZe^_&o=o`_CxLyoQ<9!=E*wmbQ$+eGhW-*Jvl?7#VN zhXL`Z!tiK<1lwICrB*Cbtp;{?ZfQnz94K;6mbIv<{iKXt9t3}^kD3AYZr!)H0pA{P;7p(mO_Peil{ z$+xiug!OcfUw)-r(W|yk!XIoYIg(D^GeL}=mTBZg8+pjf@uWq*zL@$eIgt5B{Qg=+ zi+2ZrD4U`kTfk9LKW6OA5s2?RHFbBh9EgVypOCP<^(c@4XaolEPY{8l?JgeQ0G;pC z(B)%nH;=%JW}+j%Cd(B!#c(GVAi&mSdBU=ttLT92go=~+)o;zRfF$e1*)xC*d~x;^ z@k=Wa*cj=n_^)2z7mgAUS@Qv8K2fv8J4f|qiN5PaeS~{<{?!gHam1v8SU_HTO#5pQ zJf?Cz*BWd>0n+Jr#ea?imQPsj-80uqAa9AX(DM}qj3G)d=G%0YKa_d?oL@Afec>*! z{S35WmOLWchd2Ee0S)N^#V;cFfSIfJuc^|#hV!ZNJ8}hrGbja_Zf?B-=vGSIgghX* zd&dS&P}BrSY&kSEM9s|ni?PiNFMp^6sK9~r^Y)$+=iR(?-p$B_WuSGSZu-*ZWEFh0 zSTDyUfB*rcp?~%3`t|ErpT_mcD!Yn3Kn%~p!Xgc*Vl-`R*5;@Ik@+|cU|In1c|eQ` z!-~CVKy5HC6a}aa#sez(f2$1+9u}~AY>YZMwFA<3eGMR<#epZFCd`bF`t>mS*Td)K z#Y#`(-!k~$SAHEwvVKP~{PzlxRLaxW{|~i@;9Fv=|2%Vk>Trpq?|)vKBqvM#>xKW^ zs=Nb`U%!6+5c*}vFzt9~a(b?y`u)U#+&{PJ#a=nXPyS>2cg(Uf`o)~ zk>Bn9^QK?elM2@^nVkC9Nu7vj;6843(99|L{4r97|E&@r#QIMozfK1%)&FCM_WNdL zuk-d6QJ{maFn({31V7_a*eBWqXE=xC-_?)fDl7TpGGDLYinHEo+jT> z-O{Dlb0-J6xC(ur?n|(yX~z}KjcOYe7-etn`$2*Z20NmmG!A&Meq0Gxz)9}mS(SQ* zpJ&;9Nv}M7(0~Zt-w*@%Q62zTDc>#O*_uZgeL8)W!XSfk!x-vm6zXN4xXL_BWbB>W zrMOBclFV8WBziNhfrLDEsZrE+nRm5E$_1waeW?MVjZD-gKyi;dVOs-;bR+|9c zAGHxu8PY&#kB12MmW(q6vwKn@Tf^wHLmwDtM|jALXs0)wq2ahls{HjNJr>;Ld&ZIF z^T)w6jdYbF>$6cDr}^zfa&__l5Fg|VFpEu zLEcLgJi9klB%L@bf}j3a=PXsTE)k*cjka6v*5cnt$y4NV0l|h%MdoAd1pIZ&r^6Ru zc>P0i`dnYYaOHb@W8od41BjBu=%ftuMnWv}=+Mpdk@iFKXr-9=3f&#CvykPJQpKda zpf}k!MjU=t`M7`AAVbo-lWt6#c5js=Mbo+Wv3n3!Er0+|;5=G)^}@Rf)ge02+%aQs zwY`9;+caJWFd)E{qC8BQAk+AUfc~VUA z8w>o4E<2xq&&-pCtlpygm{PuWyOW|u8f~G0K4YGGdCuh~SYiRs0CUP!HYZX>-kL_& zk}Z2JkD$}TJ|!PQ3v(q1{_J(xjDYq2E0r4O%$JM;6}mQa>$tO?(X&(CJe4~npo+KD zGg}YE_lM#|%+Wmgq<;gM=uZJIXYNmj5EU0Ug(AbjXjoroENgAHt$&{njR9XjYL``xmC>(!*H#xIz@m{Q*~Ndh%F)N1C=z~f8{vKm zfi7<#KDS3go=H_L>x8POJJS*hJcy6#XE*yt6}E`M z(N(G&GZ)Bg3?DbX_1L}L1aWQi7T7Z*x=0uQTiLP$s;TVckr91 zoVagqc-g2Vo-U|f*6wr4*w{;aU;`|7K7=4?nund}Q_jZ2K`K{w#^S63*3J!fNHxY- zBf==4=pT?0ZKlxCK3P#sVF|DSz}nuvt=U%`$u_0EpOjOzdk_psODSkLlu-X#^k93b z@O;91tY1w9AZxWqi@7C4&r4pETd7%|+fjN=M(!0D4CcTUa=50u_g-de_tt+vSCONN zUU5k?K5Mq1JMEE4ene2}HG$Up9M}|UQZT)$WoodKkG-cWdZr|PxQXhDq|cKxu2pK6 z9i!gB>onzF<<6M2?z82B9@{{pZXo&6y;X#mnE?M3(QW4$=;uZ}HcicaVqh;GtfOIn zf346BNNQ<-aXt1jyIHc?iZ_MC-&3pAQkxT$614|4y!EL5WK^8T?4O14FQ{XfR$`Kl zsZ!uO!&Pg)XF>)Wqt#k+?7Av>ZsT*gYfY>3`}DK45F0GP@vsRswL#`4iMsEtRvvoD zlDCDUSkwc%wjd&ke*QyOy@X#bX`Z^qYG)hO>}UsGb*zV$2you3`6?IN`IX zzO#m88iR(;-R*&=3){mp4}z-;yZ?>w5=c;5AYK__>t-_m=AzcYeywf59wdf5PvY1X zDzsA0*1fTEK7BW#IF;8MAt`Plic78{w)cajl8C~!}5>!-D=%Uz4pxV28uJUFwD($N0KXVN(-YhIfMh@-2T zxvJ6v#n9UFit@Pl_&j?PA>7VED| z)upZX(u8p_o;QI@r+{DZWX+RL}E--H2DDD9d^RqhZD) z@$~ViEL0$%SCy>Uf#zhtrp=O>>s7!<8vjAY3scpSRH)k^a_TM>kK7Kc_IL@iYMQXRys1 z$pBpgXk-&DrndnY30dKA!BxbDnsuW!NN{y8F#{7I zL6AuygPV7Pr2@4eyo*zM(29q7PKp}w*Wu~nIT&T{3UE3sjzQ@ZhVs}NN1>pzklZgf zl*lFsDie46)s0*Tk4j#BXPJR+qkP;t*wg&`Cg?n@Q>Oz=bvak8dQ-6#=AU>e3=+1q z4~LltrN=0=f-{qCO#>!x<>@7mt;`~ZmmNieSa?ljs;R3i-fEsuvUzM32W|mjU?C}d zT*8s7`F#denVufohzLq0^sk=zVBGa*{l9j}_eNQ?!L$m}-1VznETvM%uYZ8CrIpSEBxD`LCk#I@SuHdF)$#k!oF!a zzC6sC4%N;3Fr^xftz6RGZI_~!Rk{7XdGu<99v?s9tqp$V%OP&N^Kf-SG?)`H(Y49w zcF>@&WrBXrsA3=^DW1pam;?kK6oQxUHa()ag^$U~Wxn+eN24XuPh-Dja7|8YOd>HU!msjYrfIleTe448=iS za9V!T5UEURL#q~Ol|y0J3C%rdke9-X6H_|A`A6YR&b6n$JH0;hv9$bKBWCU`cLO}q zg1$t2%Jl6w$+nw4iDdG%i!x@K({faZ82_U+sd@;`GICa!<2jx=X`7honQvk+TC9_I zgQgNkzWto7H5uUPX4}JsMOBk z{&fI<6fQn}`P`Ph)NKkJBFOE^%kwgHe?E zA+(KosI!NI5lsR1_ZjnYL{mT~c$LPA2K%X_RB`v|Qu8}^GFHQ>1dAlPU=+!?W!f%5 z(e;{zy3RrSu%L#w5yOE|wgh~il75_nK)pCXb!4jBl~}4A8Ll;@?fg6Yh)5B2lzr6> z-Itv?u_0Hf&wew!;aS7ND{oslPW+OQIBtQ=5 z@(EAM)F@LitK5?u5+4h=Z*?ZIe(er>z~Ftt&xw~u(wA0C(nA4_q)Gr&(^Ij z^WiY>4);ghnAd+6sA@Ijr1Uke*>lz5j2eaK#Ry{NQIsKv@)p9Ar9)X7{nPMhV`*3S z!J3pl%$Jk`+b)5XwSt@oaE9k=Sl?WBZ`lI>(RvH!INQK|^bob)SkShSy%RY&|FK%r z-#C|9=xAi=#K7JEaO>1Y!1Q_K$X7e`5cYxOpb>5HNVGJS4k@w-yJ>;XQMg`_^ED96IH&spN7?(@=Q*-B1~fH zjb;Yw6L#-xo5RmWwaU&$;ciW1R($?3oON(K^QfHn)dbE*k4pWu`FuWY`z?9nda2Ht1b&gP4?4LNTp4+dBb7meT00L%P7V{hey|pfeOQ1v!mFDnG}n@m z0(QNlWq)jZZ9z^{H`fm3jITa};yUZ`*_Ha1&T%om8QCd_8vTN=Nuowpp;uGcNN|n1 zI+Q5|zD+(_PN(kKj?C1>11%5MTNCS6!^f=F;U>#AmLJ)?bW=qb-5VMt3}Wtfs&`}o z*@k&M2R4vsBr@O>%-5A0wR*7bT@GgJq!E!CJ3F3JOvl1zO@72LpFI4QDRw12H>bhcNF?TCf6tKQrJ4gzseh@F zKyg+90U&g%fpidgwCUzEQVxu})9H5o4%o=31aQk$(2Qgf_beYt7qTBOZDjnyef7!} z4M1`?OL=h|3Hbk%L@tn7Lm6~P5hPb{Ra!UkpieX}ULud`U$OISV)S%I+@!yrYqi5X zRla&4XcxLHaZr3KWs7pY0(}WG(=O{urrFF;8Mw}C1|BeY!v*Y8#-}V6ixk#iQ{J+Qt zgDT{J%}Vrtiq?pto|9VrxAL!Zhs*yjg^B-Zz?$#>RDPHF|3lgtRKdnqVpOjUNNKxz zduN7s|LFlgfNhG#NS!oMui52V=719yp67oMjne|@#GU^VJC46jyY&PK)DALT9XE?4 z(0}=7&ls=$B@x~jEzwHkHmde^{P|rR?)hzuQ=Xn4F|GLCfI!wGWJ#840^7jj+Qesn5>Sx+( z5f>`MOmCMvq?rANP^IwlU&7YE8~pWueY5gy#q)yyi3UUgk+*1`?4+7-GBFpoFtLwu z%@JV1c+^lSDYZc>=ZZ~R1J}Cq!7B#gO<2HC%w47_+T+#oQa;y*9tLby5{d<_c7 zvur#o*mR6_pZrXz`eyT1hM+Rq;3iXr`*Ep~hhf8DUCSQb-`{Y+5;WMgGB`+_FnVV9 z2|s%v2@w!V*>Dy=>Ap8J*)q6kO+zn%si2Z9IqN$!qId1G@Oe41mid~_6EA>o$4JwR zO*XzLo!cY$72p{~_3Zq5ducLn8tWI-Cbn6(pM}O*PwIWF+fTXRV?ArAvQFE8*{d!; zbA#0x?uE;uQ;NJ)uUd!yI3v#Bz15f-obgI&?-o*9wyfk^p*fDuxmdOFWeh^H?5&}% z@U!y|_k@I!rFtFoI-Ftkk{f%p4;9SZqgu2L5NTC{O+}&Yvq%c7p3$+xeY=udqb1GS zGmcX?=i;33bP$_)@fP)%I}9(`FtE5INM^hRSg)q3CVJby4{h zWACc+;^euKIGJSpuA=v)^qgV5x82p`v~>)pdO1C!*8#pP%z0)oBe^Y$)BPEv`cWWR zZ0^Ux>})_a7G0y)(*H_kBXvvQ#keko6K!T!4@UoF2HZHdqd4RI%x&tNijDJLJPXDo+ z1sU1Lw4{YQ9JH&NJ0ehtJ%uz$UKuU4w^2d+@cqAc59driYL88dWIy|v9SOogvrzJ$ z@B4^G)ACc{!aVVp1bsf79yDrxw3(FFdbR{gt$P?}glO>Nh#AI?Q&?iHXO2cz@pJHH zwE@zMVht>Z*J_c%48~7wck7X|Udr4kM2CDJ`>-9ZWYBQU*2=EW&B-PWqb1~5DIZBe z>9DG76kpH)`(QNZc#b2Jf#})K6DZ{hE1pE3Q)#o~CzB^a4fNmP6ZzFQ9di1{N(d@D z4#q5V+B4Y(P7vR=(U}qhUq7X_;qBqY3_p?0Z64fF8kC0BVB$gKSoDhOuu*LLM(%?k z{#3)i*ZN8u2ZDa6PHspP@UWET}N`mkXRmP2|wM zp%$MLN#>0ekE8Nu-$y(KUa9!+X;bWO4lfo<2WkU)R# zU0OPROC3M0#NrfS)Soe>5K)JAID9nY?3R~*vPWrjIzj~X*|=LZ7P{%smcVMaz;EQW zW|oY4S>dYaK+=vIh~je^WI0SPN&hUccdVm~={;=BV@^a4=I@KegXzc|$F$m0eS?`A z?ZWB=YyY%>Td%nj=A`>=+rBJy?FSbP&p+5G7u_BdkY2Fk-p3Ec#~5>wFy=lbh^dHb z)!(C@xAlQmemg|%cf36tJ)T2oH(f8{eyci6K{ZowmGX*KEEDDky&f*dJlO5lGz{Cc zC6VH62qyL@)y!epYWRF_qx3WPK{hGs+>y40HVWn2ZWY#WkiP&Hb}rnNTjpGwT<0 z=}=kSyimtwCUU4%4GOo14~oFg2Cgn#f_u3ZH>9h}d_5e9a$_E8r{|S9d` z_JBHRYCrwc@o4NHmq3pmslT2b^bzm2^%OM_tj^n1a~!)u zs4p}!FBCH!Tpw_XyWfNl#g^nRfbD-ik2LlR^J$f1e|Ya{V`QVQ8Z?EozVnoO*efz} z^t$*B8pdS}Yja;l{u5X6#zz&FCX?0nQ^+1<#vsm$O6Lr*8$!Ov{;)cSvVP5sX8VT# zOq@gOu^g=oX8UdPHQcBDG?=~xKpkz7IpANGBgD!wVscs*uY_v)jY)g-jPLq1{k?pxD0k0Qg{ykK*oMSKId; zY_1xs0mEytHk@=7Le2YZ%+RBh*e9kmvTV852N$i@<3!OKE;D}G`OC(lh6N`JDqJr6V>S!Okyf)v_2QPhRE)}{ zG@MIZ;gY!fja9scE$wqKQK!adX2(IGC+yj4ty(PVq$++Yv1(UF`y-7Jq-f6B!6*S@ z2C|SfXO#w zn_8@dY*4mhN@Eo!rjd0y*EWB1!qPhBE)EY(xK%1Px=($Yb%o8pYo@($(S7-+0Y0;0NK2d3kUo*qu&V;2cCc4lI?3W2{^4mHwPuu~KW_F7{izmxdg30D zKL<@v%%-)&zrP~TP0uYX9n1eS%q(uzqtF^dn=EnoI1M#A`o?JoljW$Oop7sZx7?CT zWgsfHf0X0OUF=dmXA{(YOW}%^OS=(#BT}vSXl793q8Qf+|Lo>?(3@1p_XkWxSLI|l z3q_11`_qcX9B;#?OIwqDJd4Q{wAabQB~N)9Gv+Z*AEf4Wi#~}zYS+O#Yb2joK95ao zpC^ZmnJ)0(>tk6uEmE^;fQ$A|-#etrSe@ji1Tsv2ItmHYAg78wDVGE`fZuQ zpm)4~+TnX%hPSw{VJHt3&EdU`YA!aTAAyePg0hjlO|oxqp>y2YOtQLpL?FSfwJBjH z{5wx)cAqv;Hrh2wH0C(#5H9@!BI!F%cc z;XR$1Jkz-oC6+HJMuV6zPpkFL!#?}laJ(jt&OevwRX|;n@5z(2+qz@>(?u-^ALD+L zYsPMj#V1~XM5)Z@q>&@}u-Q3{(NX@i%Ex190YB(fvweDEHsfObfwl82^3Z+v@dBZ(N7t;Mz^k6GA6t z4^Jh<*w6T3Rp@vvL(=^%%DDZ^15;t6PHJMl zij~bDOINHQqJ3uaA2%`pI{B3cf7nXyCvVBF^;t0wUguWud@XA5`W~lmEb!2i`$$J(t$Xc6rCEaE{1|Kx)Ug z>n<*q=gC-g(hWFS-HUvpcGGEf%$l_F$D%f$8IZ~L+x0`cwhuw=#T%E_D^JI4W_>d_ z&wBP~Oyg`mFL>E{>Q}Zkm8(0YCxYpvYyE4WQL28Q5#g-~izC;C)G#Bmk7r#^Ug0DU zp(~irIb*s5{P6K*(4IBVHL%a4U|BUx> zdzWKCQ+{87MnT)y*Tv&4e+seXHQ4~tc>Hds0S;eBS!cUF=7ZHmk}Di|w6A8fa1Ztr z85og{yDY5%tfcIQ*vV&?5>xXe^RohmVZ3j@ZfV876-`_%?nGhtt^DVRj6~9#x-SJS=*MmWscy<)M3~dnX{@ zTFJP|uPn$=A^aqB zUcgpJ7G=n*=XQ3KW$AZZ7(_`GH{sAQdz_y*>$j}eDCm&Dgm$gFKR07yHFNTTsm8YS zC1XqghM^ZfQ}A<76@u>Kf=Q-|kPppABW(`)flP1f>QyLzOphMi0*Hkh+qc6S++RT0 z`)x@zFiOZvsBB`Zzew6hUU{vzV`HOnRZWa;o=(Iskhs|0LDA+( z^qM>!EX#-iHd`u7k2+ekhu1w(6DA45Gfn7RICamn{CU>3T*(c8_FlLa6n;DNby_M+ zRSgovR)iOV;=Sv_xL4NNDq`tqbnB_<>K1%+_2Ol^dO5UToUvf0mULtl>-5X3rhLQo z9lZ|9O5X6yjwQb5rf524O1pu^T}hLL1q>d$jVg(&4SwolQ&duc*xJH|U{r&HglU*D zKF6PHrgOcAy(-kB6TRl9ax4OYh$cbnuj_zeLkZ+wnbQVoXtK-hN}lh#IDc}VdqM+< zTA3fgD7rprhm3C-bY_~EcU}d~A;FZ4r$gf&;Rc^hBZ~YBgnW9yNKPiq*OojdW)Tfi zW}k9|@A^fq-a{cH!P2)uCWn>FC*_)G=zc1K`TGD5Qe~uLkZPk{)1X??XhSH0AnEJH z$kd7AEvcdL8q4M)IC};EIXIKH z6ZvZV9ntGQSD@+8%k>p}UY6TQX}&9ccj8Jfo~VOpjg5^pkcK}Aufi^~eUMZ0V8@dh zHr)7Q)OfM4@RYpzV}nG24wxkTF#V$%Rh!@*t2I=uYw=*YepYM3^N1#>W-i=I>_WY( z^ih?H_BPjc>wtq=_9ZE~rN@zY)$#D&lkpnrbZ*t${-Cr)hQM^FvV8%GcV|-V6OZGK!U*Qc;qE^E3|Hal@N5$1F>%$2I z2m}cdT!Op12M_M}Bx)t|I%w2!W3c<4yhI)<#Rb&7;ASdx%~yQY zQ(Z=6TWri?(hw3a75WenFqwmZ--Jc_giK>vTlr=b{tLDL`B6$wNx_;(XE&Y%a(`g6 z-@s>NWIT?2K`6l=V|urgx>g&0;rNf6JYJg7Whq7WjwMg$*Qf?YR1T|@;gI^!C>Drl zYSCqn{&6MH)R7O7LZT^Wxq006M(CafRriv2QyctX{!kXI=@IfXcqOSv(wln41IhU< zb#l!Ux`g-5z3jCky_KGinf;C+iM|j{K4f=7znJ88J0*1D;jxZ(e>K`9 z+}-TVV=xXU=;38)6`?>le>z9F*C5>YzB4BHpbDds_t)dcLL7}Q*jY?~v7@^GN~vne z-}p{2+pO8&e_{a`qbssr0dyKxr#2=tU#~IL$$;+!`Y$L7>h6iQ@EzmXPpfiA*?;xm zpDazOR(*Q)`ZWtsXElFfGn+b=IB!iT<*=i_*7h_i6J;MvdI(bemV}FB@E6bMu+V~O z8Y&Xab?C<04W&XhV_6wF+z@A)yi#nvTv+ zOme$2F2f+Y6VkGabKJBr+&i#a;WNFpT0dkG`FS@E+{@gi^C&{Yj&#;||h?Q|* zP>OvOJDDk5G-{hWA6?l-Us81ENutlMmLUImW2_q~)Xiq@y$*wzmIbRj-bf4cQdnuz zl|yQLN==8mAB6J(m5cB-f_f;gdbiWFlI0HcV5(|9Dvk+=8GCyjq9teLVBTMFJl=dm zEvuunUSI>qBMlhu%Fa76Kpc-@)$K%c+{S*w0s=A&EvdeJ{c7$9Zo-aC zbv8tzGIMEY{s$v4n7o6VbD2c$b)e0f#%Zx6<`C~iw5Y{{(_jn85An93Y0L!GIW95U z_`ev2kndpNHLrSM!d3ZFA-j9U{nM^aPeztWh?tKK@^axNm)N(vj>nB_ zBT=cZ#!_nTYz3#5FW$N0Q5;pDHo=lGp&E4IPsxp*J_ixzt~11omG!~tGU9pBUM%!_ zuUTBGPjPi|Z1U5J$Wpc;NAxRZoWs^rn4K{@gB?T3t$T~ZvFXg}QeS4Y94?|f#>}&7 zk<R(1Cbso~5`6*VrLO+J|HJl+t3->gEuQw{8Q|-Y5++rNyydQe3E?BY7EL4*a z*F$c{Cw8ktpFMY9kOJyIl=&BVz?kphF|i4iUAFHy_tt-w{k9WxVO$;i z&{k42`bgmFW22xaxVK$iP-RzIL(BP_=#&e*wea$=n9HWsKotxJmw=|KkkE?2j*xa` z^F9&4=+5D?_Qv?^!)yu1N^yE3=kI~uSd3u4ZL!*|w_4Bif(a?Y08M8|8!_`Q9Zf0o4#sn-v>f+TwlgE6Q!FmFQswx>cSts_{mo6}6S zI#5Hb+Ia04n`oh?}H~ zE?%5;V4b2;L!t_VH_&(e+D}VV@I2a-_+$^CB;_5i_7bmsC_>F?Ni)GJNrG;icfY)d z%UYXKzhmxzyu6km)eX0;JDzZ}aC!A4q*jg8$L3DmL6F}pF_*IG(N;qGQ6x;sR6=4w zFe0;=N7|ESA9pNOkXK<}%y!h9+pr3GcQnqN$|NF99&#EG!SAd3(Un6Ba52%QmH$Xx z!xmQlv}5U)O`6fGdsViX)dmwGkPHN^a9MGDB&Wn_bSIQnAi&0b{ZS~HaB+j%z3i8I=i z9i6@oM0)QSeOo53v9kSY=E(C24S5fS6xt&HE#|pPQh-K%bod4*!BXRvqjA)1sP~ib z+jH1u%ciUe&IgT@JS9nMj&pqB^Fi~=v5KAEc%h2erT$;N}42uc0dYNlvajm-Txm9J*jYsTc`;lB%=Q9xC$`U@+4hi2ehlgtvy{6cWvMbo`(C=f z=3++qmp}EcYGihP6VZZ5cH$U+rgI0TzqZ!;y2kLIx;v<%JQ|PM38e|-mv-l~OT#|x zbmp?WKI+!a!8ksj`4^lvr8$0^NMHc{>7XmyO!j3cq)uE$O}Gq$G<#AP-&mHakA9Iw z3j!IJI+U`eUR=|#TDiE=081sAPp!{%I-|UgPnn9XnaAVViT?Rs{MR&OM@kh+os)!% z9{(*G`{mY8VP@+s6K)h5K=33w#*(=1j5Kbz zKT_;usZYK(`Zq3HaM<(O&H5iK4y-OS`7`EPSp(}23SAz#ER`EHE%>}?CzXe;PG>SJ zvb)1RE5ofhKPd~u6^lgLCkcm}da;C_n@!xf@_kV@j^jXow1)Kj$<-ZBi>53s)9o_0 z0EL_pI`G}e+7h-g>iqIM;z~Z(?WsO>v7obYa2WlOJ0mt?!#5@$Pls@8vVRaAO~jg{ zs*UNWVJ=ZAyt zt+JGa(;F(=n#yEH;eW0_Sb+sQj?c2CS-=s)14A;)nJc9p0-v$?+x*M}(`J1zPlVXw zTo+8GrGN$n|39ccm~5QBu3YX~FFQ!fW*r2W#4ZlUo_zhhK2TQbKj88iql7tlGt{+T z8k)?9Z-%!v=O%oAoC&Y5y1bd`G({a-hQ8KSCd`~!5TTWP_rkjo58$8KKcUyJ*K zApi6A_%D4<{-{+y?dQj~hvyL<22J{g)xJJKJ?BS}v4Zy;6PTB}tylD|f3(3!gTy(e z8AWy-e9D8TMz@hnT?*{Wku0$xN$W+OdR4!lCrASeX zS>C!x@(TG-(Rsq;B190{#a%xPvdW~IvG^c{i}cf`6g+C5QvIYGsetb zI&6tWT+7r)0TI6CU!>2<&{-$1z@YsfkYJR{=WUkjLaz45hP>a7rt>|#y^EDfgCFWj z=B*fXT7HFvNmyZth09-ny5EX4YK=;DqfM@FZ)ML(I#_9GY4y7OGFJw^?v#@_l8cTe zw4jmfOX~QxyMZ<`D~{dX2RNN4Hht_ODR+NC9n~KLUL52txo#}dYML_KvKdv-+dMp3 z$2v;DzNl<+BhM&zy{d;QPM+J4c%mH#aiscMxzF&f808{wZx4vrth?bR-8-y2`IPle zZ1c6d21yW0o~b0^ShARr0HT}!tvmkL75MLe4|HVKzns@3ltTzL$BNo*`sab+aErm@EQ$GrZkHt}Iy5k7x3)>9>k*B}O1qsnyua+SOF zEtrrUJ3h5c8y=E$WypQw_zr(NgZWa03i zxB%ErJw|5Ie;^5;iYcfBb$hPT~*1D^og! z!SQNOGK=5)j(U{rKbr`Dj-!HugF8Dr8-9QKPV)Z%0F2t<`iu3Q{6j+wVgFYu(MSah z^2Vs||IyXMhm$#mU;o`~=hPYU;3y+2EBIjlf3)d;J%*TM zNc_J9BVp*&ixtlos$MMqH&XgJCZ-N|_xEp0`(Jl59Jc#l`1twXSt0C$Nk$kPP7eMq zN*4h~Y$VC|8C7~mC|m;#MflHq74^w~5#xV{y+f){?Dp~hJG_76NupK9!Znt^7X0Aw zZZwH0l4S+|c<-*||Mw+(30(hPBEesG#wc)r1C;qFev=79v7V3z=2#-ZZOEtFFF_<`7 zYMG8%H| zQ432zyqW!A#$Y9SJ6grqnE&A{{dZ0V4onT+!y==_R>(EU_D7!9*?{d4LqB`vWPHoY zni|*qAApY)Z5Z)O|LZJ~AmeO7su1tFIy?||le4$`8PIWCI&ZPOT(L)rB=n!ikwQ`q zIa$qT5ZyMUE3{RImcjdu?ydv#^WW4L5fiZ;`3B$`LWqvUkiXzT{Mxfb;q1AdpT70b z7ty7C1}4wl2!Aldvq&Ltn{3%hZ-pPrA}4Gg-JPvSV-A3k2;4Z%E8M=o?;68s$8TQa zUy8Gct^7(YbJF^C#JFXuqb<$Icwj!NY89=U?zO8n@Ir9#v2BQ9sFN&TZsfB$aj-{u zINn(rXM|(Sr?>e~x~kek56$$-???Ic z&!kF(&JJGwJV-i|jZ!l-xQ$6HRVn~@^UZBi1doVyf z?b3EBuIcq+kkN*Qk(;NEL)J{6$*Vpb4HCH+nXKdLZ?HEU$6Sr-Tb{r^S#Ni%ZZ@6c zL+dA)r%)h-hwEAX;4OtWx|rQd{?aZlaYQ``3;WmhRnumaBVRUitz+X6{dTO`bYGWS z>falC_W8cgWLH$p9(^ca?Jz={iYv;^#fhNM#WSKk>CO;j#I?EzhE}!_U|bAsMiGmv zqFNmiZg`&0i1CE0jy4!Na|rwBa1~7uD=E%0arh%YMaXfJ0a?=7yoSkmgt(#-ld&we zgj(fpauby<)Vd-$k3BsM52KNCr32#q;!N@R+VEAOg=TbuM7Uos28_b4&b7H&;}k$G zGgOBof{3X9Ekh)>%K0)?BX)4WCc&38g2vW$u_MQ@_y?MTUVyg;>NE6Z=FCL()G*96t>pRnfK-?YW#F5pF;-=-A)K)`j{)vx{jK_^jA|I#_{QNkF8g2mzNZzupJtHI8_3f?II{?hAIlmdT# zo7Ikz*UL*(FXwC-TYfX}CWAW-5G1WU#o*M`_GPw2zmd`V+=}&hONHl~yVOo#QNXix zSMlpnM&ff9@nKP=mvdy!VTXbZ^{UU;pz?HbmhA5wG5CGS=G;de=S&Gc=L*z}7Ax(a zUK2uDe02FS7o2`1ogE{t>GGv!$DUBJ*bsU9QT>8JKq+s|`I#wrELg=qPmw$bdAW=H zNAZGXAEc@Rf@>-z^mNWEnK(K7*ZL6J8*qjd8%QQ#Cl9t>VjspO$x|~9tKTF3U>Mfk zE~DW`$LcGvSFktNE(#hO`v#{0_!~)<%pM;pH+X}F%tgTfw<2ag_;^f+Xy}D5TNkSIW%a&EJx$0-Y_;F2rQ*SRhZOABR z!Qz}R-%l38!mOy+fgZr-OKt7AXlAQ=v{}NOKDLCUwRD~9=KaMo1?h$3b{~3{9`{t` zUwP-rg1QkYM}0wv&)8Pdo$jO+24U5)Oau_ev8lPQZw-oewZY`_h9YPAhZ%v_*R(j|jXb4Jb|<~bRMfN~Pr$&oi+ zmdzVFQ3pel};&&X9{32xnpPh*f1 z>#$Z+Q>YDRqADGmS}}Fkh^7!uxqsh|>Mb`y@tpo#9sPU32@0)!6@}=40V79XJin#_@2x z--niO2WqQ_#(7 zNkdC8rGJp~SYQiWnhEj&wN=XQBHFk zG%m4DS|Lg#w#If-T1JX3HzLJyE`tVW-Bc7B6+o-a;VcJdu=RfRzN0732ZnV3S&d^v zYFb#XM40euOH2j8v1Y26-Fx<#zBk;}e};XecOs`-Alr>V-DuU7**U|MndfNp>rM1` zd||&GuJheEeONUHLhkk(XGpEv|RpGbsF~ zMq$byEU#&J4kZJgbBvqBTwtRc*iu`wD^ezgwg21@G^yH{g{M}~wtbPQJe3FWGuBLL zhDP497#DwXy!MyS5H!b|_u|O?Yu-w`W3n#879`VWsnms$8>Uvf9fJw7n;*`R+F;3J zbrA(Yk8D9+5vwm8uX}07uYD!FyJb?3^smo)UFAT!snno4~&nqAO$o2vJpb*3|W6kW-m zp7jkIAJcb<->q=Ij*-mo(3-UF1?ed;Qp3)K8<3PvTJc$@5h#xFrAbI=nlWoqi2lx$ zTjNp38N&7g4z*4hjVZ99qsuvKx83|IzlaM!YtnnR!J_rtWHb*=Tle$;)-7bS(A(Tz z+vH8_uEJkmP2tchF32iQw%KN*jhDz1U)&|sexp?8ChMb37zk+;N2=Se;m$_EwLMOe!&|Q zaJxM})Y6ZA?_MC}YYd=Fs&KkE{AUW$rj_Z40Z#93`J02s08|~viC862amWB8@a-{) z!nSj%y#Oa|w-F5h9Ks81aehH1z7w-tsv$dONA2+Oij|gdyOIEPYcwVcC_^mjG@3U;%z)k{PY-?(JQ?H zW^)2;g%Dslm~N-a=T72p^EY*_{7hwC?1(zoGjFbp{6R)V4?q?!i6pViDlViG%wA?8 zU(S(iewI~NAWQKEcUczY;-nMpFj7CBsX{{IE(VRyGXhnOX);CH+186!L3y zGRwm_Tb6G)O*ZQFMy%?DI9pAYM_zu$A>5Ys9^9ehd8Yc~LGup3BaBCaRjMeK?|DIA zb3D3IsKA=VMp8QKPP^S4La86C^y5vDEUqZ5{nJ zwC<*I903m;*9EqreNr7`bzTppj-#+C${o-$qzS}*msI3nA|}l;ct!xtnBCPgE(H6T zj3KeVoYP^k0Gl7Gdt<2H?^T5>@#4?Xv_P#UnqKzyV%tYVjrkPR+j5rT6>YDhZnqWS z93CIAh*^DBq=l*TV;6t(_3l)L1xGanN2%5i@Nt@A%K-MEN~|xN(WQU)m2Sw#iVNQO z(0McEdDt!XurSWOXVXPTMC^$jO?|5Z)g57i9NA^2%*jhg)el+jYob3f83Wm-o-&@Cqi6oWu!#8H@ z84A6Y=0bPl`-0~t{kMr0Lut<~jS%Kar?JPThZf-&mZEF6ES1cG2cBca>l1*a$^y>F zUV-?1w=xjETD~@wY*KAWqf~)J_;bXE@t(eJl>YLH;@umbM9+m3A=@w47Ekxlt%RYR8T9<>Qk{f;depk!-tQZfepbZ*-c{HQERTYH zXIXNxghl)QW%KjD0v)h`#D zwj4g~#HGLumc2TLaLdGF@A=7E`bdL;NE3KoTievnox$1oOuxH!`stdTZ~xC(mI`A$ z4ka%yunwcp>)upn23qQ-u8(_0kW-DrG}S{B>sF5mZU}bg{8(H|+u8=7_4iOWJNmuA z4=ndr_$K>5ovVCI77q7!gR1DwbTkzNXG{^V{+E(wZdDR6_Ka(pXSGf5rf@qad%LXR z+j=->6X2rvqaR2m4GL%0z#J4U0ro=FbB_Cc4`jGmp%CX}j8gZ4vmwwKQLW-eN9K#j z#`&`}rs2!NXLcw*QL5JVozPBhX;s7c@JwigLa=uKk6qC%1UVa6#kI1u4a~=wpv2#b z>mBY0LaFoG<(G+^FG$azx$68|UV*1ZM1*2~R`G5-9z?irVI%)ponmg}n?Jq8dW%Hr zdjM%4X!pK5u!FV8Dnme|0gV4mx@K-M>uu?oCiDl#+IzcjDc8ej0*199p5l zTfYw;C}q4)RUAM*g%WfiA(2~uv1i-hP}{?CNW3&zH0MXTgGeoUy<&`J5lXznH)~qt z5DWN(qdQd6A00P^$T(H!qrfla!DVcJ8t(ln<&x@|zV&H#$R^L@b^?eGz*8Jm+1^j0 zU7PJBH`}{S>WrR;hlyIVJ<^zl-9J`D21fB!omNknFWtQ5jx8iFU$-mL0eCjtncT_C z%V8q(b}ur$kLE3@RmP#~TgLkF;oz>x#z=2<^oZ_ZO3q5Bi&58R?T6F;7Z>>gq z?wW58_GWh#Leq4|HO=x8YM}RIH@?7P$0>LhEFAq6*m6E-E?n2ilnUp78a$hqQu3}= z9mg8yp80aRi6Of~w?EnoAuWeNwbgrrk!ZX@9-w6m8>#g`iX$SO?GtGc$UY9Y-mtV@ zMCZ*E$l*TeW2L!c2f^;5Dj*Y@qipF7Iu*l8ezQysh&>yb`bq`u}IQ#1Z%RwVec;B$J!V@>p z&d|@X8EpkkMI}XLol(@=*CjBfKR_MzO3|ItJTRJ1`J5LEMxZ+4;w}2LFuh;*#bi=M zL}qpGwkuAB<~NSHH{O}9lTzEV{8`J3S%#(}BHt=Ylxg!>$&4i;v=*kYvnhPNdsn!i zF7VD8nUnI&wxY((h15O-8RGZA{1kjW&%gDz!A^xSJ;}vwVTp??fn1-uj2*A9?er=2 zIJ#L<-`Q{eEAE5GmW{mx?!Ax7*(Gln;V~dlaB^&^RrN?S8OchLJ$ubW#yl1PAg$74 zPlaU1nB41Afo8A_Aombw4;+3soQ%mM(2e$8#08yTQcW+3uk-@>k-k?`#YZ_z%aYD5 zRM>%@eA$;$4Jtf_7!HlqB68&b8kaQBK=aT~rk{1C>)EDj%|pyVLBX^Lxp>;UMurmS zAyYf})td{GYCA&~ii|8gyav{$FUb#|xBsreK+KiWoBG9PCO6Z={3i~o;X)r~JB@v? zvog&L-`XDb9C~{PVV_-aMsz#Ski6-3Y=C!x(+@vKuA4C;Vn1J;KLe1zU2kU%B72*o z_?(~^j}ZjLHBBDk5oMp!4m|s8GQ;ZWYV;2m?GNuCgaZHsmaHC1bKMM?MMS%*z~lJU zYO4kTG7o)sw~x9f$wR#EWCTk=>xam+u@XW#i~DLWx(=b}pL^$Q&Rv5oPRYgz>Skt!}@zmgR`M+X2&C zc-``EErn$Qb}*5f1&8yS>hNqG|2`dhcFZL$osDYjbn)!8#R^8c*>9n^9pf2iM=v6Z z%}c}K7T6XFwRIV(zcqetEleTEndWt;o6D7$_Q z3nVo!{$y*sv;|mdAe8UUlQg|n-^J$&{YHz$YJO$mH8&~t02V_m-4#j7mP5s5PeQ{L zF3IZ~AEy%vHD?{4_*J7IoaCOyaHXGA%54T8^U>_UEGHNZjmGot->Rsi7mPA%KcT;Mhs#ARdVx0@;Or)@nsWN+t@yU z{!>mz3aEIwodU7^M&fpR=uuwn{sdMVz1rXaS35&55A@7BoT+ky`1J&vbatRNPlzml z679&&%7usgMv#L+X9~4=XYQd2>Ui9hkFPzflGVH3`Wn^jBK1Aj*sv*;eA7(55wzL5 z+d#9Pw^b4R&cg|Lw7pY&dlU+Dc^i6}d+MZvIgBk$gVDS%@0Ci0^r?&%A*4O(_W2@D zowwupf|+msCUpLcFC__KlfAGg^F2)0z1HlO$*Ss;a&gCldWE#(DHd?KBY8jQ^or)( zF`3g9z{w-Hw`Ik##+mB@`mr|mAs3%eEo!iPoz(gVbX%i~&qZ;;bu*8}N}dlXe6 zALm;iW3BUqxS!S4=XPk`qgTCSmwB#d*F0;O=Ha_s3Rba7Rnb_5znzG^c@7_tUM4&p z{jl)Vkn<-Wzq*|fNNu<55+%Y_WOk>0zb|SiO-#lYs=Opvjp#nGH*zU_Du_T1Il4Pt z9)Fm(`I!?G`n$b&smW8o*GeY{8t-v~)QTSwMPqX$yXZ@`aa=v$ytbEty~pH!5Z+SL z32~M!9C|8sZ9<;Iq+F?VNY}H%VYys_9brkeo%u+gfQlgA_~g0o@ICUm7Wo60w4eT{ z-cX-P<+mT=ywFp2+HusK>3etj1s?i6Sd`q)f1m|7$D<*)pP%0%zSoG}*!xor-4kp# zS`tIXc=CipLKZMGbdoHz$muar@41@n$m`qY_ae?6G3TYRcohc8P>^6bDY~hD;jRXz zO@DwTC6|%o)s_Wf%N~lH^CbN=#_i3oZ(nL4iF@#<4SJ-tGgLQab6ua!x5F9UqAySF zhQI=N%wx_oJi{Io0`Hi)wsDuWR)ECOcxTf-g0Q_!wL@ z^Lwq8 z{DR3He2x^lU`u0mV@A>6qAqG2l((O?1%r3K`Dg?Xpo4>F-Jylh!i?*%7Our=(w(0x z^^6k_{~%{RBsCAr*mU%2{8;C&P6=uv#=7{qMqi{ z8~kdT;*e~X5tRVV{-d~fEN`I5xtI!D=g|4;hiXsUvR|+4v7ohW$F`e-Mwa5eOH+tj z`$u2%#(saZy?a$NHH{-A3%>f_%wsM#L< z(-C188C1yS;eD&~CZRc&w~V6U;l2b?^-<&LRBZmjOm8!TvpAB8VFIARRXM+|rbnmn z>wBfXt(LFi7T5-60j-gH^5%q()o6rLsZfsXo_)goKTKmnLT+CEeZ(#)x$xnzpzga5 zVPfhTC77pi`r2WYZ$Y2aU|%~BvNAlS!r=N~s+qY|Ez$62tou{HI{o36h9J~RRwg+kje51e+=?HmC3;r*}n5@POcTF-Ze2Xj)2(1Cp| zY}GhPZ54ToJ-823)qs4O==|;*!^tF>2L0wR{n2GHWU~vMWU~!=4Q@l!mvR@%c8bXop}F%EE!<0)5c7UDtAi7X!*y!u14{W{LNe$hA3fFs3QR}vPDH;t!v-n_1n z6{r?}{+r=t69AD4n>$c=(;a7GtZ92{BfsSE9}?A&92pq+#y=*BGh;0Ba;VuB^zi5>+26f2!u-Tp{OoO#T5Iv{15n0t*|07Cc}9~ zc9Rh9Df*9F8(@tWTnZk*f~A{9^pzQ^#WmO3;(b5g4=y*w`TmqP(7IK(7!i5-eoC$TuVT0oBqH(ws^K09wy&Yfygg0Z)W|RBvX3jEbEUMxy3|Bg@=nh`0Ihxaxk(ZpqneSDJzt$SrUZC0fv$y#>N zNpW*l*UaqPagB3CwwZgkBpo&}cxZ#`{QU~jdKw>dStsty?~mkAsgRbB^(YfLbuhpB zNH@hXY&s)Mtr`Bdc4MV;t}HUYMZA(8yp$x9#cTkMW-5OGIqKhw06&)6&J$_gN~qu@ zVx66AivTpQQ=M~&LLkQWmDBo~qmXrC4;O10cxRaLvRN{N533v#=JS<24X)}#i6S58 zj?2OQb0v4Q2q?*%xfbQOmLmpb!o=iHyCnZk(n2O*P*nFMKi)MjK}_=BtK%)X!Z;aJ?Y z3OzW#QA;^JF>cf{e!u9ZUYdN}@(5qc<}IUx zXxci{0i&61ikuf09BA%GjI69U=Qe`nOHT%>RamnWLxV$;7vv?}yoNqhd|I5bxAMTp zDoe35g`RHsMix5L$v#2uRm1PC?BKE6yNB?txjz>&0{MA=-nR(nDFx#SeFy5Ea4Z{n z-P*fxh^T#ElcB)5&tW4k=8hu`bjEI#MN#T=-^JHq{J{5SOXr-%{0EyT;s4s}rrv+{ zNg#j@EgwJOj|}Q#=$%G`AP%O$h9jc)AC&lu4{XiEE2KoK`K z-}naeh9<(TY{&Pk&N-k6a~Yqm8>wWyfsjmu7wJx&P_pc|@;Ygs0(;*!QMzPHKZZiM z)09hS*e2>9(>g5tt@L`9Gt zGa0ia@oS*S4q>khm_`-I2Hfv!)joo*T&jJ<$nD)mq{)g9f{)^=_@sH@@~#IrsjSIh z8|?yatm3j^f>7$;L_gWCk1Mpd#Oc{?^{zi-4-tRRip2J&L0-Rn5|3uww#+V>E$X(UiWW(^o!u-`Ye0fk@tD8f= zJArS0b^lH9%=pzrJsq|Gfb|v~*XS)p#Le;XhhdoZy+g?(9|6I~~ zPp4wu$-&Bd1=Dlkl$B$l;;7NZ!oI#yd?wM#s9Il)&hz&~Cj>mYa|0B28-;&OR&9WQ2;SGdhr~NUR*mmHzImSc80+HS+!Z)BHy<>#ts9 zN=oz_e|uB#OAQ}e7H1Rf z0h8Idzt$JuQ#Csh(~IF^eM+~uV{e~N;x3bF4YuCBpCQZo%XGOl_t{NbD!!YRbosE&jF+y;dSuz@_A|B)3uDmkq_(X{ zuUwF2+$Nvg%ir8s#GB!zhf$?EpL6hUzR(gL>`DKzA*QPaT-~2vQS2dOT?ApRgz;Hc z-AFlkg~*u9<)DXLO9*c-Yp@KtFf9OPmCrwn&)CY zIdVpkbxXf387t^?*6h4u^L4@!&A0>#UpF}ie08JW?18o=?n0^Aoqpde1(j28C7@4i zB;fNC2#e^Gntu%~X~XNJgV~^0%WDd`3UuAXGSgl2ET1c&XAKW8SB59&PZZrQ^_u9OqPznDlJ|q9!q{)J7GpiS+a4&Hy*)y)v=@rSesib{SGd1vFp86qBvJpi;gEdroyg-sktIV>_60r?mf&s z>eowR?bh%%*2D)_$CELtwUCQ7qaHTXw1ZOslYHfe{?eGveZQl+8lA-&oh!lB`rnG@ z$21!tXcKLwQNXb2JKBQMui>$eT1_v{L_%$ROQ@r-NvEylS9w!Cp(aWa)ltN~cS^aU znf_w;%q5B*Etcfo`kIPe;y4ZWc3)qL%ax1C`sJoB1!F@#H#V$wyH>{b_TyPXw?1 z90^lHQ(VB6Mo*g(W@mSmM_=k#Kwq`a_}A&F#-sb^CRMMQ_7>MU5Mk}1oZ{x<`<5h% zsmX10Q}1T9zg`()R2UuP7@ ze((EGG7sNWAE3?K?0oljw(jbIp^nwFy?JIA4~R1${`BPnjf$-0lY6rtj8p&=j1=`i z?hi+5C8|UydfVI*cb>>~V{gG=hwDRX|OM-Oq&^2!s;*Ig>Mp_P+JfMiy6?xxNHm44$?IO-) z4xJEL=Dkq%>(I!I>%Pr(JH9c)IcY3#W)xv}|KZykqvy6Uk?QH8o$|h~mFPdVh`& zCG{>lBuual)#Jbb#D&-cltcU~Af_KSxNq(6NFkG$?`2HJhY_}qi@>`e)+3$gPp{f)v-!W1G?z6rx!9JeRasa^M>2Fe zjeksdCS=4$W82B+3r$-(c5|GX^C28oaa$=6!J*njGT_zO(`ys0ZgJNTR!PmBM&g}| zBM%g>Q<-itbzEq+Ijfw;N=WU&Buj%2lZ|_{YS^7#A*bru1{K@lt{}9dI|75LV+X4w z-@aG=6mtdW!hd1`YRXxHHV_LIUww6$JrpmW^zPPGsWxi8_CQ27hQ4m$ly2zjLiJj& zUhT56Exz~PB1JwTm?|65_0tV0j2nljO14ctB#$Ehq6YR*HgnZm!$|wti4@M}Yc$t! z4%{9{hks)wiiqVWq`T(%VupRFF1y2r5Gnp~K6tPZIbR(jI(4P_w~U4c!R?NN>O>k! zFP-jrmR+0e4CoQby-fl;X8X9pT#T6z7^M~j`JAlmTWTSk zYxmsz#%mT<=tpMiP(lqI+Rzc3N-&32Vb7ADKFKhMsA`u4eEX(wRx;;~xz6X3gA0#z zdH57TPp8Wf8k!`>YuNdq{Qezj_ZiEDAqBgs7(fJWcTW&}98759e`IX}@(+@k$6u4k~sn^DmxH_Ij zwD*?hX|&{_Z?y9T(VgLfboYAQlpq zymEy!WLAa~#U6Y7I}M4Z4Y!9!`qhqc?fe+8;OlfeobY1&)Hf5T%1MEb%KNyq9>dP0 zY+|VeI>(tD;%rfITmyoxjaMd$9l0why~t_=nJ?D9{i#t{%q0(CZsx4CW#Y;3kisNC z$iK#?eTKVmZNKU275X!Zcsk9IB5mZ;AN=IFgk3-)>rS_7@Y>gn%j1;x&D)tWsWu$Q ze6z=U%`?WL2*Fz}_hUVh<#>h#_QeNsE0MI;$cklpbl2o6i##<#5y*d~Rt<6G;16N5 z+XwXV=H3~lL~#LF?{H0TC8swx=uT{o$UhAvI_)}4hSl9*dd7U6YOd=|H^$#^3`&-O zSasyc&H2@00@i-Zwb*C}#ir>*)`TwirrzYnMdvJBqB92vr?EP^Fvv513^$0tBsBFa z*9;EZO?0iku#@PA5+Kvs=~JoypxWhvJdqV|H&AIdhFvLNSr8+MI%{z3O_#pXf)n)% z2lI)l7aVQ9%~`ae!UzTJtgUjU(@G6d$seIf}_J`q|6um#TQmfmi8b;5*!D^4<09Q zMk?~B`cZ{H&!t2St55<|A99tu?l2`A_Sy(KC{7Io7b~5mFl*BgBa`#{OMlX|N|(x< z8CaLzkIVREbR^60%?V|1nxZmmz(MDb`yoHsQUUPC@RZ;}7yDVT$m96IkkFHuC}RO? zO46l#^i}eIzL3U0rPZq)h1nB+7Fg_Zp^~*~$JAP25h;S@0<2eXYb4`E`tBvWN2b2+ zQSQI5MhcgUD)QtV%X+uf~4>^>-NvfOD%H((QDFRLKvFC6DCwHGREEwXZuh8a`b0%+X7nMwjHV|~i zbG}mQ-~QlFJZOWIYrCt~;&V=vtE_LBsqn+2zHyIYFoWT_;hJH(e~F+QU0B_}(P_zF z!LF9M+*x2^&##`CJ<1$TACvzYtpb)ppGu}Sqb}U&I`*6rk@snU9m`TNAa5#H`MW^$ zdKi7zUPY(=_f__QX)KYxw_hI;DjDaZQ`6zN(P(hXB{*|L550a<-y-IrwHbT(3W=t2jsAHegphHe43xKXjh zb_8OxnbuQe4_Jw>q*eXldm-dFbVcg<57f9Vh`2WNaW?Ln!f^;hXe%`)!s)?~W;%wM zdCpClPm*hWl}If5U2lwT0}Ka3hr^K2giV8$<93J(S8T(@CA?l$NpXCCQn2r*|6*s* zW7Zey9+60P+gRGRFL5mt&i^b$YOqV$P)Fp@Jd64<_`ZW2C4GaVKy%cKMMqyLVvK%B zDPJliGkv0SwK-*rWjzk0YV~SsQ138k(=LVkuF7U7;XU`*fEP-&QG|ywHIk-)I8UOsCr+V!ckxYZhjd%V6Ryhq#ad+h#Cd63v z$YpFpiBl^H8m?`P^Ajt6bHmQX1tqCNhwOj5OD-9V?P6k=z9dvgr!qRykuAS>hjqe~ z)YnnDJL|Q#CXOe=?Ym3}+dnVe%_JX1XSj3U~Cg>wm}ZQVCCWlQ~*Fs)tt83T6T zIAHa%ytwVXPE-Z+)tTh#2KoI17E_?inD_48wxO5l&r6+os~5=hYw417;c%c$KOsRw zXNFki#M>gv?$*$pK4GI%8@;fa{%XOTl<>qp#5rlGc_}!_$KQurL9O@<|JdcIanjP3_K7GH^A12J|B-c9q&tsShp&W*LmO95EmKCjNsfxXb<}p*Qr!+d)fmS4&)Dsj zsZ=lbTk=owWq{V7*prPuKX~umYNVo=_;+1%M@0|Rca}6eAgQ`=gx2bA%+Jd{Gw)WZ zN4^@$I-E{!a7?*>HICzat~4rA5u~$9sy>*He!-lDwa59aFv%D8A;T@S@Rag$B9PC( z_s8xdc?|mrRun}Zi(6UA()GI8e97U8`Ji`MVcn`z;xKqdi`8s678Lx)kc0u`C0Ruu zl9@Pdw0i|td9qL_mV3n*+79P!H8unolb;VTVe^zU8G! z2p_$dohhGyX>v(nXOQ4%vnsrS$9`qj{{5p>>r1MSVY2i=27LeFq_;0vS^oT~x52As z!?b>|gq<2@ks1gT)a1{;l5-vLHoD*-8=o!Gp()3#QmFjF(U-RYUuW_p58<9LNb2th zSG!O=ET*DrIUBFq{Q5i0l~(%pz@Xt{`&~Csv+C4ruJ~BPpYIzGGAtJE~)Um zggzL$1xux>^E+WJ{X9FVpJQGIGE-w<)tZ-jgCi*o4iDws$FO>G0FBKQF61P+89R6T zsz?!8He)abfy8m7@gKJ0pWU&*w)vqsMbmFej`6hj&+D_q2341M+dExzIuV+5>(*ln z*N#Ek#~>0e|McW4hbU6}3#`fJCLQ?&^2v8B`_S}qf_mS<~b6C2R&P@sMoa6_Lx^4KxEFq@n9WM1(ia$-XN)Bk zkFO*eb5&q1`y!7fjS(->BJ6oin2s#U>@JXW;CdiHST9EG`1y}%y>Q+1WKyVkf0rzd z$tl#7SpD?htOH)FyxZ$Q0gnrLsk2}4o8CK^*AE>-r|24ZoJu`{0%Gih2?8P)q)Lvk zJDalkSMDkGQq`Q9=(C6dIwZVa6*Ct6a6i7&TMRw*OVjeeMk|jD<%7L6W9I55&%v1j zb;l5Kg`CV2lRJTrcY2sEXvgw%;-9Gyj^~G=ACef{w@3`=p5P)!6AR>fxyc`r8P5+C zzmm1OUWoqbY_RgR5PTYN4tIrpWGSasveL}{!ige_&m-)R=Ebh@@XSnMJ$?f>lj2R( zijH+&Wi*{9Sz-fcu0nWR7u)zL8XGOZaTM!%Mn)&GO0<$18#P&jnH)0Imte>i5^mRa zHcX%z5{{;FlANgT1Gx3xHJRoU7-5i*7Q9MnDyZNqq{}!lGYv; zl>VH?OkuKw=V`zErBSIw70z_W9bHCiI5W(3Eixe-4fg%?*%~exj`JFAP6`{7=<+0Kmx7GY-{1V)P5Xi0vbjBaXU0^*B1gX8cy`P z!c)dh&yrcGH>7`Gp>!hP3gQoh=znE0;?{NNGGK2?Yrr7(938NP!D7B)ZiNO*eN?ad zQBM#z8qtGK@&{)EsDDO+%#~olWJ(e_(H96jcqD7VYv25be*!a8R8%Ay6ZL=#i@T8z zPJ8P-MEQ}V)KFhGI1Q}^z&>CLe7M<`{!}UyB-$5MT*45snd~n=nIb==)j?}~r;q#S zj?9%+U~@5-cNNLZj{d8){;)m=qT@&1aAw~|Un}gH23n7k1=PmJB^yQsmXgHf20cvw=F5l|O5Lb7A zsf8mhKyeseO4~P}jjo4YDCqKZ-hN*8L@M>R_PCCfYVPG@qLWJY8@y+K#7c<8(gHtDhXcaFJJ$1&PWI(fn8%aD@BI&&ae|N1AnTbu? z@BAFO0DN7&7ujq@M(xvpq$Duuf$LkH8bGl=Bc__He~;1pHSP*2VvPr z>4c-GxsOU%cOf;b&if)5@)zYUFt87*#Mg*WFuR($?sQp;O}54kS@g9YykjKJ4`DIY zH5fd0HDtV+5+>*($*lQ=Jj56wM6*ubEZ8RX`pJUa)dycix zjItY#iIqzP|LGhyLuSG;u$XtcarTZfFfx@qZJXUKylH-~uw{)2kEV2N=68lZe!E($ zPXy9APTO?t=Y6xO2Tz_9v^%A^`ur!y;$D~!Mc5`qMo$XV)F${(tpsL8CkDzMQ zgGSiR_Dp84n*^MEhPIIonVOlQw9woJL<9N<@ez_3`1Vs5_=7F3>?*LX^QxDb{=P@s!ILNdN0-2U69|N_3Ht405n7y{bP)v`@M0L;M zv}s-0oRj(cF+8(4`f+}Md#af>#V zvy?cxqBxbIcMMPlfa#_!idL}Y5WWIl2v9Nd>f^^Y3I-(COx5fSMzF-*4J89|I=r3Z z92;-AT_{n?os(GerJu0xq>Y4w4+b+UFS<|=N+<11Xg|tXB7LtD`pcDcv~Zb&css|o zcsf_1Wn|~JGAZ&E<$K40Uj{hQSCaBS7G>2p_Fd20DFg!;{GuVf$$Yw(2OLvbPi52S zJ~A>0u4o!cX$p6`cQ1O&ya^AfSPDc!9+OVQ=AM=9)Y?+#$|o+ZW3?WmK9DvLaUzUi z^xnqIO^hokW)CHg_oG*eVlw?1TLG8*{VCq<3#nxJBPLdhiLCLiS1)}cv+PrT67Cs) zLU{Tv%063-9hVA{94k5L-BiWaKb}&vtfJv-w@Y^CMjj<|by|m|H{9%1C0f0RN?zeR z50&=Kpx4q$zAe*IYt{QFLW(H1Xne6wUVN#bG&1K1Tkj$;>Zv{}@o8aj=GOYwnM|e&fkz0ab|9^R zaC|?M>2xzqAKbWz`Ctow#iPOL65Ce$Iomo84DT#Q4G%4u#3r!X8zhw7mNA*yFL-BL zE6tdS766~ltP!yR$7W6gx}X&ENtHaUD?0U*rz}G7cuyc^K$D!4PuX7%gqO-n# z=?$RmZo>|Yg((MfVnU6j=c8+Sj3Xs{j%{69N!91y@QV%V= z$GCd(rlMoP8q&;#nF)d00>(`R?qe?ujIACE9EmGFdf&h&JwgO(i#VWH`Gw{a4(}y^ z(k!-_GxZls8+W(zP;;RB@mtDzsJc=zR}7M+ZtTE@{N|}xyTbJj9+-`O!~FR@Uz79P zMzgPztQ*tm$c}1vI2jni(A)_$f`9vMCHY{ux1S+}_rX-&_}Z^8$mx)1KAG}4@JMBt zM8v|~IxDHZn%;jWbac91{=Vda*{E_O0lN3z{xJT&KFZm7WBNIRh}niYy(7B9nCxbU zAbqLbjE}zz4IZmbzCZ)T0>d$?%vOW(fKKE*Uv-hs7lKPV=kT^*G$GT=c;!#m(t(q; za>xUg01@2GZqC{RkD8h#QRDz^-bo1l?o>cr?w7#%^Wx*}rPn$uoY04=-UqZprsmit zGeHmLm#v1ic@%#1e!9d)Zl~#SSTr`;aHEOZLxRKFxExQWptvZZ6`5;=AZR&W`H#Fw?MGjL^(N0RI z(?1cky38QL!+JHLYjX$Itv3HjwU)b2qHK73*?K7RGU`Jw;#?ulN0NZ&r|s-d=z#%> z(cMvIhk{KsNtFu|CpZvnI{eAbe2mtvR7LJw?K@dv3HsZ)li2XV$EAxoq^UbR?d0qW zWx6S*vc{*rx>)ie7J0dSfH!U;1%#jc8{i}E$TF^>4DZ@SYozDSy<*t`fno-rq z2QuHe8nUk8EOzP+Wm&72M;9%gs5g*0AU9}qB?kxwE=P;*sJSbC5&F7QCQbIYg3T{3 ziM)MN*?aWR@U?+`ix%XXL}9LH$SIy(pjt{YB}Fl*HrhB2wgS}jP+0Ox%sGp9OD!kG z=oZx0`nei;cm)}E;fBA2%#k%apNs58!O!AzMxO&jfmSa%Re*EJ=pXN-X&E$!TBct@ z**O1H7_MQ)m$GnhF}Rw4%O9XMSgBjGLYT>Mbs~zFq@YZqyWB@QV$BLvV}BwEG1IGJ)^cN>L#((q2>`Yf+yXZ!X8|lY7yL0c%;c%RmjqN3Lhf!D4VUp%YBEfyXo2DIO-^+5Nu4JmNYwhY^DZ=@d+FUq{~$;wr>Pi&h-X4mqHA zE_}{R2A~@Nc z)Ge1N4eQs39lki>q0AD;PmqLHmvlxRLjn8vuIBmM6~b6*PPBcw6zaSUPKr>xOGQL%{=_0^}Q9H_6xym2iIKn3STWF_)A$ zE$Zv_{TW8rTgGDIf1(ysbtZA2fS>d9>8#1E@TZp;x0l*ha`9Bov764_+He+s{|1ex z80B5}#(|ruhW+jk5{ProuzmmF0ONo~@@%m-Fo{O9sILg>s(S0>Br-X9A#@#a-Si|$PE*zMZaZsTIOHP6>dawoL zkwUAF`gPU(3NLOeo-$?AQ;bw^DE~FcXA{ZQh^-bK0mX!* z6`5MYs%235q~4+n7FY_-0zPF;8_3_Uu53{yO1g*miW?m+Cs4k?X`C`06cxDo`dn3h6q!MjYn#*Ol|3sfi$Uk+<|bdO#bH=ueIk>~e5uY@!YU2%1G}@c z)6L!8`*0j_yW{%qj^z9I?-Lw9Xv%duoV`qO9 zv<*QdKntfLRLJU^^IbS!YonoTG8}{-Nur7D))TAG5XQ>bXhbCJTQP6Yh!V-~i$@gW z{-!SjB4Yd>uUeB)Mw+(rFG9>PUy}T($0A$uf39w|K(l}we=tY|Pp+WH$x9G-GH>D7hF)K?Ib-+$PY0%5+9fshEKFF;T?QZ$nYymE->E9dvxA=cnHxH4r`#&<+f|dy^PD$v}vb5!uzx?ZOEyZ=K z|Ht6`Tg_OPp}%+4e^wSs%LNwv`v3aMD;ul~Vw-pAL4g>f)0(6j*EQr`??!+vAlcIc z)PMF5R-=p74`FU6kjh^sskcu!h3%c|`w1oGEgqhtXXtihMp$`x#wuu)DSi#(uQ)A{ z&l%B|S9N+U&|nbt3$3b2y>QR7*K1~)Np)0e{mzcARYpxv^R?2XA-lpR=nE#i zonBgwqdDiGBxyZFhRrfhmb=lH{U%Bk0m;3WFY=alzZu)cStWAQm>G2 z9l%iCP}d^^=|12u*w`laj z!AzrxYhw^vfzAqT^V5aN(<$w2JN86wv~HX(jxzo24;1V<{YQBm36}Gp7{w=6>b$Y6 zEEjdRmjv}rp2aQe0`2*#tER!d`tFbJ^O8O3PXIzMzj|n^~(H3|WWy9OdLMUkP-E2{vZ;UPsqX zu~Z=5URHGpk&!$czQA>a+Rx?^;k`J2H~mfcu0bDH6k1igdf}R8%wUTbY-hvIrs3NW zBq^fGZ82LA?8-Z`CtCszPT2M=-!fr^Z*u>;P2JRi+;y?5JJdY;#bMkjiY3!QWF5-% z+H^F5p~6ioNu#nYR@{B0U;9Ljw-rq^>(S1^g=V_&KAG^Vo;Vk|x&2LAfZ&lV7V|9A z{0|cp!2N{jR<~T;!4T@r#GkPAisO|yT1Q#rxLk5&3zqGhFC-M^>2_mKu?BH#P0}J< zVsL#Iq5H44-NrpiCraxKgmHuoJN$R1&P~VlPbXO5X)cClSe8{bYD25%>ltpX$=ZPu z`ZxHls$qRUs_{_AA8*;a?k@V+A}5dvZo+Ol``;k{vVaf;t1)-0E9cMHrJUQE2rX1U zxle-Kl0@vh?=l1Ch8TyX=k?o}lll2{`x@`9?yXN{bnq}=RP)7C=~B5aO}=bQE?O^)R0uk?oLNuRJDjdpqOVL?nX zlmHyp?f9ffEaoRkY?*TE_~kxG{nmrtUot$YEhoHgQ}9DMb-PfA818jka=P+@E` z>fQ@EJhR?dMMUxOp+@5g0oq@&W;GrCgaH3`V?2^WvN}2)QyBW5XN(Rm;7Q-T5}6wx za&0;&?KDo9Y$S}G!)x#~1oenbMX&z?-$`WvSK?IuCr05cnci(#l{rI>_P7WQ1CyOc~SXvU){G%3!YJr@3?9`mTRbmZo|%Y zhVq3uL2!-I@t|Pe)Df(@142`bZ`v0xg~!iR1k|ZwWqj;(D{m~e9pi->Vo_&hu380dab>_TJR!^q&9jLMGO0W3m5?1q(U>u_Nx6L7`7{qOXP;H z_G<$8VCQ1$D?x&&2=XGJ&}Bj99M8mePh7)PA{93RUuu&KD*5s=dQTELX?N!f zc&pc1Gz-V4f3BgB3AN29Bm1<7UM+cti!Js3;AVyn%XtH8*+X@ekvwN6H=cuMo2RA( zFCnPeor=ZJIzOcD-kqT{^&KsE+ypH6Ii`4WwY=HoG5Su?$N}g!xt`mRFzfQ`YM!X| zPEEX(SMsq^@LVYCD{&uW-0_v(?(#(DsvK~t!0>Dc)XH<5)A?br@}`Z~Jw)-l543)` zs|DmyEtFS;bmdkByM2JWwDvXuy^O#I|9{#JL1Iwi*_)@UVd^hzjFp<;bsB|zQAvms zxLsl0Wj}O`$8L@fugF!uQ1u$eWJ5rc{z#8{Q1rUp6s^ufxn+`RC#9|duaxz1 z13S&NqgUUqlm0~qQBT26;sVt$u7p;X@cKyUy~QUJqihefW7H+EtAz6IO*FvZF4g(* zpM?Omb+i1zaCTt*pgt6fn{6F(>P_W=qL}3DiL{cRwb@N&GkT|6Yy}EPS#H5USO2tk z7@!y!dwWG4DeraLfo6;PL@7J}-V+h(GJEuaw`VQr_C5)tLtqc(?B$7i!OZEy5r@LlUIyc2u& zNRhojFgd99wG&oM(hnF_J+<;h+}pvC8ocG$`V)Y5t-UP0lIAI&4pTNZjSp7;nM z-_(2HU*_pm40YOOMVUo_Z=S@D>vhePEV~c=uZwNl*gIvV0g5WBr)XdZ7kn`f0kKD0 z-mlWwb0FN2&g@slXyQstvtGVqoDqhyoF2Jaya#4+ntBeK7?&Gt+f-h(_ zX5amxY62H>L&jm5tD6`u$bFS$thM|=ku7L)0320@+n7wUZh zu`g6%faj<);=x*yACPA+4J4YUDh5Lytr)aF!y}{*Ssq|**7kupmPkfEKrt$6Kzb9@ z-tP+aN9>5{yA=o{`infF41`$%0O!rsTM3 zc*ZL|d%lqK37L&0Fml6mk2c~yE|6{aC$5(Vl5@veCetV6iBQMhu1`na9qk&L<2JJX z``$9Y_+{h&(ATzSvm-8q;1`bJC=sQf%F&>749K#x`rG#-gi&gq7vo08($8tIX&N!A z`jipTaICe8L5rX?AIQ&??=T`3hg1T};5azxYD>aae^x%}=LVJKgowOXs-5gq^orPm z9W&_!kC0GY#mZTgavFh`^Lh^Kw5hVU_!5_^O6Tl6OJ`gy^%hu6T$$`lp<4^LF`{6# zH`D2&Dq^bf5i}AawA7eV3<~nsy8f1_{f9CWkq0fx6?js*79&^KWPx{+8*1~VUu1Pp zO$4in)bf$Bu_MaZ^8jsMtlYeH{C^ZyAQQ2uB^GO^d%a%oShYTkjLz!J4dudZP8>;B zbeR1Fk-JSm)AQ^u-+ixfAT|w-@#3oaR;5D6-sA!iZ|Yj0BgZL2ZHD?LcK0>d&O?Oj z{bAG^`gVC}*W+j>#J`gf44tm%y~7fB?UKv)eKq4+*4K1n+hsRl7?y~phS_GFRFA3a z-5cj*gzri?T#evcOLqe#Df5K-Q-QH3M8a5%^(9N=cBo{>&elDDej#nn(_$_eaXm z_r*!Yc!AHJTt}Q?^@N4X{OG`(kN-?Ffhf>U97)PfmJ+Q_;;?;nQZXJ*+ut`cgQH&e z_?kYrZm~K&W$u7xbq8&shN)kRfru_a4(-9U;s!a4rm1-wA)%(GR^c3qgblH{n5X)4 zO7y)lBow&_+3?y}%?y*=!^+wiQ^$+?bV#ul$zA8;p^X5u$rZ8TL|T8})$wuFm0oze z4ToPd$o5_1cl5k&?dA$73;{An&)7DURDjUCDkB!a(NGW4aso)pB#so=^)%o=C)cg9 zv`Q)CL*R_nPv*S#^KzQz@=NrC26(rEf{_PKZX}>DQV@spinmLQ$J!T?KHs!$y;<&- zM?~{9il8h9w18m8v){i2N}JWO8qbdDD@CN$|EUjVn?Q*CW4bh1fwl09wklltR5jzJ zh2`$~VxVeIU|#l~)Vtla$EX+R?#b;>=iw{7V`FUIUc<-dWHnape5UB~5G;lcvqLIR zIob3+UQ~SV<~tvNTWdmD-p&6t^>@|4r~N3K2&?2zWkgrFg5L`su(^xzfVek3wG00$ip+DfO$dq%Xz+!%L6dn@09Sq zg^N^8CRk26@WQ7kn4M}>rGj`0_>jDTk)-^L@CK#gY&4!kvJNAHyEMz%3d4X zI)K`U(95jG>%#3C%v5|?Y&ECy1ZeNC$~M%{?9L&1Ez*s-16+}#h!*GfS%5B3)KpynBT!x;qeMKG;AWbdY3 zkdK(5F?uK${DS|D&ZP-{r~IvY4B;ZpN~t0R(s~h%R!eqM9QTuu-3|bL_QQiJEd;n! zcj&uYyZgP$s6b_~Xjci}(d>f+Su+svB2m~rKINxN)sl=~C$jWOOJB$E^gO&KIFU|A z&nv}+M98%gZBeh?-WOGp??M(5E}p|ZF2A1r@X}?Gu^s$!by|jEi6J>0cE7v6Wj9-d z{kAo7ckqnav=ibkN8I+7Jad!#RNp+8-Pfu4!0u|tmELsPbMdO2R6puxpd2BQ1z+0a zEAV5Et0|B=cI-b^XCZ78X6z{oQT{7V@WdH48aVP)5V2G+&J^ghC;(3_u`w(6mgF z2sUi!*89Y4#{3CeOVa(9G)kX+*Nq7Zqw<#+g1x%#G-Trl^?Nfg!gU;)qt#KlN*Qen z6{mxN>VJS3rB~pUYr+4R5c}eL&K{_?TrYZ=03__>=*tX31HF4h_iEx%%oiM4_!9?e z^~F`8mwu=*(;9w-_?aKenjmJmj?5Mgb!Ysto_shmpRcmtT$|6nOQ@>?7h;(lW`E&_ zEhSeIVQ_&+99V)#LA!KD0<*%OHpYzI6#|FD+V==_@vwBTa7I0A^<#nQDrja-5z_dz ze5Ln}go6>GR3g5{IY(i=*DE{vR$D#qpL9MAk8D29RUb%wDf9PZZ20u=L`)j+w8p;P zV}^2**WvLJD#?Kr$&{93Boz|Psn9k$A|X>4}<#OjuLh zqnh>hRClmcYDf4<^+hC<_weXtN+c7{(m(~@q`uv4fx+-lf`W>%<}^28WR9;0cy2%Y zBdq3T?8Tj`8-C7gjowm&odFt2b&;nr+M@fzrzKqTMI5&3)x#rzCK1PD$B2C_Z(|Y( z{jTiU03mW=!{2JI1SzqMX2O2MDLojB)M2#>is}6s9ii>(d?f_RCF6Vx(KhR-N#(wO z8rEb4_};*$SXL5DHmIgRSXKC)2O+_%Yn|qPSAiNz!9Y%Rc{*C-E&tzabX}ZxY@?Hy z;<|I`jB)*P1x2oAbn5f)(>pqyydd>PT@~{eda;vZGon`VgI(l_#p@P8mEt4Rrha1w z{-TYBtkb+R`V$1d`)eXltQ^@2vVSJKF`@A9iUr+I5C|*J1+9n4llm*z7ShaSLh*bQ zyx;OFm39J(3Yjz1y8_<2!H;-y$%N}aQ6gYGVM24~{%L_qnBkbxdn7-$I_{R0 zrn1XdhO6UUAB}*+urFgtzrZO3jQlA7zv2t>WcM3kVjD}ipW0Z2ML<|82XTkOg{$K& zbr)Nnp|hG*C+vmvX-+>xFNmhRgAIS9_LNLdm}C9GaIO`To54<;Rql(y2|S-ws7Vn} zF1n|3OPxG|0ey20!nlzhL+8HF1K!Kgsjj!Dj_u>E@K{jyPjT%$lL~nf9MG-H`d%*4 zy(_Mc=cUAnWKjikC)63NI=9(>vJ$P|^9=h3A7@8pYc43~aTgR^W-)n3X_-)kmi61) zlS)Tp>@J?o;m;SxheM&CR>t)AR`-qEnQEm74I`0YpWGn>MdtcnOiZ!&nH*g9xRcf= zq~bR^^CR%Lxz07$)JHd70;bUF_MUBbFbz8$`Xh*Fo@d&Bq0fELX`tbc^X-+(ak`RP z^$<87{bs$_f$A%~;)Ym=ONApktD&~pwuBUh=Jkv#7ooDikTu)x#AAVoDSA(%9kY;6 zB-7SV=-G$B@zw6bYNM3Gnh&~VyizPE+igllHHQobOn8Pt-a$cPypPOBHnq4pv2np` z6O(%jLsV#We@DO)M>dZXKFfLB?(W%3r#|KT%Xt-%g2ejAs$xb7uRYZXh|v3y4ky(Y zRx5(dP*PzrensF-VBuG6%y8He|aMn<6Nry7)+hh`76zi^dxCtms00)J#9w@DEArgCR^1k zvrfLmLbel+J?cDBJAZpPq$iQ`*W3Yj78(q4s@b2R%<&m4Ha^6K_WsM`XJTNha}ht` zpc+OSH4T{%qnbm-{C=U=o)-0TRy-xibZ(Bp*xq=tGC|#_EnX-AL_i0OyJVB$?SkOZ z0(;kzG&QzX`lR9D^r_cNFOkXwm!I-I}dh>Z)9dBoN<<$$ajfLHUg1c(b+ zrr5@*WDEacY8u3i+GWEP(;IRmqU1Et9`G{I#@1q~1jPjm zk~cM=QLHU=&h3mv$zTC5U8tfizdtvf%Nh(an~rVB!O$+cH$7Bc-~Gh_O9WT@PrZM} zY;nDzMM{%0noPPBTy1FKsx?Z6%ZHHNzi7!b ziBdG|bl)Pp_+X6!7MQkmc2SlASdt60;}nVV*guKRYD@4?ZMoG3rvGCn{>KG)tU|)U zWHwov+tTDD0v%no5slZ&{aL-$5~F%H+P2~D$w~UD8}hax@&DP6Rb5T@`SWKt503%2 zwaH1k2}|*<)6>_gbW%|AFkQWq`N|8YPPdK!gKzprRgjoFvZ_Dtw|Vy z-oyDCdg4m0A*AtWQokPk4~>aD*om^VLtL}J+`Rt9CD~Al5_r1M%vkt?KR98WWSLL#F9|Mylz=r@#G%m@{xGj4(w+ z7Qp`Y?Nz4k^D%QPA+(vraOMF|NB`@Y&iUVZxC#MJTqOU~sZBi}Lf z-(T}5E^@}_zZDu`%fz5E!V>47{Qb$Nu}#?jxAH3!t-`-!0sdL~{pS1s?9ZbAU;XKa z^*>(+{|Ecu759HpsRCah(0&Jl#=8xeMT_=5n_7KOGpGI7_2sAL!~kbI{7Yg-+Hyxy z#KCPsn=3vzD?y&IuMkI#QGE;zK@mFIHD!5Qu>-2N#2V?v)W&^%5*TChA_~lGZcSwS zGTlO@P!|>(yyexh5YNRU!jzxHYvM@%xR8aw66$|e)lmXn) z_vc&IaqO$OG$o26KU|JE6M450m_=H%K{6htCM8<;meygeoC@sQw5mT;!`uaiU1fo~ zva>kW7Nu7HS|jrI1wNg&QJ)avb1nHM_>gSU*N_YR;GTeT5 ziIok^z~2SJYNyES+6-&KFs5cGI}9Nhh{65W02GsjAK!dMc*#zit7=?dv{9Ja^srFn zEAK(Dnq3Yio^|+ewqE2=QRX=Z#vFQMe^`Mrq&=w4pI?ila=2J{uCo<^Ri%h*G}khe_;7c>(pL0*uP%+hP_eH81iwN zpO(4)Cnb**Pm@hm7v7?RfYy5Y0mX8JX_#}-$xDT6&d0dJ3T?S`GE5t;W`iDK=8|53K3wAaz2Y#ay1xo^K3 z+WGkCsa5#Ss5SvxrMVHIqC6yChC;U&gXOaSlQ5n}E(eom>H9nV**dS7Ec;+`qwZ=! ztTpG+Tc+x+dO_{E6@~3V=apVp&K*J2 z+_a>!QkS&s9<%n8?S^+giEY#TL-K;fM*Z{k#Gx<5`;NlQgmpwzGsV-~ba}@Kg^!uO ze0Q08;%aJNbEo8t$mCo%^4(m!reVt}dsSxn!eQWq=UuUJ7kbl;tbw|qukB&6Nj2>P zR(dxk7=mmFpwt$q{Un}!cTv`nf(7#vz_`t!Ju1K-B6J`)Au@j>j(ZMoLxm$(iZ zm&IjGj*$46i}ot7rlYGUm2GE6X}0*k*B(Dq_JmC5m zCey>8n*?sVH-kCj%RA7|Qma*3q!ez;v2~luLZmT^+_mRRMR|ccdwxkRE@y?q z8<~lodhTeg^|BZ!7>pRRH*f2))<#?%8Z#F%r`mt=T>Oultzt~9@d}TnZ3cCALjZU3 zCCYPTHdFge5o_?*O`K&yXVBQpmJ##t)upWJ@g-t?5FK2{n%Y!rx+_f`)fPH&QM?w9 z8pbS-P6g{Li#k9Y_mSO)dXH%L=X2vq(L3=siioi#DMem49S(6jk+dae7kf4qk0;Be zAeJ`ONY=T^sb_yB1J+E5PBdXiS%9s0qIggAav=WNeP{BgNmPf@9&;{pL_3f z&fe#I>yNCJWUg7p7;DTi#&68IqBld5$R+cVm{fZ-(GnYjb4O)!PkF)J`;;U9J zJ#2%@e760tyPZnVS+>Mbn`pB}EQX!8!XUb%LbpzfRcyG?V`U^Pf_)MDMb@yk(uFMcnyH9t4i>U-B^MOGn z^EtCbPX@CiWMCLXyp#1oFN`Izn)tY z4%QeiZI@V(dJg@G?PNdwWwy_)^!89rhM}4j_O}MSP~%0k zdN#pIj&CS_30qs_DP?kJZTWT;@6tHB$dj++GAB5#m(3daSgt9hwkI7**$yA6oY$<7 z1YL;|OYk?eleY^S4tm6^+!U?HAmjT`I1Kuhy4{m~t7Dx@>!Db&!i~DI^hFIUI8sTw z1C1-)ukL7);1c!fEwfxU$5Pvf#A$G7~TQ+2t^;brm^4 zXh1J4JIhT^JbH8g?@K18VzMgTez_k9Ps3*eb+E*U_eR1@72_~-g9|a*_b4H?CN;+7 z3RsjId6#rt45A**HiMS%>S6gRw6I%q^kd>A<7Y^;?a7FOs}k>yW3!^qFP zSJ{xkqN4|`0!O5Tq8q>SUk=yOcl0!uiK^SvF`~IkhPh4{ylHdRbm7d2=@N8V zP15qZd?D0G!PdS%S!R06%7u_W>yLHWek~4j!!Ggfld~kvbQlm%2Nn)?EiU;O{Vnui zu_1Az5E4KgwYc(#wCM}uuF=v32|xA8kjxqSA%~l8VPfJYjW$HyGPp~wSNP5n|8^yr zV2-PLO7fVphKIj?Sef&ee)aCf8kx4d@!~*bUTi0a*@Ky)#~$wEw?mg&UEjZh zynkEC?s>_?NI=OgqC9tY5uI15Ail~%w9KF`w2r(zlf}$L&INFBeds_8DE9?QMRx9@&uvLl#H!+K4y^>w(muH%cQ20 zT&aq9P;1VOFhedxSg3!P9>y&I=CFO%p%9^V$7W9RZ0w!PH2F~>*Qzi>HKI1zi|Q3l zODSz|GdwvXwW)W~N9(2#zrSkA`&jZ`gQTg`-t^f4k_;{H12r3#my^T+w+8s} zJ?J-u8=vm}Wb#ciQFnzgpqlut`atuVy^xt49hPxTnR*+A@$EQEvvj(LFbK$bkqq zS+$h?N@dn}Rxk_v`r5D|_1@cB6JdEi?zis&>TTn|TycH%z&H<;!~vk$LI8!qx17pY zA$!fK3{ahqX`QoC7Bqtu42zfio6k`OhPFixP(yQkODrFlV#3HRWzd!_%q(-KX3%4D zhv#DB>NY$WOn2X~sV`>8Um4r;=_+b_Z^i7X--LzP)h8L!UDN)nsu%>oOyXf`$0ghaSj{y zXkf^ayu@}Cgd}Fg4)YU%(L{)*O7sXVS_wu*|XR;v;1P2{8Da%!YewCc(VNI=Z6>wV2Re)jz)0)F@d z(k7Ln|AWxQP0(7E3kz*Lc7ec#wzuuMg{ua=Y%?21q1nQFa}%X>xg_PQ^y@NM*h$%` zdgHrp?ip$>oeS80Nq0P#Z1wPnWs#X-6qwGM`NOwo@BVzH zfV1uzeQ3!>sUI$(R@JoOG2>QSY-)BOgY+)TtK4Vr8CZe|)@>Bg1#myUDoc~+MbyE4 z+kF&%UBbvI_3f92nvH((dTu|fm$xZwr7(VPo4vNHz;%7vohswnL+1oG7n1*~+0~+O z^`nVQg}i9t9+(zb7JTZdfl2Y$Hv%JIBTk+M%2e9KDpR3lRD+OF-cvOtDN}5_haqA; ztPiu@*ahDw3|w!ri(}$DMaqj2+Xb+rB<{cx9Z9Fy+^->a6ah@TRu@s~k5Pd-Hj&=EN*H%++<2)zx zc?Ub%=>AIMW>aX-28BLXZ78qRX@r#a^j~Ggcntx=^WJ;Q+aLl{1@F75$7zo*WD<&@ zh{9NJ`5NibENk>NOiB3E=30bND{4I3&aZQ4;hp;Gcsj+Ru-$&7f`_+qKt+-yHI?x_ ztzMYP92VI>maqi;HqxiOlAZl*YGh{8Ir@r+j@J1N=MEn#dgI4&Ms0%NNql=) z>(#y18~hi$*L^*D%u}S+GD}fMdJxZ*z5>!aF|6)!C}5t%stP~v&G1K7&C|L-)R)FG z1-7zOq%_cV1odK1KVfz>`;p1~9)-NoQNKh&HKm?~Qw_<_*w_ zFP*VEKc1PgZ^>#v7~Z20zv2f#nDW35cGo$~YW>^v%QI<+PFN%XooAIEvNx>=6h4!s zO)>}s3fJ$8tGG#?ip(sIgn`{PNSffOlR<%!xwBAz#(So#M<;G1zbgJ}a(I{_1`Uzk zZPH+{;q4hN0f`3Q8m@T98S52Gu*(gsPMrW&5%dF&++KDNpTncr^EeY{m>xgy>A14T zu^In|l3++f;NAlTBrm6aUVbt?FZsbm+H1x6UgT<`2`VPD$ex##Vyod&Q%PHg?#9B~ zg>cQ=<|^CTnl<=!Vcx}^wMFH7L4DKd&p<*1)lAz>-G!$-$)%=O#GrsVwxQLr)GIm5 zkcZS$0G066+cmTc_0bAV7yR1Fw?YH!V(!X*)U^ptD_bV?_$xTdA3L?=tl z%mAYu2Xxt|jF6;%MxAGAs24;51 zbUbZe%Jz{=sjk|8aQ;!KUEkIX5WH8B5I}qX7kAX*tDBFOiJHvuN66>^n}y&UVxH0S zR*i5YY@FA$yjn`2W=}MWY&=%Ir#ds_LaAfs&1*`9i(gkN_MYIx8R|?Fy8woH*5X4BIw}@iFeb zHFJL!9bBY|sya;GS`mfsh_z9ej8*{1^J!-IjPKJZ#eJo~=Zl8H*KnJJ3pFVX?4ilTwGef{bjB- z2?S6-oqPFyr+oFP+d2!5Dz4? zB%XC#8KAq<^(b|FGdRO#US2f=X*!mhw{f{WiB<9AObTn_v`I!Born`W=e$gKaLhP> ze~y$DrUr!PUV9_``97t&D#d|=qBo$C}M*JP7eyBvy!aV>Z`b8O2 zMA{R8^@ay;T1_q8U)&-}Z%4DeB)0me`l4aSjaJ)=yaILe1naK-2d#6l` zx0eiZsAUXvtveojwE4}wt;{4zK&%n2a2`21#WHMRX4V+E$^|Fz!6JfN#*5==?xtuqm zqXBo zaW>yJb>e}-iAXgok9ycKs|Fo3+q#7WniW`ql)V|03UI(kF;m=axL(n-+QAqzjo6J^x2aa{qd0*QA1zaY-`vFj zDYy9K4ZYrrOySs@_MkmE|L{E2`4KIMjor>;w)jso!hCUZ`TEO9e+DgMd*VhsY1r-YrfYTsvW*2VS-*(~sg*|wuW;h}a*3F$zcyS(Nt zEaNs%;6~vA9skzFfO{)Oa(>f*rqZjMO)o_NDGQMIZyrZ-_xVlfxAJJX#-jIgq?d6z zDT`Dwehm-V_yBfW$!+Sc%So?DW zsCkBKb=pf!dew@`K=HZo6{aohhcS=XNbo8Cq{iiu9LW+Kyg9EESL6@leWYkglmk?> zdlPP~h0xKwbI5-)^-O#5nK2_5p)3+1Jv)g&7$cp}KK{3(~oji#Q`G{F>|L;T8S+d(0?eRjKnR zUbCVTB7#tkTjWowIFJyhl!V($SN1@2g!c{gW@h&R?T`M*_e9e6#NR8&lgC&8qj{`hzJ>M==D6W8!Hns&f8SIG6K?(#MDq@x zFK)fj)-noM8CvJ~pyi@QS(C9Z1^>&#AK6^@SRorkTC9dq36w+Rb$+I<6p>`!Tx>WE zG?b349+iqg-nW(#@qQl|K4Jc+B^N%m#W=1 z3;tGjYzx36Cq?URsNe9}<(;fhd|VqVpT39>c?=-fw2#`C)pb8RWlGCUkg>P7jNjc{ zKA>Xss;n!MZ7ltI@K-;tdwXu9qBWYCxgg*2wo&#vPT^Jb+0ff7e$J7(h%7H$QHmQwOs4Oh-t~&H34(>aD3_M^yTQzorGETB)(?m5|WxfG7=G)MyMzA%$ zN%Kw9dL%)-WR85Ir~R9QYMDBaFh2m-u2*1O8M|-?tBCI0)53~=V+Jd^$=unh_UvZN zEfrGcEGvT;OS!={W9I~)el&k|!~PEWPdUFY?rL{#&bwgGZD@b*X|SBoVzCYn6M~m< zFkfgR1YbdR1y^nPlCxsWmbzzOkT`UXZY>yb2I8T&o!?Rt*t!oiTIJ)x?PnXFWr=rl z!oHf30-%@uJC(kX@(gaCQhM}2*QCo#0aDS2P*WbZ1h!-%G7$_V& zHcqwQ$X26AnvKN6>*Dd*_~l|zekgpvCDS?Zo_M8oY%Sxk{5aGk9cn8A@C36A{U?a3 zlJC{}0J+s0=p2vGMRN2L4hLedHy?hgLTh0eqw6~cC?{r1)a--g|-J^MND ze)@<|K>|{B9X_ZP9D0^jS-WWQ>()?Gm4u*>TZZAq9bc(Gs`@Mw;6||M|PxW-H?_>!~FePa=TYrAMccvtm9H<0f<%Te-K}<{2O&s<~Zt>6|1L z)r zo8S*n14O!spZ&U*?F{2%(^tI9eN8bmuW_*L;ktalkl6s&D;xV}wAaxRz%OGf$GMX^?8jR@Cau(y%o(&qNKl_GzCk+0ub&&Rp9n6~x$)->7-qDk?!(GRWK<#}Ut17>mzs=~s&yqK2@ z3e#&#wz%4iA`paSfkKGVTU$sbA!9*eA85#M4JXDZ6*_fmIe-hzX(CkFHab4k&8rC+ z(x1_?e37$x$9>=5eBT5bd8BMhX4(&DDC!?2ep|+`0W4=Hbttz9l(O?r5vJG`Zz77}p{CPMo+h22##mb>45#WAtt{0MUMz!X?_c zGAW%)Vobk`ajF)gT6_QU!Lt0tb zVN`|p)y6IaR;+hU0ByTn+ogTtt~fT8p0}K< z4A(^2c6BdnpJ%V)H7i#gzd+laK2@s}NMWWAEze?9;-Aw#l#iWuq{LRZiNy2{_mOZx zsvO6*RG#dsVM?hvi07bpWmSX+_Rrg&{Y*Q8O2r=L~xD*Hqf`2u<3bm~oegXmS?!J|13o!$Fc`RDz4Le|n{Ug8y*6UlC z5x;b8+hKet%Q+9{VSW^tQsS3qp_%xHz#mC5B^K1wUT?pnrTC{}H#hF?7Jqs7B|K>l zNO872%U|S(InLCIp{9e$O; z$m0t>6JK&h4t0aym@aZZ8qgA%8rAs~W=8j<3etFcSRY-DT@%K6}6UI?k40TWh2Umu2D14nWgwjAxKl=_LBvidt> zJD5eON8f#K5WN?8NKfG`^AIuuxBrr6v##Xui;s*^vK0{_<|Bs%DVTV^82#O}J^Wp( z0wU*OoJ~N#wvU=ue3e4KSW1;m{E*E3iWOX8(E-_kRY3}NXhUg~uJAYHGfVwHBA?(l z7chPS(wJDb)x}1=iq)&tdJM!5&y{1~S-yPldhoAdLe68NLZ1_pxaq69xEbM*ve~^- zrXO*k)aq zMg#nA@Qz&5j2@16;eZw5%nd~5^D?gU7y`NpDX7tF+JP^dVluPkFXi!W2Uud#JT=q| zE7TBUPMPWgjk+7lN_eduPph7;wOlcJO8XTfRvM&<4vh1Yp}f?dP{lr`clIG(Jg2Pf zaarzo9|gv%xeQlo6=hgmY24K*)BkcnY!%9VS~6FVaoaLN9s41%t{sWLfj4PneHATi zA|9kwItUfw|6+nN*nk_?py;Z;zP{b-rSXg$JZXvl)Smq`@DyXorAYFyb?Odw_F;}? znWqF)sF|v%!L&U;m4^UlQ>eu=h1RveFDdI1p`5voXwM4aQE!G#`hn~5bbn39&Vo+V zuVn7NYK1=plO*a|uh4x7iZrN$VpeZ)2^}r2`IdH3^XzzL;Aa$x5wI%^NIO~nit<(= zt$X?+`mN>g-1#hL3fi|35pm{ix6Ayl#UNOi#g%(VI5rEv>$g>lzSTZ*yS6+$U0q?y znU#IJ7jkmqs=Y5PTHNv9^a6yu688q+2!}-x2VH=Ivp8*Ksauv|&3Z{g@Yq1xd%$Y- zihf~?J#s5{3>$UU1#V;jJ}1P>xeb{kESAdcaTxOZ__hY`JTw&5*V!+X6Pn7j_s!P0 z5->PtKU4H_Ve`3%;VuNgc8!!>q;}OIFHPEvR|mWpw766dj4N`k&E) z@_K!ngBLUP(_E4Bl4*kU+skv<`S3Wh z5==#UPFH|Qwzea}X2y3*iiZcJrO%h#`<|(;PlRjM!3qJu?X1u^(d#~NrY&`QHpL&P zimYmB<49$Croc5d^)Y{>+f%bWp7Pe4zHOSbQZY0HL?d!4oeSLkg4E2Zc6SD6NS=!o9{%ZCeUU z5E*T3ZRd3P$Rt;^#jlAqbasZj(GWKn1tb1;^Y8#TI_58VlHN88bM^ z*a=8W%Hri)Y=Twh>Y*#>Br9sRB2WoS%4*IeXj4gEwb+@ql1pq!ZnL`!Iup?( zi`&;bPZIV?E@ai$yvmeR{aU}SEBE$hz;lFy;y+6g{1n}AHa&a@8{o*d^GSnQ5gFK} zffkPd#gzxm$}_Ixfvz=s!j6bUTQVWX&NDT}2Z3)A*{pd03Y{uVhflC_R&*#xurs$HsD7q3s^PRgq&PB#42da6zBv16&=G?-< zZZ0A!D<=Bm*T3&6T_@9)C#5X22@7u#Uui!ncuaNms_bnxVqZpPW}ioZFhs4Opdfkb zTYay2msHq#u^n1Gc)(81F1Krli!-S3s_m@aec_^|Yh4Q&CT&~YCTTzMQG*$R27Vyw z2R=HEcDsg*{>s-e%$tlk3o$StI}_71ZC61)?l58g_Ruv&*z_G{w|f}AGxsLQBsbz! zeBRimOv#${5zEyMV-*iQ*n~N*ARzQ1^B(-Q*ZS~V@w-ahA~!Ob{3RTSWnj#wqp@e6 z95_>fKp;vhG_ZHFNDH*V#c~u(2FTv0IeS*0%B|{Fr)2vgMlKZNdJuT%zgd`{O5|KB zkuyPD?q3B21Nev7?Fw@rLa~^gLnp&Zhj?`yF!#~lFfattZ2zSV;R{?>tuf$0ba29K z$ZB;uY>+3X`E-wYf-bcfQOT~LJM%i2ryTUxz4YPxp`bg$fCnD zF?C-V>dA3S1H5T9++%1eRF)L8noT=JGmpg8fLD)B)82YDRqGl63lVY3%wt!EueM?6 zbeNsa@2LBv0_spRgqd$OxLuum-)UDhtjVcf78160K3-|};FKhYl9iGBf}P|83E~pk zEJ!@JZ<5Bk+e~v#2A&>gMxz~mQ(-LX4@t=d3}v)FwTHctI@9IvSSw~B(Q4Mlv-mha zu2;^=YC043Fez&AOcq~Q(?jFa3mrB^txTSY->oGfAjNe0B{)G;me>ClHk?+MUVidTo5!4ZZgx+rY}F)`!I zJ6^7rmymq=$N@YFHB`aWC53fJQ*3U%ouM1PV{}0TnO}KWpJc#Mlh<5c0FcE|3<$^D z?2Y3Rfw6qAvP8k5XWB6R0^zAWI@ygSPjS9-)BbuX5G(fG)0CfYufB-gbPo=JUo+NZ zw^75II@~H*G*(&R;F(?G;L`_N6|spD*{%BWpxXx{kBUuW#{na z3SHrsuC>pj?2Nr5Wy&|jA3;jTqjX~B;j4Zw?WK&nTKkQiob)>{tFIn7wi@XZlnto- zzEY-GD_grjQ$r4Yr(@pBL;LyUL7x z`w_n6x<8zt0}(t7Ho$obuXv&Wq0$R5jiW!ms1(iNn=&FgH5_V+^}*uB{Z;$b{ohi` zFp?6jl#1+SU3OCmbA*O>;0yD2AIJimVInOf)roiB48iN-I(u;K(JtAXoc`=0M=PGr zaX}x?fXbkKV+;x&i%{#|K-8P9`l@{-7P4NWyu6K!7GD{+ISfEQB|aEpf)o_4k=2qEOLd&eUY*{#Dg%tJk`40B;4)Yz#}P= zF|jZ^%5aBvQU=&{z(loZ_~60w4*A!rUr9LC)X3`hr|=%5a}n3lgt3Qi4y*EaZ7kl^IGAPo0zt$)izRxk~+qsVF)e4}aiZbv_8531A zTM`qq}E*g6d8*R&z~_L&!Rn?LdbwR-gL1vz8%%^bfBEvX42{3cSaGB49d zrdqB|JQ?TAnZb%X8DeJmezINlTX%5M5IH)BJ>Uc`P1$wpkg^(olZplYtGH)LFWp^T{% zxRGl4_A^cXb2C27#0BR_(A@J!^h@LhtKp%aOZX6qXj#tfelX|c>aAgnC9cXIaoMaj zBWX$jK}az;V5aB(B~QLeqXEibSepe$T&g(;!Q66Lpb$Z0#V30JFlGlDSC-70e{AAQiS5%Qv&q(n*=P;7P(V7ULA zi&l5ZNef{;Qp7#fjv?t(No~kgWRuv_cc}pdIsQCKpMw3wgzQZpjysy6&n}`k281B% z@%9;kQz1aR__uA!%nCNqlcaR_^bN8oS}S+S!J~l)+NsT+HG0m+m4)K(7+{Q}Mx3NZ zByWRV%b8+C87~c8=m)eI&Jj%JMR0!7#_O9p@82#Hwr(_T>J?ddef`+;%Y)2f>ML=; zMnj((XxrK4!u60zIk7IdVkM+uiE>|I{nQ;67M9MnKO~)hpmhIkZDVy*)L*Y&z2dlY zXCAdGD=WLY%PZvX@6T8aJoPN-IceFxpKkkY*WGb(93DG5|a*sh`8v*aso&boeuXLDLFsny~Sn06JPh_oON;IFzn>Z$+^Dq zfARuH()!U-L*ze4Jcn$GtpDjE)w$6sFPIM*X{D&WDUCP%m8&OfOn+jaKdJk3P!q0m znlIdHd2$-CIQvXCL>Q5F6H(JrZS+4(0761IK?2B6;U1_fm zV(-5=dpZP~Ze2m6&;PN@!?iA(B94}pzr~+Dsue%U1SS>w?T){? z)QV2k%YB709*^h8@&D{OcxK=v3<3FbE0Jy@GS#V_+)X=f6uS_^w;k@ zApF<6jeATqB6|Sm_k9MvOZJnrAG{myZl-=8Z->>W-;aUUqYNEt*uP&3xCZ~=!3Xat z(Kthg)$h}B{iUCLs{cyS_{H!0nz_4RkJX=?tO6nlKkNKN@q?lDU&E&!1Ccd9=5~P- zT7`*Rl3hK2+)};jKn?ki=9l0l13&A$D)N)4VImQhc_mw^-&^Ro|C8|CV|Oo|bktz` zC)+H_}XsFRORWcAdk>BmUDBB^H2s?pto zC-xDM+iv4ekRE)I7wu`O+g*p1a~%)){_mVq1k%O-wdQURJVhPo6D zEgf91YosZEJ?l;RQEq_wEtLgGG4OB?L)bmr)gkvwPkpQnIvVq92-=ePMpasWP>p^f zUFTxF9eVzh&(?;_y&uot_fI1EZ_4-oR$S{J{X;8|tNm)`>QAju|MBXHQmlW3Ea^3b z_!F0w^8JYiK9R>x+U544p~PRK$)Rg0=r?3f8Fdt%A*H>}G?Ly1XL|P3si)UT(1OqY z7V@`}A?Cdm1BO1k>(<8!q^Z|PdVxNqudi=?kFdB-Jlro_kvee|;xbCM(6)gGJ6fjI z-dfUu2i}*D+m2f$ZRa$DLFmu)!8EdCzWz#oO#srjXgeGZcLyErl}P$+sg98L)4AJI z<}%*4G1qc%BrRUuR1}l*ENnGR0MSt*-c7A!$%^Q86(NN=C^$UMnLUi({7G`FQHo6AnWM za5qX10XiZcl3x52FU3nz*rN0Z41A=@tNW*dCJhmDtRuyD4|;mEDoC=!_?@V6nVHPL zBtcc^r@AJ0IhiX?o#K{rKyLp*vbKWf{y{^#V;U|?ktXViwDTu^+LH|P>%JPKZi#v? zj-AZm$KCs`!|5eYl>PUP|JR#Azjy0jT98DB|6Z2Qzxei@0{`3bZOO4}G!6sA_?;s^ zF$n*~>i?Y8PbVGAhDqy5e7jFg@co)nNca8AT|Oq>|C<=vv!}z$rTKb@F_N#;_3D?I zLaOb*Z7}MY%wScwXkJ?tMg4Y1A=PQ~CR0rgPS2%JcW&n1+I ztsv|1)vAK9N8uT1FPdp6?g?{08|2D3qwVQ6dw8GPo~=H@*97{cOTd;mx8x!%DY1Pr z`)l6&>~Ylidyz}GUr}D^LyZ+>8}&p>bNLp z$g_XM5l;P=YLZ(wTbly_08kuTtKWoJ{|_5Ji8=oVF!^|t@8l_d?Mqsp4~N6)eE-N5 zZL+vWV*bTV;vE_f#)cQUaJaIEhX;Ofv2IiJ+jt)7E0|5KI&uek{zUZepLH0k_K}VJ z7E2x0q^qxgg#8#d6l_yJ5}e@nRqBr;2o8q}VLV-1N~%Q1%nYgoCcSy)j(_KG6+rHq zKRm8Ljnd*mX?=qZ0Kj_p+(m;tUFF+fE?tCd+0dLDSNJU^_kRe7{`Xfl|BIfsck&kt z=UdsK#{F)j9*_=hDrxNT`5C%w_gu2bxc^4ey&s{!`lF7y?~7Z%5%eABf0MyeIamLG z(&&PQQF6@k?>?8iPVw7xB*;mfEQIC$+ld5hBlM8Hq_w{xj3n>-nNNaCz0arDS2(CH zEDRurEw29zP@bYmF>eg9p8ovae!Mn7Hj?B{*Bf_;Oh`J9l)EqEgl0fKt{o@-ZJ6p@ zSBil9{Fe|$(ofHP?sU0)Ot@!B({i%Y+=s_I^rY*w!p^dfVsEx=j!E<5cvA3h=P~($ z^phSO7f5h^PM3U@=Xm1#7Ov?l5;@*4b7WWS5wTD;_TtFmxJd1-3$I8IJL#(4-|m=# z&s@N`mW@y-Jy>9`E*Te+N*d?!@#Hd1Zf>42ufuVniDB3lRLl(`6j~-$%4Bk zm6@_RVR3?^UNWKzjQs)#A&2=}bs4n#`+0r=RRKS0N$dSSN7s+UNOulr%5;1hfY?9- zN;@t9N@%y&s(c7<$U#G{LG1*Qlqd;eAh5P*8at10I{VWGcy^)e{`V<=M;Kvf9ePkb ze%=59#E}u0tR~(|6=GxO=3chf#ouZ{Cc=Gwgn~&UI-C7{L*rSSJ=1c@02j&SwXggO zyM3#+qYfJFZjpxq(AWXRMSIpR0+VEtiiQkVP{lsfXSqn;z!QlY+J7nF){A23b05%& zWQap_OLN6jcnk6cJ%;3{pi{%QrJ40pha}o*qI(lypqU}tnRN-qZiFQ`dtgW1Q(}5L z*}c9wFVXb62~qH<65nC`w7t=1Z&%A_wT~kYWxx~Awd;o(@tUD(w-i`{3%KpE9&YUP zgR@l7o<8WnI0r*XufKoL?#c7-I=X(O z%a*G1>Je$}BtsnZ$ShPawMMRDYkWaw0u!Sz#ocmbwy&!pGv?h%|I~QgSah>(v+i){ zz~V5x*RI(#U@K$+B<(+uDk*0F#?ftXawtpAW@XWcJ2B6|_9SX|-@5m^&A6d;v=U`J z;G(E~C+G1Un67gYMWDM0O4<^e-(vw307)~YXsu#k&b_+}n1usAXx3WG?oOY!_Vq;l zv3wPeZ9<{vlvwrPG?xD>a!=RGOlGmevswv8D6+}ilib38R_&7C80^Q+bz;X<12AtF zif8-T?0@naeerv5?uztnHDFSLV%bCJp+bl@+WiUFg@U;m+O<{vbsr3O=Vy+rs4U;i zM$j%_6|8A#j*~aGB%U+NSU(AuWSpQ9yuO6&FcZ~H4YZTDbn_`a>VB+whh=6jM!9Ht z!8WKX$j9MFgQsYyziWvEh{2h9(w3gcsw44u27(aYj+%4=i z-=NjT`mq3URBChIHeR5wt>};BFoWzvU>+|;r$Bc#bWcrB)iur`>0a20YoYo4?S|Pg z5Y|!rNO*Ub2{i4SeX!qP>9!VDqQit*Ngf+UCscdr1a8DnCW@B9^u5%fV_dB0@hCTR zAS<}m-T!c@QYDmXtol}6%^pTImAI1?4{BOcFys|U9|7B#JW3)i5=}6 zqTRM72uB3Wahs%r+xcSuMDnBWXx+H9z#_y}P?TLM$uS0cI6E;?FvTji`pKcFWtlw3 zslcFAniPhY+DRMnw%B&`^jh5(pxf#v_J&OF*VKe7zXGvxOJw zcOmo@ftmKpoo3Dnsph-2VvCy+{7dCG)*E@dvuvTrqGs(Tf8t8ry47-jSl_W2*OzIf zYue3|g4q){5Vf_^Y7k+k`FlI(zI>PQqgSkz^boM8J$OwvFn)uP4$8uT`k+D-oJSpO zrSaOY;SMW^y(O^}G;zz|i>v!afo}CS_FMRXij_hYH$sZWOr~~b zOuJIL$9D4JcHP`Tu!s_-hz!&z6x6SJui~;C6^K2KW(Ln#SYtXQbV!m!7nEU z$Z@->u#-*ypSew`AN}s5ZQ%?&h^nS|)xZjlE66~g?rly>&O|l-8vwOcLe1~XB z_0UvW6eMWp#Uv#q{li46AZ?N2v(|L2FHZ+Xb>UUhy{pGfk`8Wnl6Ol&aWqI)6`d~? z>6cma+S7BF8N{ba*|wb@%p3VVmj-_?FC-*nkAVZkN#@d*Oj7x~lp7QzF>Z-qxJEd! zmyT=Z5Z*jKog96?+?(TH{y&5U=y*P7Tw#{C8Yy?B6|m{ZNIkK)Xx<2uc7P!b)Sd+E z{IK{Wk1alnPp?Tsc3&KDy7%sc;9*_IBLhu;E_NBOO+R*}p774zc*-c^Y+UKNoCK<< z7M=acuV->OZgX9<;_h~`k))sMC8_4ho^&MK3$wiZb8L^f{V$WQHHT)0NsqVRZ-I;t zkN<5zB=g^~yzD+j*BcsJQawAKcWg&g$lMm|MT+oaLR_h-Tk9e^|wn&b z{e>yX0JXa0jd+QToo`<2N+#g`{9<`w958e#sN>#Hjn2k#JxnXUhNi<)5tqcQ8_ymk zWxUEs-gc3`X%bn@?BXvjM&QV*v~TavAC$h~I3%&pu+_J@Ji-PD3qT#oiS-4M-96ks zO<<}{o?Hz|5($lLv&{wp4=R4=yX~$&X!A_& z$y&V8F)t5PuP2A``LKcYa3UhoYw=6f?&i(ul^W7rb1K44^^>z%O2T7xW_!ycR?W;% znWO!sf@QwGqd8kEC<9s%8b={Ic9d_ghaX|(6571}lk#ORzGG~h>I>kqjjkPSI*+m2 z5T01RB_)I*CTpfRZW1KM0psP{T8ySS%;B*sbm9#pxQIPTd>H+P)?@pu*kN^@&9@>K zTkXEsB4X+O%#IlYm_ZLp8;uIuojv%9#ZLFwhT8TITk@y(bE}k%iw-Zl=?41jY#BJA zeDH}*%`^V4t0Rsn!EW=Owzi+0G-jC^9f}%r`bsBs#y%fjOO10wRq%CJOWo_#GnN@9 zew$AAaO}<(T;#1;sgVRNB#O*n&_Tj~I7jl~^ZpLSKv?l=zJR$7*z1+CG3|97Eh zs@JZfqz}2;BSx6>vssSoBb&_jzq_d+w)jQ+L|aFBC$fgO3LU7Jy5#3)T2<|plocbgA}Lf? zzL{SAt|w|| zEbNe9t6fer(W98`|hHqeWe15+k{)g*S}rWpNo|BYPC0sSI5u~#OkPP zcYucJ2^P`1$T&3!`~St>dj~bWeet3P8!8GaBGRQxmm(b^BE3oPp!6O(gsRe| zcc~F+(xnp!pmYd?-b-j9gerud05^KhJ?H#>_s+X--pu>w&6{yB-?q!zYp=c5XRW;# zaz6>`(%IB)aka)^(s$FFHUU;OZufiTGMFNL<=NS<6 zJIDPMf|ZfV$psN8FcOOG;esF!BrsrJFROKkVZLQT(!yX?*kRA5@ujRmd9|ab*jMRv z{8C>LprwpqK_+b?R4%3Kdfy8*NG67o^u5Cz4Gwi9dYZk?IjICx5*ni@ zy+P#-*!G&;7U`pT4~Rh4Nq{8!n^}4?tSAsWK@HuOf}A(&=v&V=yDk=MpDseeTqoOi z^IE2SHnv8k;r!gynXViA@Rh5ss3BhTm_2H%-XQW}S8F^g;X)blUI*fVb^+cg>Y>w^|%Wzk-b%^ zQ;TS6x9&wmfv*a^f=J;VNzwV^1_oB}2tdpPA*3|;mAD+v5@wRF)PnG_%W$5bg=~f| zoL^<)9;GI*K~#FZ)hmC7k_wzr?pT1VCvCnjO0{jFC!TBB7^iL^b?*9c(``7VC&yUyLMu!b~O^hyUVNN~VYE@-?E6!_geK+EZt zNsAuS0(=xW9e9{y7VPG!+F*A)=eBOgk18|Zz?z<*sOJMFNd2=32PN3Npw;f4&3-oJ z(_YE8$3QdM%g#sB7t7ZhdWxS{?Lx>0gn{!tk=2^1D{h0PXQ(m>5~W!)jfR45nLbR>vw$PNY> z8m|W_07h7G$x1@v!&#wXL@#!Z&O30@SB2m}p>sZ73&0wen5nl#ez*z4Q(=XXr&Rv+ zn#G~SFaS6!VHc>`ms>xd?Ddgqt;TdKlk6j2-YH4)UN)TXKy_=S0zBGEyECj;7-Lj- zBLhD*0b4nMxRalyqML5kh}lVESo3jf#!D=t+n5PQpLNl2jInse>MhG zqBF}Y<{`-&3q5fNolL1#TygCpZj=ZDl&Pj_s;YvKk^B<@5VF5cczeVCTS?RUT3j=2 zgUAe+ZxKPaTl4=si`>t^0Q=K?CDTwmfzKubfXN{7ddZ4bK6cGw9k|bCjl$ar=}yb) z9UoZX$y5&%=i@)(vtzjOav&59HPGInIQPOb~PYpr#f|lysFfVVjJtR_qBrWeZ zyXssf*Cxbe%q{J!dI`_+cvC6>ph| zFID^Lq~^K!n*>@~u#oF2qTsN={2LB`E_I8uO25?$vI-ycVb$nxYJqjEC%Sro0@r+#bB!E_PP!pg zRT5@&-A=P5T<79Y`(TnjHdSy*W?tOGbgzM1fs*1>x`P4b#hk5gSCU|dY?G{P4_kz1 zqf$AU`MdBvf@Eq~N$6xFRsBFfQ+W;U$wC2ab4GLJsnRjX3B{FHtf#D@2oX5kn`u1D z8+tmfecHA;*z8aBXJ1b0eyTLlP7O1yHn2L|WAer!K(U23x@ziH9R^lb6ZcYE5S@RjK23O)8XfpXS>QL2Mb$$Ta|viY@8W&B?3wphYH1F4jCp{YeVqNyiCh# zyICu?%gs)4KqL38N2a6k+vytMBp)8Q5*I7xo-Gr>c!TCJASW$jN{@}W@shQB%Grlk zC@WHqICPK;_2agHkfo|s2I!giAghxEi_`Yp zPF!vNW@ZF2UJ}1RviX0y&l8w5GfkV#ceW%hTFl*PsnfSVt}xEWVR5>lvEaW0@zYE9 zu%uTyoa35L$;`|N#5vNQd0Txt%Kg#W+Zj7vP=KOEPd7e;x%H(z3&3$o%|?JO_5sLj zwUTP5-R+Shj;+s;9EStD@C7!dR=^Y1EKguTi(j<^MEbaN~ z8I9IFy)Cmidb&CUr?H>|7-{f`fA2gMGbJ5seGr`PjvaqLou@8>e1uS`;4)mzCR82R z!Ahh$>Ts-{lOuZ43l~1E2+eRI*aqGf! zN50xD?~QCP#fv@It`$tG88aWlwLcvhUu3%Z4RB~ zVXNyIYJDPD4;Tbt%%HTrUxGVJ>2^Dy0raNu%zZL3o`hFL7p|^MW)DzpW+jWM&Iybw z80>m0!l#yosX?1kr*Mo=-Z4HG40^c%dODKle%YQs-HK8`*Q180{WfE(#yRQ>2Oq(# zmz9F>i$5?=A$4>Fc&V-VX`)8F`YGrLXl<9N5^&Un^By{O?M2U8k7DsUeHTYQI;j$5 zxxSt>;@Rb9CCHhI$2bO0q1A}kys4${nT?mGqsRLJ(?zqR)3x2A`mVU2cOdr8vg52& zNzZ?+OW(Z7Zik%m;1QG0Qe4h|ssgEIv&ODCp03q8EN!o5;H9->=4-_j9aw%l3wAAu z?vfL*JxV{Wpkc&@J-_IKx@@5#0X?;lygJ(yLpNBdu4zV|z9_Z3|BW)|w{Y>xE^+7f zZ_0Lc8WV`qj?BP5b#(L0mf^CjezkQ)>Cd&RkewV}HZF*r;KJ@!=0OSA0>*q9Ng^3p zVu2VXhLK6Yd&jL!vZOBp^k$yhf$2=JFLYW~GmU;uN07J)FhZJ?4 z!Q%?bB;RDk#AlmSXwc z!-Z?BE64JM1w?{oIR(CFccFky@bN4T^gRf2QKY6h`4wcBVklv_QzI>?Z$3?_*K~~WhnK*4b)E=^&F2VyXBi58Uy8HgJPfBl_cgJK|D~v4u2pTQX ztw>VL2XWy^|E{8}_iA9m^Oi|~p%G5eX{NsR`!<7apV;KVfK@j%u6f6sh1}h7Wauj1 zbo$Aq!TE^adGY(f)^v4_ocd_F!819zB7rg`kNSXMEW&x=3F@_FR9 z^JUSnV(%z*wKkR~?F{TH;`yCOJ=eqad%hR)9fbM_i}$?z@kq#59Z#*k|8{?6{Qr>5 z|ED0CUwqMW@n6olKbZv|u+nwqxo|4X^0)HG>6agiIe32V3OC*9Uuj45vU;d!RF6Sx?S>SSYDRMB3BeV6mmodQc8PWODa+a>UXkQ2ro>1D#kZT zF0Z@HS3{g9cab0V@1J%Xhgl_8w1b}nN{R+mK%b>9_?c!uzVPf)Ems}D=fqlZ5<`ZC z(WTE%*e1W+*k5Q*UF%1fWV}~vO*rmKuErmDfv&Nw-@@gtxUL>Kx?W1zTMkm)K9#ym zbp`E;oJYYx$2?+I+wEaiS^Qy^>n`?rc9o`_fA(_d_3y|ZnFx8NmPZ z%ZeL@8CBS=Fo~K02eK;pCj%R}{1YZkDYIgA%fNNJCKlx1UXQi|!`x4-oNDY%dv*hz-*EfZsW;-5%ZkzbqWR9kmz`lG-bNwJu{q;xH2+hND!13NcOCul_=ZT65@b*gYG zqE+ZBZN{e!c$4+yQDerR;N;@0>~979?w5n!S&+3KTeK)Jejuff{3uJi%x;8l)G!)$ zy1qbKjp(gkn;xdK@H0-tvxC0p1)AdYP>L$w!`3?he?*dq<3TnA)R8=G8q zh(0H@EPF0T$qiz z(sNConQ%jq7$~IkK85>Q+Nm#squOorrN*%l_vsI{{lae9)$Lf;f+^R|(s{?$%&Fbr zt#5WKXjY{J<L#&ZSSg4w}17 z6!}+AJV=X-0By}RyY*|g^KHzl@k7)%OJ_h>YWIz45wlH8&F9-bU6Ocv!?mvyvRO3A zSJ$FHQ?s39(%QfmIAeY2C!%Tum%9q@1F1y~y80SrP^oRlTN0T%WR{yW8qct>O*UuL zFO;dImt}AXI>h(SK#hzO(>H7Zs7LcvC}P-Z*XE6a%eXystu%%Qx_~_Ew5l(+4SmiYO9rh*={!*p8v{G4{Heh)J=d#W%Qnoqbc5_m7yheScM$Z?EdlP0k zQhGEm?tyYVg{e1LDZ>g~jSXvSO3U_2PWIM-Y+IBKUfihnmroEpv-(;0Pp?!LQl!6?>1E!D1U1@RMZ0I>*{Yj6flQp*cAX$K)@7d+jcj(VkjZ@UFZyu6* zS4;b&HrHqlb^#4Bg01FSyX}?;S!UPImBy@w5W1drwvTLog5!a} z!Vo2k%@#51&drLR?*!8P2^dr&G(dAsF~DDl7C9zUaxqH$|RzXbe^ zbkBiG>z!;Y34{x^+aPu0Xc`bk?f2r$X_Q_Gu2V1vMcG2iQ2m#w#0c>wM|bZV3w%$( zTeYSWo5Nf%V{dI*pP%_-9{RuytNNp9@q?dXMH}w&jb&QO=y@u)k&3W_xfPta`)2G& zi%UXgod3iW%lw&fQY5W7XX=q%c15|Z;DX<|mMO0=PxDWo4NqgC=;DdKAF1=7f~-qV zWsZb%lzdEG4V^9rc}78_X|sFFipFk>>S312)8&wcHWQKElx8c**S;@A57!e$v553; z_;&nu2HZAf!y#bnaN4iy5+>r=6jVJdS&vF-G99FstA%y2?!boB(k;VEcKgYE2SixT zuX|Liou;y|3<&jEZR!mAI_7wIik#}A_ty77i%C1vZ@xQ;{Ol&QzLcozXCG*3sF_Z| zTEvc*_tOzB#LIOZtM1y~LhXlL5s0pj%9WkS7cB|?31UI=_@T4ZVMsp_;7gv0gxJcw^2*kiPky@)EnbcfEk$AEP! zE~ZmMlG@uhGzOUM=(U-`LI+K*FUYF08r`)RUq*s9dUZ9M&TqI)Jsq4QNkt7UX5te> z8S#yWxUxi1rH+tOhQW$x0D|C&=dd$Fhd7o%O8in*rUWrcPGe;sJcMeFTeeN9@#VYB zI@I-6v56mh{&GdQCW`1V4nnmP0kA2T-UnIr@`W3Q`!j~SdF4w6oRd$` z+Yh?@{8;qqy|G>EvQjcD_%wFf7yh>FJwhBao_pY^8S7e!au}GHLvHd-ezPL6kL3xxLq2!;Xr)liYD`IJ zl*{AxWpj}jO$Eh|J}%Num-Qllo5%GZ)x!MxivI}bT0EyW*Vp~R@86hWAvA2SkihiU zzd%h-=agR;G!K`RXk?E|vh)3$Hr(xf$?4{V-qEQ+gF-RcsI5dNWClL*1$KhUR=b2L zzF*-^%ekbi6FR^sJXdX9_Eguza_Xmuk?Y=#g}_U4;Z+u&iCd)CKvaNbDsH*hCR$|w zOuVBNNxa_av*o&t7F-iobBfoLtw`7{#JRH5*PFGQ+Vl@B_%>2Vg)cjk$Ivb!B-E2} zHF-~AvXX6wR|_9F6sNrzZTLalHIUVFwJ;OzKguz*^uf2`{A+REw~xT=<}}u>-O`wM zmO#_KTe{712jP-)L#+~rFqWzS__K>q;8T%|g;~O!+wOr5oTO@jVebbe+as?6SA$ct z7aIt}_FNI7vt9!+TDhu+-k-3fq%5eB=3&}%%{JKxr0odykqLV2W5x`1_h`jj_aeuv z3#c|4Tu(f?K0v{>gG`SH?l0|=3VUq7Uchmu-nPzG2>ap*{7u;3guW=cBdqj`=)~+H z8y>ml+rAV4#~W@F-SSlD^a#tsq0Q6!b%X?HMQS)*+4qbIZZdl6UhdA&yM z)JBmuna4Zy@}ls1#2>2(X9LaRA_3hVFNhI$=ze@W5fqnPrNF1Tb@~40RMDi#QJDayhp*@>#Zo`eLR1Jo_;2Tvgi*MKwEPNiP{&t$HHC zZrbfJd0US5$S*1)<361($10-z1d#9bVah& z{{+dZ8!R}J&VLMhC%oKtZ`C4!X1)_0@0!FzMK8K(9nd?o25AspzS%R-#{!Jqymg

y#Hwv#Thi=A9i_sPSBe@KGfP(w*5rHr1pPK z--NtYu*8LlzSy7Kb(9YUgO_URVymIDnlVm#K~*yCtDISV4a10MtR>gVfSXDy!r|1j zA-Rci`@^;PbT+f))aoraL7qE& z-PfOUYZp6caC=fn`#k$7E2hB8j#>m(z|WgYGf2|%DLtM>yAgfvyzp?L1tS~4Ma?K= z&x{GgX1f63jQm>Z=1z}$l*lI-9$dTT5;mIeW|{4OaqG<8@I{5Wy#@pA#Q8oc)#5QR zJV#*0Lo{i&m8vg!-aN`yJ!LK=QEznlmWgn^MAjw(7I?!{zOa^cq|(IpK|9qa5hpT& zRYSLcTLRlN@gvfquH7!(82dphEjCK}x-+o?1{ufl)J;BBR)J_*Q0f&0S60Y_Khi3F_Lj43ZE-)d#F z;jqoVp~g^UnSlM+@_QV$Qxle1(*OLHY$=K6SDV}UeS)i>ayR21^a0is4z>^Iy8Pq% zBT()I9Xgk$`kz8|TibgmV_gu5(kEu?kx@O-toeRil%8w@#MJ{-a?G`6mKvm1dq~*e zPiB{giriA@;zP9a1?WH&OWjCkAdb*wA}c^LC^a||{#py#{wm4s2^eE&_4dtQ$xamU(b^^)H=O`$I@k6j};jFKMY zbGTTP6ln2O<%&utZB2vgvE-;aR4D&e8m|T6EhaJ^g=y)G(UWf@!MA$YG_w0PWqA+K z$9lDr%1avBHdB~OZ`=__Q9VZGNzo4(sAL@lP~w~^C@dD4u>^>_ukzU&vN5*nj6c0B zndPBw%qZ5lJJd_|nbVf9U$Y$zQ_AO;+bIXl2O8xPt#@r_{ZqBX@4`h>bF&*GfFBPR zq1l#ut!aOYmb}2apRTJTwE%06B`_~gWUqRdctC|^F1YC(78B0eeUm5z>%R4V;>nYZaVe>AOxPizd8 zh%1vyx&S>74=}ZRTb&T~1~Z9L{LK`<8Rmd|?b83(nlbVN*u)c>{I9xy^Uwz~LhHXp zAzlK8ULJG(x+VntB@F)cfvC+^U65PE1Lp8fv*4HXW|dR#zy9-WLY_Z2H8E*q=Tr4B zucT5Lem$89nZJ>#siE;n9K?s;htBx$Hcfc?ze=1znN>b+JwKviV`IB+{PEWlTXIh- z=W_jO7W@u*R5x9q1wJ&3@C(bo>N$cuU{;JvNO(Dr{+y`s;jbqn+*^W+cV6Q|zRr!q z{#E|3E;8NcUcd6+_iXw9nmPX}mzeTK=HFw7{~#~ONPv?0LBvCMieCf?CioYjeiy7j zc=!KY%CDMf1pZpL|J4jpo5z2uO#fVK8> z>p@;n=>J6nY2E;EKd;`pbt~}9>z@kF#Q6TKZ-ih13c~pBH~mxSIZY>-JHhWN&qp1m zzP$zGxc~VwQ0^~<@1I)FHKZlk+xLPEk*(-vGnvGT9C zYFP1{Wm3l;)Yi`7oeQf0CY+Tjm7 zg<#cLyX!RB#Cl?DQr!M0gp>!q(VOWVyL)L6j)1jXp@r4l3Kl-MJ<5rY#HYp(;=6|K zUyj*~znbFSsO-^hnU$uUQAjU5hLe*Pe0yUl_>fz{V4&S*Vu|U@9q?hq_kwRbM7-c` zX0uA0$=ab%Y(bOkZGK065v__Lfh{mv6m9Q^j>~(U6w$E4E96I zzqEy`PsPMC@Z#s*wI6h%t;S8B(7i4yYyKxjLkLO&{oZFd zfg->Yub!GT6R6B2=gPZ3Cn~sT>(L!$Llp2IM(z$4UzWRmI=wl^8#N!wQbN<=>iPC_c=Gi@Vx*Evg zyXQpK)dIP90=K{p|BNaAP-|E!klZPz%y6(c7GT{;)!uVq%lC&2lHZJ7Q%iFr6BCwU&1oX#XB6CSpI_-doep^93O|jZ2dbF+r*Y3=_sgg= zDz+U3%(*rb9$Xx}y#3OlS8fion|fmFucF$31sE-qGlbNMQ!$(Wc<_ac;kw?EsrL7c z%2?;ol@&ehma9VZURNdTSgMi55th|9>cp0$UeCM0-vVw$j$FMhRIHG{y%XoHIPUbK z=v?4mqXyu)`GJcbHPv{?>3_zYa@RZBMn}-WM|@>-w>SHQLxkT-^C-csJ~&f4CurZ^ z=$9x&(^)p1SY0?{GA%hGVu?r@t`R&`mH%v)W#>!d8e_?A4N{GgpKliyu-p_1ivQ9n zKZ6T9OayJdCqH%Qb6De1U^O?6I(eWiT(t>0kYI@%2DWsQ1K@8ItiqFuRn`Oc#xoI6 z>I}w?N*S;#!tpAFkS}kE+m+kNrHbuG)~?ebG(`qB7+!OVlaVGrEJkaMTVKWV^(T#5 zAGgVB^0*uKl&q)7xG3sCK^rC=i|O2X{@*!)mujrq1GS%5W4Q zu^6960nb07Oisgh3wX@^&GhY_Z}v@-XaC@}Z6$=7R|8gatV1!d(o;^8me4Jm;4ije z!%L+^XpMET1xnF`Jx%f|(RAg`&@AEI4W;$h%uDaK5h)@C@V7q_$Sf>S_Z8Wd%5r^w zR>0tSwrRNcJ5M<-go06ocUDRekK)O66DZ{bSUmI{Cdri-+!uU~%u|9lofiVnhO5^E z2~M2vvuklyrTS8t_mU6(JQht+*>3B5W@$85`$!>!d*DgBoXNeo zy(Nzt9DZbw!ly;`kb(*M@?9T70JSd<Z|*nUV|3-NyK^g^acjWE88iA2nK>++tdP@|_7N&Yw}v{k&dZ zXWLaqMgHPc6TDPbLV1r6uT1v&^0a&(8V2wKx$?AZUt}c0Q8?N|wz|_t16c#%DAToe zx`4N5P|H$dI+miX`v?AuZ&iz2hUzN*F@NiB3s+oNjCDD?Sv}gz*XT8_eDLlhfhy2c zaPj$rVqN-LYt#qM-}5kOP=^48TUxu0E{TYJbu&aT;HAg-h6Ckzg|dms!#5Q#;Y&$< zT5R{%x)tbtcEvh2ob)VjJ*A~61rG=@cI_D!F|JQR$U2uNt1Xtvqd4>BfNiG?Cjl6DEP$TK;!8` zh-RY`mD7R_EoPxPEs_=&TFQ6V*563!qm}a8t#yLAXG=m(K0A^=d5)Y<8lA6z{SQea z!fFboBNLd`@-dsbxgcygk++!9r`vbaN59yU>YV{v9%EU&79OiXbh(k=g0EHw8m>K^ zepk1hk@x`Iy`hi5j9U-7%x4~oW7}H4g8#Vp?Wjo(a&T6k27aB!Qs(;_;>_a4;@2yL z$$jmLY9h-LOo*?}eP}n4L2AEU-gKP3;~0fZl*M!gKi2{Va2j(wq)%!NR#@rUJCe{% zpuN29<;9u2>v2c@>w-(>WXncZcU$jRS;LC1NDnT)kf%B2$7s&WTpf3@I^mqHeB9aL zV_6cl{1r0eqB~pzm&|1&T8#ypmY~)<)~dDXk(fzd-3=tUl-;ie-g8{^{TkuMy}%ax1V9d zP=7=|4tUWn?q$((HOR<1Jwni4c!|t*2&# z$g8K<()2g!ZxnSVJk@4M!yk1lofS=w+T?apLss=RWiv0y!y9X85OWdA-5PtxNP-VeYChMoBXuSN%X#tyN3wrZuvnG&a^9KZ1be==fGCVd z%U%dXe`_+YwB%2#6_m{z&KcvVfl1#Qk^9*(ibzn;7m5}4dam*@M)98OlXq8& z3MC82C1}`M@;}}5@HHMh%-D!L3J4(@^b19+l$$TM&reNV6U(SO26v6``gd8kUPQLX zoJf?kTpp9$rUS8@JIx5l#q}POWDjV!OD>*A_!l7rXuphtR`$Hoz|KsmB;LW2BpyoOQTd`F4*Iy@<82} zmNPEs?Npa_LH`L7F$^s+)}K(gdYa|{a_S}h$NZ~<8bL`D;#}WGWcYb?{qv2 zWber^Q11JlQ1xq#i$A20cQu{J`ye{(6xf{#`F6CM_()_!d!x%&ZPb zzeBKEuGhOyzpJ^I9!Nm{NK*2Rk`QVO%mNhot=ek+th1mO3d_(f9bk~;uG(XL@b>&n zT&J`@PpVl_t30kRHgWAf%d6xO<|2baN)icv*VqEKNi?yE&xH=$F0m`!rDE^9cA+ya zt^V214Cd9Hjj;|N>hWjStH`S@R2)Ww=rt&x=jbr?wSgkToxC)XGHXlpGYqq(Nfbg# zk(`5b^+4I6El$@D_m)=8n0EPsslKhvsz(h*p?V~(M;oTrf~4~VB*GG@Ug=>6P=581 zXAH^dBTQV%?r4S-$Av2&hd%GoGu=SFF2YUu3*UGZEyzhB;(qn_c&_B(kPwfgL+Cg?p## zkPbz!HJm1%G9*!YPAnz5*716~&c$+HO7$8ur*>5PGWxy_V{Z0&Av1T914y{Kb&)64 zVj7}?Vd`Kt#E<9nf7>YM9uCC9Kym}(kay84iFKj@x+wWy<^pj8m!m;NQ-j3h0&iRx za1-{yvLyUE0W8J(TR?l)JGWjlg;Jw586#okmuA$O?N7^xjjnqV z#v*~^0xh%`EI~H{``_8K@~&LoaP~sEZV4Yz7U=Dn1%GhhtKOGLH%eN4{XI03djFmG z6R$nJ8xlw2yZ%B!2bqt9R}`XR@4rr4cS;2NvTA*O7V?syvQ)Y1iu|0dl~C6*h^Xgo zYQ9eNvS9^prs6<){!JC5@0p#vPbsH+EjpiOKVZ?Tb15HS=|R`Q>mtoeM)SP>60^L@T~b`Sg3iOE zMwPv@(|$v0#*qfe+GD4jK;^g}!1nCrh)G#qTlE_d-tdQtOqqm5l@bj-LYx*0BadBF z?A84ip5$~!l_ggj`f8cm7AbempWkqUPfel@^u`PGO%8605z zBEI8VKzj8Xr3Q$DU3_!4K+7vf12Bj~PN<|K9|h=64$w+L zE_ZEe|ILEdjd^GOtEiNm>4;Rfy|=axEx7>AhmR{Rt0tLubQ+Y&*vW|ZX8TRk>RMO_ zE}SXd)fSk-ZiT&nQg=9+~Zl+Jm+lQBtsRtHwkFJY zGsN!^>Y^woe1N7~w>mdzcRZG`d`r5%uFPhuW5`8kIQ81|2?6E4C0*|6VU%O?i#YVm`{Rd%3%Tz0lfs8%=Q4FtF zpFq{|{#=9TfJmcqc;+qwnF|^=rUu>Hax`P>dq_l@1;{W?Q4DYE?d`a(&uN-cD>uBk z?YM~IUD2blZDS@m%mr4&)Hsc&6KBQd;RKbUA|r#I#NGwX_9w;3=JUPXw^A`*6PyI? z^cVF2iG8}!2mG!==Dnk*7lzq;hG5^AYg{cGR5%cS-qBq;mbTR>}xSx*xX@Zt)(z0rA z@KO{%!$~a_A1;(Ad>KWo7GO-wE%V!L^y(iJ$+VTKf!jOw0F_S*A4l_uzL&nV_%33! zXA@Jjcjam*0xqLZBi!i29HLf`R~so4Kx^CxZJGCP^%ZI zZezp-GhLGsVZKf#-)oPf7m+1C81?y3fv-C0ZKdYO4{SJbkuXmZ5@c6FRs(K19=AU< zYveVdWl;N7dbn2eNhFMb@*Dv-2}+ztp8Hd{;RA+T4$(OGeqI52 zC59A8cm)3!G01*hrgA4KaODUz={h@956K_2u@iKVFLUjEHBn);6a_xDw7q)P?8`%= z^ypxLWfYf*vDrUt_w)2MeH7@zc^CGh%CyC*zr*Nh5>T70$ypIL3GsIi5;|%N`A|0Z#5NK(=r5 z&5RY=z!?fgVz9uS7w6UG`Ns{LAWS?)#D1<)K$S@ES->5{z(8&ndeYTr8-TUF`nM1& zdgDl?Ma<0dy42A3qlbO#=!)0DZ}_n2&6Ys#C%~#vt!gcR+Uds4WFQQJs(9Nm3D}2y zQYh`eB`?n{lP}%4Uy%r39@9yV2x{KkZz_}Lf;V28n5jWKx&hF^l3YwU6N@@$E%hN4 zonmK)#Mf#YrE)0N%oY5&ubz%%sr%%Cmgtsn&#fnK<=CdZ**zdxsT*}mWtYU}V<){) zSt(LZMtnuc64zJ9J2moG!*lm<9rJ!ZC=tKx>-NJgJ)0nBm)@=;cWw`{c2=H|8shPy z+d|aco&J^ zN2xA;N9{LW$|$~WQIrtPn#rcTFZ}pOP~-I4j<0A03QXH?ZA!9Iug7N_Mk|wR2RpIS z&Oz|Qmo(hhkA)%m*{iL&E#@b2)bjES`RS%CcZzD>L+txGS5rVvjj%{RW5;90~ z!e{OWPeY@_lGyJG?{yIgw_5ur5D7c*{5^!{6wFE~Oq9_NZij?-9_^H9w=X>#wn<80 zR@y1t_&uwA84kAV5j%XkPzP;dFTfGor14yKpJgJ6mhp(GAzV$|6V7~x3q&TJy`=*A zxuX{Uk1RlO88yTO2VXO&v5|UO<2CR9;mP7=MJtPtQ0i?m!2lwAeDawixisH={C@lE z#%(5%uNXSIyQ`h%8$WQ%oEa)8Dl%|zlzfK8UFbk7^85#}8(`am^qZo6(?kB8Ko9x&QVKTJ9A zCtpeZ#?JaA$A*o4(jI0xd6e%p`tWFnf9Y=sI^m+Url#ftx74pY2dsF2|03xbv!PMH zG#5Ab`pdtG^XHF?M{U=Q-~HE3CP%CP4cyOI{u@Qdr_}wYu3x_i{x>N6J>LJ9duN~E7+P>EStDppojQmJ{ZIjeYgd}5-4k`l+d#(&aRL$c|vaA9E~UASmoSzckG zCe+)dShqs;=|hHxx5?ZU&ZusEc=zO{-nTadM2|Q>n{|G?Zv0>M&sgADsOYm+sb2i+ zr>{64;p;dMdPp2rq*uvMZ8gCDzgD?~_j1fov=7XH@vgC)*WvyB{r^k1kkxWDnL$sc z5FYZgw?bax-76Ps(5`voN6!%?ZEt;FT_kpPcazf5nGRXvEKj`> zJehcT<81^CeqDOgZBNl&|F`o?s4Z(Rg$yw|~KMOax{TKa+eZG{ZO{pFRFyY})}J*EeHEeS`w zL7zri$Rj&(Kf^BsT1}VK3uE2l0 z^_UdS#AaFvP*aLst=?SCF~w48Uqa-cX1;_NsGvO;XrK}xp4OMFyR5W38W}ZkH9lay ze%CwZ3b4Y!7(<5~LolNY6HD@Ezik$Gw69pj`6sw3S0wd0lADsbOTBTDV+$JLN}IR~ zRMp6PHgBTHDjav+j`d5w?=E1@c~Z$Q!|A5i|E@)`1Ssm3)@o8m9>1hm6nUXSEdRRi z+Fs39Xbc^~FO64;(O1amTRNz9fW?14`x?d739gJ^xnb?xo1!+$TVpujfRLC&M%>w& zai+&Xe5R!LktzEswQ=L8{NcxFx`p=k6<1GhOX%6hRh*p6>v z1ji+$;$Kd%))X57MW(7$$nR*H878OJ=*;IISiv~DP4?_wLjbg6FJIa)yU(yWVaqJ! zXm+esDbEE#=)HK-!4+$v<`bM<23*|U+*v%x4q7)k_#>&3q|~q~SeqbDDCqrhE4+39 ztMRtP+lMwW8v^!9?S6L;&7pHISMU;AA4yOmcf4}KPsl4)ekIz#b7iV3qSRC{F#>US zX}*0Bx$Jq}cqQgqDfRIaRQ4ozSEp0GN>$U~@aroL6H&K-)Az^OMvD1PtRv4nE(MKK z|C8m|ZLnNi6o$=lA!)qJ8?-9b8aZXzksR5Im1S0Nt3Jc?_4yk1BAMHoHAWIMCO?Hu zc@Qn;+o8O=>d(2A@$-jTVJYhE=5cX3Lzr<#zVXNVd4cUyy&x*Oery`6uTZ|u=`!A{ z!c?T?5hHr)89F%qZD1P2c~J!*uPKv*dUhKuz3U8<@A3LfPr5+xcn3U+6@khfcx%{tW`;@u$S{06V9wH|~dC~9tg;`d%J zasRL#b4TxdaK=ngD)yd)Bimm?uc`(({a;d#N zY1%1U5TUV3s%iDfMr4Lmuyp?f>V2icFF9bv_U`3Ro8L5ADgc;Pgal}c5xr0`tT5xW4Yb8fKm zV9@?)!Bpa&nG%J>Pqu|Kk?0hOvmr*VG$>i*Q`4dYVht4Uh;AM!QEIMnt6Kz}7s1uD z*1_jNY7Eb7_D-jH0By4{cGn{!-PfyqYA05wxB0Hh<6%I)ZO8((?{s%**;IlF%CoSe z_?F*K`1S#%#Cz**=m6-s;EuV&530=3GtN*>ZundLaYAjyE}ZAKOzkat@&ZO?CB=NL zkgS-jowpi$xgw_@Hj8SO$QJ?++2Fg+g64Jsiy!Q+4><}qM#(7ce}3(sE+B7JV&m`U z^06Bg_~gyNUeZ9Q42sg*`5I-tE=IWB3}NKZ7plR#I(%z;ftWGY)@SB$h7{}7 zd(lccefP6Oj#CUpDik(!DkkwM!S`01WB0qhn(Eb*KeG+1{o=CBjz5i8-CfWWaC(n% zG|?8c8#y56AOYG{48Br_Q=+$`v;M z7&wOh2rjDr)auQwKP;?KEVy(61Ag|(;Q_e}J?m0VhxI|tv>ZLJOwP~8uGl+mcxD6V zM^T(+GF_q{+ANC@YYt8gtMY3tht$BB$Ae>?`bZ-M>C;ou|eE|7+zKF&&`I530ZR{#e$`zPxppNpeRlm{4?L zC3nXka`FX(9xb2Hna?nfyy3Run0rf996t4yT%Dg_@sVoDe8M9y0NfmG439KUd~);V zJLk@c%)kMp7F?+7=gb%;MCNk#_4)mo%opIj|)3AcM}Kl=sbG*Q}Oi z!?FV2=X@>zBZtlhNT};@tFb;Rmnjl$hHUgVojQL{go>7s>uQm-hwggsOuKZX&$S~R zIrvInebPJQ(|L7OgYh0GC~FgV5v=XOz0%Hu9Tj|j?b@8@nkDt<3dpGu&DGcnV$YYJ zj%q~7E|}=0lbTR=2M&IPqObHWZEjKyA4NphUYGh~m`&Vc;3}@-gbjB*t1DcD>l!-o zkl-$~O+|s$({@Er7r95K9|EiyY{!b@uW7be3=si__eX9#B-%b1Dy5@cTur32bX7F> z$#!8Qb1nRdHoOWs%bQ+}e%w!y+YWYE zs88kJ<2}pt1CV|hxAB-ub63%8JH}g{b&0KO^(eq%e7WV#tHTge%t9d|aq25!cRi0% z4m2OPJ4!;~-RW}Y4y*d<*CTgfq@Lch7!m;0cS{u0>phI2ZD!BzX0}1HpoAK-!Hk~I zDrTvjWCvMu{G>(8-=JP1yGwyW`NBaM9}q8?#@xDy)Pw==Fo!KiD5^7I-_YW%8sSXn#?3Sz_Uv3NRH`4AA63u_-0nWA4 zkhZTPOW&fmBK&yGIIF8ThA@y>5vL|2ix*B^iaIE=rSM0075ugsA8|%pad}nf-`}nI zB}w$0l6&qK2tb~%7oWvs0Pz3yO+C+>#E$IyrY!ykQ*@7pLxuDzvF=d*J|M9JXzLd}dBd1{aO!8kXUl!nJ7wLUR=* zyA4;mtDky~=|~-1WzfoWnncKN0)fcLrlw&tZ!fs;u>*X4I;zHxhiVv&Kj}t+C7*h* z8Z0goTSawsCe@=QEvB%gO*4qab>s5+OcmjhYZhcL{&JC^&6;$~Oc6MfDGbAgO+E^f@sKmVEIUwPNjAwPrIzIZ~ z@P0s##0RR-=7HxKs^KPw#N-~$QS|4u%fS;QLv}FX`@{gOUx}1i;N~ z0Q^Kxv=oE?;6n$TS7si~G~L1Ou~5>T`_4!j)iF*=e6yYZVJB)l{LwA!(b9)h0J5%& zDmKz&E-o>qIhhA>8ig#(l$pMFuc&i6_U`Hy7bE`6u}k~z2%eU1Y+`x7R4$^T{2WsM zpB4_f!Wz)6#+YRHKgfH_uqeCsUl;`iX#oYKyFr>E1(Yu7M(M7h(;%d!8>G9tkP(togF=RI0VNs*r0Wl@r5a-3ktaVi&dtdx>1@qzBC> zwg=vq(ho67I#bp`3$QEKW_N|KWyI#$X!o@_TVi$A#B4aWs=@E?Xx664^ZGcG2rCGb zKD=N~%#Bqbo{>6Shrb41T5zGMb>_sn zrxmP}PtWj59Es4X4+SA}D3Lz|BT|NouNqJ1RYj)>VE^#gZ+h5xAccN?$mo2G-k}C7 z2V~1JGYS|_Bnjhyb>kL9LY#|~Pn`61o>IlNdKtAhB6LjyA~Ym1H(Jr=KJ#xOUK=$5yjo+FYL;}zm{<(>1jE-en_3M&453%Tb#aCa0$`pNEvF^AW>}l9 zj8jVr+DT3Zm4#6KZYaOsQ{SO-$Q0!Cw%)RLtWw5ryThG%&XI){s5&S?-4n-YJf zJWa}|5Hb}e^@-)}UB`kKueoSm62EnMla>pQ?89T`FIBwo z?vfw<9!r9&(pTQ&j@QZ#1V&pa+swzG zAOy3ya&0X*b8VgK4EbRppUA4I9lsj?r-QlVT^hisq})G>SHJZDwuMeIGOWf z!zjumR!Q&FaN1hFySX0f1G49yo2Z61V=jU(>XCAk#gRg$Y*E|o_?tA@qr~pbY5|bi z72;EqWR&S;BqW~Rd&NVF&sxi_+9nvXKa9L7x3=hMw-s5}%K_Z*$b3n!N*{ja_vwIj zy$$Qn*&;ryf3qs?`7P%l)r;4JAIS64T&n~pa>a@xgeTXk4pjg{T}<%N5w`VAd%$9@ zovV`v39CnjNLDz1Aa7}N(t%`KPya^eXMy(@A}NZOp9I{XXUPR^3^7e<7xlshCq7Bt{%5Y+Ol`1;l z(Ik8qp?h~_N`?2(@avRpNCX`wipw;c5HT%Wdv{gz2^$|7evp`}BmnkW=w2UNS~@p< zYT_qT&{mGw$Vyv})5rshhTYiyAw!PTHh{e8YC|pBSm^$8HM#!4&Uu0oUm(?R`C|{r z(^_@*y4qg!YP7~*9guP#8+i2zbV(M?0n?OT4fb}s%~)e-F{Ynh=14h3AP=ucK>{Qi zLo%zZvn8-RND|u%FAi2qM|YY~v=3(8JZbtUsW{11>rwo9^P;Jo`ECrr^v{BoRAwqK(!MuA{d*Uc^6IT=Q_8)O#SV8m63H!AAwZ6e zJkDL8o3H5~^alCtt)%cCJyNi|dp>B%o%Je9JBH~Qtyw=_kB@MiR$@VQ%Z&k7NT7Yq ziCg)yj??aiU@z}wxPo3phD$$RWxT?MuayADHkc`&g{x=^By?o>ms(Mmz0 zO-19giXX0r5*li`-UMw5(o~O-#31A(qQQ6%UU@*sT_#5HnOrIacvOjB6PLdgXU2Oh z`al*>>9Iim49ROzq#c^-^^_Bz7uodK^<1(W`&*O0jGxJ-i}Q}o|<^0YspaG>&~5VTMDSo^cPJ*>su#M0k|%W8}3nQ zl{mK}aR7Eif;jC-gcSM*m1?yMq??^cI&!iG-he~4A5NJ`xMK3*emM<_c%FC1)}?0g z0(HI&pHcPG3u_juX`3(-WSR87@{BciSjWxItQ)CNBNw&JWUpNEF=^XVNY6*t)2x>W zfg}Jg55>5`tyLdRZ?e(=S|7O=-zsU#N zHO}MHAl#k9wl`0^!q3@XR;5^(u93GsIyrZ-_v4AS!>f-aYL)o%rk5(q*i1l1p=3JZ zzUcK2&oi*QcuXrPPyt>5SI7&{Z*M;m$7ALd;^KvPD?3e4)wt==-NePEjdzS+HHWI5 z$FsT=5x)?RiA$mO#FuMK2Aiq7@R{>W+ZcX?#o;Y0Xt81WEnlaAq%x9XS648gHx7L> z?uhO9+X8*TlkhJ_P4YK0nluVT9*?m|y*VQmE>X7H93J;B3j5RHmVOt()!%$S-}^XB zF;~ii!IEq-jdr7Uq(k1;5o6qJ`nyP7=$qT*5e~}%+7JH0%8g^APIjKmPs9-X9h(ip zUvcy=Ann7W$>7MmE_z*{_Y|2vM)}hVrw3M3wzBa(uZ_L|oAu6FZJUA2WkOdJL}+SX z-lqF(PKpt_Nuzi6S(aVeQvJ=N(3 zG!?RKbHF&+={%do@vmd@5LX2&EAHS!3?gSEXLohSqQq( zo3*lk9<94rpWzi4YkdpAsZu|J>WJXx+@?WT~@q!8gI~8vEM?Cw>#o@1_f5)puD!~^R#|expzig=-l=`uW9*E zgBMJ#RQ)(_@rpQav0*wE&&KIlXPQVDG4bNp$Az7b#91k=c9WYg4rH5~JaDPAU)Oq| zDG+ge3IXxORf@htc%{A6x6V*Q$bQSN@3jRWHNdB#C?TFCy2#x2L8?ZyD1n>xt75i6 z^htdko~{Y&%ev4fRx8JvFXd2$1w$AXNF^ulvfR!-l?q#}(T%(lAb} zmwP`p`Xzi;oQ8LHk6 zhkC3!lajF~YU)xbhs1u7h+Z>Sa#{We`IF*GIGQzQ|^edTKe*QU6iY>vXSaKOL*cgE&Q;BHo1u4p$j06-#K+j46weywxV66Kf< ziH*7OD!WUB>#8ENoZ(s|E{ie0eRvS_(!o)rElukPLi1mAVt<{#2cCSrwSDp5y8r%A z`=?5-p#4u*pMrLjEmy>`gO`+#DI=wP>VDd&{nbqN$G&$}sLX%39Ki%1rl`GnmGv4P z`a|XY3-UId-yqbc8LM^x0Xk`@aCT}8T+s#qZmzo$T?h8TFUZsX;s#Ei;kKx(e?JWl zz)evjuYr5i{94^9FSq;g`mOC>3eIX|PYgcEtkI97zqwpB*e)%k`8G~{S&i}9ei;>` z@&`?_n-4WsH-+Fp`xEqkJ6%yr`wDoXvBOH{!#H1I=Adt22H{;#&7ye=`o()#~(%ggdotR9nhEnP>e91xg6;S zLG=GSN&oq9w@Mj_lA%Q3Hvf&{;2S2N+3?%0FCh(AS7rSJf80z>QZ9(X*Q?2Kz-5W2 zNI}6GZm%mSU9b~VG#SGRYYZ~mEG3V+d3EwlLcgV+HAfjYC@bc}eaoP|#B zik#DDDPusUR*S=XZsC9ZqtWV@XF(SkhXO*Y06_AC7+Xqqq zx4teaTU?hEDWy*O%Tc1MquGd`NU3##FII~-*4wcsygT1W|ir`x- zp)*r_wv;1f5CcuY=q|Ga=sLjy1_%UU6e&^C1jR&gTX=)aH%r67-!42_-L4%Qd5fhg z#H6Y5StLs~dpUQjO4=gi$(9D#O@dV}QVMQs*KB^H%9!ZqK-?6V%x8N(l&(+RK8hm` zJN#6b#xf182J-whPtJ-$eOJ}PVLUza5LmLr5dzWWN?fT^^9B`Vto9i6l#0G~71>nL zJ7}be{B17|V1_O3ib65MEg*46a;(LUjxpzzR>O1uft(9&2nmfqvbSg4wz8?9i^zz# zet6uX;up^byvlgCTse9pXLx*gas=s@qN@HlNRJ+);^#^v&COk`d(tjt#Hd3djZf&3Ruy70m$b!Ue8JReC@`@V>%>&e0fBeEC! z9?7M+l7uA%1l?T{Xe^&S*1{!~zt7VDsZlo=r*iQ-8Ar2RnR^ zJY#m(Yj_+3%ddz1BaWioBFK${DNa};)=51{n}`ImYh2k0U;yb^`>dNGKJ|YbHzcs-Il& z^g5xY-*rqnR&^zwA!xEY_eS z(CCiAG%e=1mQ{eu8&38VD&t3TA0+TdIal6ux3{GSON5oW19ET6ud&)zD|nvlifkE* z^FE0}CXQ8<{st{q5GssVDj1BDp;s$Y`YHm=3Oqmi`(E5Y4Y?1h7#>QuCpvkAjq;HE zDUD_>nrrjrbNm|mmX^Z+HbU3VSafd>+GXbDmwwpN(hk;?FIa~A#xE29gSg_XMJvHG7zy?K$KR4v>Y02 zCST3$*mv6EM{RWKuijbpYVxlVHyRw$pNuy;4EI$CUfjM+t8bu-bxp0j)%ZXm_JaA@ z;*KLn%RNrUrdycge{`okF5d$TfuG^#z96%f|+)+zOGz0VemhMWGo;%P(! zC9upSPB;l%k8+#@b{WFiaQ%uE-HtZ=k%(@S&C(l^_}h@(c{yX5Bz>Vb!xW6_MRK}M z57WIWW6Z}Ln-op9%-aMV+iQ4_4kk1-pH9ai=L!yJ<<$1%8nu4CbMgp3_(y%XY{7r(3ss-@jrrbkOc4^mJIGspNxfsH> z6=-4UjIeoeQ5s7Ku;lZeW6AbS-o*?1D4#xTbb{&na3F1{JR|zj{7_TD`t%WrXLW|U z$LFDLvgdSGf&LDFc{W92doWV??r37vNch%ucxvKu-h)^b@s}DStMmH{mK-6jWmbbv z3??^bs2G*0tKYwZC~oeMA*w!G2rkSZXcGpq)9EFNx`b^^TszUrV}9rTD=ft?q~fnX zntTI4#_}g1N3{A&+Pe9jEY*Kf7dLn#*D-l()-fn(f5V@7)Q>04_NpXn4rqL3gP6OP z57-8nYBWU5-*Lui&m$#AJVuOf_FFrFB5S8(8&mUwvVPOuuAC%@!`RmK3Ry z;Iu5qVe}{)Pd?8H8pl;)K#AXDWA<31l5(|Q#r@432TvCcgL(leNq}G{%XBsQWBR!- zG#J6YU4=$TuNj=$AN($Hc>j8ySZun0pC^94CbI?MVzBXCjaB@z&AR5^RLMz`KQt;O zMGkIL1{d3*C71fr4I>va1KvSFLB=K~kAq$wH$5SF3D54*H`*8)ik`$}A?D(8PCC7@ zA!YRY8Dfs^e-a7*Un_IRwhyl`Ua**;PZJZcPSY!H;i$od*=_Ov8Oxn$4ZsVwz{)0(Bvjk_>J&==WE=!AX^;uE{Y#+TBy!1iCC zzQ1{P2Rjb=-j)rHxl<2#VU%+LM7fZ3fnFmEV^*tgT zGCWdKd}H4hj5O`rzTcqL{{JJ$_0=XDT3v2O4)Rs#Q5D82Pys5iEllC01b^g&LouA3sO{8_pFu2rKbPl_iSFRvou;w_5xv_*YbqpDawhlTL?4#|Mig zh?H87fML89TkV)I2U3#A=5-t^y1UrU>O;Rt($p%wa*H^vY~ERF!vJ$I1G$*oKF6Ffku~!r-i!za+qXSNeiMmq zjJll4y+jTOfXKt&U6wc-I$4^(y}cP3{W`p(57EsH^9)l%RLIeMGf(&S8OAjml_FCk z_o>%XDzWFfv)7a<5-=B&S_q*$ymgEF%Y4=vA#8P+ON2ID34G#qc|^SwY&DXohQa&C zn}Pug5tN+ByZNj%g@oF3?OB``>~Yo7bxMwwMRolZj{-v*P?PUZ!3KP9t0mah@GSVu zFPJ;aee$^-tA1A$JsukL?AZS7yt>4LDxLW@(tz?a=|icUSIM;0;XaX&Rs-?>NK6 z;Cvo6t=Z+i0r>2WU~tJR5|C(d>gk0_<(XsKLR7>l* zojv?rk6~>42|SINVW04VIT<4{dA5zj5l%t(wF8r`?5pCzD#~A$+h3z6H=yIAvsaA( z#dx_0PP^_8-3qhhr#z!<^uSy;g*&An?ASDpbDVMO6E6hlLtOG4X2tv{L;5di?&kpW z2KzKFfaip~&)MwpA|F=OpO$+K`TfpvzQ8L2drYO~5h;D**dA`GyyrWuiN-xRQVdB7 zJJ&20+HGC>y|TzmFfyZD>y;!T(zkOeor$ds@UteDOpI+;Mejte)Jl63dYnxMJ9o%2 zaG`=&YwQ=J`TtNMCjLG=)=n_k;)e})i|2)~CiE9>i^-!^Op|MJ0UtMo5nI7+gMI4C z4d6D`{cv;*!js+hWSNQK;tKwXWP_U^7Z)@C1$JeAH17!|1Zc-cMvB4{Q1^jAOKbd+ zIKK~&@%iuI3bi!j^FLu3Bn146Y?A4A^!`!?%h@r|U5q)SnY zL9fq%p1*`=jB=@b^Ywn~<#)8*sgmU75-B*M(p8H9k7_LBdXorG;kx0`?hcQ$MC`iY z(9rU$C6TXku_n7IC?#>(=Ep-y9|KgR6clJVIXT;OBB{ZY3G+m(2Cag1bumBpXN$U9 zpydyKzxM1u`whZ_7lYaUAa*vq&-8c$5FTpjroOy)z))uc`L)PZtf&gUBoP)oV=WPm zwTjgRz!4KAa)I%BQC|Iew!W@__o8TFzHTfao~{fKe?oR0vwwT=6W9G~@$De2tF!|; zK0KPXKlps(?wNRRORsxscwJ;m4^(a;LR?*Lc@EPz8>-j1+^@4XL@rl!`nq;npcJFM zC2zFx-a1C3(#Ld89?@K%J5}t+f%-|2*w$kM;%f4%)}V^bHA%iQalL`33gmd`pY8Wi zd_t|)7x%)m-3p8d&v)R7QLTq>1Oc~iX-9Md?0%up59090_@6Z0gSNbk_wJ0BojN?x zfEn4K2S0H1Fbj=U0p$(*+kHE(7$KZx6~<~DG(7mGf7-Gm8(b%tCQ7GHX|d)QJi(G~ zAPo}=W`RQuwjUGf3osWIS`)6jKN^#`FmHSyN<5joDArADpAM;Qf85&h@6Bij(rKLS zs8+wz*6-FPP{hQQbu644P{(`~UgoPMTh*L&n{pf`>fXhECwWTakAE`mV}Ri*kdg=8Kn4-H`^* zUDpSi*UH)?qBZwPY#)AtM_@?r!&J)X6X!@IR z(Gi>Fr()E2j0!bR>44KZOfwEjcE)!lT)`1*hkGIvo`HKh`eZK?l_j04f=!fxqs#ccBp(-g1idFJ^HrS(BNzB&!2 zXXVw9$r!%Z0Uw)64eVsQ>6MAEci%^jhF$MrgDff;t z&sH4GaF9Z@KfQ^(3pJ?13XFm>RY{;{LRU=~QWB(Ojt01PeFW^vmRqTTn{5_4dCV5l zM{u5!If)K9zRuj&;|Z>~j_$3mpMM;~lp>`Z={T_`m_WB#Vlpk-R}o8g)JL;up~@bX z-DMoCmM}O0P#}fS4FRZIXx@M_(S_Zr2Fp?-oJQvNfmgkW;`EAbm{TE=G00# zC{sEpJEri}Ue$roc_m5G{4LFhzB409vTB}FB=z^TXa*lme2Jk5>_Ird@YHBB;eh(C z)t6j1F=T1r!~O`tY}unp8GH(M)-WiF@CL~))!cqOBbz4A68kT z&Ay!ot0)=n8>?%8z~)}(IiUtgzbcrh$I?)|j*|xnbcpQ2Pf@so9_dV0elWg>u5hd> zuDIbqjcH2O*2i_Ah<%fE;*`XnThNaMrhG4I3pXVzq=&tHvOw;VJIo_hVFkt*sC8}e zkZtJJU#fiD$GSdBF;`*zj14nu?I>@Ym!)scjx&Mlh`%v3@G|PmV%Y*gGN*W>DxU6W zU#&$`<2$E5UkkA)`Ar~UXgYs#muW9hY?_1G1Ui7Ml5RG!!$R;xE<2DuJj|d0g z_T0W)^+?_3&F5zz!ao65VlxD_LlWoqor$C@#}ZZM=qk^P&~roE!buHm)=L0&->4n- zlFop(+1`Qkmx5sWaFH8SM(f0piHfXCjV4I{^&t(Yw354%REIN~!lv;keWY{3eEwtA z^%JVSI>;qOj8vpvFCwlHIK_8-YsgH?cVTgeU^1HHhQvRj{BluRF0JB2qn;;wxeVib zXAyR@IWCF2BC0mpA(Pu6lUh13VgZ-PjrO%V);(-SZ}glG2s)SFThpo=jcLC=Yyp5P zpZVQgFe(Z;u&1{6t*2^f0AC7rafqxGc&3|5c;I@R?#bm;(=*}cDqTe&qbP0nan`?m zVIzj{m6A)C8RZ=a2x(Y z-~Qk;`vvctHek7&tF4zk!SLF<8OFwR{di$TI?hXftcJaOJ_O2m?hKoj5O-)|ye7Xr zw#gkzK!Al8i2i^~GX~+a_g9i?Yd4JaS|}S?vlG8gRrcPttAbFYAV;_Z*}}l<-ncxK z>42^lC@mXER}q%RfMD!>{uEM*`npb@NoMOgQnT=y1naXKsvJd+IM?3OJYDmxkva@+ z)-i7aHld|hq<1sg9IWOq^N`6lBJ0Ysq;HTuc@5{w2C(yjk?xv{Io>xbCtTMvCFEM}9=NO1N;u5m9mvtP`>L7G=XoIA z=6=IDy=t^dV8rIJr4AX-&CSjBw?jjHFMCQfWc1uIva2=Y-HRr_!FfnZa~P{nFa_@r z`P6D#v%rRKVK<^~F9WxZ{R9gY!O`^_(!HeH-s=fW-ow)@Jy#FV%s>fDL9iJM-(bl( zo-=)FDj61T*0DfjzQBw=3OoAN&C4!OM94er5w;g0H@iW>%ee&# zA%uFHfP9@XsphgDBN*b>t@=?Z7~bkBI(kP87PJmRJR?4sn4gu&!uaY+TvES7r_ay+ znEMaVw83O5EwYob({7}~)PW5;^#uxf5=qO|?1ds+dYL`UVX057o4x)zclE@DZp0-; zfqmDjI#2g0aG#YfrPZp58?))QXZF<=6;xZ#$8>Egx8C?*u!|8-xgyA~sUOe9Xc^zf z-q@Oj9IC85=XWU<1vwTayLsNC-QrkxHB4Vzsnok)jA$kpdDdl7GbO;T*j~QxtBZC& zh_)VZ*_Dj$GlWMT?8%MG&WCC|V)7kmfLr4DZ2E3*WOb9o1a?ad zn+A*NOB1wbsRWMZ&Ik_^fhz1L^-pbyC8y%kk2myB8rk9bLEDq}l+7p0NP^l}uAy4- z(M!!VY9E*`S6b|V1UHMGCB@E6nzf8CI^ovdpO{TY%XHfCMjxmo94^rYpOJRZ_@eS6 zYLRig9fN&QP`oCtO*43E13rl_epn4xK2DhdFX=fol7>cs#Lb-1|6XYWLhb@z-PaVE zHJ?!|+}T@h9u;qQeeafj^is3QRERz55du=kXLUX)>m3gcBhPw(W+={%sA0%dxl5q) zDy2m>lA&?w@(Xkn^@G76ma^53_@1NdxzbY^Xc!^k$tP8Um+{vCul8-6)+<}?Y?ln5 zSZ~4&w68ch439%AZO^nbUpRerW&ZS1^GJ%UQ1E!`Y&B|7lh8kysBLX8y)wwk70G!G z)@<9vV!Yre94YnsT14Q(y(bqXZQeM{qB~I(hLEziHaz9Mt(3Q?i}x!ttrEP{F=%1# zoCC}TqIix3956JZ*7eyv)~%^L)5GCo`Ijh>F?hYS_l;qs9wT>mOsylBDlI;GsL)B$ zM3KWb11e*-`sk@x$nDA25tCL0Evo;?Ipm3T?8)zhW0X4PaUn**Mlh_P_Z+}S#74(P zs;r{&)M-e*`RMn~+^JXQ?f38RG_Bdr#F0L};A#Y}aI%I!*ST5N&Ju)<><>BTwRWkn zm3@)SBb4)XMcYsSgCafAw-4xLm{F0=y*V7o@o4ehvG|_ilD|lJ26wG2ZQZ!z3KvMw zPGzL16@lr?1{5ssAsLnl4`-t(uBYv))K{+>NVo${_TEBF z(XyH*0KW5+!T2-}(VvQTc%`A>ZBJ8kqdU+dMD&`1rejRw!1%D!z{cQdhz->5-2+#QL{y{F3WxqT|hejSLItrx@O2o|P2M*xe2B=F=-luSN^< zUYY|Ri!V~IgOMniFE=zQkDDu?Prke?0|GK`@p?ji0un2&c1r`j)eKrznl7mM_+=6hp=vzfy0zNZ;J#FCCk&%>VMQW%HEJqweiKxk=N~ zVDv|(v4%Y``VJ5?)>K4vxe}Q!h6tYwxq`)dw$kc5;H5v~lSkc4Z@n#X8(o;1=8Ii0 zE604}&e&B9w57^dheOF+F`Rv1vDT)j@epi#OtnIp93`G*@9PIde4#OV7YwSA12p0< z<9q4nTZu|=&hru%qW(v2Xm~dLNw}rxu_j*}5#%c2%+oU4nCh7tdL_S+ARF6!S;Fqu z*V}v`p*@t!<<|K3buAs&!7YHhd~fN>r{8DvQ>7xjIuLn9dOP-^b~LJ0OnO%Sn%ol*U3U5#DNY??Ll^@khZ);b6goj-pesMTwwe&up- zXTO*}B5)wp=*ogDBGO%g<@L2k_rNit<84P*pKjIpMb+Tm?`vRy$X$>g@P1PR8jqHH zVc1pE>v(xe>SUw+A2Y1!eUk>_pRrF z>A(j<5P`%X1Ed01=!8YT0lx@X{x#Ye@q+60s-Jj_LL}6gebm)Mo$1V_MRY5J>eOhYaaBm ziPTJaLRlQoO6?;JCD**Lk1+>l20i*b5iYKJgM_X%hMU}ypQjOn){C;+d>kGsHiclSfxe4OD}I62V2xHSc{=TSpmUFPT5Dcoq!)wRqoY|fd+snh z!>yzuY-6t=eN8))rWCz(1)>#hGnYHMJdk=;-G~rL-GOyhc>G5-A$`bFQ0|lH+2i>- zFP%Fa{l*dun^GbWLs?o^bUgRgA%5d%#%uSeDvgtqt@PK|!CDK`G`&@=7t&wMZFXbO z;BT@bLVLAPPuo4&nr1=H9}@V_zih#%-g{;!cvd5abxXNl!F3KWVA)BRXHh?Do>H-# zS~z&|qbW@tMkMCzwGWTv&~%4uE)-1$sH$d(6J2hw}=hmw#bTx2od)nHxvO_YoQKR3_`cd=tMV+BO%C;#*v$dTRsHMCe0#+lH_}xZTW= z>y)_TBStbGba_;>d+xaQvJ3*r+pi0J5tsOFzgX}0f|tu#;DbeL`vJUFoX% zSvR+-v7Ed^5tJQh=<0e|Sy}0FJ&1UHlgw@;5k6&NZ2T=-8W$eg`J$e61g^Bud)ev} zm)vvr!qA+(syA$P5`)C;FrZYxKbiOL98sifq2mB|?H+0@e`xS4tQMn)5?Cz6S4-R& z9`)~yC7>`~mgRYLEm|&1@vX(ZHk*Y`(T6zn`VFYvxS0AHKbaOD%UDDd_1j}NXSO|f z9KaGdPDbn@J?|BDwaA=Ca>gfO@+8CZQahojdc~)gh$G4u^JY-^cAbDkEQPdy%i~8YhPO>?ZLfTO$NB7o!k)b z0h=&ypr<6Sk`|?wy_dyws!%~87EF?)EHg*K8iMiD!F3NMC z*I=Q6?|}c}3*>#lFFmZ&Pb;}sZs)$*Nk&y8B7z!dUtB*<-SK?sa}mk=!6bRC%5MDD zcI_L!RE}w~@Wc>A_}BFg|BRZiOGc{;Pvy0+r2Lbn*^9>`1wV$j1EHBl1i{09c-p4{$Y4k69p=C zKVV6C^&6RRG!${7M2DBH_D?M#{t)EhFOUD#Jqx1WU`hB5sOZ0!fho&Xj(^1`D zHA^u4Zb_)<@c{S_nvzsH3azA!HL|6KbXIE6vhT6sfGTLl69he}9Kx72WlrW4E>q3d1L%ChQN zSMQSDu6kKKnQ^ba^MuREWZ#7W`(?C{@v;8gB+VmO{1M>pO! zV1AG)9Hh0^G{$YRcQ#`;?tWK-L0!imxwPRsq8@0;xjh<$e!X^Jwc~pgSxp3ZA9PZh z^?Dr9n*Esj!oUOnWbEPLX$t!(6E2dW?vl~-;YPusMJ(^G9ak=uA2_j>{h}XEP}X}rTjQL%^I`8PV^erD)zeWeRDqmx7egK%S!4TP zQ2l|qy%Qo1Wr)_P)%rV~Ag`PI(VM0!wMGWvq3|PP<|}6HQ?$Lp+Amrjq3Obx@48>V zBhLvJ{x}GN$klWqvNHX~6&51v^6iPw&lCg`16E_@e9xb#_q^K{(;xiHviGoH3maG|wEocU(@8%tz z+P%(XimPJuSaJS+Ga#wA*S8@qbfC;512W;a-l4Ox?2YtW(H;+_Fb||U@TUe_>(r$2 z2AsZG5oaoxyuk^$FqiU=L6J2e>FLgDTLQw-RC4TD9aMgTA15Y6$Qnp^<1S_!Ggm#! z(Hxfc`sa@LSJTP|16A)hzaF0oWZ_N^Cx8-yU|9#1bXWApu>D2%m`M{T^5I1);hT4& zaiX(auYriXa=I#_?88rVIXF3oS>l=HImfFfCJf>>Ae&{=faIw`WCc>ID9MZ=A5%=bKA}?vKBZskRareHioOKK&sgz5! z#rjXqwjclL+uV_##lNOF6Y!yHI!}m{WEB<^xm!ak(Dz;TDl#Z)n3~AW^I|K}w+Y-Y_i(0Na5M#7_ht|Iny}l6 zIBNMguadZ%%xyKoa~J<}eUVGD`v8oZu!;THTI0bg;;nh7u1Pze-mIuzl(u)JzGsq0 z;<0s$=98+2+!85NtIeINLo=S{&Og4Tt-jrCdVN|rAXIlt?MY%VP^K`;ZD3s^+6tW6 zyn?=-Hg1z&8j_zcNhbx%Bnle3(SjBYOSO2HMQ%PV2wv`|2%9gW&-=_~j?n*)_9&e27u#6zb0dPpB;;d0AF%w=ArZ zD_7uzu99p*9!7|YZZ!X6dc4uL2t-I1#=;#N}tNzbLkNm*wpU?1Y>)lF!Wz7D& zL>vA8$dCCJ;qsE91d)$$X^j`^9fm7}{%$|pYPz%lp3pm8*qf2$0X*9_2czd#_pVQm zEi5eu`1guc4od!$0T*G#NFwZ6Y$TOruHABLY&d*?FA`%~Rs`X>#?c9$e_5FSd&uo{ zPCH{Xoq*Z4Y9kl^RTn#|0ZA5JDh8==|OZC7=`;ryOg zz#sV<|GJn(lai8@_4M?1;ExQK&Z2?3dF=)rK2Aw3lPC^GFHZH#a1VP^{&PD5LV3OA z`3GQzttqXXzR-=qbHS0No6h3Al^^5#`x=t0nhrxtg{L%@L>{?*I{>fX=Rz8qew`CN z=6h+?V7;;dCtbT&Lf(I$ZO4J^}^2eZAY{a%})elMBWK-@irOc?`vo6ZtAqOOMqL`!h|lb2YZHN$MqI zx!zk&do2pJ3um8iZ-XT{JUmROe$L$sSv8eAmb}dhmD<5CD(M45wtJ>UsSl0)&pA&H zm=rf4;$?k|%Yr;jXAH0c7U`Xj6;~rO0TZQ7lC1*vSE|D)QIG6eqUgw4Ir0`9EkFQI z*zNfouxblmM}wd7CpD|-H`w?T8|bzS4xMsYV8iIpt(;kt*^WR(ZUrwkGG-N>b1I!& zu|{hLP0(fA@R%h?oU>>Bt_o|QPT^Yod_IR~P}s|*c2`yN8|}|p%T)^)F9N!QvN#(v z5|So)`z7>5^p{F@CTIq|_Pel-JDlk@t%yoeN}b`aDzjy4?{Dtz>xdDe#mzGdymzx%>`7-TiL z*AWf$Je9(d(D{E!Uf~`x7UQ2jx`9H{f~S`c~VOimOGt zI>lsa2Kj+)&#P=}d*2ol= z;VF*YA^pjy%&Y^#UjYRJ!Jc}NzJhKRK3v8*p=~D`0PCBY zN|`nx;BIP}+0>g&<)xOjxdq+^R-OG?XUk=GPP^7C(;*2ewI;^)EXAaQD_@;A9E&jIGQixgYKE8<2IP@T5|>&$ zeJ^VUFt;|A!@A`Nc!j$kJTR#BY*c^3={~lO7hSz{JCg!U<>uJQ?Hu=wb*@~C+}Z@i zKjX;TT{zthA)Hi=W-Dz{pYyfOODe8C(6-R=U}I~!1l=EDPX3-P=hc=VCa=d|&BPpx z`;&p*RD9cC`=G;CXZw)sB+$AE%t%;0E8TE~kH6I~^B6y8O}3)2 z5~Arv$0iK3H3gj8n}qaf6LTHC~YE zURlxsNg;>x{)zkcQs9ZDc)Ydqfaq+#nsUvU>+xW^ZnBMHGqw2Cjb!bj&q=YmK{VFV zookwxZ}RQY9K@t%gnjYyV;gA_i;oa{vTd!YN3|ktga^5JS$YDGm0hBI)6=NkNyom~ z-mM-RMG(VBo<8v=>uBK`qvLNZbsGlJ9$PvZsR<=>@h7qLn=Pwbn+aK^iWv@;v|-*f zio&;260Jf);OPYcd;?GQ)-iX`!Y-EMjpF&x>a?5!6m4+pY}qEBXCw4)QTGS^LxL*t zQ;O6VSVRC0x}^=!J3)^@kz)mMb{qb)K78I=bswMY3V`F*voUKQ-@UdOarj7 zUvyHJfxi(>STbHPU8v>TYkNh!xJjKOXS2-Nl7}()4QSWrIbJwsI~zM@SEq73Kkkzt zT*Yfu_ca1I4{ZTn_iwGU)#=9tK8x=kfL;u6vp?hv5athB$64L>xnSZ?*sl}l9KAt;|ID!nt8 zdt+l`^TU1JutM|e%ks;D!fW$W6N{k)FQe1#zs_D8(bdUTU?S;U+6ICCmKKkV)HES{ z6IFAE%{$1q4okREXmGb7T#Qemc+4_M;<`|wv=@Lu6n6)`$*ZVvc)thVVE;Kx(5J&s zY$N&;_u)`JV@*vBOpW2;Wnc3~`R=YItaJsaTM zu&L8<`~KuQc%5+H;Cc^CW4x7N4TduzS(hZpa? zxp$v^_Sxlk_StuBoBW}#kKb}of5*og8Mx|*r8GDisolhM8-nb9{z@k(E@Tkfz0K}n zy^UF8?C&hQluo4?-gd*9%M~^$dUB$IaVNf`WU>#_y-i1-VYJH&;%t8svi5x9d8^Lm z>h?+k=xKw8?78G$6^|W|HfaN#W|Uj>XA&L5X_Npw9EAm@cIoL z6kU*dV(3iDSr7~bi1}8CiN#_|D#;p?bRfq2*mOL4pI#M(gxpwLnR8&C0zEw8ZC5!q zE>u-&B6w)@9}4h2AqAO2-~J;YqB)=~x85GNZF>j)%;(?3E+D~9O0d-rMy;T@B9+@}$zg zi#m-H&WOYo?k0l}mX^%Vj{pwF4+;&POTvBv*)_u;BHP(6QvC zPMo?nTHPb8V|qIQae%Vs9pO+t*D9ixMAjx~Ny|9H4A9Vmw8?%tco#avCTXLCMW$H^)5jx=>VTx{L8b|pYFE_PSrZ)8b+Q?Lc@j}NdI9*2D zz$JA&mK%g6Ia8PZ(cf}%dsgHK?b|snh`nTfXuR&t*qT881@PLNJJ7O1+`>;^h9Iul z+R2G_q1@l=EK~IFUr_i_$ER7DyHjl`nLVaIDz@wg$1_0Du)vM`fYF~s4JPFHe@=JAn@wb2|RY-(`$Lqq&G z1cI-*!!xeKYx7oUK@)EEO?~KQBq1AJ3RLOznrhQpBrf%qH2$vkUS$A<(xC=z)CrHo zYM3X2rMX8aT8l6-htjM>f|cgL&T3}un1*-X>Vnqd(!^B5wv8Y4r@vWiZEiYd$c4$ zWla0DD`1@Id>`u4H2rj@lA7B{ZvB{JM}BRKhf$%lc2v0W^0A~Z7#-+kO1rRUoPN2x zaJIuT3EA(T+5*=_waSpK9RpxsKCI%XHEqC{;B0L;=$@lcnu*FZXGocwWcl9qhEBhM zyL*tPx!rY}3tw~(2sA|j9++MVJaBKPJ5PJ3N2Y8fWBoq5y<|E>c7Yz@yt%Ys5w);Z z?boZZg-?#sddmAWahvM!j;Ag5NOgRyH5tD-S9L8idA1JAC4KFCS^}Up?mGj>2hjq7 z9yzDlipZb?gDv@Ft1iH1Y-jdOmKv8uh@fC4oJmf43*-!R^yIXgn(^E$qR;nmin8E_ zWsNQ)ntFY7yJ&;6H5xZLsCCYL`EYQ{V`kpS_XAy;uGj=I^x;juAkYz^jn$W=X}nfP zrKQYX!S$>SRcYJ)az#J)=qHMLfXFi5T9Bf0F;#X#t8m>1h2gFw4f))|UAbh?wwwhtBKi=>agB zy!Cg6+HQJ_4I$sL;ic!MESfTj9OK5+OK;G3@TdH%q9Ra&vfFFj~`efI!+zJ5Wi zb>;I<9=ao))ST+V3_l~Zc6(G*R8Hw{mp=v|Wn0!dF)@*P{r;H_JixV&4Mt2g*U9`2 zsFjZg#=5(!>)91wkq8M8zaFsEGG^HsB=r$3j78zF!)FWkvUO=@KtV`n)pd)zpevVv zHxPL9^^pAGJP#WF@JvN6x(RZZ`E6=c-2}Sj?d8>G z&^)y*R9lllk&%Hw1O)B@QgH7(HX7rgog}sfq>Z2T(^K`IVipr10%2 zT6D+XKp7;NVu1QCKNM@QT4w6QxI)LPg+p=@p9W>sYWtxm%+@rx1Uw#$Fp}Of_*af5 zit=9SLza=Y6XaGG;@fsiRWbiU|E%s2O{vvau)v{%JwA`zW!=g3<6MF*8dVQ}_IqOt zwHO+B&CTMeVb)4ch2w$_)oX?p`f_Z99CvU~zT)*q9zIhkEH36{+xlfr+?o38hnJ2Y zMab?}n$j3LuVOg>Ie|b;_P|F+{b+boEMeoiBz%>^?Tp$r*;Wp-(r^}r8cC^UGuX~J z#qp7K^A^hc%u>O(svGIDH`aLLN^2whHf@GP<_v$8vA){k5c-dF=WB&w0NMxm!zwP0 z))Ej9m!BAvK|usShRO%GK=!|n87)j<*=22V&8i_2r9u-+rkXITJ?KSede$3AAA(qW zM77v6ITwxINY6=qA?voV>fFexHV*Aq6!A>vCAW*6QPcX^Ir+vzHKUHUoSW0rk}f~q z1)bgU!sAXFj5|QtfJqywu2_r;uf$4Ipk>yKumA*(UY@SB$dn5iq$sp43*j?%-vQgZ zj~|7w(o$KZa1V21a3WZvU)TY*KZ3o8j?IbSquK zW7({S)s`7OwF{}8X*+^SW2)v}!0hBMJpRG4i2(-|BA!dCS!$j6gCv zMIu5&`M7348f}I5TY9ddQmu3NRYC4_XC}8xfLb1D-L0ZyPK(l;k130+5nErLeOstu zITEG884iXfQQfUrqot6rK6^LB{k(G0wjr3zK=NEh-N716arFu&9nZv2|)yq+w=h~KYWNfnH~k$?{OKFqg?S}HPsoYvc4W#*LYUrAZ%#Lf|GS#Qq_OmYka z$*Y3NljbfC;5#Rj4QRQ(fg902yoGe_ni+JBa_iLMPyktfmmpE!I-H4T)^Mlk+f&sg ziKIx!huc^Dat=yDRK=N}eEDY?Ywtvah;N_o0#^F;bQT?*XyZ)!#`T`8ZHFEMF%U5S z&+7|oxFZjkb@U5KrAC_{&Ik__OW6?8I5I-_uPo_`C<`~`lbc&NHTcsn48ZUYLe%PL z>lBNm!NpxvKcw!&?1=WG7_%AvSk_dLq~_G?z2=?qr78JowF$Ax8yvpxW>8-xJaI-2m zUso$q5HE9p^HwuQSN_j|{E=;p3H6cLvd3h~vc8x-GLcdo z&?dS|fK+a_YS9?6q!7{(soojVXV_z0JJC`g-s85=WKRe-0YJ=^W;y?qO{dsgaY?wm z8%nKhk5psr8B%Py=1jq4%@8E38ZR5E&2tnpn!%0}WkOqNftY6&(oo% z(;B_fvfxoXYqnL)rDM5ZvH zYHGxW8W~j@@6ns()@^r9wsb0$d*EJ=5)&_5IA8Uf+OFG$9%(QnN%bApyexD|*Jj^Pj@#Y^hATQ^S zhUD36@4oR)$OobV<7IAQyKW#(o`Hr2lxYMMXsvata)%%;hBRLVMl}}Oz-h&IGm>)~ z8a=4NnO96~GF%*LO>4tu>@Ekh@=d_f5(W5219WdAl1)tIAe?7b&s-jkZpU#QtWB@g zI!Jed2~jmVAD+Qxx)vsii~C8Z1(DK|?Z)P9iv*lvauO;-v^gK^G-O4&obG=bOgsu@ zG_ga5%@xRV=J-ePnV5X*`YKbm3J*8bp)hYiJ(rdnc`xyx@UreO)7B(!ms69sHnM6-9zB z#Cz75w0o5dIiwOrWunN+S|sJVVl%Y|wb#%HgB60K-OGFreQ?I5o$%i|xh@hwtVM35 z-3uyAvoL}(>RwgMa01ON3HXp%>h10Vhb$BL9CrQPpEJtUOK)CJnNzY=@KJ^Y$c95y5Pl~XyX=NFoNZ48q z1X|n<%Poh^wSD0CSF`7y0o5#+x&W4)SvXyN-R3EHYMJR&$&DDoyee>3;o;{D{Kt|H z!Wqt%J~YkZr4q8l@m!*^CE*dtmoYg0%6N+745k0Fv>tHXXESz&COY8bN|sm~f<@!( z_1|~bFHCl%mQnUf9ZF-QLNE={BmU5(+exA!?bVRzf;xL4^%zA3=T*39e_FCgK7-_l z;yCLpTAcaj z+hDA!BLsEF9}d?rxDek2fzXkf+ui)VohJkWC+`&auoAPtWVF*BcFr}e1r>$`P!#{% zbjjf`$^d&P*FS4Ba^c}zW3ODbvh+kV&&62LB?CX-BXf?zb-p(GBcq=h#4Eo+eLTSM z)D$GQIjNEFNfcRTuX;KA5fgaGDI~;@afX00osOSe$*b)g*nA$dw(NzR#@2?6yvOGA z3>ZiwDaz7f2F5&h6j-&~ie{`XKECoaY%31wD4~7?&7QUOEs^Ll>t~e%UT7w3g@sC@ z&z|w_0oGiHw0Kexc1b#}u2I$}4UbCHYN^(a^r?I1K!XFKMisa;o~d^alv_fFbHXz1 zjaXcr!)L-IGkO*pG-uYQkzAT7yfarS3vdQjn8W@UznY#Eswod zqPQ&S;(|QN?N1?1+@ZhE0vQ@R1Z~CC{OscQiB@!p({GL^QUmJeEaVUI89|@M7xe6i zwY4>lP1e-qFb07v8J`xbN!5>8GQbUXe*?6xZTyFUErIBU!RNrA zpOBVJ!2&N$*W%ACw0`tAKV3K_{?Slu{m0Ia>-RDB!|l5$0FbS;n2*c)0HnL;&IRCK zT%M{6Alu)rgqQxc)o? zh(33eeblL62t+vng(6skzU3IJ(-(MhNmZQbER#Goc$; zm&xqtqDpF1~*=mTES2jz-^$V3S6>q1LmDGoa~$h_`(1V?q@j|%d9l_ zisH67a@*3DbVjF#Bi69qLyol;(o+3pNNh^z7Zv)Mzn8l;d}H`4T5zkOs+^wLGkBzf z;NS@!Ele*Ub|qtJ$hH4KvtlG8O)r_OFVujj@hwLjY}HPUJoN5Qth#e&mZ_>ed`{JJ z$d7YX$NIZP69A*H?hi#|rRH}X)sE`LJe;DLNj@3*gy8mm!I zC7ZZ;N6qW_O@=XtAvv0nX2?mQw$h$dEV8U~ktaZYDbU|`PdmM{f<}0#swSHKiXxgm zP!QvXG`ab%d)*Z&P#Fc((k$cMvv+&t&&EG4#}w{UXd3oOvG2)Z=r-ZfYWWo|HS6?5 zE+wDoZFIEMM>9W^VqG!s;XbTp&=2)|us}m0f=UVpZ2IG5SDi=oK*1<%Ec0{weR? z%du(NN$n%o;IeuvBdWy_8R%O6hF_77CL-n?>w<9h{meBoTq(*zQ4YRbPYov3$eQM4 zL~gQ8<_Rkz)P-rekeQR52^K!eHh;p=@7Ej=mslBP)V<32ydSADWxcE79Li{B^S zLFjfSmk)yn76=!x+EM0`8FpE7v2Z;wy}Hctu}&Z3#iSayyVjh-EXYY$j*a;ZjGu4P z;*E-mUQyRjKOAi|pFIpa`c2eb@7naK4xxh#!8(kp!}x)n-n{b4ikS%A4*a;>+09z4 zXAPfum0CpG1)ZpKV0$PQ+6Umm3Q=g8fI79~GC(=hqKUlSWHujF{UR+{mtM25jXQ6v zk-tRGgTCixN@=TaEDwiI#frWy@YIN$%|`nMWX4cl$OMwJd28*W!F`IN!*Gmztw}-j4(A=pmI{dk>3N0>9Ou9wQTJze`eMg(#8cclCa6{au`KQPNU(pkFTYJ zL)KuD=45x|y}b=G-^9fW;?onI>cpy!5hCptp`(8%P>+TyIHgPF@~y<=9%8$ow32~( zjl?`>0LRW>#_G0-j$AvlFcKBEv!pV3<=o1XebMels62#2>V&cp0h27a`MT~xk#CVl zsVw=lZ~-&Xv2w%)@*dl6A6~B=x;ik;>c6e0yyRKWa2XG5-|!4T3(C5`n=^1{Y%lMq zYSd(88I&W|u#3>i%=q4jQ$!uNOK3t+vR~-z_QGqPjM^TrKv_wIPNcK&n;^Gnm-zQ2w%-#aEYZKv?o zM&Gq0{O5ec{lpzj=YLt5-}UpsCkKS@7E%^^(9{{)0z8KuPWqPi-uu%@uZ{7?*}Aq6w@RQOWW}o7Yzo=_VrY5j=$IZa@9hQW7Bjvck`^*Tlz!n-@b8pL} z;<3tjf`aou@fW3H9X3IEAuIgmJfSIzka4AVw;Z62>mrAddxBK;hB)I(BShDh&^%oI zQ!aY?p^bJzFgGK$(O&Nx^&gY=yCa**#C(n)*$3&ZB!OmcBH<;)C!sKhkQKrA*bpnu zQOBMQ7+9Qh7MTm*u{WR&fzg}CzMwYM*TsrwyT$p?Pv>@!0{`r_@ptbTR9|JM5T0RA zXZ_J*d`d@NI!X8O6WD(7)Pf*tX6aK$0=h$cAgpud;&tlC&1I4g_&xH7vRvxLIio}5 zm^ z`X(B@UP&(Yin3!<1e6v==OFI#H1yx5$@4d2W)6@Qhid(0u#@xtq*>QVV!d6%$vb5I z?bB~1CAu13x$fjNrgP2xJbG$=MeW#i#&knOvQ^Wb`&Px~m!JRK_Im&CHv26l3HOb8 zhpTydZ+7-KaCR?}MNTnkf23?gdH<7us6KyM=0SGLL1XY}P5buuTAImCy7hk=D@a~u zq#u2DKb-GqY+8l5lUH96L^ylYo?m$4hhKR3|I`jh5xeUY7&`Fxb;-*sPiz@(UYT#3 z;t>iThFP3KZ_RAOJTslRKSs)nQ6k1H$Q<<;D=Dz4zt7m-Y7ty5aY>QOm@@=fn>!i4 zSvs?%RlS{hW^|n6Jh3QK^KcN7YzYtg5TEt9Q9S$ZQLmA^=No-uyRQb7+?jwOG+caduIZmPlicIE!==#LQu%$+-LBOwMy~xeK zW;!}?MbTn^p3i9hJ1fBRA}^*jV|#Z<{lf=tPw+U}e?Q=ze@WVlEOeiO9amPU^mE=J zWi4YENPD#Y$W2r^;zw;Iq4^I%w3I4^Qzv*E7%jW2hG93w>jdgE?+zs9Q^vOaY}qHD zHJn3H=Fi`ORVn8)_xrz(B8Lx0ymAlIY7@Ud18nr8_I^Ou-OvQ16%+5RKT1o^Iv-52 z-$&ka^jyktHul2+KczbWq@OcwR?jKBxKl<@tTX5KCB@h`ec6#$MSB9E5B5rm|2Crr zIq?qpw*QIv9ervqci^>Ru+bjF>os#vr9=Klv9v_P4CApsnZjo0UWSs$?&SE;8Ece{ zT?eY8yZq_pu81z-DM5dG4iUVql-0^U59Chl<1YW{!gHNDx;~%&$KmI}+fJsUpD6A0 zG8$2){5@G#`y$W>GUGGNtCpTPB#1epneV~AbUH7N7~8z$S9e-K`{6pCTlAc|Om8;CcPNvJ-tccPSEB~m30bTGYeV4%-@V2V9yr+SCH>;MS z$P$gWV*R(Pm0dGPm|-Y2I#iI8ZjD|knf@QU#QsiswlKqt=yn+lOUX2c zU$)M^bcuXd_`#X+wMG2p`)=1!UExHn^uv+6EDMm8e)JeE%hU@|5t?SF$tNCgCiWzG zyp`ZQUny$WvQkXwMoAy0HY&*U+Z<@UTc^3!?fm_2RzPv)FCMvhAEB8 z|HKRaxA-KJH&;F2d|XxaVB8I$aN$+q{XcHIDy$k*73lJ7{KcymFI~E%XYijA?k6Kz +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "umrr_ros2_msgs/srv/firmware_download.hpp" + +namespace smart_rviz_plugin +{ +class SmartDownloadService : public rviz_common::Panel +{ + Q_OBJECT + +public: + SmartDownloadService(QWidget * parent = nullptr); + +private slots: + void onDownload(); + void onBrowse(); + +private: + void initialize(); + +private: + rclcpp::Node::SharedPtr download_node; + rclcpp::Client::SharedPtr download_client; + + QLineEdit * file_path_input; + QLineEdit * sensor_id_input; + QPushButton * start_download_button; + QPushButton * browse_button; +}; + +} // namespace smart_rviz_plugin + +#endif // SMART_RVIZ_PLUGIN__SMART_DOWNLOAD_HPP_ diff --git a/smart_rviz_plugin/include/smart_rviz_plugin/smart_recorder.hpp b/smart_rviz_plugin/include/smart_rviz_plugin/smart_recorder.hpp new file mode 100644 index 0000000..f852ae4 --- /dev/null +++ b/smart_rviz_plugin/include/smart_rviz_plugin/smart_recorder.hpp @@ -0,0 +1,62 @@ +#ifndef SMART_RVIZ_PLUGIN__SMART_RECORDER_HPP_ +#define SMART_RVIZ_PLUGIN__SMART_RECORDER_HPP_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "std_msgs/msg/string.hpp" + +namespace smart_rviz_plugin +{ +class SmartRadarRecorder : public rviz_common::Panel +{ + Q_OBJECT + +public: + SmartRadarRecorder(QWidget * parent = nullptr); + +private slots: + void startRecording(); + void stopRecording(); + void saveDataToCSV(); + void checkForData(); + void updateTable(); + +private: + void initializeRecorder(); + void callback(const sensor_msgs::msg::PointCloud2::SharedPtr msg, const std::string topic_name); + +private: + QTableWidget * table_data_; + QTableWidget * table_timestamps_; + QSplitter * splitter_; + QSplitter * horiz_splitter_; + QComboBox * topic_dropdown_; + QVBoxLayout * gui_layout_; + QPushButton * start_button_; + QPushButton * stop_button_; + QPushButton * save_button_; + QTimer * timer_; + rclcpp::Node::SharedPtr node_; + std::unordered_map::SharedPtr> + subscribers_{}; + QVector> recorded_data; + std::string selected_topic_; + bool recording_active_{false}; +}; + +} // namespace smart_rviz_plugin + +#endif // SMART_RVIZ_PLUGIN__SMART_RECORDER_HPP_ diff --git a/smart_rviz_plugin/include/smart_rviz_plugin/smart_services.hpp b/smart_rviz_plugin/include/smart_rviz_plugin/smart_services.hpp new file mode 100644 index 0000000..9abebe1 --- /dev/null +++ b/smart_rviz_plugin/include/smart_rviz_plugin/smart_services.hpp @@ -0,0 +1,54 @@ +#ifndef SMART_RVIZ_PLUGIN__SMART_SERVICES_HPP_ +#define SMART_RVIZ_PLUGIN__SMART_SERVICES_HPP_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "umrr_ros2_msgs/srv/send_command.hpp" +#include "umrr_ros2_msgs/srv/set_mode.hpp" + +namespace smart_rviz_plugin +{ +class SmartRadarService : public rviz_common::Panel +{ + Q_OBJECT + +public: + SmartRadarService(QWidget * parent = nullptr); + +private slots: + void onSendParam(); + void onSendCommand(); + +private: + void initialize(); + +private: + rclcpp::Node::SharedPtr client_node; + QLineEdit * param_name; + QLineEdit * param_value; + QLineEdit * sensor_id_value; + QLineEdit * command_name; + QLineEdit * command_value; + QLineEdit * command_sensor_id_value; + QPushButton * send_param_button; + QPushButton * send_command_button; + QTabWidget * tab_widget; + QWidget * set_mode_tab; + QWidget * send_command_tab; + QVBoxLayout * send_mode_layout; + QVBoxLayout * send_command_layout; + rclcpp::Client::SharedPtr mode_client; + rclcpp::Client::SharedPtr command_client; +}; + +} // namespace smart_rviz_plugin + +#endif // SMART_RVIZ_PLUGIN__SMART_SERVICES_HPP_ diff --git a/smart_rviz_plugin/package.xml b/smart_rviz_plugin/package.xml new file mode 100644 index 0000000..db9598a --- /dev/null +++ b/smart_rviz_plugin/package.xml @@ -0,0 +1,38 @@ + + + + smart_rviz_plugin + 1.0.0 + TargetList Recorder + shahrukh + Apache 2.0 License + + ament_cmake + + qtbase5-dev + + pluginlib + rclcpp + umrr_ros2_msgs + resource_retriever + rviz_common + rviz_default_plugins + rviz_ogre_vendor + rviz_rendering + std_msgs + visualization_msgs + + libqt5-core + libqt5-gui + xacro + rviz + libqt5-opengl + libqt5-widgets + + ament_lint_common + ament_lint_auto + + + ament_cmake + + diff --git a/smart_rviz_plugin/plugins_description.xml b/smart_rviz_plugin/plugins_description.xml new file mode 100644 index 0000000..21941a5 --- /dev/null +++ b/smart_rviz_plugin/plugins_description.xml @@ -0,0 +1,20 @@ + + + The Smart TargetList Recorder. + + + The Smart Command Controller. + + + The Smart Download. + + diff --git a/smart_rviz_plugin/src/smart_download.cpp b/smart_rviz_plugin/src/smart_download.cpp new file mode 100644 index 0000000..226b7a6 --- /dev/null +++ b/smart_rviz_plugin/src/smart_download.cpp @@ -0,0 +1,88 @@ +#include "smart_rviz_plugin/smart_download.hpp" + +namespace smart_rviz_plugin +{ +SmartDownloadService::SmartDownloadService(QWidget * parent) : rviz_common::Panel(parent) +{ + initialize(); +} + +void SmartDownloadService::initialize() +{ + // Initialize ROS 2 + if (!rclcpp::ok()) { + rclcpp::init(0, nullptr); + } + + // Declare node and client + download_node = rclcpp::Node::make_shared("smart_download_gui"); + download_client = download_node->create_client( + "smart_radar/firmware_download"); + + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Download node created!"); + + // GUI setup + file_path_input = new QLineEdit(this); + sensor_id_input = new QLineEdit(this); + start_download_button = new QPushButton("Start Download", this); + browse_button = new QPushButton("Browse", this); + + QVBoxLayout * layout = new QVBoxLayout(this); + layout->addWidget(new QLabel("File Path:")); + layout->addWidget(file_path_input); + layout->addWidget(browse_button); + layout->addWidget(new QLabel("Sensor ID:")); + layout->addWidget(sensor_id_input); + layout->addWidget(start_download_button); + + // Connect signals and slots + connect(start_download_button, &QPushButton::clicked, this, &SmartDownloadService::onDownload); + connect(browse_button, &QPushButton::clicked, this, &SmartDownloadService::onBrowse); +} + +void SmartDownloadService::onDownload() +{ + if (!download_client) { + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to create download_client"); + return; + } + + // Get file path and sensor ID + QString filePath = file_path_input->text(); + int sensorId = sensor_id_input->text().toInt(); + + if (filePath.isEmpty()) { + QMessageBox::warning(this, "Warning", "Please select a file to download.", QMessageBox::Ok); + return; + } + + // Set up the request + auto request = std::make_shared(); + request->file_path = filePath.toStdString(); + request->sensor_id = sensorId; + + auto result = download_client->async_send_request(request); + + // Wait for the result. + if ( + rclcpp::spin_until_future_complete(download_node, result) == + rclcpp::FutureReturnCode::SUCCESS) { + RCLCPP_INFO( + rclcpp::get_logger("rclcpp"), "Request successful. Response: %s", result.get()->res.c_str()); + } else { + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to call service firmware_download"); + } +} + +void SmartDownloadService::onBrowse() +{ + QString filePath = QFileDialog::getOpenFileName(this, tr("Open File"), "", tr("All Files (*)")); + if (!filePath.isEmpty()) { + file_path_input->setText(filePath); + } +} + +} // namespace smart_rviz_plugin + +#include +PLUGINLIB_EXPORT_CLASS(smart_rviz_plugin::SmartDownloadService, rviz_common::Panel) diff --git a/smart_rviz_plugin/src/smart_recorder.cpp b/smart_rviz_plugin/src/smart_recorder.cpp new file mode 100644 index 0000000..5fc9e30 --- /dev/null +++ b/smart_rviz_plugin/src/smart_recorder.cpp @@ -0,0 +1,216 @@ +#include "smart_rviz_plugin/smart_recorder.hpp" + +#include + +namespace smart_rviz_plugin +{ +SmartRadarRecorder::SmartRadarRecorder(QWidget * parent) : rviz_common::Panel(parent) +{ + initializeRecorder(); +} + +void SmartRadarRecorder::initializeRecorder() +{ + node_ = rclcpp::Node::make_shared("smart_radar_gui_node"); + + // Retrieve available topics + auto topic_names_and_types = node_->get_topic_names_and_types(); + std::vector available_topics; + for (const auto & topic : topic_names_and_types) { + available_topics.push_back(topic.first); + } + + // Reorder setup + gui_layout_ = new QVBoxLayout(); + topic_dropdown_ = new QComboBox(); + topic_dropdown_->addItem("Select a Topic"); + // Create subscribers for selected topics + for (const auto & topic : available_topics) { + subscribers_[topic] = node_->create_subscription( + topic, 10, + [this, topic](const sensor_msgs::msg::PointCloud2::SharedPtr msg) { callback(msg, topic); }); + + topic_dropdown_->addItem(QString::fromStdString(topic)); + } + connect(topic_dropdown_, SIGNAL(currentIndexChanged(int)), this, SLOT(updateTable())); + + table_data_ = new QTableWidget(); + table_data_->setColumnCount(8); + table_data_->horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); + table_data_->setHorizontalHeaderLabels( + {"RadialSpeed [m/s]", "Power [dB]", "RCS [dB]", "Noise [dB]", "SNR", "AzimuthAngle [rad]", + "ElevationAngle [rad]", "Range [m]"}); + + table_timestamps_ = new QTableWidget(); + table_timestamps_->setColumnCount(2); + table_timestamps_->horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); + table_timestamps_->setHorizontalHeaderLabels({"TsSec", "TsNanoSec"}); + + splitter_ = new QSplitter(Qt::Vertical); + splitter_->addWidget(topic_dropdown_); + splitter_->addWidget(table_data_); + + horiz_splitter_ = new QSplitter(Qt::Horizontal); + horiz_splitter_->addWidget(splitter_); + horiz_splitter_->addWidget(table_timestamps_); + horiz_splitter_->setSizes(QList({400, 100})); + + gui_layout_->addWidget(horiz_splitter_); + + timer_ = new QTimer(); + connect(timer_, SIGNAL(timeout()), this, SLOT(checkForData())); + timer_->start(20); + + start_button_ = new QPushButton("Record"); + connect(start_button_, SIGNAL(clicked()), this, SLOT(startRecording())); + + stop_button_ = new QPushButton("Stop Recording"); + connect(stop_button_, SIGNAL(clicked()), this, SLOT(stopRecording())); + + save_button_ = new QPushButton("Save Data as CSV"); + connect(save_button_, SIGNAL(clicked()), this, SLOT(saveDataToCSV())); + + gui_layout_->addWidget(start_button_); + gui_layout_->addWidget(stop_button_); + gui_layout_->addWidget(save_button_); + + setLayout(gui_layout_); +} + +void SmartRadarRecorder::callback( + const sensor_msgs::msg::PointCloud2::SharedPtr msg, const std::string topic_name) +{ + if (!selected_topic_.empty() && topic_name == selected_topic_) { + auto timestamp_sec = msg->header.stamp.sec; + auto timestamp_nanosec = msg->header.stamp.nanosec; + + // Create iterators for the pc2 fields + sensor_msgs::PointCloud2ConstIterator iter_radial_speed(*msg, "radial_speed"); + sensor_msgs::PointCloud2ConstIterator iter_power(*msg, "power"); + sensor_msgs::PointCloud2ConstIterator iter_rcs(*msg, "rcs"); + sensor_msgs::PointCloud2ConstIterator iter_noise(*msg, "noise"); + sensor_msgs::PointCloud2ConstIterator iter_snr(*msg, "snr"); + sensor_msgs::PointCloud2ConstIterator iter_azimuth_angle(*msg, "azimuth_angle"); + sensor_msgs::PointCloud2ConstIterator iter_elevation_angle(*msg, "elevation_angle"); + sensor_msgs::PointCloud2ConstIterator iter_range(*msg, "range"); + + // Initialize variables for recorded_data + QString radial_speed_value_str; + QString power_value_str; + QString rcs_value_str; + QString noise_value_str; + QString snr_value_str; + QString azimuth_value_str; + QString elevation_value_str; + QString range_value_str; + + table_data_->setRowCount(0); + + for (size_t i = 0; i < msg->height * msg->width; ++i, ++iter_radial_speed, ++iter_power, + ++iter_rcs, ++iter_noise, ++iter_snr, ++iter_azimuth_angle, ++iter_elevation_angle, + ++iter_range) { + // Add items to the table + table_data_->insertRow(0); + table_data_->setItem(0, 0, new QTableWidgetItem(QString::number(*iter_radial_speed, 'f', 2))); + table_data_->setItem(0, 1, new QTableWidgetItem(QString::number(*iter_power, 'f', 2))); + table_data_->setItem(0, 2, new QTableWidgetItem(QString::number(*iter_rcs, 'f', 2))); + table_data_->setItem(0, 3, new QTableWidgetItem(QString::number(*iter_noise, 'f', 2))); + table_data_->setItem(0, 4, new QTableWidgetItem(QString::number(*iter_snr, 'f', 2))); + table_data_->setItem( + 0, 5, new QTableWidgetItem(QString::number(*iter_azimuth_angle, 'f', 2))); + table_data_->setItem( + 0, 6, new QTableWidgetItem(QString::number(*iter_elevation_angle, 'f', 2))); + table_data_->setItem(0, 7, new QTableWidgetItem(QString::number(*iter_range, 'f', 2))); + // Update variables for recorded_data + radial_speed_value_str = QString::number(*iter_radial_speed, 'f', 2); + power_value_str = QString::number(*iter_power, 'f', 2); + rcs_value_str = QString::number(*iter_rcs, 'f', 2); + noise_value_str = QString::number(*iter_noise, 'f', 2); + snr_value_str = QString::number(*iter_snr, 'f', 2); + azimuth_value_str = QString::number(*iter_azimuth_angle, 'f', 2); + elevation_value_str = QString::number(*iter_elevation_angle, 'f', 2); + range_value_str = QString::number(*iter_range, 'f', 2); + } + + // Append data to recorded_data + if (recording_active_) { + recorded_data.append( + {radial_speed_value_str, power_value_str, rcs_value_str, noise_value_str, snr_value_str, + azimuth_value_str, elevation_value_str, range_value_str}); + recorded_data.back().append(QString::number(timestamp_sec)); + recorded_data.back().append(QString::number(timestamp_nanosec)); + } + + // Update the timestamp table + table_timestamps_->setRowCount(0); + table_timestamps_->insertRow(0); + table_timestamps_->setItem(0, 0, new QTableWidgetItem(QString::number(timestamp_sec))); + table_timestamps_->setItem(0, 1, new QTableWidgetItem(QString::number(timestamp_nanosec))); + } +} + +void SmartRadarRecorder::updateTable() +{ + // Clear the table when a new topic is selected + table_data_->setRowCount(0); + selected_topic_ = topic_dropdown_->currentText().toStdString(); +} + +void SmartRadarRecorder::startRecording() +{ + qDebug() << "Recording started!"; + recording_active_ = true; + start_button_->setText("Recording..."); +} + +void SmartRadarRecorder::stopRecording() +{ + qDebug() << "Recording stopped!"; + recording_active_ = false; + start_button_->setText("Record"); +} + +void SmartRadarRecorder::saveDataToCSV() +{ + qDebug() << "Saving data to CSV!"; + if (!recorded_data.isEmpty()) { + QFileDialog file_dialog; + QString file_path = + file_dialog.getSaveFileName(this, "Save Data", "", "CSV Files (*.csv);;All Files (*)"); + + if (!file_path.isEmpty()) { + QFile csvfile(file_path); + if (csvfile.open(QIODevice::WriteOnly | QIODevice::Text)) { + QTextStream csv_writer(&csvfile); + csv_writer << "RadialSpeed [m/s], Power [dB], RCS [dB], Noise [dB], SNR, AzimuthAngle " + "[rad], ElevationAngle [rad], Range [m], TimestampSec, TimestampNanoSec \n"; + + for (const auto & data_row : recorded_data) { + QStringList data_str_list = QStringList::fromVector(data_row); + csv_writer << data_str_list.join(", ") << "\n"; + } + + csvfile.close(); + } else { + qDebug() << "Error: Could not open the file for writing."; + } + } + } else { + qDebug() << "No recorded data to save."; + } + // Clear recorded_data after saving + recorded_data.clear(); +} + +void SmartRadarRecorder::checkForData() +{ + if (rclcpp::ok()) // Check if ROS2 is still running + { + rclcpp::spin_some(node_); + } +} + +} // namespace smart_rviz_plugin + +#include +PLUGINLIB_EXPORT_CLASS(smart_rviz_plugin::SmartRadarRecorder, rviz_common::Panel) diff --git a/smart_rviz_plugin/src/smart_services.cpp b/smart_rviz_plugin/src/smart_services.cpp new file mode 100644 index 0000000..c4c456a --- /dev/null +++ b/smart_rviz_plugin/src/smart_services.cpp @@ -0,0 +1,138 @@ +#include "smart_rviz_plugin/smart_services.hpp" + +#include +#include +#include + +namespace smart_rviz_plugin +{ +SmartRadarService::SmartRadarService(QWidget * parent) : rviz_common::Panel(parent) +{ + initialize(); +} + +void SmartRadarService::initialize() +{ + // Initialize ROS 2 + if (!rclcpp::ok()) { + rclcpp::init(0, nullptr); + } + + // Declare node_ and clients + client_node = rclcpp::Node::make_shared("smart_service_gui"); + mode_client = + client_node->create_client("smart_radar/set_radar_mode"); + command_client = + client_node->create_client("smart_radar/send_command"); + + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Client node created!"); + + // GUI setup + param_name = new QLineEdit(this); + param_value = new QLineEdit(this); + sensor_id_value = new QLineEdit(this); + command_name = new QLineEdit(this); + command_value = new QLineEdit(this); + command_sensor_id_value = new QLineEdit(this); + send_param_button = new QPushButton("Send Param", this); + send_command_button = new QPushButton("Send Command", this); + + tab_widget = new QTabWidget(this); + set_mode_tab = new QWidget(tab_widget); + send_command_tab = new QWidget(tab_widget); + + // Create layouts for each tab + send_mode_layout = new QVBoxLayout(set_mode_tab); + send_command_layout = new QVBoxLayout(send_command_tab); + + // Add widgets to the layouts + send_mode_layout->addWidget(new QLabel("Radar Params:")); + send_mode_layout->addWidget(new QLabel("Param:")); + send_mode_layout->addWidget(param_name); + send_mode_layout->addWidget(new QLabel("Value:")); + send_mode_layout->addWidget(param_value); + send_mode_layout->addWidget(new QLabel("Sensor ID:")); + send_mode_layout->addWidget(sensor_id_value); + send_mode_layout->addWidget(send_param_button); + + send_command_layout->addWidget(new QLabel("Radar Commands:")); + send_command_layout->addWidget(new QLabel("Command:")); + send_command_layout->addWidget(command_name); + send_command_layout->addWidget(new QLabel("Value:")); + send_command_layout->addWidget(command_value); + send_command_layout->addWidget(new QLabel("Sensor ID:")); + send_command_layout->addWidget(command_sensor_id_value); + send_command_layout->addWidget(send_command_button); + + // Set default values + param_name->setText("dummy_check_interface_file"); + param_value->setText("1"); + sensor_id_value->setText("100"); + + command_name->setText("dummy_check_interface_file"); + command_value->setText("1"); + command_sensor_id_value->setText("100"); + + tab_widget->addTab(set_mode_tab, "Set Radar Mode"); + tab_widget->addTab(send_command_tab, "Send Command"); + + QHBoxLayout * mainLayout = new QHBoxLayout(this); + mainLayout->addWidget(tab_widget); + + // Connect signals and slots + connect(send_param_button, &QPushButton::clicked, this, &SmartRadarService::onSendParam); + connect(send_command_button, &QPushButton::clicked, this, &SmartRadarService::onSendCommand); +} + +void SmartRadarService::onSendParam() +{ + if (!mode_client) { + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to create mode_client"); + return; + } + + auto request = std::make_shared(); + request->param = param_name->text().toStdString(); + request->value = std::stoi(param_value->text().toUtf8().constData()); + request->sensor_id = std::stoi(sensor_id_value->text().toUtf8().constData()); + + auto result = mode_client->async_send_request(request); + + // Wait for the result. + if ( + rclcpp::spin_until_future_complete(client_node, result) == rclcpp::FutureReturnCode::SUCCESS) { + RCLCPP_INFO( + rclcpp::get_logger("rclcpp"), "Request successful. Response: %s", result.get()->res.c_str()); + } else { + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to call service add_two_ints"); + } +} + +void SmartRadarService::onSendCommand() +{ + if (!command_client) { + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to create command client"); + return; + } + + auto request = std::make_shared(); + request->command = command_name->text().toStdString(); + request->value = std::stoi(command_value->text().toUtf8().constData()); + request->sensor_id = std::stoi(command_sensor_id_value->text().toUtf8().constData()); + + auto result = command_client->async_send_request(request); + + // Wait for the result. + if ( + rclcpp::spin_until_future_complete(client_node, result) == rclcpp::FutureReturnCode::SUCCESS) { + RCLCPP_INFO( + rclcpp::get_logger("rclcpp"), "Request successful. Response: %s", result.get()->res.c_str()); + } else { + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to call service add_two_ints"); + } +} + +} // namespace smart_rviz_plugin + +#include +PLUGINLIB_EXPORT_CLASS(smart_rviz_plugin::SmartRadarService, rviz_common::Panel) diff --git a/umrr_ros2_driver/CMakeLists.txt b/umrr_ros2_driver/CMakeLists.txt index 04f4e1b..add00f2 100644 --- a/umrr_ros2_driver/CMakeLists.txt +++ b/umrr_ros2_driver/CMakeLists.txt @@ -64,6 +64,7 @@ install(FILES "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrr9d_t152_automotivev1.0.3_user_interface.so" "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrr9d_t152_automotivev1.2.2_user_interface.so" "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrra4_automotivev1.0.1_user_interface.so" + "${PROJECT_SOURCE_DIR}/smartmicro/${SMARTMICRO_LIB_DIR}/libumrra4_automotivev1.3.0_user_interface.so" DESTINATION lib) set(LIB_PATH "${CMAKE_INSTALL_PREFIX}/lib") @@ -77,7 +78,10 @@ configure_file( "${PROJECT_SOURCE_DIR}/cmake/config_path.hpp.in" "${CMAKE_INSTALL_PREFIX}/include/${PROJECT_NAME}/config_path.hpp" @ONLY) -ament_auto_add_library(smartmicro_radar_node SHARED "src/smartmicro_radar_node.cpp") +ament_auto_add_library(smartmicro_radar_node SHARED + "src/smartmicro_radar_node.cpp" + "src/UpdateService.cpp" + ) target_include_directories(smartmicro_radar_node PUBLIC ${CMAKE_INSTALL_PREFIX}/include/ smartmicro/include/ @@ -89,7 +93,8 @@ smartmicro/include/umrr9f_t169_automotive_v2_1_1 smartmicro/include/umrr9f_t169_automotive_v2_2_1 smartmicro/include/umrr9d_t152_automotive_v1_0_3 smartmicro/include/umrr9d_t152_automotive_v1_2_2 -smartmicro/include/umrra4_automotive_v1_0_1) +smartmicro/include/umrra4_automotive_v1_0_1 +smartmicro/include/umrra4_automotive_v1_3_0) # link smart_access_lib-linux-x86_64-gcc_9 to the node target_link_libraries(smartmicro_radar_node @@ -105,7 +110,8 @@ target_link_libraries(smartmicro_radar_node umrr9f_t169_automotivev2.2.1_user_interface umrr9d_t152_automotivev1.0.3_user_interface umrr9d_t152_automotivev1.2.2_user_interface - umrra4_automotivev1.0.1_user_interface) + umrra4_automotivev1.0.1_user_interface + umrra4_automotivev1.3.0_user_interface) rclcpp_components_register_node(smartmicro_radar_node PLUGIN "smartmicro::drivers::radar::SmartmicroRadarNode" diff --git a/umrr_ros2_driver/cmake/sensor_commands.hpp.in b/umrr_ros2_driver/cmake/sensor_commands.hpp.in deleted file mode 100644 index c62e8ad..0000000 --- a/umrr_ros2_driver/cmake/sensor_commands.hpp.in +++ /dev/null @@ -1,31 +0,0 @@ -// Copyright 2021 Apex.AI, 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 UMRR_ROS2_DRIVER__CMAKE_SENSOR_COMMAND_PATH_H_ -#define UMRR_ROS2_DRIVER__CMAKE_SENSOR_COMMAND_PATH_H_ - -namespace smartmicro -{ -namespace drivers -{ -namespace radar -{ - -constexpr auto KSensorCommandFilePath ="@SENSOR_COMMAND_FILE_PATH@"; - -} // namespace radar -} // namespace drivers -} // namespace smartmicro - -#endif // UMRR_ROS2_DRIVER__CMAKE_SENSOR_COMMAND_PATH_H_ diff --git a/umrr_ros2_driver/cmake/sensor_params.hpp.in b/umrr_ros2_driver/cmake/sensor_params.hpp.in deleted file mode 100644 index b3372bc..0000000 --- a/umrr_ros2_driver/cmake/sensor_params.hpp.in +++ /dev/null @@ -1,31 +0,0 @@ -// Copyright 2021 Apex.AI, 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 UMRR_ROS2_DRIVER__CMAKE_SENSOR_PARAM_PATH_H_ -#define UMRR_ROS2_DRIVER__CMAKE_SENSOR_PARAM_PATH_H_ - -namespace smartmicro -{ -namespace drivers -{ -namespace radar -{ - -constexpr auto KSensorParamFilePath ="@SENSOR_PARAM_FILE_PATH@"; - -} // namespace radar -} // namespace drivers -} // namespace smartmicro - -#endif // UMRR_ROS2_DRIVER__CMAKE_SENSOR_PARAM_PATH_H_ diff --git a/umrr_ros2_driver/include/umrr_ros2_driver/UpdateService.hpp b/umrr_ros2_driver/include/umrr_ros2_driver/UpdateService.hpp new file mode 100644 index 0000000..2b51044 --- /dev/null +++ b/umrr_ros2_driver/include/umrr_ros2_driver/UpdateService.hpp @@ -0,0 +1,15 @@ +#pragma once + +#include +#include +#include +#include +#include +#include + +using namespace com::common; +using namespace com::types; +using namespace com::master; + +void MyUpdateServiceInfoHandler(SWUpdateInfo &updateInfoLocal); +void StartSoftwareUpdate(ClientId client_id, std::string update_image); diff --git a/umrr_ros2_driver/include/umrr_ros2_driver/smartmicro_radar_node.hpp b/umrr_ros2_driver/include/umrr_ros2_driver/smartmicro_radar_node.hpp index d9e3d4a..488e851 100644 --- a/umrr_ros2_driver/include/umrr_ros2_driver/smartmicro_radar_node.hpp +++ b/umrr_ros2_driver/include/umrr_ros2_driver/smartmicro_radar_node.hpp @@ -26,6 +26,7 @@ #include #include #include +#include #include #include #include @@ -42,6 +43,7 @@ #include "umrr_ros2_msgs/srv/send_command.hpp" #include "umrr_ros2_msgs/srv/set_ip.hpp" #include "umrr_ros2_msgs/srv/set_mode.hpp" +#include "umrr_ros2_msgs/srv/firmware_download.hpp" namespace smartmicro { namespace drivers { @@ -229,6 +231,21 @@ class UMRR_ROS2_DRIVER_PUBLIC SmartmicroRadarNode : public ::rclcpp::Node { const com::types::ClientId client_id ); + /// + /// @brief A callback that is called when a new target list port for + /// umrra4 T171_v1_3_0 arrives. + /// @param[in] sensor_idx The sensor id for the respected published topic. + /// @param[in] target_list_port The target list port + /// @param[in] client_id The client_id of the sensor + /// + void targetlist_callback_umrra4_v1_3_0( + const std::uint32_t sensor_idx, + const std::shared_ptr + &targetlist_port_umrra4_v1_3_0, + const com::types::ClientId client_id + ); + /// /// @brief A callback that is called when a new CAN target list for /// umrr96_v1_0_3 arrives. @@ -333,6 +350,21 @@ class UMRR_ROS2_DRIVER_PUBLIC SmartmicroRadarNode : public ::rclcpp::Node { comtargetbaselist::ComTargetBaseList> &targetlist_can_umrra4_v1_0_1, const com::types::ClientId client_id); + + /// + /// @brief A callback that is called when a new CAN target list for + /// umrra4 arrives. + /// + /// @param[in] sensor_idx The sensor id for respective published topic. + /// @param[in] target_list_port The target list port + /// @param[in] client_id The client_id of the sensor + /// + void CAN_targetlist_callback_umrra4_v1_3_0( + const std::uint32_t sensor_idx, + const std::shared_ptr + &targetlist_can_umrra4_v1_3_0, + const com::types::ClientId client_id); /// /// @brief Read parameters and update the json config files required by @@ -383,9 +415,17 @@ class UMRR_ROS2_DRIVER_PUBLIC SmartmicroRadarNode : public ::rclcpp::Node { const std::shared_ptr request, std::shared_ptr response); + /// + /// @brief Service for firmware download. + /// + void firmware_download( + const std::shared_ptr request, + std::shared_ptr result); + rclcpp::Service::SharedPtr mode_srv_; rclcpp::Service::SharedPtr ip_addr_srv_; rclcpp::Service::SharedPtr command_srv_; + rclcpp::Service::SharedPtr download_srv_; std::array m_sensors{}; std::array m_adapters{}; @@ -401,8 +441,10 @@ class UMRR_ROS2_DRIVER_PUBLIC SmartmicroRadarNode : public ::rclcpp::Node { }; bool check_signal = false; +std::string update_image{}; std::shared_ptr m_services{}; std::shared_ptr data_umrra4_v1_0_1{}; +std::shared_ptr data_umrra4_v1_3_0{}; std::shared_ptr data_umrr11{}; std::shared_ptr data_umrr96{}; std::shared_ptr data_umrr9f_v1_1_1{}; diff --git a/umrr_ros2_driver/launch/radar.launch.py b/umrr_ros2_driver/launch/radar.launch.py index 23946f3..fb0bd5e 100644 --- a/umrr_ros2_driver/launch/radar.launch.py +++ b/umrr_ros2_driver/launch/radar.launch.py @@ -28,17 +28,13 @@ def generate_launch_description(): """Generate the launch description.""" - radar_sensor_params = os.path.join( - get_package_share_directory(PACKAGE_NAME), 'param/radar.sensor.template.yaml') - - radar_adapter_params = os.path.join( - get_package_share_directory(PACKAGE_NAME), 'param/radar.adapter.template.yaml') - + radar__params = os.path.join( + get_package_share_directory(PACKAGE_NAME), 'param/radar.params.template.yaml') radar_node = Node( package=PACKAGE_NAME, executable='smartmicro_radar_node_exe', name='smart_radar', - parameters=[radar_sensor_params, radar_adapter_params] + parameters=[radar__params] ) return LaunchDescription([ radar_node diff --git a/umrr_ros2_driver/launch/radar_rviz.launch.py b/umrr_ros2_driver/launch/radar_rviz.launch.py deleted file mode 100644 index 5d2c84f..0000000 --- a/umrr_ros2_driver/launch/radar_rviz.launch.py +++ /dev/null @@ -1,59 +0,0 @@ -# Copyright 2021 Apex.AI, 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. - -import os - -from ament_index_python import get_package_share_directory -from launch_ros.actions import Node - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument -from launch.substitutions import LaunchConfiguration - -PACKAGE_NAME = 'umrr_ros2_driver' - - -def generate_launch_description(): - """Generate the launch description.""" - radar_param_file = os.path.join( - get_package_share_directory(PACKAGE_NAME), 'param/radar.template.yaml') - - radar_params = DeclareLaunchArgument( - 'radar_param_file', - default_value=radar_param_file, - description='Path to param file for the radar node.' - ) - - rviz_cfg_path = os.path.join( - get_package_share_directory(PACKAGE_NAME), 'config/rviz/radar.rviz') - - radar_node = Node( - package=PACKAGE_NAME, - executable='smartmicro_radar_node_exe', - name='smartmicro_radar_node', - parameters=[LaunchConfiguration('radar_param_file')] - ) - - rviz2 = Node( - package='rviz2', - executable='rviz2', - name='rviz2', - arguments=['-d', str(rviz_cfg_path)] - ) - - return LaunchDescription([ - radar_params, - radar_node, - rviz2 - ]) diff --git a/umrr_ros2_driver/package.xml b/umrr_ros2_driver/package.xml index b24ee2f..7b545fd 100644 --- a/umrr_ros2_driver/package.xml +++ b/umrr_ros2_driver/package.xml @@ -2,7 +2,7 @@ umrr_ros2_driver - 4.0.0 + 6.0.0 A node to publish data from a smartmicro radar. s.m.s, smart microwave sensors GmbH. Apache 2.0 License diff --git a/umrr_ros2_driver/param/example/radar.adapter.example.yaml b/umrr_ros2_driver/param/example/radar.adapter.example.yaml index 8d238f2..0b62adb 100644 --- a/umrr_ros2_driver/param/example/radar.adapter.example.yaml +++ b/umrr_ros2_driver/param/example/radar.adapter.example.yaml @@ -4,7 +4,9 @@ # This sets the iface_name in the hw_inventory.json # sudo slcand -o -s6 -t hw -S 3000000 /dev/ttyUSBx # sudo ip link set up slcan0 + # set buffer length using /sbin/ip link set slcan0 txqueuelen 4096 # For peak CAN adapters, only required to set baudrate + # sudo ip link set your_interface up type can bitrate 500000 # One sensor per interface for can, for ethernet we can use one interface/dev for multiple sensors master_inst_serial_type: "can_based" master_data_serial_type: "can_based" diff --git a/umrr_ros2_driver/param/radar.adapter.template.yaml b/umrr_ros2_driver/param/radar.adapter.template.yaml deleted file mode 100644 index f1c3e36..0000000 --- a/umrr_ros2_driver/param/radar.adapter.template.yaml +++ /dev/null @@ -1,14 +0,0 @@ ---- -/**: - ros__parameters: - # This sets the iface_name in the hw_inventory.json - # One sensor per adapter in case of CAN - # For ethernet it is possible to have one adapter/interface for multiple sensors - master_inst_serial_type: "port_based" - master_data_serial_type: "port_based" - adapters: - adapter_0: - hw_type: "eth" - hw_dev_id: 3 - hw_iface_name: "eth0" - port: 55555 diff --git a/umrr_ros2_driver/param/radar.params.template.yaml b/umrr_ros2_driver/param/radar.params.template.yaml new file mode 100644 index 0000000..501d612 --- /dev/null +++ b/umrr_ros2_driver/param/radar.params.template.yaml @@ -0,0 +1,120 @@ +/smart_radar: + ros__parameters: + adapters: + adapter_0: + hw_dev_id: 3 + hw_iface_name: eth0 + hw_type: eth + port: 55555 + master_data_serial_type: port_based + master_inst_serial_type: port_based + sensors: + # As many as 10 sensors all named as "sensor_" in increasing order of numbers, + # e.g., sensor_0, sensor_1, etc. The list must start with sensor_0. + # For sensor `model`if using : + # can: 'umrra4_can_v1_0_1', 'umrr96_can', 'umrr11_can', 'umrr9d_can_v1_0_3', 'umrr9d_can_v1_2_2', 'umrr9f_can_v2_1_1', 'umrr9f_can_v2_2_1' + # port: 'umrra4_v1_0_1', 'umrr96', 'umrr11', 'umrr9d_v1_0_3', 'umrr9d_v1_2_2', 'umrr9f_v1_1_1', 'umrr9f_v2_1_1', 'umrr9f_v2_2_1' + sensor_0: + link_type: "eth" + # The model of the connected sensor. + model: "umrr11" + # Adapter id to which sensor is connected + dev_id: 3 + # The client_id of the sensor/source, must be a unique integer. + id: 100 + # The ip address of the sensor or of the source acting as a sensor. + ip: "172.22.10.101" + # The port to be used. + port: 55555 + # The frame_id to be set to the published messages. + frame_id: "umrr" + # Specify the history size. + history_size: 10 + inst_type: "port_based" + data_type: "port_based" + # The interface name of the sensor + uifname: "umrr11_t132_automotive" + # The major version of the interface + uifmajorv: 1 + # The minor version of the interface + uifminorv: 1 + # The pathc version of the interface + uifpatchv: 2 + sensor_1: + link_type: "eth" + # The model of the connected sensor. + model: "umrr96" + # Adapter id to which sensor is connected + dev_id: 3 + # The client_id of the sensor/source, must be a unique integer. + id: 200 + # The ip address of the sensor or of the source acting as a sensor. + ip: "172.22.10.102" + # The port to be used. + port: 55555 + # The frame_id to be set to the published messages. + frame_id: "umrr" + # Specify the history size. + history_size: 10 + inst_type: "port_based" + data_type: "port_based" + # The interface name of the sensor + uifname: "umrr96_t153_automotive" + # The major version of the interface + uifmajorv: 1 + # The minor version of the interface + uifminorv: 2 + # The pathc version of the interface + uifpatchv: 2 + sensor_2: + link_type: "eth" + # The model of the connected sensor. + model: "umrr9f_v2_1_1" + # Adapter id to which sensor is connected + dev_id: 3 + # The client_id of the sensor/source, must be a unique integer. + id: 300 + # The ip address of the sensor or of the source acting as a sensor. + ip: "172.22.10.103" + # The port to be used. + port: 55555 + # The frame_id to be set to the published messages. + frame_id: "umrr" + # Specify the history size. + history_size: 10 + inst_type: "port_based" + data_type: "port_based" + # The interface name of the sensor + uifname: "umrr9f_t169_automotive" + # The major version of the interface + uifmajorv: 2 + # The minor version of the interface + uifminorv: 1 + # The pathc version of the interface + uifpatchv: 1 + sensor_3: + link_type: "eth" + # The model of the connected sensor. + model: "umrr9d_v1_0_3" + # Adapter id to which sensor is connected + dev_id: 3 + # The client_id of the sensor/source, must be a unique integer. + id: 400 + # The ip address of the sensor or of the source acting as a sensor. + ip: "172.22.10.104" + # The port to be used. + port: 55555 + # The frame_id to be set to the published messages. + frame_id: "umrr" + # Specify the history size. + history_size: 10 + inst_type: "port_based" + data_type: "port_based" + # The interface name of the sensor + uifname: "umrr9d_t152_automotive" + # The major version of the interface + uifmajorv: 1 + # The minor version of the interface + uifminorv: 0 + # The pathc version of the interface + uifpatchv: 3 diff --git a/umrr_ros2_driver/param/radar.sensor.template.yaml b/umrr_ros2_driver/param/radar.sensor.template.yaml deleted file mode 100644 index 98e5634..0000000 --- a/umrr_ros2_driver/param/radar.sensor.template.yaml +++ /dev/null @@ -1,114 +0,0 @@ ---- -/**: - ros__parameters: -# An array of sensors to subscribe to. - sensors: - # As many as 10 sensors all named as "sensor_" in increasing order of numbers, - # e.g., sensor_0, sensor_1, etc. The list must start with sensor_0. - # For sensor `model`if using : - # can: 'umrra4_can_v1_0_1', 'umrr96_can', 'umrr11_can', 'umrr9d_can_v1_0_3', 'umrr9d_can_v1_2_2', 'umrr9f_can_v2_1_1', 'umrr9f_can_v2_2_1' - # port: 'umrra4_v1_0_1', 'umrr96', 'umrr11', 'umrr9d_v1_0_3', 'umrr9d_v1_2_2', 'umrr9f_v1_1_1', 'umrr9f_v2_1_1', 'umrr9f_v2_2_1' - sensor_0: - link_type: "eth" - # The model of the connected sensor. - model: "umrr11" - # Adapter id to which sensor is connected - dev_id: 3 - # The client_id of the sensor/source, must be a unique integer. - id: 100 - # The ip address of the sensor or of the source acting as a sensor. - ip: "172.22.10.101" - # The port to be used. - port: 55555 - # The frame_id to be set to the published messages. - frame_id: "umrr" - # Specify the history size. - history_size: 10 - inst_type: "port_based" - data_type: "port_based" - # The interface name of the sensor - uifname: "umrr11_t132_automotive" - # The major version of the interface - uifmajorv: 1 - # The minor version of the interface - uifminorv: 1 - # The pathc version of the interface - uifpatchv: 2 - sensor_1: - link_type: "eth" - # The model of the connected sensor. - model: "umrr96" - # Adapter id to which sensor is connected - dev_id: 3 - # The client_id of the sensor/source, must be a unique integer. - id: 200 - # The ip address of the sensor or of the source acting as a sensor. - ip: "172.22.10.102" - # The port to be used. - port: 55555 - # The frame_id to be set to the published messages. - frame_id: "umrr" - # Specify the history size. - history_size: 10 - inst_type: "port_based" - data_type: "port_based" - # The interface name of the sensor - uifname: "umrr96_t153_automotive" - # The major version of the interface - uifmajorv: 1 - # The minor version of the interface - uifminorv: 2 - # The pathc version of the interface - uifpatchv: 2 - sensor_2: - link_type: "eth" - # The model of the connected sensor. - model: "umrr9f_v2_1_1" - # Adapter id to which sensor is connected - dev_id: 3 - # The client_id of the sensor/source, must be a unique integer. - id: 300 - # The ip address of the sensor or of the source acting as a sensor. - ip: "172.22.10.103" - # The port to be used. - port: 55555 - # The frame_id to be set to the published messages. - frame_id: "umrr" - # Specify the history size. - history_size: 10 - inst_type: "port_based" - data_type: "port_based" - # The interface name of the sensor - uifname: "umrr9f_t169_automotive" - # The major version of the interface - uifmajorv: 2 - # The minor version of the interface - uifminorv: 1 - # The pathc version of the interface - uifpatchv: 1 - sensor_3: - link_type: "eth" - # The model of the connected sensor. - model: "umrr9d_v1_0_3" - # Adapter id to which sensor is connected - dev_id: 3 - # The client_id of the sensor/source, must be a unique integer. - id: 400 - # The ip address of the sensor or of the source acting as a sensor. - ip: "172.22.10.104" - # The port to be used. - port: 55555 - # The frame_id to be set to the published messages. - frame_id: "umrr" - # Specify the history size. - history_size: 10 - inst_type: "port_based" - data_type: "port_based" - # The interface name of the sensor - uifname: "umrr9d_t152_automotive" - # The major version of the interface - uifmajorv: 1 - # The minor version of the interface - uifminorv: 0 - # The pathc version of the interface - uifpatchv: 3 diff --git a/umrr_ros2_driver/src/UpdateService.cpp b/umrr_ros2_driver/src/UpdateService.cpp new file mode 100644 index 0000000..ea53b4f --- /dev/null +++ b/umrr_ros2_driver/src/UpdateService.cpp @@ -0,0 +1,99 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "umrr_ros2_driver/UpdateService.hpp" +#include + +#include +#include +#include +#include +#include +#include + +using namespace com::common; +using namespace com::types; +using namespace com::master; + +static SWUpdateInfo UpdateInfoStatic; + +void MyUpdateServiceInfoHandler(SWUpdateInfo &updateInfoLocal) { + UpdateInfoStatic = updateInfoLocal; + uint64_t downloadedBytes = updateInfoLocal.GetCurrentDownloadedBytes(); + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Downloaded bytes: %lu", downloadedBytes); +} + +void StartSoftwareUpdate(ClientId client_id, std::string update_image) { + std::ifstream fileStream(update_image, std::ios::binary | std::ios::ate); + if (!fileStream.is_open()) { + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Couldn't open File"); + return; + } + const uint64_t size = fileStream.tellg(); + fileStream.close(); + + auto comServicesPtr = com::master::CommunicationServicesIface::Get(); + auto UpdateServicePtr = comServicesPtr->GetUpdateService(); + + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Start Download of the firmware"); + + UpdateInfoStatic.SetUpdateStatus(RUNNING); + UpdateInfoStatic.SetCurrentDownloadedBytes(0); + bool readyFlag = false; + + if (UpdateServicePtr->SoftwareUpdate(update_image, client_id, + MyUpdateServiceInfoHandler) != + ERROR_CODE_OK) { + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Start of SW-Download failed"); + } + + if (UpdateInfoStatic.GetCurrentDownloadedBytes() == size) { + std::this_thread::sleep_for(std::chrono::seconds(3)); + readyFlag = true; + } + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + + while (UpdateInfoStatic.GetUpdateStatus() == RUNNING && !readyFlag) { + // Waiting for the update to finish + } + + switch (UpdateInfoStatic.GetUpdateStatus()) { + case READY_SUCCESS: + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Successful download of firmware."); + //std::system("clear"); + break; + case STOPPED_BY_MASTER: + RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Download is stopped by Master."); + break; + case STOPPED_BY_SLAVE: + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Download is stopped by Slave."); + break; + case STOPPED_BY_ERROR_TIMEOUT: + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), + "Download-Error caused by timeout."); + break; + case STOPPED_BY_ERROR_BLOCK_REPEAT: + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), + "Download-Error caused by Block-Repeat problem."); + break; + case STOPPED_BY_ERROR_IMAGE_INVALID: + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), + "Download-Error caused by Invalid-Image problem."); + break; + default: + RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), + "Download-Error caused by Unknown-Reason."); + break; + } +} diff --git a/umrr_ros2_driver/src/smartmicro_radar_node.cpp b/umrr_ros2_driver/src/smartmicro_radar_node.cpp index 6bc38f9..761321e 100644 --- a/umrr_ros2_driver/src/smartmicro_radar_node.cpp +++ b/umrr_ros2_driver/src/smartmicro_radar_node.cpp @@ -19,8 +19,6 @@ #include #include -#include -#include #include #include #include @@ -37,6 +35,10 @@ #include #include #include +#include +#include +#include +#include #include @@ -54,6 +56,7 @@ #include #include +#include "umrr_ros2_driver/UpdateService.hpp" #include "umrr_ros2_driver/config_path.hpp" using com::common::Instruction; @@ -125,11 +128,16 @@ struct RadarPoint float rcs{}; float noise{}; float snr{}; + float azimuth_angle{}; + float elevation_angle{}; + float range{}; constexpr friend bool operator==(const RadarPoint & p1, const RadarPoint & p2) noexcept { return float_eq(p1.x, p2.x) && float_eq(p1.y, p2.y) && float_eq(p1.z, p2.z) && float_eq(p1.radial_speed, p2.radial_speed) && float_eq(p1.power, p2.power) && - float_eq(p1.rcs, p2.rcs) && float_eq(p1.noise, p2.noise) && float_eq(p1.snr, p2.snr); + float_eq(p1.rcs, p2.rcs) && float_eq(p1.noise, p2.noise) && float_eq(p1.snr, p2.snr) && + float_eq(p1.azimuth_angle, p2.azimuth_angle) && + float_eq(p1.elevation_angle, p2.elevation_angle) && float_eq(p1.range, p2.range); } }; @@ -138,10 +146,14 @@ LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(power); LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(rcs); LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(noise); LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(snr); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(azimuth_angle); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(elevation_angle); +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(range); using Generators = std::tuple< point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator, - point_cloud_msg_wrapper::field_z_generator, field_radial_speed_generator, field_rcs_generator, - field_noise_generator, field_power_generator, field_snr_generator>; + point_cloud_msg_wrapper::field_z_generator, field_radial_speed_generator, field_power_generator, + field_rcs_generator, field_noise_generator, field_snr_generator, field_azimuth_angle_generator, + field_elevation_angle_generator, field_range_generator>; using RadarCloudModifier = PointCloud2Modifier; } // namespace @@ -167,6 +179,7 @@ SmartmicroRadarNode::SmartmicroRadarNode(const rclcpp::NodeOptions & node_option } // Getting the data stream service + data_umrra4_v1_3_0 = com::master::umrra4_automotive_v1_3_0::DataStreamServiceIface::Get(); data_umrra4_v1_0_1 = com::master::umrra4_automotive_v1_0_1::DataStreamServiceIface::Get(); data_umrr11 = com::master::umrr11_t132_automotive_v1_1_2::DataStreamServiceIface::Get(); data_umrr96 = com::master::umrr96_t153_automotive_v1_2_2::DataStreamServiceIface::Get(); @@ -187,6 +200,15 @@ SmartmicroRadarNode::SmartmicroRadarNode(const rclcpp::NodeOptions & node_option m_publishers[i] = create_publisher( "smart_radar/targets_" + std::to_string(i), sensor.history_size); + if ( + sensor.model == "umrra4_v1_3_0" && + com::types::ERROR_CODE_OK != + data_umrra4_v1_3_0->RegisterComTargetListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::targetlist_callback_umrra4_v1_3_0, this, i, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register targetlist callback for sensor umrra4_v1_3_0" << std::endl; + } if ( sensor.model == "umrra4_v1_0_1" && com::types::ERROR_CODE_OK != @@ -194,7 +216,7 @@ SmartmicroRadarNode::SmartmicroRadarNode(const rclcpp::NodeOptions & node_option sensor.id, std::bind( &SmartmicroRadarNode::targetlist_callback_umrra4_v1_0_1, this, i, std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register targetlist callback for sensor umrra4" << std::endl; + std::cout << "Failed to register targetlist callback for sensor umrra4_v1_0_1" << std::endl; } if ( sensor.model == "umrr96" && @@ -268,6 +290,15 @@ SmartmicroRadarNode::SmartmicroRadarNode(const rclcpp::NodeOptions & node_option std::placeholders::_1, std::placeholders::_2))) { std::cout << "Failed to register targetlist callback for sensor umrr9d_v1_2_2" << std::endl; } + if ( + sensor.model == "umrra4_can_v1_3_0" && + com::types::ERROR_CODE_OK != + data_umrra4_v1_3_0->RegisterComTargetBaseListReceiveCallback( + sensor.id, std::bind( + &SmartmicroRadarNode::CAN_targetlist_callback_umrra4_v1_3_0, this, i, + std::placeholders::_1, std::placeholders::_2))) { + std::cout << "Failed to register CAN targetlist for sensor umrra4_v1_3_0" << std::endl; + } if ( sensor.model == "umrra4_can_v1_0_1" && com::types::ERROR_CODE_OK != @@ -275,7 +306,7 @@ SmartmicroRadarNode::SmartmicroRadarNode(const rclcpp::NodeOptions & node_option sensor.id, std::bind( &SmartmicroRadarNode::CAN_targetlist_callback_umrra4_v1_0_1, this, i, std::placeholders::_1, std::placeholders::_2))) { - std::cout << "Failed to register CAN targetlist for sensor umrra4" << std::endl; + std::cout << "Failed to register CAN targetlist for sensor umrra4_v1_0_1" << std::endl; } if ( sensor.model == "umrr96_can" && @@ -351,6 +382,12 @@ SmartmicroRadarNode::SmartmicroRadarNode(const rclcpp::NodeOptions & node_option std::bind( &SmartmicroRadarNode::radar_command, this, std::placeholders::_1, std::placeholders::_2)); + // create a ros2 service to perform firmware download + download_srv_ = create_service( + "smart_radar/firmware_download", + std::bind( + &SmartmicroRadarNode::firmware_download, this, std::placeholders::_1, std::placeholders::_2)); + RCLCPP_INFO(this->get_logger(), "Radar services are ready."); rclcpp::on_shutdown(std::bind(&SmartmicroRadarNode::on_shutdown_callback, this)); @@ -365,6 +402,29 @@ void SmartmicroRadarNode::on_shutdown_callback() m_services.reset(); } +void SmartmicroRadarNode::firmware_download( + const std::shared_ptr request, + std::shared_ptr result) +{ + bool check_flag_id = false; + client_id = request->sensor_id; + update_image = request->file_path; + + for (auto & sensor : m_sensors) { + if (client_id == sensor.id) { + check_flag_id = true; + break; + } + } + if (!check_flag_id) { + result->res = "The sensor ID value entered is invalid! "; + return; + } + + StartSoftwareUpdate(client_id, update_image); + result->res = "Service ended, check the console output for status! "; +} + void SmartmicroRadarNode::radar_mode( const std::shared_ptr request, std::shared_ptr result) @@ -513,7 +573,7 @@ void SmartmicroRadarNode::radar_command( } std::shared_ptr radar_command = - std::make_shared("auto_interface_command", request->command, 2010); + std::make_shared("auto_interface_command", request->command, request->value); if (!batch->AddRequest(radar_command)) { result->res = "Failed to add instruction to the batch! "; @@ -581,6 +641,39 @@ void SmartmicroRadarNode::command_response( } } +void SmartmicroRadarNode::targetlist_callback_umrra4_v1_3_0( + const std::uint32_t sensor_idx, + const std::shared_ptr & + targetlist_port_umrra4_v1_3_0, + const com::types::ClientId client_id) +{ + std::cout << "Targetlist for umrra4_v1_3_0" << std::endl; + if (!check_signal) { + std::shared_ptr port_header; + port_header = targetlist_port_umrra4_v1_3_0->GetPortHeader(); + sensor_msgs::msg::PointCloud2 msg; + RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; + const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; + const auto sec = std::chrono::duration_cast(timestamp); + const auto nanosec = std::chrono::duration_cast(timestamp - sec); + msg.header.stamp.sec = sec.count(); + msg.header.stamp.nanosec = nanosec.count(); + for (const auto & target : targetlist_port_umrra4_v1_3_0->GetTargetList()) { + const auto range = target->GetRange(); + const auto elevation_angle = target->GetElevationAngle(); + const auto range_2d = range * std::cos(elevation_angle); + const auto azimuth_angle = target->GetAzimuthAngle(); + const auto snr = target->GetPower() - target->GetNoise(); + modifier.push_back( + {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), + range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetPower(), + target->GetRcs(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); + } + + m_publishers[sensor_idx]->publish(msg); + } +} + void SmartmicroRadarNode::targetlist_callback_umrra4_v1_0_1( const std::uint32_t sensor_idx, const std::shared_ptr & @@ -589,8 +682,7 @@ void SmartmicroRadarNode::targetlist_callback_umrra4_v1_0_1( { std::cout << "Targetlist for umrra4_v1_0_1" << std::endl; if (!check_signal) { - std::shared_ptr - port_header; + std::shared_ptr port_header; port_header = targetlist_port_umrra4_v1_0_1->GetPortHeader(); sensor_msgs::msg::PointCloud2 msg; RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; @@ -608,7 +700,7 @@ void SmartmicroRadarNode::targetlist_callback_umrra4_v1_0_1( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetPower(), - target->GetRcs(), target->GetNoise(), snr}); + target->GetRcs(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -642,7 +734,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr96( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetPower(), - target->GetRCS(), target->GetNoise(), snr}); + target->GetRCS(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -676,7 +768,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr11( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetPower(), - target->GetRCS(), target->GetNoise(), snr}); + target->GetRCS(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -710,7 +802,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr9d_v1_0_3( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetPower(), - target->GetRcs(), target->GetNoise(), snr}); + target->GetRcs(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -744,7 +836,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr9d_v1_2_2( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetPower(), - target->GetRcs(), target->GetNoise(), snr}); + target->GetRcs(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -780,7 +872,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v1_1_1( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetPower(), - target->GetRCS(), target->GetTgtNoise(), snr}); + target->GetRCS(), target->GetTgtNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -816,7 +908,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v2_0_0( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetPower(), - target->GetRCS(), target->GetTgtNoise(), snr}); + target->GetRCS(), target->GetTgtNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -850,7 +942,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v2_1_1( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetPower(), - target->GetRcs(), target->GetNoise(), snr}); + target->GetRcs(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -864,7 +956,7 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v2_2_1( const com::types::ClientId client_id) { std::cout << "Targetlist for umrr9f v2_2_1" << std::endl; - if(!check_signal) { + if (!check_signal) { std::shared_ptr port_header; port_header = targetlist_port_umrr9f_v2_2_1->GetPortHeader(); @@ -884,7 +976,42 @@ void SmartmicroRadarNode::targetlist_callback_umrr9f_v2_2_1( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetPower(), - target->GetRcs(), target->GetNoise(), snr}); + target->GetRcs(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); + } + + m_publishers[sensor_idx]->publish(msg); + } +} + +void SmartmicroRadarNode::CAN_targetlist_callback_umrra4_v1_3_0( + const std::uint32_t sensor_idx, + const std::shared_ptr< + com::master::umrra4_automotive_v1_3_0::comtargetbaselist::ComTargetBaseList> & + targetlist_can_umrra4_v1_3_0, + const com::types::ClientId client_id) +{ + std::cout << "CAN Targetlist for umrra4_v1_3_0" << std::endl; + if (!check_signal) { + std::shared_ptr + port_header; + port_header = targetlist_can_umrra4_v1_3_0->GetPortHeader(); + sensor_msgs::msg::PointCloud2 msg; + RadarCloudModifier modifier{msg, m_sensors[sensor_idx].frame_id}; + const auto timestamp = std::chrono::microseconds{port_header->GetTimestamp()}; + const auto sec = std::chrono::duration_cast(timestamp); + const auto nanosec = std::chrono::duration_cast(timestamp - sec); + msg.header.stamp.sec = sec.count(); + msg.header.stamp.nanosec = nanosec.count(); + for (const auto & target : targetlist_can_umrra4_v1_3_0->GetTargetList()) { + const auto range = target->GetRange(); + const auto elevation_angle = target->GetElevationAngle(); + const auto range_2d = range * std::cos(elevation_angle); + const auto azimuth_angle = target->GetAzimuthAngle(); + const auto snr = target->GetSignalLevel() - target->GetNoise(); + modifier.push_back( + {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), + range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetSignalLevel(), + target->GetRCS(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -919,7 +1046,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrra4_v1_0_1( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetSignalLevel(), - target->GetRCS(), target->GetNoise(), snr}); + target->GetRCS(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -954,7 +1081,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr96( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetSignalLevel(), - target->GetRCS(), target->GetNoise(), snr}); + target->GetRCS(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -989,7 +1116,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr11( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetSignalLevel(), - target->GetRCS(), target->GetNoise(), snr}); + target->GetRCS(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -1024,7 +1151,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_0_3( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetSignalLevel(), - target->GetRCS(), target->GetNoise(), snr}); + target->GetRCS(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -1059,7 +1186,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr9d_v1_2_2( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetSignalLevel(), - target->GetRCS(), target->GetNoise(), snr}); + target->GetRCS(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -1094,7 +1221,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_1_1( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetSignalLevel(), - target->GetRCS(), target->GetNoise(), snr}); + target->GetRCS(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -1129,7 +1256,7 @@ void SmartmicroRadarNode::CAN_targetlist_callback_umrr9f_v2_2_1( modifier.push_back( {range_2d * std::cos(azimuth_angle), range_2d * std::sin(azimuth_angle), range * std::sin(elevation_angle), target->GetSpeedRadial(), target->GetSignalLevel(), - target->GetRCS(), target->GetNoise(), snr}); + target->GetRCS(), target->GetNoise(), snr, azimuth_angle, elevation_angle, range}); } m_publishers[sensor_idx]->publish(msg); @@ -1240,7 +1367,7 @@ void SmartmicroRadarNode::update_config_files_from_params() for (auto i = 0UL; i < m_number_of_sensors; ++i) { const auto & sensor = m_sensors[i]; client[kClientLinkTag] = sensor.link_type; - client[kClientIdTag] = sensor.id; // + client[kClientIdTag] = sensor.id; client[kHwDevIdTag] = sensor.dev_id; client[kPortTag] = sensor.port; client[kIpTag] = sensor.ip; diff --git a/umrr_ros2_driver/test/radar_node_test.launch.py b/umrr_ros2_driver/test/radar_node_test.launch.py index 16c4b14..52ad86a 100644 --- a/umrr_ros2_driver/test/radar_node_test.launch.py +++ b/umrr_ros2_driver/test/radar_node_test.launch.py @@ -33,17 +33,13 @@ @pytest.mark.launch_test def generate_test_description(): - radar_sensor_params = os.path.join( - get_package_share_directory(PACKAGE_NAME), 'param/radar.sensor.template.yaml') - - radar_adapter_params = os.path.join( - get_package_share_directory(PACKAGE_NAME), 'param/radar.adapter.template.yaml') - + radar__params = os.path.join( + get_package_share_directory(PACKAGE_NAME), 'param/radar.params.template.yaml') radar_node = Node( package=PACKAGE_NAME, executable='smartmicro_radar_node_exe', name='smart_radar', - parameters=[radar_sensor_params, radar_adapter_params] + parameters=[radar__params] ) frequency_sweep_service = ExecuteProcess( diff --git a/umrr_ros2_msgs/CMakeLists.txt b/umrr_ros2_msgs/CMakeLists.txt index 23f66f7..a6f7494 100644 --- a/umrr_ros2_msgs/CMakeLists.txt +++ b/umrr_ros2_msgs/CMakeLists.txt @@ -1,28 +1,26 @@ cmake_minimum_required(VERSION 3.11) project(umrr_ros2_msgs) -# Default to C99 -if(NOT CMAKE_C_STANDARD) - set(CMAKE_C_STANDARD 99) -endif() - -# Default to C++14 +# Default to C++17 if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) + set(CMAKE_CXX_STANDARD 17) + set(CMAKE_CXX_STANDARD_REQUIRED ON) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) + add_compile_options(-Wall -Wextra -Wpedantic -Wnon-virtual-dtor -Woverloaded-virtual) endif() # find dependencies find_package(ament_cmake REQUIRED) find_package(rosidl_default_generators REQUIRED) +find_package(std_msgs REQUIRED) rosidl_generate_interfaces(${PROJECT_NAME} "srv/SetMode.srv" "srv/SetIp.srv" "srv/SendCommand.srv" + "srv/FirmwareDownload.srv" ) ament_export_dependencies(rosidl_default_runtime) diff --git a/umrr_ros2_msgs/package.xml b/umrr_ros2_msgs/package.xml index 261bc82..b4bc9b1 100644 --- a/umrr_ros2_msgs/package.xml +++ b/umrr_ros2_msgs/package.xml @@ -8,13 +8,8 @@ Apache 2.0 ament_cmake - rosidl_default_generators - - rosidl_default_generators - rosidl_default_runtime - ament_lint_auto - ament_lint_common + rosidl_default_generators rosidl_interface_packages diff --git a/umrr_ros2_msgs/srv/FirmwareDownload.srv b/umrr_ros2_msgs/srv/FirmwareDownload.srv new file mode 100644 index 0000000..4557eff --- /dev/null +++ b/umrr_ros2_msgs/srv/FirmwareDownload.srv @@ -0,0 +1,4 @@ +uint32 sensor_id +string file_path +--- +string res diff --git a/umrr_ros2_msgs/srv/SendCommand.srv b/umrr_ros2_msgs/srv/SendCommand.srv index f0446e0..6e16b52 100644 --- a/umrr_ros2_msgs/srv/SendCommand.srv +++ b/umrr_ros2_msgs/srv/SendCommand.srv @@ -1,4 +1,5 @@ string command +float32 value uint32 sensor_id --- string res